From b018966b53731c4bd9293777234631664235d0bf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jun 2022 16:59:59 +0900 Subject: [PATCH] feat(obstacle_cruise_planner): add new package (#570) * feat(obstacle_velocity_planner): add obstacle_velocity_planner Signed-off-by: Takayuki Murooka * udpate yaml Signed-off-by: Takayuki Murooka * update dependency Signed-off-by: Takayuki Murooka * fix maybe-unused false positive error Signed-off-by: Takayuki Murooka * Tier IV -> TIER IV Signed-off-by: Takayuki Murooka * fix some reviews Signed-off-by: Takayuki Murooka * fix some reviews Signed-off-by: Takayuki Murooka * minor change Signed-off-by: Takayuki Murooka * minor changes Signed-off-by: Takayuki Murooka * use obstacle_stop by default Signed-off-by: Takayuki Murooka * fix compile error Signed-off-by: Takayuki Murooka * obstacle_velocity -> adaptive_cruise Signed-off-by: Takayuki Murooka * fix for autoware meta repository Signed-off-by: Takayuki Murooka * fix compile error on CI Signed-off-by: Takayuki Murooka * add min_ego_accel_for_rss Signed-off-by: Takayuki Murooka * fix CI error Signed-off-by: Takayuki Murooka * rename to obstacle_cruise_planner Signed-off-by: Takayuki Murooka * fix tier4_planning_launch Signed-off-by: Takayuki Murooka * fix humble CI Signed-off-by: Takayuki Murooka --- .../obstacle_cruise_planner.param.yaml | 123 ++ .../motion_planning/motion_planning.launch.py | 80 +- .../obstacle_cruise_planner/CMakeLists.txt | 39 + .../config/obstacle_cruise_planner.param.yaml | 123 ++ ...plot_juggler_obstacle_velocity_planner.xml | 150 ++ .../image/collision_point.png | Bin 0 -> 263981 bytes .../image/detection_area.png | Bin 0 -> 220257 bytes .../image/obstacle_to_cruise.png | Bin 0 -> 24795 bytes .../image/obstacle_to_stop.png | Bin 0 -> 25818 bytes .../common_structs.hpp | 120 ++ .../include/obstacle_cruise_planner/node.hpp | 165 ++ .../optimization_based_planner/box2d.hpp | 135 ++ .../optimization_based_planner.hpp | 189 +++ .../optimization_based_planner/resample.hpp | 50 + .../optimization_based_planner/s_boundary.hpp | 33 + .../optimization_based_planner/st_point.hpp | 31 + .../velocity_optimizer.hpp | 73 + .../pid_based_planner/debug_values.hpp | 79 + .../pid_based_planner/pid_based_planner.hpp | 138 ++ .../pid_based_planner/pid_controller.hpp | 62 + .../planner_interface.hpp | 192 +++ .../obstacle_cruise_planner/polygon_utils.hpp | 62 + .../include/obstacle_cruise_planner/utils.hpp | 49 + .../launch/obstacle_cruise_planner.launch.xml | 36 + .../obstacle_cruise_planner-design.md | 326 ++++ planning/obstacle_cruise_planner/package.xml | 40 + .../scripts/trajectory_visualizer.py | 384 +++++ planning/obstacle_cruise_planner/src/node.cpp | 780 ++++++++++ .../src/optimization_based_planner/box2d.cpp | 101 ++ .../optimization_based_planner.cpp | 1370 +++++++++++++++++ .../optimization_based_planner/resample.cpp | 220 +++ .../velocity_optimizer.cpp | 276 ++++ .../pid_based_planner/pid_based_planner.cpp | 537 +++++++ .../src/polygon_utils.cpp | 309 ++++ .../obstacle_cruise_planner/src/utils.cpp | 111 ++ 35 files changed, 6380 insertions(+), 3 deletions(-) create mode 100644 launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml create mode 100644 planning/obstacle_cruise_planner/CMakeLists.txt create mode 100644 planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml create mode 100644 planning/obstacle_cruise_planner/config/plot_juggler_obstacle_velocity_planner.xml create mode 100644 planning/obstacle_cruise_planner/image/collision_point.png create mode 100644 planning/obstacle_cruise_planner/image/detection_area.png create mode 100644 planning/obstacle_cruise_planner/image/obstacle_to_cruise.png create mode 100644 planning/obstacle_cruise_planner/image/obstacle_to_stop.png create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/box2d.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/resample.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/st_point.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/debug_values.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp create mode 100644 planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp create mode 100644 planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml create mode 100644 planning/obstacle_cruise_planner/obstacle_cruise_planner-design.md create mode 100644 planning/obstacle_cruise_planner/package.xml create mode 100755 planning/obstacle_cruise_planner/scripts/trajectory_visualizer.py create mode 100644 planning/obstacle_cruise_planner/src/node.cpp create mode 100644 planning/obstacle_cruise_planner/src/optimization_based_planner/box2d.cpp create mode 100644 planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp create mode 100644 planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp create mode 100644 planning/obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp create mode 100644 planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp create mode 100644 planning/obstacle_cruise_planner/src/polygon_utils.cpp create mode 100644 planning/obstacle_cruise_planner/src/utils.cpp diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml new file mode 100644 index 0000000000000..32af994e49938 --- /dev/null +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -0,0 +1,123 @@ +/**: + ros__parameters: + common: + planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" + + is_showing_debug_info: true + + # longitudinal info + idling_time: 4.0 # idling time to detect front vehicle starting deceleration [s] + min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] + min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] + safe_distance_margin : 6.0 # This is also used as a stop margin [m] + min_strong_accel: -3.0 # obstacle stop requiring deceleration less than this value will be ignored [m/ss] + + lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] + + nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index + nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index + min_behavior_stop_margin: 3.0 # [m] + + cruise_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: false + pedestrian: false + + stop_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: true + pedestrian: true + + obstacle_filtering: + rough_detection_area_expand_width : 5.0 # rough lateral margin for rough detection area expansion [m] + detection_area_expand_width : 0.0 # lateral margin for precise detection area expansion + decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking + + # if crossing vehicle is decided as target obstacles or not + crossing_obstacle_velocity_threshold : 3.0 # velocity threshold for crossing obstacle for cruise or stop [m/s] + crossing_obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop + collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] + + ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] + max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego + + ignored_outside_obstacle_type: + unknown: false + car: false + truck: false + bus: false + trailer: false + motorcycle: false + bicycle: true + pedestrian: true + + pid_based_planner: + # use_predicted_obstacle_pose: false + + # PID gains to keep safe distance with the front vehicle + kp: 0.6 + ki: 0.0 + kd: 0.5 + + min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] + + output_ratio_during_accel: 2.5 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + vel_to_acc_weight: 8.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + + min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] + + obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] + + optimization_based_planner: + limit_min_accel: -3.0 + resampling_s_interval: 2.0 + dense_resampling_time_interval: 0.1 + sparse_resampling_time_interval: 1.0 + dense_time_horizon: 5.0 + max_time_horizon: 25.0 + max_trajectory_length: 200.0 + velocity_margin: 0.1 #[m/s] + + # Parameters for safe distance + safe_distance_margin: 5.0 + t_dangerous: 0.5 + + # Parameters for collision detection + collision_time_threshold: 10.0 + object_zero_velocity_threshold: 3.0 #[m/s] + object_low_velocity_threshold: 3.0 #[m/s] + external_velocity_limit: 20.0 #[m/s] + delta_yaw_threshold_of_object_and_ego: 90.0 # [deg] + delta_yaw_threshold_of_nearest_index: 60.0 # [deg] + collision_duration_threshold_of_object_and_ego: 1.0 # [s] + + # Switch for each functions + enable_adaptive_cruise: true + use_object_acceleration: false + use_hd_map: true + + # For initial Motion + replan_vel_deviation: 5.0 # velocity deviation to replan initial velocity [m/s] + engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) + engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) + engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity. + stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + + # Weights for optimization + max_s_weight: 100.0 + max_v_weight: 1.0 + over_s_safety_weight: 1000000.0 + over_s_ideal_weight: 50.0 + over_v_weight: 500000.0 + over_a_weight: 5000.0 + over_j_weight: 10000.0 diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 89d04bc5b3a00..0aad10cb6812c 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -21,6 +21,7 @@ from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -172,6 +173,52 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # obstacle cruise planner + obstacle_cruise_planner_param_path = os.path.join( + get_package_share_directory("tier4_planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_cruise_planner", + "obstacle_cruise_planner.param.yaml", + ) + with open(obstacle_cruise_planner_param_path, "r") as f: + obstacle_cruise_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + obstacle_cruise_planner_component = ComposableNode( + package="obstacle_cruise_planner", + plugin="motion_planning::ObstacleCruisePlannerNode", + name="obstacle_cruise_planner", + namespace="", + remappings=[ + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), + ("~/output/clear_velocity_limit", "/planning/scenario_planning/clear_velocity_limit"), + ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), + ], + parameters=[ + common_param, + obstacle_cruise_planner_param, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + obstacle_cruise_planner_relay_component = ComposableNode( + package="topic_tools", + plugin="topic_tools::RelayNode", + name="obstacle_cruise_planner_relay", + namespace="", + parameters=[ + {"input_topic": "obstacle_avoidance_planner/trajectory"}, + {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, + {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + container = ComposableNodeContainer( name="motion_planning_container", namespace="", @@ -179,18 +226,42 @@ def launch_setup(context, *args, **kwargs): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, - obstacle_stop_planner_component, ], ) + obstacle_stop_planner_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_stop_planner_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "obstacle_stop_planner"), + ) + + obstacle_cruise_planner_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_cruise_planner_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "obstacle_cruise_planner"), + ) + + obstacle_cruise_planner_relay_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_cruise_planner_relay_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "none"), + ) + surround_obstacle_checker_loader = LoadComposableNodes( composable_node_descriptions=[surround_obstacle_checker_component], target_container=container, condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) - group = GroupAction([container, surround_obstacle_checker_loader]) - + group = GroupAction( + [ + container, + obstacle_stop_planner_loader, + obstacle_cruise_planner_loader, + obstacle_cruise_planner_relay_loader, + surround_obstacle_checker_loader, + ] + ) return [group] @@ -221,6 +292,9 @@ def add_launch_arg(name: str, default_value=None, description=None): # surround obstacle checker add_launch_arg("use_surround_obstacle_check", "true", "launch surround_obstacle_checker or not") + add_launch_arg( + "cruise_planner", "obstacle_stop_planner", "cruise planner type" + ) # select from "obstacle_stop_planner", "obstacle_cruise_planner", "none" add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") add_launch_arg("use_multithread", "false", "use multithread") diff --git a/planning/obstacle_cruise_planner/CMakeLists.txt b/planning/obstacle_cruise_planner/CMakeLists.txt new file mode 100644 index 0000000000000..7ba8bd9c000ed --- /dev/null +++ b/planning/obstacle_cruise_planner/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 3.14) +project(obstacle_cruise_planner) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) + +ament_auto_add_library(obstacle_cruise_planner_core SHARED + src/node.cpp + src/utils.cpp + src/polygon_utils.cpp + src/optimization_based_planner/resample.cpp + src/optimization_based_planner/box2d.cpp + src/optimization_based_planner/velocity_optimizer.cpp + src/optimization_based_planner/optimization_based_planner.cpp + src/pid_based_planner/pid_based_planner.cpp +) + +rclcpp_components_register_node(obstacle_cruise_planner_core + PLUGIN "motion_planning::ObstacleCruisePlannerNode" + EXECUTABLE obstacle_cruise_planner +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) + +install(PROGRAMS + scripts/trajectory_visualizer.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml new file mode 100644 index 0000000000000..32af994e49938 --- /dev/null +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -0,0 +1,123 @@ +/**: + ros__parameters: + common: + planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" + + is_showing_debug_info: true + + # longitudinal info + idling_time: 4.0 # idling time to detect front vehicle starting deceleration [s] + min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] + min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] + safe_distance_margin : 6.0 # This is also used as a stop margin [m] + min_strong_accel: -3.0 # obstacle stop requiring deceleration less than this value will be ignored [m/ss] + + lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] + + nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index + nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index + min_behavior_stop_margin: 3.0 # [m] + + cruise_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: false + pedestrian: false + + stop_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: true + pedestrian: true + + obstacle_filtering: + rough_detection_area_expand_width : 5.0 # rough lateral margin for rough detection area expansion [m] + detection_area_expand_width : 0.0 # lateral margin for precise detection area expansion + decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking + + # if crossing vehicle is decided as target obstacles or not + crossing_obstacle_velocity_threshold : 3.0 # velocity threshold for crossing obstacle for cruise or stop [m/s] + crossing_obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop + collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] + + ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] + max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego + + ignored_outside_obstacle_type: + unknown: false + car: false + truck: false + bus: false + trailer: false + motorcycle: false + bicycle: true + pedestrian: true + + pid_based_planner: + # use_predicted_obstacle_pose: false + + # PID gains to keep safe distance with the front vehicle + kp: 0.6 + ki: 0.0 + kd: 0.5 + + min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] + + output_ratio_during_accel: 2.5 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + vel_to_acc_weight: 8.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + + min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] + + obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] + + optimization_based_planner: + limit_min_accel: -3.0 + resampling_s_interval: 2.0 + dense_resampling_time_interval: 0.1 + sparse_resampling_time_interval: 1.0 + dense_time_horizon: 5.0 + max_time_horizon: 25.0 + max_trajectory_length: 200.0 + velocity_margin: 0.1 #[m/s] + + # Parameters for safe distance + safe_distance_margin: 5.0 + t_dangerous: 0.5 + + # Parameters for collision detection + collision_time_threshold: 10.0 + object_zero_velocity_threshold: 3.0 #[m/s] + object_low_velocity_threshold: 3.0 #[m/s] + external_velocity_limit: 20.0 #[m/s] + delta_yaw_threshold_of_object_and_ego: 90.0 # [deg] + delta_yaw_threshold_of_nearest_index: 60.0 # [deg] + collision_duration_threshold_of_object_and_ego: 1.0 # [s] + + # Switch for each functions + enable_adaptive_cruise: true + use_object_acceleration: false + use_hd_map: true + + # For initial Motion + replan_vel_deviation: 5.0 # velocity deviation to replan initial velocity [m/s] + engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) + engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) + engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity. + stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + + # Weights for optimization + max_s_weight: 100.0 + max_v_weight: 1.0 + over_s_safety_weight: 1000000.0 + over_s_ideal_weight: 50.0 + over_v_weight: 500000.0 + over_a_weight: 5000.0 + over_j_weight: 10000.0 diff --git a/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_velocity_planner.xml b/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_velocity_planner.xml new file mode 100644 index 0000000000000..634268b93f2de --- /dev/null +++ b/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_velocity_planner.xml @@ -0,0 +1,150 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/obstacle_cruise_planner/image/collision_point.png b/planning/obstacle_cruise_planner/image/collision_point.png new file mode 100644 index 0000000000000000000000000000000000000000..29a4f913891b3f47f60430a5137ed8c54647d93c GIT binary patch literal 263981 zcmY&f|S8l26Ghiokh2%fD=6V*HVJ1OBlQ+-p z6*+Y^3kt1Vx<{a6lB3x#8NAhWU%&ohIVd!oEmrxla-_IwjaSp+&X zeWn{}P}4W=UgM05BqC_RDO?Hrk;X{#?9p5;f4VjVhq}$$&ayn?%CfC}wr%8SZ~ruX znc!WnI(I@3hwqMDlTg?yD`54nH49JK0bbpK7`kYmX3YcvX`{;ru1Cq1q~~cC0=G zm?zMwChRCjv52{Dtoa0Ws`AAc@DssE%Vfm^zKb!=DpL5|*b3*#O;YBhl5_ZHq;5PY zMlLQc9c#KMd2MgTzhgP&o>DY1B~@&6W620aUQFoU58L=rt01T7lN0YDVefet_TxJj z-z;$Dqa}dl1;?r-EdOtKGU2#%^2?UVP0s$F+rj3aiQv`2>k(cNV3o~Y<&ed%e#@suf#8ytO<*)hqEZ+6MuN6~Fh9Px5 z@5Lcyj|o@_Q=Qt$2||Ac#-A^lEv(n#gWw-YUxQbF7Yl7sJ~1GCb4;(`$?XM*y5cAH zuwyLu`7$yXmrwk}@%?>wXF*|jVPVsb#I^yPyd-HXdBUdiop9Y+&c##yer&~Y%vS?n zD*N0x-)zna8_~z8q<)l+b;;4=i^s?|2*vghUo7VqWtILz%jDqK)wbQON*BL!Fm=Na zv%V>o<82a+QoME>Nhu0AXe=Bp1DbIBDx)zA>*t~khK ztGq%wY&_K@S=*#!DlYE5-4EK19N??|c#l>61ant5{)_-=ya|TyP zR5;K7|5n$hKD)n5Q5B1Q?Im_){{7u!DRSv;f_4Y?=%>B~YG=w6q14I0=PO5HVPjl6nb+~`~Dhf0U=G);jC7FYy zX*1;GU)r7QR-Z3j`&6r^ssX}GS6-b8h?nzGhcaZLCA5mD!Lc9BzW@)d?{IHF3+p;5 ziFV`nyG*)rX7T;ZGyJqz9!f>178S60T(wpzZ|<$5LU_cBz{(8CLu6 zIokRKWQEYU7d13QzVpOnmmMeuk=!Fl-Q75!!q?tKgGTR03Ib5pa6DQ{>s<-4>*W`l z7jf*6w}vo_XlMR7?rd<@IEFPVvdC5EU*{QjRNATSKPbt;LJ4O zR4-@jsoF}v$lB{sSC2EbC|U2UFwaj10_4@tj$U)ihYJ2IxqcCIoz_zcT`??9xJ?7j zxbFX@9850swTh}L@Ycb1?cLqoxjh`mK0WP1vZ4*XR7ALY=Ld`>)b)x3e|D4F3ex)b z8FavCtqH!QS<5SPj!9>rfCfjrFz9LVgq@5;Qz+B z7yqoMXiBeAbIfPwO+HG@^VSW5r#L&NQyOL}AUsUYyn_#;g7fbVG&e3}nQQWl;4vDz+I1P&Q>|w^*Y3Z#oOEWP z79--YJN%7MT`_B9N*8yYEkdhRhlQoQkK%cImON=MqSC>%0@|~+CFr_2?LL3EFc4{% zG)8Yq+DU5@`(`-aEB~iJryA8&u!*329D5ZeF8Y(OlK<(AIvswUHI5=jNTbp4Z-(Pf zT+?Lv^t-xeS0YY7w;cb<^er(u48*ZyGg~@SZ)LdAf>Jx1443o11YJagzV)o<7+M4z zo4KbtC$WdhuEZ@HT}Qo|_pM@4h@TnPs%^p2)^cB! zrO!OSOKv)Ad(&S``|n4)s(&D|Bup@vw?|-7fIey*Ib{lL$QKpbs7^CW`SiDDy1``W zb65Jr$IvcDUoP1chI884mq)viV?EOawlZ6MOlxr&7{MdFpo?btkw@=ve}+c!1AS-h zlT}>!i(_5CM?n&CMj6!SyIZq)C*tau9+2U6dGAy}J^vRH*MX3r?k*#>=Ih)w#^v+! z^xP)zE>8tYkDCyTn?xhUB$8E-SnA{NN%mq+${-r{ zXDMulF~om<>!&Ctu&{OhG^t(j6^J}RY%L%vxk-RZ1HAKd0ndN-)bIl>K66VhVv6JV z^it&J0|<~I;N?K5eqs+UEF92tdjB3Mtj~FZa6V!aH@&&_5;)`;>IT#cNL zr%KE+?y{N&5CXU;$AM%`-ik*0AyvL<8`oHv}zKx*`mV=!(d$sMHGgYYPXP!zCc^`Ol zQ7{wkY9IBcFN>%tsxOJVr|e2msp_x02%G;{Jhjf#k^U^8(5a-fmrg z*^0qr#;<`Oxj)NO+uE-9?3c&5VdpL_4u*D^v`kFUy?vW!Gxi`n`;9Pt96Pb#a|z^N z72lYi#W0<2LY6}EVi!Uxc9f= zaa*k4^-6S$wWN;r8JNBCd|hvEsHmz~P9;p({CX#BBAv3>__kJWuxeuyK`{FjIFh(~ zf9ym~XMiZiH@o{Y82Dz#FZ88JPS?A}G&VL$AIk%{`aJ9F3(5}(FVD^SDa0@v>^WSd zslWqu_G2GnYd&D&lCGQf&geTk6O1W(RN>2xEsnK!JDV2Wh3RiWnh;Pwdmu}i`mm3P^&@SYRVC*& z)fGnbgzdRa$#uwEFZ{~w7!_5WSJcg?dv-r}QZLdXk&S4|gMz2($akUsSYtoEtkhQD zrE}ac(R(w3|Gf`pW8>c;`&2ADf|Fs|-lTt{#E_V{ng2Uj){yEq>?LO$aa?!cgmb5v z5bWoT3c;Gbc}X%qQTh}e$Io#vp0P=vwbyd-LF}q8DxPtXnBJ7&uF%LQnYL8Qe^U6N zx6Yz*R!!_?_ed;^XOdRn8ib`RSmkzF&L$&L%3V2|dW=>hC6+Vcq?@!z*znm*l@#+G z>&Xh4m+8yxw5~3^c4e34WQGC>9GKO+NGOO{u8zpg9AG_b^~+{$j$|nLAwI9Id3rQ_ z%yll%pZru+{S%SDg>st8#emZEE3Z;AtOYOKe9|3)BncYwZtQlG`h&%OB$GMtJ2|;h z#%o%sSEg4Y{+jp2aJ;&BHm}mQRF|h}-O3AtHT;z%V zw!@{;@FVah`@C6cX5syN1J`0k>C<4D<1WE@ilv4nx@l<+@88SYzT}isv0##m)fkWb za01eD>78)wHYt5msUI)~tm`+3Un=cAbZ>GM6glm5tdqq6;l6yt0AZACZ6;npS_%01 znku;GnnZrnvK9p$oP5jX9-o?uGom~1ZQ7%5%dRvxGZmiwJ##h000Om47Ru-smzGYz zdOj#6UK~uSceQmwkMUWQ(v-4$uVaL0-wNUaO{PSI$1hhw)@WvgfZJE={sAD{2t z4;o6A>MtDw-fEc=4B-12n|HAZ4>#0i%Vp?uFf#1?j!o{zNpa;@x$^QN6*#~qJmCRw zCqm5Xaf(vfsC<@hk-EznDE_pUJfN9!z-WbG=Hx_3PW^jxbBy4he|x${-a9vd8Q?I; z#3Ra!^Xag7!ro?QN(#(3P5DbN>^JNYY?#Mf_al443nQ|!wBLQ_DG$J6>=1zh&XuPc zv}NkSX*$k@f?+M(AY+nm)dT+4Qm?|tpL?P3_^2(7yH?6A0)KiPYu9C9BJDkL^qomF z?iAMQodfQwi&vW9@6vKAc;d2``sQ!zCd8ps4~~2IEtBtHu8irG3A44o_=cWw?nnC$ zu_kzH65KddYQJ=(;SiQih`{$p&8s#QWydp}FJ)VF&@6#v*txnWY^oKVq|CKs-faRDuHASTll7igmj)wHI;y8&QDAmbgI}+3&8qUqwX7E#?#vIlfQJr-(%^v z<0CZhngCOVz1*Cs?KwS_UfiN3KuJccsshp0?IxS>_G?wiV|B&7QTBp+JU6=yTMyp+ zekXK~Bj{TE%ki!|2nqc~`^p^nn!()6t>H(4@+NK*fi7nbxm4iTr-TRz<=D*1$vwXP zE0ed?xJOk3V&vJrRld^gaIF0r?msRL(;F05C=|v>yZH?zFUC=7p+)4>-$WWq(U+=+ z!=NFVCwuDXrv3J_qG*ALq-L@F5|MR<<1Xft+NQxC{-E<3_ID!Wh@RI>K3rhgbkuq; zE~)=55Ww<_TWZE8p-*MYQZ`kFsZ#V}rJm)Id=5|{b^o-Nh~kmc`uOS7$AQ}D_oI$g zhI8H_XbJtPg*rG{gE5VlT?Z{OYi1=gtmVn95m7p|Fa$DH70DHs#msRlBW9y*Yu=~I zxK@j#m}=H@vMTqcf29+ zi8;xo_wy-TOxx^G5&$HXX|(G*OH>?=-*V$^7UKP9Hs=|H+ReJnE`>d^)AZIp&K)y@ zd;Iuu=1(WB6cJ5LbukeDd2P8p*G*s-Wo>_g7j8|J84|OHvVO+%t@0^* zr;mU3STcEQ5Is#JT7V@=o;w!+m$|OWvGMo7+!YI(r_!v~v{G&Y^dAvznh9lu662(} ztlLQ=+nV)FclOCp39bBsd(&YnU_vD$U&pozXq!ptisU?`%+vT@j}T`)jljhu;msS; zN$lXIt6u-)jKM?ErTC!!B+8A-aw(Xjs)M8 z_rf07Cf(BZCSa0fck8z(@6?l24*TH52P95fHr)h`C2`&KoJx6Xi271}mu+&eghyRp zTvk#%hijX3Pu-uTr9jvQ$klHI)=uQ|vU&g1?j(w{@7{cl&tR_J{oN7~2MS``<)fYI z#Sq@rlZzq%sW_(`6WZE9L&A;!ABi_;&f{z(76Di?rJxWg&sN5JMdVdfI}ifAJ+x6u zzbwP}_{>OzxFZ6jdb^=2>3_bma#&KBP+N}Ogp3YUMZ=vc`UZu2o#KXA3G3kKHh>$I z*uTO5It0fAlvI;Ubnp*`P}YINXxbyWFjhhUaisw?U3@k-cMk;t=2=!~o9R`IWm?;0 zMTtY$ZEMQA$k77ltPF{MHFn)!#cd#y$W*>N6%bG?`$>4`A9L@e5}hl9&s+PSSY@dp z@Bc2rFDJH4A7dqL@lzpludRE5g1x>T3A2Q6zq<%XUp0hFAo+{oSDeikA=)10y4Yq{ z?2I%@dwUMi$Ywn=a58Qgy%uc~3z5U+FU#(+G39-gQ~b2NWd2O_*MJ<0SIUS0LvK=^ zQ>T@3^{Rc5^pfpV@SaC6tPr4ZHGFaJZ*!zxM`~&s#}O9e3nQctHuDP5FxJkU?oIN` zJ~alBCnZVm4HQt4`Y0Vf{OYzaMBR!Z@4gxdqRP21t1w)O|7V$x5Lb`mHwgG;h!Y9Y z#ktKiOT=@SZbrb;XPq$&;uk9DpbYu5n6o@;CGBHM^NEduJjt3FuCWIB!(D* zqX*O=#-`wY8M`U0WWN*f-|7C7T0hu&9i&B!6Q4i|)xF>{%2 z*NY#{M6PSeQ&2eP4py4PDt}piDc?bKFJDm|pIr6+o0zp|%1wv?rgiac8^n~T?sOf|922vrR}Brj*`m#lr3haWvu{3{?*x zjIH+6)DVMtZ-oT&5tkrA;^9?*1C|3JIX2Ti7!Uq2lY%kbe??&mz|upn7yu`i>hoF7 zp!sIC&{=C{Q~>LEcLKPZ;4dFdy7z^EKKMg!B!{`4#&|$vq*Qll%RbYD3uH!E z*ab8!n%KI^S1fW~`P?uCQ$RBcdAS(eZI5(udv(@?J6VQ)U`SBxqz$<{-CSWR8R#b% zTnKmbIF6sHwlj^J@1ef($!A+%Zsj5G=yRSSVUB($8!KW~HH63{EkMFxcp?~4c_6Z* z0C-XNPO4P@Rtu$AN}`HTGsS~}X2BD3&)mBKr;VIRPY=d(n2S=VeGoSRV!h@%*}v12 zNp^}ZFMl*7oXbs8SXj5l_76S$VLBiC+B)i-fk^7Nn6C8>!Q(J5qe(;!CTMqgS?M5;@#B|<#<>o)Tm#5Cph0zBd(Fd^h>+>wF+n**B! z#_gcOX+t032h%3-+C z2O#rb0uzwHLiqPFlb1@Gnk(&@rtHB_O-OUH-`M$PEL(M0G{VplvFusA3YkY&v-)Zg z6n;f|SxxH?-o9t?EL8IhcOy5Z!1vg`PzrU59<_?X9MK3>H6jO^pMGK|?o29@NdL<* zbX+i5dP=$p|KnNF@RXMb zc`XVpPf5R(WmE%>k$9VxYwxv>%+J_dLpPoSH@^+TLEk`Vi4Vv9nIc zyGb8D06j!5_YI&(-?(Hhya&4%{KHGaw6a+>(jU-5G{U9&zbJD`xo>|hfmj+DU1r+6 zCXgwEzT%mX2~_JHBG)TN8Mddf9Hyi@hpA<}0DS)+r*cuaw&EO2TQMI_u58XW_IP3% zmC7=H+`tO%^IO5}ztoLNc$G4XLzOqT= zhzleE#tsh9N{-m+xSx(RvbqFl?S?$3nTMJE zL-D|3#A^tv8W|lh4HKCXk%5d{%G6ejQhewvj*=5?n^^VG2LI?y|75Wz-zt^!Ufzl5 z*fd2*99NCSTJY$8aX5>^OC2w<;$%ER^5%JZCMeFDx>R`G6FH?@J*!;Y)8+W$SmMHo_!J{i*^Yn&XYy@h#_hI3BK zf#bp3aP)XEqCa@HEoYti#++Vh0apRHMJ^lCTbl++5rWC2zAO@nJZM`9*=!(?X9r^$!z2vofc z6I`(qUc-gIxxyW~IPMzITyy7Sl8BX*T9D@S;Y}l^ViABK;O#Md?{vP;q1GIMr=B2F zQm|vOul`@)c^Tln^sE7LDi>p1vgcY391z!8&yWz`BfkYB8fV|NgEPC6Cpqt*>r&@O zapHy9@b}ryMA?KdrLh0T{b6Ke{D=})FD0hQj`!^qQj9}MU#tp#*J&3TWm|=uP`-?O2R}2)^rJ@rq zo*3r0HBc-nZE3)FUb~38llI#NzBx+pov8pg;96(S?X8ticJR23=r@G*WL3vxyzA!d zVu}LtdqJW0>{)U1n40|b*}7ncTrNAos#YORZI1Ok(-byKp;Ls{S=SaXs3M< zmHYF?tyEA(TABVsqg4d`bzbVD2UjcWb{(jxSZ~;0v1&G5Kl5pL6KHhaf-H1S_}G=7 zKxHpd0xP_J<6+lZgBYwN`oY76XFq&C3dtmI+2TId`#OYdFUEE_`x|+#izPJrjNZIfZB+lh@Xff+$vxb&x%a zl-mI4AWEaYE)F1|!UGB?2V9udgyFe`R-$MCT3qoS4IjH!ECL?lw^{e`U{?8K93xVJt*4e@! z;`u|ytH(wjbw(1=voZ^B4@0~T_Ck1ls~5V@_Tn9Ng@jBs(oAwV%IPFlC5urz;&@Ly zP(pCV@39r|<)z(tKvy3Y4m2KI920#!YjYn!MJ@(epC|b$rymyXN~phj@R zE4yr}#JsA}O|tfJS63Vcmk45sHA+9;w99&bX5yMcezfWoY%db{G~N7U2*NTDMsLv( z61JUBl-2yuPn|wjSW^>VF@Xj+S7g+q*YPlk{K(!{ih2040_i1dsEjx>8)R5*>1vMS z^Di_ug(NIS2E^5RJildVk3E^?Go_i*bAn{gv?yoE)B=uX_Q;xPA~-xf834T>dv${g zYd)X*pLW%5HifL2FHq7S%f);KzB_xX-N8(lX$w{D+fv+dyBw)v*<>?Mxb32Hnm0{t>sQeTUq6%w$#1pYixLUo$M;JUrF6cH3TYD(kB}7#P zsJQ$6)^gSClGmEJVNL(3QNN0J(R=_j|Mc6b>DF;)A=&S0riEG01~Nj-)>OYKQA-Mp zRq&c=_8|7P2V5})Av9EmVFS$_^`BkAj^M2-Y9ymtwjAX~{V9T;qNFKp$~alM9Vv5wqpWXC;h5OC(pZ9_;YgVd|T> z8sL_b7Gh7HOt(ZZfFHW)ZiH!AF*r1@XxUuB(y}=aHP&Ype#NkmoruKCT1PqA>b$Tl z72QaDeg9@h+Eu?JtA_KYE8hLY+rL=HN`$$FwzC7DI8AzgG*1X6l+ zpkvOU&{M@+exLWFb!0ylg|kIT;HxU#P5WPS>%Z>`QMlgR1hi<_>SoZza)hFPiFW~V zM9YWkOYT1ZQ*f_)?#$!ZhfesTv4%gSOMjo8q{=|g;>k8bXzf;#qv5OH!geh`?oa^Jk%=D?X+k;)?ZS31S&0!2&m4Azpy`Uk6!%!YQSak6fo?)S^`X{@ zOB5K}lv8+LtB3==mt0slfkftUlK_a=lHP^?vl5RT^*Rl{VXCp`lXPo^huG@3&#XN!%Y->9y`QGM6*pHGV2%;& z1juZlU?Qkf3fJsBSr1f{g$NhX25;X-&VAszboe%!P8;klfbGm?wn_q zCMzFKs-OixI}{g})usQ*e8QGQxac45(uA9g| zr)~J@+4?BrWC`JRa=|dx%7ouAGt1!0g!5#cI{5B+g1I*zcz9QY3nEkCEqI`%ICvNh zv&=_(RAV(B1R>vBy3RcO0iAkJ)6jOvzHjb;!$fd!qAndM=@T_AZZaMDNe~8*)ekgg zypTDQx;Hf-NdcPH%m6SZKnGnZjQ~NyE>UE&Ty~auRWE!KGW;fz6-*J!zS@Sal4E$Z z`@vHW1JK7({rIP|d&AuTL;E_Goyt-XttXlizG!?2Rg~FBM@xjw=+s-0@XZ%w_n zex#Ldv&WyQzXKvU-)%24MWA!*0DKJp`mnBhF3!7}kb3Tjvm8%cZ@_PXRAeMg8}%0( zxd1EGVFl*Su7974nQmY4YXvi1l21)_Iq;+KSlFeSSE^-cYSO?@Mz|LJ3XQa_XA8Qn zv+@>8>vGr(QN9}wewI3>eP^ZK=-pxLh$lii+i=(T-fc|1G_T8MuCXVnzksr37dhA_ zpb}8CHkl>m?ctz;)7pGAAP8(Vu?3z=M`UOG5$*g4qw84?fZ4uV3(o!tjtwjjETvbIMeaNR7Cr+)?RIO^#bKx!oPBp-Ky@|b`gO1EEw1(EYK50oBk);+s^)4{ zD?WNT8e?I4LAn@!pDh)H3m|e=Svt%dE<7z3>7)gehneqR9q~wL5O}I;L^BG_2uEXQ zstnl;iTX{OE4C$NA|j}{rsO`OhLMS$KlpDh?d*S4l<LfWg!P%~qQz)jH(u_HG7>o@}NRG)=Q?M zVGa_x^CH0pi|bZvyZzl#(U3~V+VwL#91z~4n$^^^<0UZF%&^+(9<~oSXHeq%nUPnT z-p2Pl7$h>TBNNHIPg#Q&7V3JSnTIx4e=ReV*PlVV_N#1jcW692s=Wt4y)d$)c%RiY z0WstPJ4$bO&#xPx0FM0vmga1Q-s=ycAv{WsYv%+dx}7DB=~av!z{#pB$Clh@amCg^ z;}$RXOp^DKree;kGb!3){OO)!`;4TkYus*0zy+1KWgAG~wR7xZ!pwTTvd%|@8#-l3 zQpLaTlW5-UCC##Cd66gJC2;h6PvgHiqo#ZI#Q`+ZSUO{8uwQy%F-8XP%Y8q}qek}z z1LB~wgt>n7izuK>DqDR~e#@QvzLNfeN37b&&DVX<3!A_mY?*$m1itVucZ%+{0BIte zK?9z%9~}h=n!RRc{CcoR+KHf<^#sFoWRGia+irx2q(1tgaJmt%_M8L> z4zp{#@v~ZN^6DRld?$zK&XGv&!M1>38z=XlKDerfIbxtb*(fTMweAJLZsGmk0&*EB z@iD!~Az^5Q#!1&u)@3<{Hcv97d86UZ!PX+?P;9=wAgJ}*&CR$wBv;Rt4>KS4vCTjG zas1&KUr9gv5KG|`o}O4h$^XCf8_3Y}APpsc9e@3ptoh(-NcAmXhf-5h$z|WviJ5Qr z1%}ama^-399O4Dhfrf<-$nWlJGNxgyW&I5N#$A|-_QLDnA$~Pv0g{*yxrCc=C?1TK z=KIrNup~!`?Eg9|$zRvk1AU-$Y+xKw8BNKnnFN1iI8K&u5e@4~&d^xFi z=Ax`+cdj6Y#fZJp`i%MVBJGuy>kVWyh4QVNS=GbiH1(a8WA(|g!b-05yP`{Dh0R_J zfegbqp9i_YlwHk7tZH|zDi#y=H0 zJZ=VJsp;vL-xP10{pmP8@ygG+Fviso17b5RNSz93e*ZZx?NK|Et#-vC<*SiovuA#) z(uaZPPDsh+^>xw}>*o~aF9gZ&^|{mlQpwe>fu5P2tc-(Of(!N0lQ&sihu2}>K<8YH zre>l<{$efG6%%jX zxP@c=$lhk;PYx)SrBy~U#UpUC>Ds1#3A$D+Inba8&_%hS(manB-)5+fjz*-9u(0>t zI|U&TDHW*x3JJ}ms21P#EP}myG__AgdiwUE%-JKBll8Y$a{jV{DgEzfkQ$yBKC_g& zfK{jT@tL9e#pwxUSgG_9OS!O%7#&Y!I5<1ETU9RDl+wyt%Eba!vyacC^yEd+;k{)o zE=+Q|v8ahUWB;O#H1rTa}VR)}nUCV!^$C6IqEWI7(A!BLk863Q=XWiG=r(-wPP9%Enegli& z6H8dDFlj6(NV#Q=_uHE&_yb4do2II=p!i#nP=c}by<8^^Oh*3xYA4)Fwc1tq?>=W3_k~dNBs!bgFYjYfl7&z zo>0`X-AzCc1)Qp0qFs|a;kOZcnmmx< z)R5dZ_M=VrMr=3Fkp#t~T?I@lcD^4vyng5PeZc2-CzndJls#-U@0W{=x3t&b(=`6I z=YzOF%$@fh6@s*;_Hd4)Tc*F^Abrc;!D2R*{ysMkFJ(9ykFjsSJi@YV{?S3FZxFr+7vdmYqF>kQE+vY4ZKUf{3!+WQlR&Y`+fup=TURUcQC-Fo1SYf%!jR6I3aRKO*h1lqf z3zHAg+Y}fKZY`=Qhn)(ueyD6M!w_irjU+5ldJN|!sLEg-3x6YQp_4t_5&dxE z$b(D)xj0kt7%^14snP5@Ga?L8Lew@TzfS9aah7$6gx>X%f)E7Ehb!9C#EHxwT(R|vk# zeHet)vj)^9NV&0My>C-^_77T6Hbr~@%ra{u@AoKnI*43NZxM923fep}1ULhXoC~5@ zd+sUb)(3s@b}MnsI_G)}CW^)#!;Yb*1_WB_#FM$vVR9 zXv(ucM*%6s9D~Pt0@j!iIIfHr7^j8K`2GJhiEev_x(CJat$OFuLsvfU;R4QRbB#Yz zFkTL9{PGo%lmQ>OC)VrLCT9|eXv95gpT5w?VL{Ywvq(_OnkCt`%@W1fv{T=`J2PFQfr{W8-7h_|#7rqvPfVr6nNPq= z8Z1+0Xx*Fh9ADcB5#nfM?TYa+lYDyI2X>9 zsFgvszlGib3T;-MxMlh`M>!ZkoqFFk+j*PMyMCfs$86x9OapD|BH$gq83z7Y&X{vo z^`)b=c+uE_n;`=*gi@U`H1)xYA@;|p&@3a~RSAWcVj~cUB(Kf-hxLd{xQ|ybg{6x@ zzIHtE^p~*_ERE#JxErD;4=ZN*zA@U8c}Imp*5SYIL0zkkZ_! zR@1_n4;YDtsFumE8CcP4xgvV2O2c!CMOk)|o3g7=0zmo;_bHpvQ;IAtk+~Gh&dToy zaQ&9mo*GrGu4l(-2qzmFAy@%Ws${XC@x~{4Gf()Z?$Z=gyQ^bc@GRH~j89jN9m~l; zv&t0z^`jdQ-XCYvIcK^#V~DfsCD4uTawWcM=ypg*NCR%x6Trx+xY55Z??(|G0f32l zex5ZiFYlG6%l{0|;)3$Pbs<0?ITv4xXAJg#wPJ*ozVuoU04P^e(?*m*emRsE@+F=v za!@#ptrt)J{x#y0InOnqq}hm4kLZ&$i2?HV@PNzA;n!~q9n@TjLz^@<-x|pMjOuhF z1LwA+*8?z35%}$m>UsNg)Dqwr-xFa2;;@(lvay*urFMAyiJv#`l~wigG9yDv;A9~u z>f<&aNAqs%_&(YZ=Ts&HN4?Ur&}wY-psB<_e6gnlGmUFbb@hcBir{$eTePN*u1=58 zLA8Uqo^VYO5cmY=_Z^;BYQZiV!ORJ-^e$o0kMcO&q zx_H92S{cTtn;td4NA4_1ld)s}O_4`Ab}o&LV7BY-EM7pX-`M~mgCxY@i|%``q_Y!~ zk&yw);h&{lcEk3Xjcp~ewSwT1C#QDI-d~MRCZUY^+9afb*Dtwb&rzbfSqUern9fLn zTV8^tF($x)c5{0XJAK%sd!8CYB?Y}M4|%GpQ!VCQ{aZ^87;m0!B%=;%&dBHbs)#If zJH15NRzGM03i@zng^6fdSyKNNt9_keN8e&Lt?yV;;Plcfs9d?t<0mpqo~4r3fb~`w z;^e|(L3@gF4H!lE)|V)T#f@xTV{OM)L!qP-_<|iVpIa}Kh4w`;o16Cb_CNYIZz&dx z%gt7miq-pK=Mm)X*17o8P3MLTpa`2uWbrBu@v;dL>vdUu`kFzgop^Z@y>FRl4%SU@ zHc%KA*0Ej`eD~<|DktRS(C)(N=dn`NXd<-PCQfLjm-h^Pz#BEnx~ zW~Dm%?gsy+$Tm*3WUOL`g;ji-6@Femm5lL#4fJEy>-vh*Qd774S$u(2_-H=y z8TqL5dwso<0m5$NzZc9?Ohb=>x22lbwq=pHDx*hTMcZZGBne&SOlcd9tyNAu){z z8|zpImE1GkJFnu1HGyWJ z3{VT(%RN2|r-i&d2Wv$ofE@adi{YR0Kql=brNtwcVBu#{KJy0p?G|uFVrDg7S2sHq zbQ_;p&RbviL%l#+3ISxg)Gal_zC@Ib=#ruO$Z zp~FKH;RTgz{2B+Rp2Trht(%*h2al_@{Lh9K&(^lckcPNy73!le!E$%k z2}A9=RSN;s+Mj5O8d%2Jq@w^`H*jWVM%DA<1)K2q;}|^Cz2ur;Ze|%SJ6L;*Man&4 zt2d|XcTYIri|G@!rbnqICLHtR5?vBa;e$>AF6L6=f}W&Tlw&ABYR)bE)%3?~e8Wwh zBYXCXyf*`mj5Mi-C*oJl6g59D>2_MwGqs&;yq`h@ z5mt-=x>thvS8zDk#6A^9XUXDB7Qv?uGI0MP8MAi^1tDDl>s~sFO0LhMd>#;xC%o=d zr(gSt_lT>5cR7)kvNIRwb5c+3T|)xGI$9@cK|htGI)NPm9*!sH1vombiefG>edA8!@V!c8K*kr!a!J8^~&2t zFOp%vjgEGXIFY1DHEL@A$Hw03XIXwauG{-^{tml<(}^sL>>VFuxD&hqXGoMY+`LUD zy&E?b&f7megKyuodt z@qU3u=2jiFqfxxZVn8q4>3Dz24q%TOcD`CFs#7H%<&V<(x%SQLOL1|_Av&(Yz_INF z4P)&jLSt$9M^E}k@9&ar@i8@db_M*7 z`8^r^w%_OcYH-a#d#f4_Fs;RPFa5fs_n&2H52=r9@4c=X%dQL?u4&h>ENpn1%hR&* zSihL6kW68!szY3CEZsRR*V0M?MFe>&0vL4!J0owa8g~OzLwr5`RHt zN$1mcYD#C@V{o2_?-y}LPoMM%y?1q;n3*t^NXx2d6<0-w*b$DB2!t7HXqM7QLI77B zJGg6eoAoDSt1aqs-(eAM?}&UCzl}|q-WP$FZ~@vz+6+^w(^oK5@SE(vUI1AHBF>E^ z57ATh6<+OZ(4173K`W*gmmCNySd@!^v;A;0Zq-vV5OZjK0=$A0RrmO0=Ir#thwE-E zZu?V@Qk$0-l*o>_AmcXXb=zATWjNXYPkIWSs*l4?c>?z%zadI<>dO=4t*fSPnkQ#}<|M@SnKl4Y zB_LP%!aJ%QSm)FfD4d@zt8LO$)Mfi<4cA7ucWkaBu3}bGyKr&8OpCj72PA`MA}>{F zIM6NGh?>5A8)C@=KJhSv1)G z{aZ4K98OrkDY&SePQ%;Z4_syH^?<~hvs)_aCU|owQ|4{g<}1^|W{Le_WJ6JcI;a(i zkTEEd4h}3bJGj$|A$LLe;Ol*HFRULRmsCw{^!9@YG#|8nC2RH_#zxaS>?vkx1f6Ne z%v!nm?1a=mXtOSzu>~0Jc=NEK`&HeUNxc>T{oAnT{a?F(O(WT@=0!87Z?pv|68lf9 z`6fN9rs!X5QRy=8Og1e_^f<<{w}=DIkFdsBZCJ$>Gk@Oh0hz`3qyb#aexgD0Bn95rP-}|3=i~b;w5pK5A;@j zbhB7{9+e4mLE;>SJOP-*z=96%dA48Qihez2LRQit@C4~%K)M!1C)rpz#(PJy25wpo zT=Vnk17N0QLQc4j!mtYn;ksh<=;3{%ik8V+xx!xrGpShHyTZNaN~O)+pr!^`;2jTpKne=G(62d*iNZV@MvD_G9 zkxxYDnSI6C-~QG$h=mg@jt6iu!YsRY0CN~q6(F;H|527v#!NA#grjTd!clX%8>&$` zh%cKo0XLKC`V4gg+y}ooI(*Z!E^A_wgityg*`41NbqJr?YaGWEi@8VipcbnR*VP0U z^g}elv$f+4FV`><4gyYcdR)eh+34ldMY4z zC`|2VV@B^=j>W>dA8!;_!Ymiq#YvbMrRGKlZv#!;*1a~q{Nb9BAsKAxB7Rl!K7@V% zX&rFwtlhLpY+!bc71O@8MSOO=#RZU`oe{S|d*F*Q7oBn81O1nZ@T!p{ZUzxm6q`3r zWPWZ9@q_Y>x#(b4j?z)&!JFua441`rob{#0TPzaoSL493k$bll3m(s}Pv>5ZZL4st zDbo=O^cxHQO*+AddF8!(Mv>@h6$Osfafr?Rdg8o;wV(B@ zBd2jZ>gnP2<=@p}5neix-|H6m#LWLNU+fO|EmXT+kBw*!nz3g&7G7Qf`LK#s9r8Ie z_ey*C@IH4gmN0(kTLJ)PXL@^PRdV~;x`UPF9~ zD1%O8bZ%#BVWdA4s;^)~PD|3U?Ud_9)BQ>Lz?CtamcA-H>#1*qyNVeP3Foq zFD7tpSQE))ASRNAt08X=#)_y=7`;l>Up;DKWG164(_%MQv~@b}ET6DhcvU*|l+^q> zVB%d?6VXa-&yCmA1QCIw62Nu6BkjA@{)5KwM1p@>iEdz}YK+X)ODnvhIVOui%1w2{O3xa&#I-JlXJlf*RdS2n z_%W*3D7MS2JJ4*|N*RMB7PvXk(8#%L3S4#Avyz+Y1iP7%g4n#%QC>T}Vp5*_kw(5J zd&7*G7fSZukN-#2cYss9$Nwi~Wfj>YT^S{#>{*2Doskg|l9inmi82dOW(e8WI%Jla zWOIaUI!2sh9vtWRzjg2L|GU5E>A6q$KHVqZbH1PV=ly=IckngzQgm&jwY!y*Go>bs z*~*weP6-jd;L3^G%)MCteI}bC!`JBi`$IooK5{PRV}7V6xb+3A!74Y-1k|v2s$SA* zBO{T_zOl(k(3_Ymh{@~PmesT{fjmgFFtY2uq8`0_K`t_|Z^y}Csx|AQ1od*H)6a!( z&cjaA!K= z=Ml|?VRZxbCCUj8eA5Ae(YjtGV&Wts-6W{27m#=j!DHsn2ZY%jDJ z{oH`m!{9Y&6G5c}wHW6R9=^w%Bc6> zLA2!9+5nAB!z`!1fN>Mjgm%V?^+twVcV}-WC#; zFECT>&vTK3+e5Q)9P)L6Kb$@*?Cyb%?M=ktq=b>s`IUDU1Ln#7Gu`Gd^&^t z2U&(kp3pp3WPaX7<;YN^0fO5f{DFFJ&bem34HNAKC8Iz${G{-^sQ8P=J!01HezctC z6JEz+3I52m?5|yeqR2FdA#{I$Dh4kj&)vax**c)va8sOp%ynpdPx{hJ>v9v_q|>WA zEcPT_xyngo%%fvGNZlE6+07^$j#MC`?U1T#vLqU)M-*uQck;z zmj5y($9RrHy-eESZuttpB)x;hWkY`_nyNDfm|rfSw?JX!!#^P^ZG*S%3a7~m%zyi8 zzmyxKm5HyE&GFbk4T{=bEBII#^@^3=G({w{2XyQk_Bf0$SySiBUjjJ-8j%&;-CImg zQhgs5SGyM;?x>;tshj4NLzC)C%aO5BeCW_s!ILYKlkC5?{2JT_5PQ8L`U}e1DLV;M zWkwB52_WH6=P!;S@=5C8$8ia2lxCnja);@I2m1y=NsYBDV2%F z&`llFjr+=45s_V9%ij{<)jF_rH7w@jRGjV}TR|@r zbLwkc8&0L9+b(~&kR7^Ex*~jX!yQ1)4yFfN%rf<7q$dW%sZ>@sWNF^;w64l*BS>wU zac-mx>QVPy}s96KY0I1=OA8 z<1SJbC73`5b&T!XaW8fw)7SP=W;8b+J}#h8%97Q+;+d_+(rJY`TP)}sm|43%%?TLBW zC!rQEgAQ4*i|z3yzF}mQ$0Ow=ViVX4xB@s@mz&3_(vr`urI5f>LeCBxtZC=RVWUnTF6;H-2KI|$o zE}L8Z-foERcT`A)``zom6QT2@>7JZhZ&o!2Z{0-cd_cY31j3i8Ro_V_C6A}?`nQS; zeU(kdW;s2J{3uBx4sYTWUA@G1CU`mB#k4)>E_CZNM1c%2Hp@NjVq9~y_)*y?#e@U8(8S<`&9GLP23VuzQ{}3w;thl~c{5HYjf%%57vsnm^(l+lnkkRr|Q6p2ldRtRX{WK?z+N|CP4*;4NvdI-#5Qgh*Qp+5ACIOn;McDH7=+sr|#^$*UWdO zu&|}x1Xo^ZvW=gUSa^x9aV=vFy0Wc-MUspry+tV*pTK&M)HLmM^3nCU}$gdm^L|@RNkZh~+ zX|x=Xt{L46M!9fl)@g;BUMVvt$AeBih{`yjp=Q~|#qMPIou@Q=eLXl_Cy&yQwir3X@};KhvNzInn+#DK@;)MKYiT(yEGyuL z=?Rd}7wF#Dx9YQCQycbT2Rhfa2HZS6L*!GqJ!#*#fxNPaPh`yzU4+?_ox;_>8#}!j zCan5r^!vd_II$*HAM|0%+I4jj^qqj%b zUWFcYG)o9H>y)la%E{T)Pg*YHwTBV`*PsSust?7Pd!Tas^3ORROCto6GY|gp0Eg99 z-xp5>8=K2d54?D*VP!SD=?WZ2Q8hqy>q@%@!!8S9EFzW}ImZz(=~E#=n=;YoS(IK) zjwh9t-F93FM|SYr=-LMR7#RhQbSYm*<908wOM$M|+b(`rFazyHWnGSSAG1%gtjM{tG1;05|iO2>MWbYJzST;%aaAsfP6yqZ2%hz2)r{$lJoLfE& z`}BASakw|s2T5k|UGX+YM9H)!ANRd&`HxdA{tcK5pnyTKbam?E@1e@E-`e>aR%K27 zJiDH*2zVi4#F(dS4=_G&w@D6OuK5Z;C-7xnDNT_hFQI0FO5DVgBR?-9?- zK5b*#Je+$QaRU$&42ap)9RrT!oUS@Mb$+&DeYT#z7D&cq3n+pn4_(^o?QP(Gap7+==-8h5#b#kC44bOf=n` z!R4Fg1MFpdUU^a;pL?%6zz;&r1a+sYjtpoat?Pr_jXVAWN0S41SMl(%(f657!>?QL z?Xy0IB^+Byo)(>eQBBk}ZQ`>Oe+}fQ2H-`_BbOaERXz2*S?#SZ%>2uI^aZ z3z*H=BZ)^7Nmc6oZSD?}I!w=O^tBG&`>R<1yF7_il{ua@&gn)9pW%L)MRrN6S=6n5 zGCPJ#Yj6Yc;P(;IR=E=$KJDXuxpYd8EM(_NOm$L10v*^p3&AMUV<9)g8n?e&YuUJi z<2nVGs21I(tbK5B<_s|kg`&)))}^QrVCCHq8qGAc`}`J=C&vkr+-CGSQy`ukP?t?4))m>^g8hTf050(9dbq=&c`Nf{a2O4G{8Mu`j32J(Jf8YK zn5x)(e`D#44(8Qu%%AZWKGk7ox;ZjxwKenQnSWqIs(e=M;kDg@K8U_5Y^eG%_$;)I zJGoG&g(=7#Q+PDgYY!r8GT*MmK^j)T$mq$Jw0 z#LnKHcej)^<_-&5&M{>ZGw|1TcXD}=oYoxvC){q*`VM98M^k6-P!O7(4!^5d6NYAv z+UI>_e;tXrGyhWEURipviOLVyXlJZhmHkg8P;4-Y|G-~gUk^H{X~$|sG9r}R`wr!V zsZMfh)K8{bp}yp_jP#1JM+aRl9+&n=fPQ#6%jCjaK2-mW53BJL+3skI>X=wKK z`ri@=X`C8^+}1um5j_tAQH?EA{#AF}TV%T3dadtvd)K$~DW`m>D$Q|BDYrZx*z_wc zOZ3!jqdA;7!<$@6<{y6#$QU@Sx?~elDMF(7zKjmlapm&#*{3vda+=qg$5?~#e^-|} zSvEdVPRav>z}PCV9a?M%>_9lXdN*(`OioTG=L0Re3)!C5^^>tgB>-z^jJZTy$~M;w z^07F4%--vlwu5 zujpEy-6c+YR;Xa<>r!G@Ujpf=<)yr8ow>;Xf-NRnZGy%pHa7MH_U`{4fETR&tqVRG zD4!q{*Qu&l_Mdj9yZEWA_V)I&!5g9WeZjWXmRVI7g&r%CEhyhK(sH<~Vd1(gt&z0& z!O^>%&46Fi=JqCiLL1IXfB|%QQ#RWfgOx(6hFW-!8^&B6Ka%w0Mf zJ=zEcj~Q533JZTsPuq*924c#aCVE=Uo$e}PY)@Dkowpdxx|jBCRQ>FMybtF|isvh< znl{Zo8unL_-c>OmK8JKWe;n@jF7_RFm*jxLJI&+hGtk4x3IzpAEw7sOE9?d?O#3N% zH)f7P;N`8^CJ*7}*_U<17NZbk%HqF@n{s_Bsx>w-VGH#SXQFxKKcz3zH0^L|jH@ro z-|uO!SKxV-D6G5t9BuUFT(>D82%-H!I6AJdOd$A9PLZ0UbSZ%P5B>5fmi8oK?PK4= zsv#!l6T*2p&c|_czt<-6AIrck%cNvv zR+BZRgtr^3eRP6-EM$}Y){p&L|Kx2}QgWXBLRul4<9zoKtJ3<6+$kMHVQT6{b=zgcG; zC7M{vV!lrBj?vx?0|^L+NXcU=A^$?BxO7FAvV(iWUPh<>p&kd26--L;ANFQUOCdyQ z>t@2V1>>s8T>0rLBzJ3DB@$oa!l6$(ck=5HBnuUtHv=ywKMe;P23nwszWd9w!i|#% zD$}I)C-DNT`7=c4=<*R0h(<%NbFCnb8Y3br@X`4lD?!yHLGAcJFLTtb^o&HFC-v8j31)s`F3uDw#4FoRBRggZUAz$vBfivwLUx3p>s zkD-y&t|loOM{!;&K2L4w(SX!TDu$zfX9LRzsWsU}C@JG_Fn? z&=X>D*j~_T-!e6l4LUrnej0)~z=(4!rWC>+?g=Wy-2g}2Zyq2&ym18dj8fVUIcTN%0>6F5&pA#7aXM`MByFoP}D!Ekj=fd~?v@M(2iN$baDAIeh%A z6$IG<8M^q`FMl?r8XzjQ%HJ2wX+ru*bDPl79E#{Hiodk<0~qq-WSnqat6>*~{{iy1;o)>uS+8#j zw1Stl1noa@J*{R(K~{E3{37#IJ>jHEgEa(QfU4+c$Eya2p*UDG7;u%_G^QBgJ2VD? zmtGlxiEapNI9ppD$5C&cws+K_F@nPftyu7HlK*o}PQP8Dp2b=iUy($YBciqj0{7N% zYA(+eot|MiP}1;X3{4!%OM9+C3LY-%Atj1kB~@NvM{*6LX72KlPASFC&`2zN-D0#+ z;=4~Tq$M~{%r&a6GX3CDJ6B{J{b|T!4%g|?TW&7652gBti#Q+HdSOai_uF6Gd48g| z{e(Gx`~7P#yZI{FP;3^Xfb`YN)Pu#g+(ZDT0mB5zjgsnF=ltGJkhc+2jR;Z2CzHp{LMw`<;sOc|sO1J*Q90!S+HTqmX5rhx@W| zN}jF#fraIZebmdh%jG8GO#FE8_JSrKnSDF9MjA?MZgd(Il8?aR3IbasfarN)rL+epL7u?Y^O zT1l~P;e(wsBrAi)ON=j(RnE_<%LUta&{13`bP~cqtP~(`udj7G`jaV@4+Y_j&JU`M zEvnH&>m9|c-tz<@4*5;77sjfphnuTqt|h($W^s(+|9cgL(KZX|@tq7=7Tyn}p_!BJ z>`oRsCh7I>h&oUBuy*FY?3D_Q%R==NIhR~Ir7Nu+?SsswzwgI^vJSkUreEi!Dp#=F zR6*Z&`CMu=5u!S2Yir9r6z8SxzKC^U5SSupKBvW18Kq=J{~9SWrnmd@XcwT3PvtXIolAini0pajSYYQMPXwpQ?v@} z5xf2kz@o!|ePomv^vTUfcr;jX?i7viN=pBCQZgyk4(fZ*P@O+VEX8?69x-t>Q(BaC-|2lnt61;qE1(i zHDq3Ho^txY@|kOLC>sYKF3ALS%)&`eAi#3B;|q)ciok^FTJ#{ok`lv(6K;T59nN*+Y1r*vauyn$JQ9 z&GSwiGG%(@q=E98?!K6(YGPlwyCCIfIFw+TBOvm*>1I^Sc-xGuA<+@$LHaD`H?w0e zjF&~{5C4xLY6ieP{y+;!|9QxtHT9N(a4>^ zrz?%9!$US82Rm_Uk8&{HzWIwSXn-jLj#_D8oFOtd4IqbJ;h%K?ZK@&y*Z-;Yb8+fd zO2en2U@q+Ahn-<`ym zgFz&QG2rA8-cIx>#<9HP)`BGovfUl8WVCFipXkvumSyU^zpYORntJObOe5?XO|9N>>`vvp zxu`YxW2l6RLOBJ3jVSma(Z>;59ore`Yk50T5zrs$6{R4ns+={P?hXn-sxMJ{Ki#^V zUq-@C$QtTG*pK{1vl8F^%}WaSZ92&Af?_sJ*p=XrdqU5?<3zFsfAZOag#pAhrQFi5(j{5k>UuFv$@KSHF72_uE-XiwzBSg2w$1T+Su z!^bT~zev>@bb43byrK-!OBi!d4kgRQQE#p&Pfd?Tghzzbe^g+;tPHUO3i!k8s;a8< z=r<4(TD~W6z+e=t4Ym(2x$sHHl-M2cf=6b*FD!IlUdr{a-4shB(B5mDg4tlBm#%?# z&&2Y1HZ@?CkQ$HRstBz{0LB;nb&xVwl=hjv zS1Fl&2*SCu>v4&gkx^En%_s9g1VgT<Ghg_JXpFqH`pz| z%^o@p@c+~l2c(rGD!=qY;hQ=_qz(Fi&XK#`REX&oQh4AS$U_dW`kPP5yi%t2A zQ1Jd4&@JY$$Ng`4rVSRIU#L-pEVSc`;j2~Zk4Bk4TLgY|$(@>3x+kr9j#uqmv!;1~ zlwmr3pfEbExk^=!h^RW`Zz>ZT(ml+^_X>dlvr2P8(=s62ZTO0INL5C$1~TrDh@x<` zuLA}Y91eFl(Trz>E27<=&Kq(J0SAj!;g8II!FYK}FZi0~Z(`#lE9&VNL=r!GA2-S7 zS6}Vjk2*-m04tSEZ?aWT*Zpgs2>w+-!N!v77=-MM}$@kq?P0^K_XB^oJ+>FOOuh2Hq*$Nsd++?15)-oMys^W2$L+I zfZ8morDT-!_O9{EhB52FWKclv5pZa~jk(hkYe^u*20bdw%k?##4g6?1pyNlaZr3)v z*xcL(gdZ>3OycF9wYcf;vNvkIfdcTvOa_@w$>lq0nwLPXlM&GAd5u{p`p^B@NwIahXz&RnmsxgLt~X@1ASs+}-i~=OPT z)0B@QpqW&BjPq6_l(UtvSYf=yf|O(YHag#J!)wv7V+DXu(5MgZcvCh;tk9r|)tw?M zW-zm@CZ`iDZT$*JtBt}MZ|ouI;!`6=58kMlK0m7eOLJY}(7SiQi@|A45-*C`dIa$@RlDSHi>DqDg+<$b}v?-XYK@^Rx!U-Ao%>Fnu65t##W{n2-SO9z4n8%v^tz* zSmXJV+$HULky|5XukA$AEL_DKd^gUO%vE$)?=Pa-{s>k9nt>Z&HtiVx0l7oCXruLG z|7H2qyevnS;%cAAX~#N6o-pA%>22$-VuG#3g^v#ji$k)8?}Z6MwC|ng0};-2#2B}; zKV&$GHz44EgN*~Cyal!1G-n27=?RIh-(^(7q)Hnv9S!eIJ`G+7KHBAU0Nq*~y7{e!FkYx>Z*D41>G*RvlIuZj`IjmFS)N5ZC%-)MaHoUb%`}NKS39fvYV+ad z8Av=A)v#TAiJU*DSz@y%_YMf>;!IgRU(PrX30xVPR(BL7k^UT7lL4ih;E)STtL7T# zAsrWqU~=xLi|y;eG{nZm`5kQYBhCIyQSu8#WleRvR<|1BQ1DpFp;8XId?zn2O!g9lvP_1V%oQ}U?YKBt5n zea)B4*L_Xf0XsA)-xjnas&=#BN8C@dDt!lMri+SYvgzv%^}Fg4)ktuu_B^SMJj05+ zhxa)1nM-i#@XwT8!>x9F`Ai35+2PF3iyq=At;;>AXJT01(TIgjd(kPV>(YxX#C9?W zS>E^4)=NrM9`h+~UVB>>)MwVc|5(jpR1(!OPN$gW@7=3+=X@Ne!UOr#1eB>&(WVP1 zTQm5FKPir-HX|SA^fx>7yYJh*C8_PyIVpp(Q4MT9we6)AA5FA}>L(V0ga1My6X7hS zpul-_*X-X5JpM}hbn>%dfu0|elX$*_Tp`P*1ysI{T0&wmO)Xrk@k)sodp0Gd9#MYr zKN&qVJJr7YiwUvfPW0gGm$fG>)6thu5L#g;@;k^2VgVX?v?`g%R{P3^fUG*cyI~T5 z`Yzk&x4A%W6|{dTs(sE!sW0ov2foO=qqz+_qwNphE$+wXIrrl|1Enn+`ay&-=4z@{ zNnc_`lQHrpIQ+yEsq_SJLC{=_9PWnD3MM%}F#QJI2=ve!O=Sbqr4OI)3q6zmwD>&s z1bFL8T8?^x6Bm<>IhxQ4qySvl(lls3{ZBHT`x^r2HQjnGR;*$R)!MC^aIwptkI|$6 z-F|~s<0cqx%1=n23c%PNlLc?NUxv6U3=}7-IL2(nA{;S+M>YBskx!?0+&Ao+-ws6F zNU}?``|`LNGN|bkftQNk#ui?eC)}^aX4IAL@1ruM z+ss8$;p7Lnw~sg(%#i?Bi29;CmpAF(4vSUhS^tt#er>RzL>9bnB50h+XS1Ug5D2!( z)Sd^$rQ{-bjv`msZt-Q73+L~@U`oLCiJU(AI^Vpp*GZ^G;+)9dXFeQOnLS#USKkZt z^!y%`EY!J-olQoj!1fNSqXT1}1l*Cwf84}voG*hwRnHV}d1pZ?jzbQ<9)E=wU<~W( zB1d%tU~XNt{8v8{!ORJ^uRSnTVCEp620~6++aEUrJX0w;18J5M9V$8#+KEU)IBo>K zvP`=4N96#AQT}hd?CM|Rh(*{Xbu456qObuA!jR3qs7?^AuM}COMRi|@C>xc@Mn79m zj<4$-5HH6~Few#^*^z0EvNEhvZ6WL)P#R@eQ52MsjFkBVE4_DQ0cpI`4(|Z%Q-x!m z(KWL|Kb5fvDxg*fJ^FN}VP@`ncI+deMGb$%tpd4K~VVXqHj@#`lsb!Kx z0i8Jy9l+uCkdBE{0nhp4yu-CMXehxAD@vsf5ir>of7w~9qGi7 zdKHJP_^Kb-)1e$TS!XF|AOr|d5-Hl<^Og9e+py{741H-kqaWIoxh)T!`m>CyA;993c;G(OJ{kP^sC5+o*P$`xUdL0{09z)PT61qBJNpOUvtCKEXE^FO zVcN(2J^F9IjAwc`O?U6Mbi~hjt{Y9Oa(zBWO?&&tF5iHd;)eNJd!^IjS_ z+MJ#VC?w7;81dzjWcqTp)bv_sztF#u!q@VEdF{TsD2oC8X}=6o1>AYrpI=*);QfP% zkYkv)zrL(B6Db9K=5gu0mfkdlUkhOvE>Mvh<-@v+s#)-DbBYCx&eK>0pxP|X(F=P! zG-2cXLR+BcjY#kH7bFY4Ko;u8$alQH5iSEz<~UF21l~UWukZ__UInmXcYu7ec(Fy< zohtx{VThg4gxG8d`PZ}zczg4ugb32Dy!Kv@h<&4FPL+xkc~-i|jGS7^D?2I26q3mZ z4@vaPdfO`Gpg2{Y*j@+B=M)j$Y)Ayx+qK?mJ{2XWC*|h%N~qS+l65|7u4Gg*_I()} zz|;Z7ZJKhN<^uNQvM z$JB@DV47$Vfg}y^H>XY0G6WtIGMw`F?d?&m>`(uE6v19#8>Lq+zEhO-;^Lpr<^mb^ zye%O22T%3_cj)Ma#KUu2auJB&T0bl=8-~g^Y}7)p?|J+7?%U z5d{k0|9f{z4{>R2o&o!rnj!|_Tt74Xnupvk1Kx`#?fCSDo6MWbCoxc?4_3?IPUO|L zLDWFF!SNEYz+nWoNVr2dv#(tJ^%|Nkn83W+8j%*)Y3MaX#i#|E_?vo<+uL(y)bTQD z-Tmu`*!H>5k%wZZrf2P5bsm90FvWG;S34MA&B}Bfe%TVZjF~|DDqIB{!7v4u zH9|=K=c-NP6sA*w@N)4nxtlZQ(r36Wq4*x$!!e$^N&EkQg;}xG31}RP%fMrX$=<@v zwnnhY2kZ?{I|R9Zfh()Pg%VrY;aSi~Lwr7Ap<+4U5(a5zo4z_eeRaw&`!eNc&%4ym z{;a<;Sp~UtHXj6y2qd2=7PG+Nh>^b2#I}?m3Q0^oNA`w*e-;P~u6*4*&geL3G`zzs ze&cP2RMM)L)q;F`4$N@%!Saz8ITW6JhtLkS zl&~)aWnfvm7Ke*zcWur=v^~e%HJTxGv@EqgpVk_J&0OEc#-!k@eU8fEt4nS*JN=&r zJ~eBQm6|sTb*e%jg0zfergAxP?9uK3^+y2>keEnGNo6^va)o*K(uCye)3%>=lo%eM zGY9HmEv@w}gZ&ho}at&|`(RorSnY%is^^NC{2$!40;#vM4Zv-EZ_ z6&60Iw|Sn$DqBaB zAJCO_)nO*2bet&7RqTcjjTtw8Q|T`9y3P+Ku}Vx?~# zu1}!%B7*lwQxFgmxB-+$(?M$4kMZ$?51k{^$#tclYHP{V<0W~79s}kxC{6h_+O|UA zOq_Drt_SHFxl;e#Q8DP)BI|f$t(}?3-aTNxJ8}2RGt1}~Rzu;&fGg0jSo!`e`{~rg zI`!E+s~K5K92bn)NR-Uz-pbU@Kjw~VYJ7wkZv6ju`S>@p26UIyHqqk0)C(T<$dpSmU=R_|?1D;+<$2=BeY|Vyck6krQ4Hr?Er@r09dc z`+ZWPnR2&<{~llhI#091wko#YY|?@0O6kEz^f{;2CY-gRE5($5PxsV1hiS^|2mJFJ zwN9k2rRMoMO2Lz$lyYPN^|Dr!{y{|+I*`d^g)L9)Eh7nk!R+Ir^-O%D#*pxEMX>#i zV05F$65qvGTR47R?7M;0m*gK!K1U+thdzE%G(!7YUHxb_+w_?4#?js^gVvlRmxck* zYT=!U6j4g}?Ed}zeHi)vDQG_#O2mS3HNjCL;R=VdG?@o(|9&#FZ}@Uy%ga6Kbeobz zRAw+og-Bq5!4F*{BkcL)9`t(yrq`%_RS$J+=l0>=+k~M6ZRe96Rjr@ZQ34b%Y_!-^ z`Ml)ZVq~0Oijbf~#oJAyv;^+Jx;w}x8ww+FXN&lI;%(B_z7+f~Qo(%qmuT}v2Z#;Z_2z1wlkcckjDBSCnW9!NSHTIK45r)a@RT`d(~R{GJhivm(txuu_j zm1Hi0Gw4D$bQH+9TmsY~<(FdTXkD`ZM$R<;rFAY+mXpMWy5!zsIbB3o>!`7j@?89Bs=B+y?*{q;}OaxRsWh=XhlU z_Fkp0ttB5!;ECgK-*2AUwYocgl$CYBdF40S711|+uBd<7(cudrrk#;fCAb2bF}X8M z*gQx1uk!!*dPI|59CfZUaHP!OUh(v9UD zTpmV?OnR;BwFXO+1@pX7d@xx!e1mB=b|D{jIp(ZxKJ*Th-!Kle&nE4kV+?~c8Cl06z0OTK_ODF=-oD3a9=9xJ-a-1_r}x*(N$j5~)E(6kT4myp z6zopFzt61F24TNZo+!!Tx{Zzy&2z*!L_FB*ZXBq|8cp2}+MEgutWFPt;idINzhtDJ z@7}B9BsH+O!#$>Nw?)33z5>jqsFqqbnbjzF?^&q`lIU`#RR^sJzj3STt7PQW5iYb3 zGpwk48lJExaA%b|sT=6$v3}3^(#r<^!mXKoj{fx0`)tFP3W***FPz?N+MB_5L^uyn zEgP;)lFnGWt8Xk}UM)YO@I1pWE${*OQ@GO@85w<={y9U0P1q+^QX+gK0Aem$X%qrh zl+OM0YK0kZ)&VVM3q3qU%U3@&o^+T9qKNV|O$xxR`2aQxLTP$E`jlR9{g8i=csiK; z>}dQLt{O+IjgOF@J^TGjnV`jlo#|tD_nQ`@t@qkw`+!LTMCJXj+e68P*Ikr23rYKY zJ$mG}n$p-ZF_1z^eH9I>e2;}`kHqUM0~=`Y!hLy;q4P4`wg)2ZGOuo$lA+t zy!Hv=$US(Ei(ftZ10+^|D0NEnFQ0XZ2FLp2y>_ns>BS{HS+(A+;7DCmGV4&ED4@Iy zZZn*c<42|Ka_%)j14SOn+s4Bh2>zN3GwLzUR zjC7}KL?yU31I)>Eon3!lc>LzJQ=)NV=cOJUsQR^UN? zwiN6bE4=I&bmpJI1e-D{)?B7_=Xb;n7Td2CkNPui>A_Z)1;3l|+?+czxQ^|yeP+f3yJef&GEL=y0BD*v}!#_k7iSa>~EBQj(DlcS>&LV?j#^+qWxe z28njhkppnv)L(-#y2k)7Sh6PnYOMy(1<8rPhV)rGJV*iyBYdcT$b@bl0EXB~0T&w4Z1x-v0W zLPbq(@Mz1{JnE6NGXV8Z&QQ{l49BYc1#4ryET+$(>;J7q|J>{Wk1TK7ls);|72)88 zDj?891}WfQ(SsDWl(4!7cEvI>Aq*mz+3cC1*BrR5O2P zOt$&QMP9sp?lzs_xrksVEw+eX2M(ea`#j>gIV@d`@9u;20VM^Ad!Saie~ny8E4|ak z%^+fWqxM~^FI|;{`*-`yK*;&ZncZ@Qym~xu45wef$&I7<_syew<(-6*cGvwH^aSQU3a=8bi5j1{xHyHW*I3-TAf7n9iLg;qS%Q9hNaATV@|LMeQ+?FrRCb!C$r2fBr{n=w#?`#7FkW|9qY9>&ydhZq z;A;}LG$NwTZ&=#@m-5fHkNP?4&k^YzDvoBhm|mic{Q$x@r`aIXz0sT_wya+)9T~gL zuC18vYQ?M5mbP>D96ax}he??OOzA<|QP0NCP8GLvKsOx-Vt@?jX427jkLS6tW^;Ic zoeWuPfB(BAmK6UUHI7{R%wU3)Y0?I0!J$0AnzkIu0J~P40^#fQVb8RA(8ik+0kRy| zSz_epvaD=M>?-;Ff&#wpK2l-pG&Fi%$&h;?))vEoV((xn_L>ydWK5Yw&T*Z3Z%<*% z)&sG(L;JP1&~8_n63ag-n?QrRqS}l~Yg{r`K4eb(Ad>GJrgD^rutE=CkEoluVxTreR zBOF<4HtBrAa#YMK5YJW`RK~&1zR@Ew4cs)kz46Z+Jev%#z=EGVrPIG-aTre9DzT(+ zC8grPY;O{A6^7T=d!6zQzlkvzhTCG2<*qV^8-cLAB40tlPCPvxCFNy7^N{XdzwI_L zk(PwRAg-J6WC&rHPqp5b^M?A%!+2U{7AGoa)|NKmg=;72?I6Nka111xS`a`BpiA)f zRxoSIVmuII4?l6g>$zQ1182;5XMcdi6*zJ+XgW@ zhr+Z5M`{Up9p<%WXZJYSC%^UHgx2s46nzS%_}T163uA60EV3;#mPCcW=j6Oo4|{Tb ze3F4A5)>3%U^M>IOuK+VzRp0t|8|@FQ{Cy|q(WfpBca?@lrgOBh+2BmH0Xs?L zMU@;ICO%1)7%*W=#_Fk4ojHY#`6}%>F(_#KC_cPMPYyc|$KFi-)c- z`#rPHy=%ElF}`~kF4efWk@ORtGfe}RfT7!WvW z4mOZ=)!!_eeUzvVcSpzk2Cu<+@_!2XKmTmWpUWLjXyU?wfRt;YY2|M0{M*Vck3WN3 zf6=!5rerLMQ8-rkUD*3FJ_^qd5q)00Ahli{iA0DoISC_eB$C9%-WFWCoBt>V0YY(} zZjUN`UqQR&NZR)u?wV}S$*B*Cwl4JJ0EWBB8KdVHt7TxAaxFu&1iE+WB%@y|$W$x}(GIAskm`-^#{1Fw8zywPihg-g%WhPsGH&RnDReoE(qp zwxFX&P{nM@_C;Xok50JtX1^hk-HJM+$@rFr`xLr{SoB%xE#~KDmk-O>2<4reQrj<| zTuH8Z7`l7QD6+m`saFc}%v@b-{F4=}VwwXwK^=?Q-WC;*53rex`E%T`oC6vELc7h} zmicmij(g4}b^uMS0xR_#Q}6m*A@Bf}RN^;!=O_Yo$61t;PP=+ehyz=6?U;?0rECy= z;BZPpOUVMHCC?mN=gT9zqSD+&9^6-@V=u& z!2A_HX`f@e@j-3qJ^f4A(rz}SF9Bvl612kM3C;FgZ*Bo@&!}^gK{13q7Vl|NT&tGG&36w3YNI~+m!*W(F;C|;d9T>6k^E&7Qo71YX5_T6C?YER20uGXzxs8S^S@QNCJ^y%4P8&sdWi^U>qFje@f2VE zxi%0X$D>0QP!`r?7I9-r3bb?pe-zhn`zeYrpY1%m*Z*)gw-d53-r34oxx2f60TtEU z9M}!K>|VE0-)ySBnF)x8C7C~NHu-ovxVE1!=G6cdwq~4fTSEHO#1N}v^|K}PU)jxZ zy16Zc-Z?_<^F-qS35!Xo*{$`xcz^VtwlhvgkaLwl3=rmAw@@=>)J1H+fzY2Z2A_TO zt|FK;_usPq(+4V&J6olRK!!)%N@RZw`+N`aHjrh1} zMwTA*ylMV8>)PZIBB4iooryj6#pVlPtp0%L)e^^zFmd1M1@zGN7u=-W;~n{uJ4Lf> zuGG!Ho5`uEcgIqCZV!2y%q+ho^u1j=^4$+p-$~~oWYP_ncewihb`@yy4J?_+=fLH* zuTA5HUITCf-#}on{HYlL+iGe$2?PQ!KI8mxUjS`Yk{#TLAVdT)xB+ME|6GXIg+?+? zKy3pa0J4|4)vn1-t^V=92?{cBdO6H>yCJg@FZONq4~mnZ*jIaaJ_}B zRqhw&D6g!pHECWSh5ibKsZ~T$>cp-ux@GPb*4;pZPWkLm7wk%RSV__P^ob+h_@>u9 zja-#Et6_mA>cD%(M|RhTx|&?u)u_=tB)f{@uLpFPPc*I9(0rsmy&|c-zS~P~zJVv7 zJ%nUQi{q$IXs*^D8oVD3jp1 z_9=PPjNAoXSok+GT%~wUKO`Fz&G8LwxrgPBS{fF{h9ireHlG0ZeePzadP_}|PhBM^ zbn)?*$K|(%#1h2zUUwSbWXx&+oVE(dG&Cp*3oop+}77pH*nKOK}-z$2ve)n@_MRJ`g%106Pj&1oV0q2Q}aq#n9!J`+a=Q38>Z;HS||R-?}~K^Gidj^=!wHQx;eIVU#sStP%+VKdD2w1>QVzw3-z9#XN-utukxA{mw+}vSjD1=Yb%uNbVi zosjSmBM6W_H($^!7g?G4i_VzZC#>B%&E}rd^T}SWVtglc)m_NPc`=oY(Eg{C9toLq zJK%#fu2z{=DJm8rkd|YP&a@ZMxh*?{yZALlH-${xeNydfv*o9UqDZ2AxuYJKD)d*S z{Ea&{o-&6;ErT2K>^VS(Yf>f(iucY-X=P@dq|(DmJh6Z?FB10i%oO9C4SA6CdV0VD zYLVy_Cg{^r-WrCdwbXt4&a~<2^_!IQ_nVM6_Z;5c(GDdgwD4XT3K%|dKycZrN%GrQ zul)RE+={1RUku(~0FJ>r4D6DAdhrXO~S@n4060sktqQur+-5XYX^EFC3 z?LJ$N4Cm|a8Q+8Ti~g@O$`(#a@hJE3%HFv;hKVW>Ntkx$T zcnZ+fw|@Q{deGMI$`jiT`cl)itv|<}^%0R{|NB<|HejqNhh-2@sqh!C|iIE zqBoY@#?x{gwP#qw;hK=gpoi)g`d&>Zx~NNJ3`&|%DMpB> zprw}9mW{tFH%xlxjuZV1pH}Dml39q2YiqozqTOfj1vX`-CnI3hs^a%MHKGhe z12Q2l!*BES!B*_SXIR?umH7XK!8}EaIX$=AmVJJsqit9$b~(8{r{Yny>FWAShJ{^t zz}=dlFu89(jd*;g4XC-zH?GNO56@i|xfvuLNFRSBO?5D{lhI=G#aV6E)@!=AxM()6 z|KzeaibF8eI5x3^s>@L82~)WQk8|KXI+p7{_?x_SUQfdyz{Fr_%ME1{KzHU5A7%Qm zsO(w&rpg}0pP5mr6)K$BLk8h>es;)PS}7Mkxm;s)3rS4NeV2;V2K8iHa`&E}jl8(i zm9z|x7O$U1N{ z^6tq`rl}QXb^%dPoT{=u@sm&3A+|%KM_!&5;8gwM@6&DO{puC}=`h8%yz?0rFQph< zhO^VG?+vhD^+288`)djX)5uKyPrqT#$lUcgF>bm(E?`n_G&-#qD{Sez_yzT58fVLPhQ2umZ zSX)x4S5Cy-lQm|XHa7ctL4iPL#D@2?+PH$+0DHCMgZnung&_|80s?Fcq~+Ve?L3N1 zv1Z2_x!)!<6FhfcU(c9Zb_$V)oRX9<)UN-ya43@H`b3HtWDVk_QoDXRxeNWScotNk zXaGHP96x|Tm6w+9{+VT}1|Ax@E;{)_!L3a!R%cp>fQ zKj3aPB>fX8mZsh_P_pzzk+UgxbC;S0BETH7l)jzExPyw|k#nb_roqe>U@C4IhTFm-;X_3Q2wxs|koTVu1(ba6Hys6-Dy}Ob zG7W^jcjHc=*<82|^Zmri&4(3u1G9)@jE{;bg>|Mm^VZBrw6&fmj;Z0Nai4tWrKemu zIqW!;mSCEsEED>}7jdx~mDC9;Uloa;Jy+4i7-^^M_o{nu_!t?S1Agi<%x0MTa&Im6 zz8tvdamt@^v^i#a+%n^<9U{$#un;?y3>GyjD=VXm_kWKn77Ao)7!ny-P_PArPn#^$ z{~jQK&vu9h;6RmU@5JlxLx4W(yU}kTu3(GKEf9i7dJ&5!t%bM{{9`7ci!9Rcn{)Th z)>_`TLN_I6Dy?+WjK08g)EP8?Hvjuu;pIu$3lZn;o^c$O=+Q-fzB?q+@`=x|-Z60Z z!>roWgZpp{0TiALNdjC_GfwQ{Va)ImsCh=&EOl?Mxd|Q3QBbSj(AOnfDnehskUGW} zr62Nh7&f`YiG7A}pV5%)9n82|ORbL?zdc8cQFza61GX&8SBZ@u0X8lqG1JO@*OPQo z233CHxMS$;;e{!^az{>9X#?NgkR5fTM$XsFYt^xlm;aqV{%mE-4Rs&38LXDOnwky+ z-}+OMl@Y7@8>6;Cqh(N{?PbLh(JNyt?O&N+{^q@l`!+C=PS#-btB9HRXotTDq zh4+6r;nMnzb0*nMSigI9U+6Tn*Un*WGaeESBKg^rjb+|}6B#{GCdL|A{1$`jD=fUG z{pWZ&x+90@w8w5OyA$VM3D6P0R%gEcfbEsnj{oLKfY{xE0TyE6z@7sM-X-&&KfO+# zyvUl#YTTauvDHwG)%LxCRzWG(_lpj>y#d(SV|&<{!YI|fOc#tx@ShRQtpRPFQCL|HR+F8z?kdr#}9EPqy$s$Hy)2udEuiw4^CPy?iC+$yBAFQumgq01F#6r?O)n*?e_|EK!C3oeGUgncstl$|_ z8!k618LD{bq2S*cZaH9%dwVxUAmYW;bAgx_eXKNwOz2}Rr+m&w0ffmq|5~~+-8Ce| z#>Yp#Jg5&We(X{=cf=KHjx}88K_qd+n&7p~+c$o>2gG{!-%{Q!z3vv|-d8?4wI8v6 zZKZT2sryQ{?1gVB{4p(ix;6KP4dd@#Bdg5bh{(uthE?zA%6xj#sYdUxb~2KK=YCO-|F-uXCB*bzR=8j6{_PO2gCi`tXI``*1AsKS8u4~HUlLrjfMrT_utfiU zOEO}}nvZM&&@=Iz{O8{r?nDD5NqNDE8Ok_ps!kIgWSg`$Akf2_WXbM5S3k3`kTy+L zMAwimdotA>8=I1ife9JViz8ARZ=I*IT(wA9iX#Vsgh~Y^8owf4nVTQ7WI4Zcx(vjJ z`O7n+*}A<_^5)isIJnh$33c_n)K?p{@gpSX_wvK?U?K*9sWCDoZ(?%tL6wqSCg<+k z6sOGT^hbH(LRvc-rPvga&KhgS@B!XXl2ue|@@B*-E>HXQ(IfLp3K=&4WajG@hzEt^ zKaR!UchfdYu=;}k93Hl5&2)U$7KO>o>Q)_J#5}di6dK(qqc7n0__%UTT8-9N- z9v+AsgOUT--1g8Kip`(cHJ+1m4vyD!Zlb!+U!Pqf0ki4e@ZR;JZ_-IIlY4 zkK&`*%QqRj$DnkWlwr6K@aXwIL7=X|yL8F*5sy%jGBF0ARb5s<0|0|}VI?L7@-r5X z{^92!YJWeb@wFahNCudgq5R+3lJo_-orhc9p4NX{0FR_Rd$0inHI$jpKDwE}y!nxA z5f!3zSZo;Q!sQBwLL%|OhMXP z6RJUQ_33Ob?VJk?JLbPTm#?MXrkJgqc7yCM`T1LCQ__A%M)#Gp zW1@B_)6bqn#SUiGPT|mTiO?^ALeh8NS2^$E#lQ+2asGcyq)Jc$<|?RfgkoX>k@5;k z-ma`b=xO#pm9E*k*W%SbY2LabZeO@bi3k|mcbhczP@D>dzzwWBv6F#=Bk-er^H~j_ zJ;P%E?rDq~9bVo@~AuV(zH0lqhd zc<}8=!WWIK4(6yr_5~EzylPIO(5%iF%M2IR_%)Xz54GV&F#{R__gF&_aF0x|a3
jZZj^v>3TepW20apRYO#Ox*SgAKoIDN*=HA%{j9 zuT85#T4?A?u;W&3R1oi#JNss5bi9+osU}A;DP}p(2{IJlA$*C)o9EDjC!rpyJbMEE z9@^`Ui#0`(Z7*$%PW{Xy)OC3&&h*R#T(D<}DLv<3OEmFcYej*T6s9oems#PIUyg}j z>sx`(MQOII>QG5NFP&Z&7$~mf*k9mv?}iIqs`eFnEk5+jMHw{U(`Ao8bdwT2YLe#ci{JFEeY%$WwcG zM8sJ#FC8pne0)eb^Ird!s6V}LLhVVRo#O{X`U#?T5hGn)tRWJR90kBoTAv)JxSLC3 z@w8ZDj`Amfv}-;pcXYof%+L3)X6cTR9(I&2#0#o07o8hDGM4%Nyfn32c(iAqpfTBY zu#e9)ARnI*gxlCM)3Fii-uG?W-A*fbf8$lW#ooLD*#ZHLMic3;;}&;G�`wWV%E3 zt6D?T6xVPVZ<&~wG!e#-7IHcytw$D&<>VLRv!cE^e@W zyyt(_PNCgp*E}oNKq)PQ`W`2?XF!28cNz$Ivp34>>$`xyPv&uesV91P?TblyKy=`)uv@?=2VGu$Bfn#71!6x zXanz(?*(h$T+}}g!(wWvF`F+#)&KIKYZQLAuNJzWPwQ6TY+*EF%V^>G{qJB7Uq=7- zXDZ2r7r$K~Ve&EGsSCxCN66&?ZLapH_9+z)fq%x>+ z;#=0-F3?Y;&1%<`zE)b)ud%j1AAIbt9i0`=VLEM$&%7*%6gaB%E5+)L6>p$08^wL3 z=uIRHHl1rotEV4~pT*{7A;R>7yst~$8vcmTzKqDgwc__K#m}Yn<*G_q`2a?oBgw?X z8yx)4Q-JA};IYNqfV>ek;>6W{tMcRL$Y9tN=Tj=}14yU#Pb}fc#*-%TcUiquPPDhw zmu}XOIGg<>+a}+)di2yeSJdcNff&E3XDl3y{6JeGCU#?uEB4oe544oJ=QyPk!=IgT z+jkXmup_Q(m(wfBd-o5zL|$)irt*V&P_C#f94sfWrFX)kHPO@_dy7<^}|F zpT~vP2?(@VmnvM0uvV}fqBg(GykQf&nZjaCKjt&Ze_`(FML-o?LS6S7b!1Fm`F{ZX zeCQ)XN{ZD*nXn}H0AtXDlp|l^I|o8N_%*{MRk$bLH_0$oQ2FKQo|>;1SdC6*4z9J3 zA0dc1j#Z~-LXYx+LTE_MF^&~A!>v7{GMW2B zc)BHK)o<+T?0hxlf^5K^VZvQAq%2jBlFOEeomjj<)3)#SpjDaKR{D%rZ@z%~FE0Dh zmqOb5KYt9;zp_F29UCRdQ2*$zMrQerRHWksw|KmE`QJ2l)G3uL_6y}nfo)os=ok}I zy;rPTel!@Py%)Gqd$Ml6+259XDWY^*NSq3{zq2iz+pBx+sm;Vye2FsJO%}@;gocTW zJ`Xp8yg4&=nVw;>r|i1mv$fZGQi!&%2)4Y(R-;#{x!-P%wxDe8+XWEhcX^n7)-Oj7 z35*nTLkGkXPM5GO*{8gLw6dpi=WkC=?C!Ke8ZOxodO%#R_xIGk)oF9-@8zu(>pCLX z$AO+rX@l=yjzKf$TnhnIoItt&Wya82B^`!u*Rl?S(Mh!7J5v|ezF|JG;k~AB9HkTF z*7Oheb;(+J`8W1MQkEg?Q;*)7CUP$PaF4cUQnTC5zLvvud`ea$U(iWGBWqbRSn$bi z)8QfkxYraEICs~7{oq@%h(>*7$GpHT1*2$r)+&4Lz+((i7nyAd|Ah)Y&}&RhP3vYq zce`p#N#@KwwbNk|U_+dBjFej3u;$z+p55D6Q1({5j``6Wz6x7HO||rAUHln);@G`` z{$r6`12I|1Hx}Nw>n-wN-S^%=ILa-m?H(AI>*-C}xmZ+ZDtUoZ=`<1XT>y7`*DP|5}Um z;q&GP<9J_jQR?LINo?4n?r3iHa)NA>H+bLQe7C|u}T>+Np% z@O-?!-3YXlhJ6jLVfeI`D>9zd=n4q?CXUN>y&xc@Z`z*;9n$WbeBV;*ba?#PL~fED z8fZ-e%_wVa!;$AKaMp7(>r3INBv?*bQQRjC9HMDv?i!f_INg8o`MzIhz=CCG4kl)a ze|K}Ntg`kpVrOEN1ktph0Reo&@Zs-KYeJm&e-pjMS(v0@=^-24h$VTj_#@F*jK~Irc#x7m{sD0IM(=(0Y(sHWv8%b}~;A(tleMYLnQ zK1%V%-3mJ5kEu$1-m<^=x+7CsT1}iTcYNyJfC}bNn~rCa0#r4OGQ98)o4uW zCjHBKZFwp;UDl(-=}+z1?|bUMvxLrw*Vd>opAu=|a$cW(uXk^yJ)7o=!` zRd)f_sjp;_C)f3m)EyyR)~^U{yHa5$f1V7yVYHrsaB$h~4w`$|0iq1@s57=*xpV&RX|{5N))Bge00&j; z1Ch{i?_AtXqqU*JSw+WTV0vsF4Enq}uUUlXS{f-VV^C@j6^y%jAyCBqXkme%s#D6@ z`aD{n7Me+)Wl8U*BQo)41)JGS3Uaj~5)wXBojCsdYABO5-jgsrSy1qIb*fKP4DIzj zng?tXP7ZP@24Mj^gWCighEQ3XwL9k|0<-UTrel9#0)rk<{s5*d+LNJ7wrPeI%~Y@T z?_F*Ara7BG#%0nt@jTp6OhmETdY?fE8!|D@?Lpdfk)5xZoSxHqy}LyPL>pE|LEV~6 zZwdC7>ZiR=T%Gl8eDBM$^(1UQ?OcxmlxQ$lD#ABREK(X5hYZr|MMBA6VL+1>MZ_Y9)V`RSA962}8fn>ht@tE6U1QOJ{a;gs2>p=UL{wM8HRhQ!3s zzP@|i;@w7KCk^r5jsWxnN%RAza)60`lnpCS103IsuFq?FU~7u|^7&glKjUfoyPHI& z7n7`t47~^0BpoU{G^`9WGO>_7Pw>C4r)P*f%@|(n_exFC0Bq|Gotd~dO+xmtTf{MW z;1kQG#}%(GTBCYaoMj(^Q_HB+=YN~^pQqJK^DDYf)Ed%P%ZwfAEAHce*>SalBUPde zub-!Wzf{?F+S(e#bbPw9W63(*vMWJ<`XQyp;PcFHFL&H4YO{RtG{!rw;1kd5FQW}A z^BjTs^iGuDYeZEL%DeV+P%EjL?5Q|k*+1@_PT;#WMscq;g}O1`HY zmWZG==~=JcDwKZ)Q{$IY$MVVqf!4n5+vF>4tz>bh9}K%K(Hj|t?2PP$=+lfe^_O?^ ztj&t_;}=KI=CbOtU;2DE`_8NLM`0@Ap9{3)$-*3Ses@lR4pxY%l~WeWV0jHTa798K zeUGKE7SD_Y*Dq@?#~!{v&X^uBQdYI+aja230ltr)USp&s`DO|J&P!n}Rs^a)B;^5Z zW-3@sQu3<5B_99NXhLHX&d{1k0`UU$rH>@okBhOaTOdY47GzF?W_fZL)i4d(q;20NRA4#ZZYtIO z{H^2rgyW#oVPFp2`}9EBN4a8OuK|vLlc?_T5-0B9>$;y{V=_vtPjdV{+$_5Q0Rvbe zzMR5B2D$O;QPtLOZMGwB4hD^oD*RY^`9uL11kC?nkszrth=d#mNQ>pag(n~fO zg1e~Kt2NREi{-pL&b6_{-~D9Y;jHke9HWz#ci-lphm&f3-G{;5U6-{~xLmqzy}=PF zVm!ymL6D&u(^EGa*iVzcuA2yisgsd5yia8E=6a@mmD-KfxZ3y5bjogWq&A&__;Nh4 zN#*s7NRt03c1Vfr9*TJJT(!#%ae*_cSNF!MdUFekce!i8;xaouw3z7!L6Q)1bUL6`N@-!uqW!Vu}?z5q1O_xe{L)3v5ZMqyb}lk2#{4;*J1 zrcx&{dh6->=?vwqw5gt0myQah)tUh1deQm&SqE3n>;|Yl=iU^K^s{rBt2JAOad|Bx zU@5l8aracaB-jr81ZlZQr@6_%Z=ZqY(Q}YRj@aw1<@>kj5z;Gf|9oFzB5KpWPg8;+ zq_=CXt{j{jGS)ImfS(7J^1-KJ`Vm+0Xm`g`{`nWq8&V5&wXHds?KZ?8cXtG?!j67< zMPjLlWLsrii^PIoufg|=9HtA-)-z^3=f)-q>Uorw2d=r?lH-bFq(yQDy-VtgK17q_!|{#E3$RRux_ zVToGJ<5iZ(F$faqoTgirk)%LtPA0F|eezUj_z>h2eO~+tw3BxQ1sG`{jkX^T3JcjI zZ)aRlI$P;GDLSuuXk%6N-Nta^&$DSEnWulgD`hXWeLv*Fz6A?xFMD4e>_>aq5W-0*DT*1C>Vq)Stf$*mgE<&TB4{zCj74cuEMNXg#2D`63DjTd& zYD8#*(roK3xDElO0@`9&3m=Jw#*RDF&N2th^$hC4U#U?x<$^o_ZWVzveflM+>{-qt&h#8GS6j_LTEJnhQkIO%f>4QYx&V z40DNNHp`)w%!6D>=4X5^T$Qgsvjm?Rhqew?x@PtE`5ZPY_AECKwQ=tni^lhErlz-& zdu+ipv|#gBP(`|To1;^6#szDD?_;dv5PZFdZ`x-IJW}A9NSof>1(M#NdFtY#j9ZJZ z^hM>*q{F#Z>?hif8>LvLt8(*7aPiZpN;Y}X9)F)FtnU@$7ITK)E+wV)$qIJDf`)_r|(ub>oa(w5PhsQbm{vHXqZONc+#Vh~)`@Geho-d*W zVQL=pz5gBoCyG|Fb5G3%K!f$*!?GGDWwh#qGn(V9jVwEJ`%1TFDlg0Eq1Hj)w(Y^w zovm?A&Vg7J-Yvo0t5YqHrTA?t7%7kSi|53jjX3-56I0o(I4U&7`wA+sj%ZHK>(Blk zZ!?#qb8o&TuL$|r&SlEoGw;dU+*OBHJMKMd?CRGvC)Efa|MJ(JuL-3!rs*@SJugd`xAD(pznman{!W1T>uT-+MULQ1k+{`#7_K*$qfUfMM#_z{uwz7>LH| zedIa!e!rNza-U1ToMJa`*quEX{o~Sdh8EQXuve22XXDV^vW}EZIlBs!I0yyNcje3j_FGqBPV}^78B*(k>fNIM3Aa%4?ng z<+VIjKU2?B>?JNH@)*<;upi`wxQ+{vdsos?7^LsDZyrFs-jlK%aLj&REgHVEgKXXE z;L6WfbOktmgA=)NBzCCKIvy2ZYt#ngvu50S0nZ=I!whDaN!eeMlao0I9{-6Y>y8rm zSJQ9jlW9A%eoY?fU{ovqOJQ$LFtRn9=-g7%&rNms#cg)BbJ;3Ua(8AME9+@O4uc3Z zs_k4H|H=itv|)z$FUPe3nl3sC?45ooz3K3?jMS7kv7&S9?=-;nYTl0u=QQP#AP{q! zn@fT{`nfwJx^90%Wq8aSod{w%$SXFh9IIWM;WCIn>k@aO(tHaf6A{7L0<`6ASCVhr zf}LORKdnc!@1d^LSE_EHH;O`5maNbLKh>KYDpZAwRW$oT1tQoPuP+dIODZcdA9{vo zz%f?8P*1t;K2n=~N4oq8^N|!0ZOiH8J)7HCgpS4_0O@jfZ+onS^IF1DOBqldaAh7~ z4j~W+_oDr_oa7RG6Cj9_R9aFavX;Qoa z77^Wc2#Q9>&{&ws4aLB|iC|+JaD1p2rNBcJ#l?snYCn9^;hyy|wfh?M)GbPNj4jN$ zPkGM>O{e#3auJ&rF_f75*s7GkO1Po`=zrC9!Hn#LgGi^(U7g`T7 z1pf6UHgS0CQgVn{sNZw<#1ur*g-$rrlAYe6lTi}>C-s7;Y8YOBK@spJj(Wi1UAVLE z-WIpI|Dm5#?Xjn$HTGWC#Q^x-115@Vk(HyL#3Ni8ZTGAt*d@5=ebPH0vFHn`vp@U( zica2xKjf3J`L{3O!;Ww9ln=TdjgRcjmA5c(FN7T9{wwB&-aMtAwS7uT=i-!%LJBfN z_a?Lv?SI15;zW>?K5kR^TIZT$*)pjsZOKaPF~cu;EvrqP;DzhX!CH!H>w(+7JqN)& zqdQqUUnHqh>G@{Yigt#Fhghxk-Qga=UWdzvhy$P4)y(ulb+4TuCDt-E)R(p)sQVD# z9UBYp6YuP~ann;b@D;JOv77pshqWBuDEKwmdSttWt+mc_qa^}P`@%KMdw11-+3lNA zQfBJU@*+Ck$u!tMK)1@Z*ZW+AxVb0QpAdPxt2J<3d_4nrl)LP#JTBqSLq0bF4GQ`d z;Q9*-K;}|j7yIu*DNL>;;0e`a*+^Ef`i6T=q&E}9N_OW9ivdQX!FHkInJ_)Kdpsd8 zX4q*m1hzJ(Sy?D`w7G0pN4xW^^_*AOL-{lKLqp%T(Y*P{KwW!ggo$Ef9&C5*Z&8NR zDc)D&%8(5f;%BTU4kzb1(m_^@pV^t}`q%tgr|GYoyMC+qs)xId12+_FdKKpN*v@Dq z?+GN-VBK;j3`x3z=~c88BD%?NcqxJDjgC%_r`JwgIR0FFdQgr!=zj@F zx$JiduP0a;Oi}T}u8MP-=8ZmTb8JPqQ%Z$BJ5XdJ$Rp*ANd~n<+w#I-*|7Y-1=FQr zcU231MzR}=TzUlY4@p6#isfn9JZLe7Y7b7Hb-vr* zWF8W3n3N+QhpRL~Ay%2K$5v@AI?_129X~#+niCPtd}61!mjkcI6L}<8@WYGq^ygGh zF(VEO83^Qm?U2v*vwS=zVOcjfBJ`A*S>pq*!xi?pH}3}g*Sls1YNgYse3BeK8S~x+ z@QgidF9QMv_1N6ZDrcBk=^#79+*z`Ed}00k+FVpYfkd7W)5p3K{wV3?VLw~m$p5$i zhemiGkp7{x=+{pg+BC5(;I?~bO!NqNrCMB^;cB_~OX|*E$rq8%=TpfNbYE{)MkEc% z%)4D>ZN1e47}>o?8(gnA)2efc{*(@RDk0!6gNhDNo~F~Q^FK6Jfp3xcH*4%$IYYy+ z>+t9@+$+DkEf(khuAUyRal5}{s8kwx54PI%jV{Vm|Dnf(#%2s0#k6>gK6i})gJXEi zH~PMZ$8e^+L}-y65sL8geP>r1R@r78oq4Ga=d939-Qo?D_x+5#r*-+QOVIG?Dq|Z# zZOw*NN*2vV{jjHTaq*I3NAk0>Am3%|^lQ*3BG|2~s}JuN+|jE@NlfO~uAk(OkRGa& zsq>!_L?h(tf926pWa0d5iT<=f^dtt;aVSF zGr9(uQtz3ek3?kJQRUqeSz=wey=q?(c3|St=oHvA0cAfTyNWG6^7q5Vh>X@Hn#ElE@9+slb*;9= zSS!(nY_D-(p0E7R8ku4ARIdJB$m-A&31dOv1m%3StF2zTYJY@7=-$)?#*XN$l2 ziv7~q@HyIDhS;S%aOZ)>1t#FoWC$KF|Gb^Np=4|G3!Rttw=)j5)d&%PI{ukDY0Ql^ z&P-TUgU0u;_)KwazcqP!TxXuY3BWFO~#xI()GCeB#ZQ3LAXf@mM-v;K_VJ9?;H2R9KH|@agg9)u0!v zx_*-G(gl=hw>ygB1a;EN*ePx1)VAUB6|J$@6?BLd@EDMu0nOBWI0RXYX<^6tGByWF zXg<$Q&T}$$jO6vN&L@5@xXjUi2fw4Qtoq)pO+`29&&`GGQ6g1tOLHvT~I_eQG1ymS(_ zN}Ivx&N_1;cSNm%7---M(#?io-uHX%U0}Z-PQB(6Deqr~-F_@R zHK?NuE)zX4Q@FDXt6e9I*0$$o_;-}-A%gxC%2?SLFxcaxrT8BPB;Rf+aR$Dp+`33& zw&FYdkWXA}3{+{@%Oy&W)gSE6D3=*e6KdXByq1n<3=Rxu;u&A&E0Q{y8;{Zt=iA7k zyXrRxF0R#)_`|J#y{qL+hK=yUXHar_tPTKtnUU5ilu?JiN0T_*3&dmBA>MYxTI z&FcjyV6Q|;4lovv&?Vs>)-Hb7;d{BC_xVBf!v;goy{^Y?4hh!j8>DYnax0n}g0^EKK31Q;#G3bFmdNl84RI+*T4DfMf&?CWG(XKHy1-|l_0%Hre8|=^U z%O)T8oMpnty01imw%i4~d3Yyp^PzP56L)v4#adUJml3N0$8Z}0z4@ua996OLqe9Ij zX2X4XddJ5AE;Qz&85K*OHF#!svCYloa>m}9L@PfGHM&>s3_Znr6Po?*9i6LoXd`N^ zj_fx^`xFzE6r@H~+8uBnGZ|^jDmTb}yUNx;WSFm6s*o~DM2Ei-Qa&U_OFfgtKAv+Yq@=J{`u#7{XgoW>fHjTs^)J1!B<|MqNxXL^|@_C=0o z;bUYJ9L>Oav%>YF(j%_GRfbJ|&0XgfS-yzuMN2&u8{s?$RjER|n<1PghCv0xM~e7v zKgjN-8Q+s*<9GQ+6O(@TR|08XE;k(CGQC874W?&3ZRW60s~fECN)ltonJp@Fo$3#@ zd0Ti?nzVs*26&>98C^iy0m|O-FkppmQl5>L{PL)5W2HQ`61!o1a>kuur|z{_qXB2} zoX#}X;Uo9B|BXk)5`o;W#;@|`u;bsBSm;wDQkHz5s)^UGEx3t=o#~}=xmx7fQTN7J zKe?^WC}CgwXrsTA-}3%7wRubWCD-s2q5J#ZhpSwR0($JxKB$0z9IEHd03CwA*#eE_ zZ}qsd2PB~R5SOfeTV{EC?__!WPm-D{wo5Imtc)35u0`%Dfem$&oobA@O zcW+ZaOl?>a;e;jUXpXb6U4L}jg|O*-tuH#%ChT9%g`@}x)SMTmDKig<Zc^YZt!l(s+~7Xg%!!S2V)gVk)TCR^ENqBau?M^E)dZipM&n&yWRMnK^Nw^# zmNwXYTX#ST0OiO?SFnfgoc>1o!l{;+_eoQgnd-Nd&%R$twMy<)!KcigGSyOVyDsc# zJXkojh`4BAHiYjbIWTwU2E9)zeo;YfEn+Mj+*tcweleR(K)bNJ`cxa;}ovWAcuM7t_||=x>&o@+uwfj==qujlC)Li3HJbn()Q03|d1b z-^Kkg1OtrTe$xybzXus5o|K+*_*nG#cxkZ-QV|ln>vhBf!Uf*mz9Nz1D5e6 zchSW>vPYv{zvH-%pHJm6KiCTIr9Ku?O}sZh-81Bww7{=+pdi~%Y8oK?hhmW2AcTDtjG{3mZh#P2=n^reUL}*W?mN=%p zt#|~P36Eda7kBMt%g#t>w+QtBxuXves&du(a3$98n%k!_hm2>&cdJei-#77?eCB%Z z&V($--em

q{HTN!hcsT-|aI8FoD#crHxO5EU*8=-LV_DM(1IyVax z^^e6`bs8ko_M@x5i_0DRCUnzW29e9iVvm_inBX-ThsXG6`;@SLhkiy>KYe)4m;d4w{$Yi>t0jjz889}wD$s-7-Rx)DSiHsO76|S@&w8Acq*#F9@Tr} z(C-_jM-W1L`{yg2t)*H5|JHwumxQ{8gK;*9MS`Pcem?o4fSw6HL*AHFq&+QCNv$8i zg56EJg8^18Eu6Wb(;>khOCnV z2((#ZA>jflymq~@@J6Cm#B^MZh)=zy8R>fd#_~{H%G}fD9%bd3!7^JYnPnZWDS1vb zmK?-v(TftaM}wWUP}$$xD3T0`wUtr0+7KtV!NUzo zq9#R8ZGqo#>%u+XGfQsb#x#4(Hwb)@e~9`!&ku zJKxhx|ehs(2DcId3E-SB$yQ?~Ko+~q+ zDY$(~(pa$g=v?_}#~Vn3$zwZ#*Qa{fT4=^9qiPYBrF(_gh^wTm6l525J;nK$v$y&l zANe-Q+%_=0W+3w6_^wc$j|p;ArhZKUvTHZJU-dgon~dxQ-o&H}54eS!n`B`_q&><% za5ro_rPSOD!g*5pxfj($FSz@mj!elLJT+?>**=_wepQdmH9^XZb($xf2;2 zdJPw-9s2d?woyWIY4vEv;c%2&Y#{UZn<`VOV-7_nIQILLJ364+oKM>aKFKDr{zRTz zcFtAdQTfr%(w}e>uk?8Q`)Sl&Zkc!qY5=m;dQ!mlDd^Bj|K9jn#4F2&}HHtMUph(Q%tnnCQu`&`Mef`ZSHX}|+` z{40czEg-E*=*BY^(+~EC344c|`1-M^Or_-(73f#4M)Z$4(}{%-&UX;S9S`n$GTxD4 zum|(6l|-jsrHQTVYRpvpnj>QfXGC6;drHa;$w&Zz)yp0`>G)B+HO``Yw)ZKR+U+aP z!L=+4yJ98HtJ8ER_x-kocDoomoh2+K*ta-MA2VU-TV9rmfHY(fOM<@Yx=3=6&Ge@z29m z#-SLdNVk(@zWgOF1|N*;Kpgd*55Xr4C%I<}g1%(wJ8q3iN6Ejs&YAlFy>>HN_Ckzx zx&B_G3L#^YQiQV)epl^2W~wHs!&|A(V$5#Lxe2quy(SWvDLviEU9~ESW_`m1q|9Pj zY`#Z%9qFdKPswPJ)1r&T@Ft(bDXsy%XguY2gYdGw@lG_sY%Ghr$C069#Js3>BGc_E zvt1lN^-!LF2~XId)X!SK=h^HyY9a}4Cj2F`Mt5eUx~ef@l^l#n=ZoDm6Q?-arvpu` zFdq>I4SZWYd=8sCGP)h5lYkzDg!oww5A(E3x|z9pd*3u0@YtOBt*7)~ByV~lA(W6b z2`P65<SHAl&U=r>^m);{0z1C-smmH6p3|T1^Ag4{~ zxp~k`Ua4CJ(%Ux#e0}SWXdQi--x3ki*_mPvrVLA;Rp!Gj3N|{hLC$#k*jJ(an%J(T z%^nH*;YW`BGQG8p^%jGvTSHk*32p{5 zwQRDLO?Jv7t8r7c9^S<$>O<^c`>3vb&GlURnDNr8J6o#Eshw!ku@4(sMeKHB;$;nj zhZxb6<%}PxpKw?YyMC9RNe@5?~y%RyvfiNzi6i?NZZIQFR(0Q zk+#YaZ>&PQNj#Z*RoQQY_RvfnZWoq}70;jbGiIrn`j5J-E?~njH}`H!jl3jJoSTLd z`B%G8awZPYE&KmZS3U>Upq$MTKbZoyDD{vptG@U!VOk`90uBY!C3^3362&rahQgqc z8b(+a{}vx1!VP2N>DcSDO7%xDz$L|wNex#w^3lhA+l3(tG$ZhiE?uj?CEK6#q^nq*s~muP4$x%g7k)~s@?zilhGxL>$=DV5`AQVXGLs>JaQ1Gpxs zWDdl5Ank`vddyJ7PJYf1&-D!%_1e%(d5Ex4)BTnF%`&Q9@yN?Hf|ShDA3E<1QrUT* z7uGQ}G9(|2p)ArJidCwc+Q0->m+Sb&qvXx+mq(#8e7^Ad!Q=`y^7*LW<8>%gXG=H} zAO~RN0oL^YtnI21{%2BroXkBlMv_H8b3^af>%%~+1cOQEB{(w<9g>-CAqYe`cdv|Q z>|cA08@>AF%8X*KeTSXw&#`(IyVOR%NElivzPxJ{;RvYX%Umg%J|ThEe;O{y;KKEn z4J9<*)KRQ4_>JHG=3d>sx982bwX@^lXrpG7=ubO0NG5oIMN>!itjU*dFJk384xXje%kKBEif1|KWg1X6MMh@UsNvr^p(jde|$i0+^2m1t5K*Ev;}kfo&2 z31VBR<8o>_D8wSLUAwo#$sg@9NQzrpDTs ze&aY@Jt;si|IQXzs$((~Bupy7Aw%PXo&EYWVdD!c~}qZ#6>!S_wCQUm!@;e;-ez=PQ<+T2+hE81$vN- z`ytfh5227=C;ATx^e3`Zyd0%F z%pEz9Xke=#v`L%98Wl9C3V1)wa*j*28RI&fIA`0u(>3l5u%a72F>#qmrfS3SQzWTS zNtT$kxbtHqth08&s~nG47^z{vh*zR(+lV_R!%f7^Q%TovxzDI(#cwv1N+su2@6K~u z)J88Z84?(9RgaitHf{X;eA#v61Iz2Bp)xmRTn?Z-=Me7hUT|9N)#+Q0KkFR3j}I5` zSj9G@`UUJ7_uGOuKvY-m%|bb!t!QvAeD6y(9j||(@#t0)g*83&*^m~>%{FUgU$>S6 z?l2HSt%o=fO6PBoySTsOZokDIn|;bE)4?)RWxgc~{2{r!o1CGg09$21WgwMkAFg2* zm<7jB9Cqh$ATZO-__M$Ma57Czu#vzSL6qhaVfvWK}*-n0aR_q_~E21v8qBcgC zQoCTU2e2}2?kTo%X;h<(R1@E)T#pu>GoBHE15)@BJ}ZHHgBuDk4xOfd{C*9f7qUF*7J@4eUmb9)>_9RNP`hJ;s^>R~f-uuC|LlH9yZcfOT!e{^&amEo zQIi->0$6L}AI0|WxZergFPd)n(Kv;7^@`_iwGRAtoq6i65BqytZx3|W>mw^L z&5vm77sSGjtc9JOL6v3s@?r1ZYdde}F6ZW^8$+8~UktpChi6iL*J8D&niGNA7CGR* z4Rqp3!NRJ*;j*he5I8_C#5|ZU|BfHr7l^O+gu;Ts45-tSW<4L@^iG`r)OMjwdu}#; z)zIdaNw$W7$U#~AMUgBYO~GE9knL>&;uJ?uV8F4um0VQ-lv@P_S;cUo=D%t7G_-B4#mxo2x{wtb}1ZRNc48&dm!16@&ZO91d%|MQF?Jjf0TCfpW z`3G?@`wEmY9VVt?f#NI6JRcEup1n%!oTm^_?yHYL!cG%7iQi|HLeuf#Iq!vDK$Ugl zsn>nGL1uOD>z|8&dqx02JyfbwllkJqxUP>w9S5-8SYWq4lXXhz)rAP3gtTfxLJ!H^#}%|_qME%Bk+O9lS| zv5!-}Nt}~@ZK>iACaVIYB{SXXAH zO^A__g62^0Z*LE0SPUHjnCS2>NWDnyeG{8Q-X_6(bTVl;c(74jmCvy}j$X0atv70d z{nlZAN>>PQ5zZV)cFm!&(c)Os$>ajvYU+@RSrLHY>Txc2cC-(iwH-aoW{NtF`5$$E z9H|*Udw%TowxrRynA}aQiUW9mrK*FSn#Fs%npvfktr^!kM>t6ThZF3sf`TSAqg*D& zOU%W4bbfB7Yz1lIkF)@g#L$b(^i@VQMuzzusRVW~0vH0JH%SNqxO>`c zeMi>uHwZ!j0(fo8z+={^sP94#mn27za0AL((IIv>jI|AQ|D?1l(I)(P^z*CpHN>ws zsm_g}zyi1OKz7TjYRBa8t$I^8S5LY1yVIGdkz$(r+WLL<`j`pgD7CmB9XzQM@6Lz& zh8~39r`^OuEvZIa7Oh+RxX~cawR5PQVTUFc)!eTeOG>oTosuVW9*h~Do#349*o#k~ zakhVX!bt%oH9VYXa5=D?m&hN`#KuP|+Qn6wP@_Ml@ve$|u~dp?<6Q`Ef?iDJdreGu zn`r<`nZ1p9ITpuJjQ&p_>we5K-{T|m6u^mZ@1LOr>_z}wUuR5bTM`xmi#X?Ykw*UX z@9TmBF4Ta+9Wr7#$o{{Bjaq62@w0AeK8ah58O3lQwFA<-rRG(ZI-E(6o6z2qpr5$_ zYp0(G@vuyyYX3xD(*ISVYO(gP zT#OWuCKW#+H_&Rt)~p0^+)nvFqCaqkB?{0XM9+Yw9`C5YP2p~jM)+kTPtOSPY4gm6 z?u%lL_Wg^^jq4O+#xkNm0Nc=__v1=Q!blR}?o_28)rcSg4;<`3)V-Tz$A7{F0JDDC z>0~vr`1$b+Rv{H1p=pEEqy>bB%_pKem4z%7G&u008zhA1TRr0M^*3D= zHEE?dtEBc^Y6@{TUZ2MA*9jD=7rWQFlD4mn&*&F!B3*u)B;_)VFT+OOay>Vs^setg zJ7Em9^)%;ro}O~~d3!N-Rv$PRjUySaY%$fvX!9ebM)>!Dlmw9DXT83CEf`0FZlV>? zzbO)Zjh|(ACfU(Y5CG(9C6{zC`6QRg4IZmC^?*5G!tv|1s`ZPGkU6U?jr+_Wl6~MB z*Mht=T?yxzfNd4$LVxz-iGrI1CQB2WBPY+Ke+W!q%fhW5puKFyR*V4Ld3SME>&c*s z-H`aQHIBgdZEFH^0c3)}HcRaFQ^fcgA@d~OWW8&o_`{o_6jD!p=EO%))-1?Ho{tkc-& znkw@0SvFP@yvl(kne00e4o#ZYi~(9<+f#|qPnfCRz$;Z+H6CP#qgj_!1`|uUJE+0) z4s5G~fATpPUOCr6f0F_~iB0YO?5K1<67z!D_gUVcH+|vXjff-xx(49ne@2S&xqJlP zmD=65#s9h*FCfyuio^_?Ji7p84HP`%=C+T{HvEgQk2O6>v1Cc*>xZdlR(cs7CogTO zIBqgAn-wWOQ2cUx@_hh>Kh#$wK36Cf8dQFyAc996bZ=t)Pw_ERpp=ZuZ%RT|obdLB z^Bi;Q7fAlZjmzH~)qCtswP?P^#*e6Sd-0I64n(uq%deGkT zTX$$r@yN-%7rJU!wO0VDf(ftc*!5D?MPtDq z5T{ZbMIMcpeg_jHM}0M%#N7pTsYXwjzN*ZSd1Vykj)zQ2q)ZiP_8px&hWti`p!bQX z;np5z8K$<9JLyM|fT{}x06ll;O<+>%SJO}a-huU4p@`2p%IB9W#;fz0^!Z+<>*Iem zBgGW9C-*+A$82Nq+;XUu(c^a$5+KYGXoKpCPjNrMrs+F{(tQqYNM9V8N%L;;4_XSw z_s{^^Y}YHLB&DysyIQfC^6g=QWDmq8K?M)AkS=68;f%+A(dvE<1x9ZMg+Ut)C?zEF zf5esGK~=#l5Y2*)Q@Kev{$R4~;p-n{$)a04Nj9!-pVy7uv}fy1U&bvaj)bI=hA5OZ zxzL*Gz*OVUgPq?YRaN9oixoHA(#)R9Qv_O1 z7eV}Su#S`d8P=Bp%)CL_q(7W5EkSoWE7ok%FbI1P3^uzF96i7~_0_t8iC_iel) z0Mqmc5c9CcWxyDE-~#(Z2O9aZ=+JR(oFMD}+oX-amI;XdK=R4x2_Z(T(fNbWQ}!6c zS-S^E;MK-*F*B!Oc|sy!S*0(QpYdux$Yt`i5a2Dq{m8T}$gcK0n(d$y#yRw2MroSR zCcAUJ7XzMYQe9NgT1G6p+Vw2XhJN^ZFT&Qq)#pv&_T;0wc~PVF6QiiQ^@pw^PYr$C z#xmELM|8r5!#ryns0@wJGw9Wol*Nn0vt8|~yCtB0M}1zq=r(%a^{Tsv4j}Rp@O}0R zx*seMQJW`6M(oyw3S}cyok9UKQEaOHez^rI--OniwdeOaGUdocxD8MHKp+Y5Nopy& zc)D~y!aEC)PcTc~1T8*fkjoMZt5R~l14obb%c}sdSQ~RpyF9D7tUE1f*|G|Y;v6f3%Vbs~#Wa08ZWe@(0_U|J2v*wUMEQCu2Xp$53O-li#S-hY} z01s55rLP`<)Pfru9}Tb(un@~tl4`unT*Z0L2x#ztgKy>)E{gM1!p^SEavf-Lo|i}y z`M(sHxvDyX9U)3EN+#&{moQw^>>i_d31Jfp8!yfH#6zkG2amc-2N?ObdaQSuR)I99 zju*wWug+9nwprXLTY8G)Vqs8CJNCA>#0Zfn@MD6JLJ#iG!UmD|mqD=BY(UvBj(x?$ zp8NrX4^LiOz7CyM!L6dL-;K98pU6)5Y6N{ZX%%G5sCr$dW6IztaT4PacX0ixh@rVw zKK!cQLBaJryT}ygp@-0ms$av`UVi}85~b`LQW@Sa24>gZ039)v;;yh_Dn?p_Cj#_ViS>q0NC7^|$E1#)2EHUpV5Kb>vR|=AKSHqg;lk|>G6!pUGI{}`SO$YB9yZwI)QfE2Tke8lfkQ+G@iZ-1dMl> zCr=0w8@;Z~AFkqR(o-r*v1zOL?XJGhO5{~Nbu5mR%YKjLUjJyV93JEJ7i0r5b+>)y zYrS}=n;KL7fwrMmZWv|s7|OXv4nz)&Yeu>{C(n4-v~q`lmyx&3^3=PhNxAx)6*f_Y zLcyTF1JmnFee82?7Y;&c0ObTY!O#g9HtgKV!hRL}+A7PeS^(oLtaTXH>S7jxOvP5E z?<5xhgbboR+?nEoOhO&)yzOP7P$@{$tdrU+v&N8xxjFhl`bodLN8Dfxf<6ki)1)3! zix6sZSS2Lu$grx`tFgZs!v^?!m9lUdFu$2@cNVX^QE-y6Z8h3R*5F0qS$p14@7{Pi zvDdOw*t%&wA7-88Lh(iZD(=HRZ82mab#X@i>cw+Bt3?-qyu$?f3)t0)Q%PrXGd@LK zaF9(XaEKS{SQBtHsrSk3a;Rmeuk3K{nAB(`0ypkR84Wimox2ca{FQTk4y^oKi@T675C3%7botEQ+l9ieC1n3Vuwc- z6WKkxHqlUL;^BCc02VfqM!60|xX42YkjEAjj0+y+$|PJI|617Hh(^?1^r-r1OQgRO zfn}rh!Uvi}iuCgii`ThiESU|(*0&GVH+eQT89&bR_34@ECAgvvHul)jW@x-aF&gly zsb43wRH6>D00~-kq&Hr7@4@r!Vv5P3ft^P~iCdEy%Y@-V_xQ;rYxOm+5F!6SMt;?Mh?8 zTA+OWr|Uy>12xv)J!nS<$ZcRlfsw@b7>;MyqLTkIJP0F$**RaU=zTJ{7ySo#y$~(Z zEtY&M#Lzq>Ri+PCFj)(E&Q7Vv<&@j6lI;M9mBMOm4z+vocjd1V2{wx%cdMG%Ai`}k zU!gYm(;3H?V;+cG%D~rbQ|P{QNGIzvAT#~+wmf-lV|in_pDaU{gl#>Dmg02=n!qX3 zDAVJd>Kq?^EvguQt$hW@r0?MehWpc%bs=cpa-DDAy3G{c9d-S5GTFFAsrwnK%R$Ry z`HVI3Gv&<2LdetCO$W!jB7D}XXEX3O<*-ZFJ5iIxo=s18`@_GY3Ml#|s>CjxlgP`U z%1w zS^ro@k$S=-`bz`1;Z2yx}?emAu4V$a1Ah^~l0z~S_&#H2Ldhgp8)UEX-_5~+b zSqGV#87A@i1WmcwA#augcg*5#+&dPRIUU}{8tFWX7fs)9Ou3wTtWF!BN~yxO3&OfmC4c-Ke&Ms4|hdKbj`Uj~z>7e@}8 zf8L3w%9ZDS@Pa+ha-|hMVq(L*R={E`%urTQ-vfe+ft_qt;f0HudJNn8$BOz>*+3RK zzc3nmdP=Ums|@CMc;ic$JJ`q}s$d7&4h6}@=ecjn;55%70O(@^bTOo639VO6`J>aw-bLjP|?<$*Cb z2>ygZx0m|wgk`;3I7JR_P3Wo82V?syVKpLudmMR5)0}!f`4B_k{Mq4Fxe6)jBGNAAW{k6*B?l&GrI%(^Y#kZUG69j8tvR2%{ zCvQhEE>1i691I(*pLn0t@?eNz7Pf-pHD)I38uN|1Md;ze>_9jgTlgU;V%aAjp~TP zWe60Mp9qpcAQ~O(9`wOF);hGRN!4EWF^uDn0`UtrPB_~u_;X}G-&XM>Z8>`yfM+6m z(>7$WBT=34`TfryfSwg-yH8?lq^m~caW)G3|Ji?!ICFmNrht|pR{Y~}r_Wg@<6(XE z-&MX9xfmkL?9FH<4rI~A-J24m$QHLKR~Hw+OMV9Rxq{`R81U=xhbKcLOj#lFS%M%m zFA#rB1#cBkh80#?r&p9RkX_;qm09wC(l4S7ruu>os}5?kG#wTI>+D!sU)fZ>H&Z0& zb_a)!G4se}@Tc?qLG}2n?3B}J^Wtwekw^1E&dbG=>?02os`Wf7Lw+g0?+1^QfYGJK zu($G-HOdbm@p8hfcBOfL{Bxa69ZvlXcGgKZB4DU2*<0(pN(*vFK(4WitLrC~+AT&D zez_$>Wq(^;gwS`Brzz}T^W{WaYZ3M913_&7kD7OUU1><$51A7ic(6#$yQ5R5apu-T zgU2>nPw3Iv3;}x}v}is#*Q87b#68|HzX1sNjUP9fd2%5BzJDFI9Z-J%>`!d~q=CMm z#^aE`gC5&k9bb03|6T9xcT>vXJ3n@B!q=-#Mm-m2#Kh0L-brHV9S{StD|XqWk!0ky zLjv<17J64Kqd`8TYU5issVrngTw0 zKswVY#0~k;`9PDJ3ZJ-$RBhFNx1azpDtUhy40dv|L9PT+Y0Pk!1vTr1YvD>r+;8&Q z3k6Z9J>=u?*5ABrEa?UUXN0a^-O^lZY3-9DiOe^?Uw6xwnAFSrQ0r`0YS{F=6W=dc z2FN&uoW0D>F0nV|c7qzgmVxvPgzQR6&VdYfLjjPw`_C@sI0j07-~yjnP_X$1oZcKu z1~4fFAAi8f7jh(wredZmhC@EeG3FR%3{y0D%f1#w%pBWk}A1#uDr`HqLG5CNW>gUMz#u=87{7efO`lE zova_w`N#I(K>!s*K9J&txtOepu(@s>_r-?Dn8>f#Ct}O2cEf|;QjfsKEay%?jW}0< zH2X5uu09(=)!eEq#Gzw=;2+2bh|_G;4j=4TPt-}*6al(kYw50!tE6QG4Rq}pFmK`0Xqti$+P{du5IAoJ99T+2COUiJ`nL?Gws}WVeR@v$kjTa zr~uHYTUvH3gCV&;&b6O(yR1ibT;h>c3Xt}9v6O4vdoQl@%e~^cn&*TTjx~Qjl6$QQ zSD8+|o_JeaJ#_Z#HTC)F6#haWX)Ij;b}n$bA1*mu z7vj|qG9`~6XSV$yD73%nN_wBqdJx34eqCjNpJtSj*Pr4zug^E#yV<0E#8++l2QZF& z%pDm~KkCzmjmxa{KiJ@+bf{!jUcmUN6{%HCtgxpU(w>_q^61%k0Xxyte{Ax+hd{&=Nq#K z97z(`^l{twb7xX8KIAjqHk}cxA+|f_P&_Ts`x!~Pqfke@Wz~2K8{C?W2fRlBJcoFT z!MQH9^b7}3z{_+Rn$CBz2Y2x*@K;y>#!pv30>SAPaFO|YoOgfkRHUE3wfHk7{L2w@ z31-h`Br04|$8*=C#mC&$h(VeqFbu@@3R4|hQ}ncgBP_AE-p5_E`4O3s8T;k?svkao9e*8+k4Z(AoC^w)LF4FHzmSLHM zUBw+8dI-j!mr5hB{Tc!jpd`(lBA%afI1V6K@AFlo-E{MbKuh8iabSEdFRDpS`ztz zS3W@Hpit8JW!U#ntuV=6<-u29LmRntvhxdRBGYe{iSvi9hO!suXS<7=*x$T=;~9|g zts`;EmKvsN+dJYrDnZouFhePRsET5S@dB+GcPNX;CBsa2JbzA2Nx5!L&5so6f42v``!8s_BA(ijGy_R; zuZ(2#8{8VOIB!hgV3u>ZHE($w=llj_DUb4-&=<>Yj&x5sscs|BkYZKRolJb9gLs1d zGsWssiZf>1l}#F#PE%=Nn@5cF*h1wG7(ROL{u1L2_kW3?hnJ#}f+V$Gr=kG2lL9Ju z{V+D{Q}Rv{bq9h6vInP654eT?`O2+c@*o7Qcfg=dN=gbiX~Es&YQTYM``sCX{3If> ziZELQsw-qfn?kGl(q5UyrFcXA>fkdRHs$ihOW8abWpu({O(zseK3v(cRMZNe2r5Wc z6HLG7AHLohq%ANO8E&!@bZ?#R5&wCjXs3O<$A_{Ph0(`jTzQWl>&S462sf{FBFLJ> z4jaioBQO<>1ofF=_P^NUw7?QvTu32oF|UEU-e1SoJ3aThK`e;sc&;pQ-dbqZ(tuY) zOyKq_IVpxuPAb$z`+`bEBKujHpAiAGjoRt-W}qT^=DjBb(wTBT?z?u^%A8ev!D5@X z{79Pl8L*FhE{rY#e|MKuQ4>c}#1Vl+_C|W|W%ESl|62?G_nYGP(_j%Nw$Yp}s9g7W{(=`M_() z;rQgBAG@p47{NBb1wN@;Nq9`aMRA?g?cb_TQUFXNfkHJ^!WFm^NuMu2L+Nc41!G3^ z3JOd`lgkhYG5jDegTjZ>JK2vTtGUf=32CiK)Zn06P|)>N<1@K_`&Zqu`9yVU=S03B zzHy!mL3#WadljmBZnGj0EiQ^u1KyCZH?ET>W{4XKC2j5D5w}a)%v%n(#-A5n*Jm!) znSI`CKln+g3Vb1vYV2D*@UlI+USJXe6J zbBNWJtgfT|H&~y(7-_qMG7Kv0{0q1^02P0*yrU{8CKy>Nan@a4!^Sp#!v}>W-2x0f zHEY+CB1y8S1H2cm9tjtK|;z1h-SquG>!{{0QeM2f$QHJ%-D0An8h9*3_5 zjbD!dP|slsGSXe*y+J`R0rGs7h-f`vpMEc}Y{< ziCq)fpJL1TdqKtQKnnEcWO+5W^@s%VyM2wvr{|T5#;KTW> zCxA9hbnn{M->1~^L4AEaczhV9lX3? ztmDG^)<_d0(JV0N73#duNa^ePj6@Q~cTt(7@b)U^nOhseh&gNf;t{I)+uOPZfsIac z+_U-BQpSm?q2#@|15N5$91l^)lW1PXg0d2a-Vl=~(QM!CU2lDN-^t1=+2D^?Ma@-N zhwNrMtLnx>X5?J+>t5&3K7~i+%PCQ5`t`s5dIFS_b(T8R;8M&PwtemJgeAiPx7xz+ z_wq;Fe#rOQ<_$d*z9Y$>w=mo(u~Xh2;`})~gL+w(diG)b*92_~#1no2AJ0BMkWRo#}$nsMw2|i?&|7rAey^*`lrTONBUfcf1XvWL=cldXU z|KkFb*aQ#sk~O!F_=wSP{N`f%w0LaCA;;_~eU0@yMPi<1SS*Mwd!J>ISR>d`%8iwn zfP^Y#67A0drL+YFEB@BiLmat6p+D9WtcIQ&I-2pRa4%kZKlk}*MbV=TX_EM^!a{!6 zg~X-TbW?XO(>F+_(gqE-uU=7K-CcDm_SrI^8tB{fQJU`E^AT2|J{dEy3uSP>XsZkrTa79_% z&1_v5fj&C*8uk3v$?<(b=o9B%5N48^%4CCnXbgID3#((vldjJIUj;2&*lipTmL#_U zQj7{XM5hW)Ff7f+(`;5h{?hZyj1E>uMHA;!YeC)`TfQVU zhmj3;G$z+wj!J)P{Cah)8PC*uz{TL@HXr}_o~2iJX)tRk^`D&;YmYAN-VN)Mz3}tX zpi*Oj*bH0Iy~(~*d=;SW%+^$juibk1aaNU4&oH>2-w~ubwxTXPdwUnD3s}PBy2~et zs}P;mlmOg&&~61rlyB3--a9s|KFwwrh8pW@lk&645xpKHT3med)2My+hF`52g`=N% zt>n|{{PwA`&^vj8Zd_JTMx1!K>&T(eN2)A%-x2D510KJaJ$G@!=NF|R0IIN(pN^7zpG(|&;OO%VWbmuPaMoowgf z?K48~VuPC?n(aNX&ysuY>nY5@jl|>_O+L=1oR#EIyI;<09&7#z7Gy`o!KNHWj0f0s zHr#SIsMv5#*>q@s+fUVht>}kPRHh0rTzOI4t)m0^a2wK^X{yV$7&+1b9jf;ok>b$V zsHK0~l;1sG7_hd=yMLxx1Vi&bC1jOIcS<3lnXpVEgHH6q%*4t7feuhX`A}C!KobI) z;f_tunJXQ+9mLXe?+>RblzPL{Wu}+{kCgzw?+fXG%B$Hu=8hzF`zwQ8AC~vda@uT@ zb=ExM52WFrFpxQE?zzmsa95?r#x^%zu^NFqjqjgi;)%DfMKoFiBhtFuk{i-=e3s^UcbE^{ytcbm3|NWe`fgn}+MI zXz2_4AZ{Ag-$YZQd{Ee+Fki(o2#!c7DH&Tnxb1=&xaj2D_j!K%G6QniNwF;*R6=bh zO|A*ax|GU2P7Xe>Wf-!(^1c7yV5M%M=k)ONQ;wT!n5Ll6w*LbV|E(ye_yND+*wcIc&(fx1o2pLXv)A|Oo&=jL;q~&bX{mrPWKawRJUfOp zi_lPg*i9L>Qq=s$*)x#(wH=#}TY#OJ7Zh`b)7+*|aC@pRLcd<%0i_^`xa_W5@tjU& zU@wpI{eiE-84Fzve&10ufxG6IwW&sWs8o9NlQ5d@1xLcwAKI|cgk`n0VOtEtHO3w? z^XApuQ2DL(v#H-P>kQ9jhYDO&34DEpP^4#C}k?X6X9L{*^_Gm!z zorr&l03u#0qh4m4O1Om{HQ-FVEiuyjAXtj8uUjc3tTvc$FTt~9sb#TBsIrL2kRj1bu=Od2O360<-E zrR!cWmRyT!bwh!c#gYL$HxkaSp?^CYTYqr1Kl9$X-d#SoJ=+NYn&V69|5kiT*Tu!< z?>nY#K(*`-{Eg%wAUU*3kM!65^eR3OI-&BdDkVKNvu>;2s6#K@M);-v zhcfiz3j3RNB@yOj1`U1d%s5$;q0jwJE~#Vj>dl0Z!lM$j5>*=46z2VHHEZl9Kl1K8 zY0^6)4SmU?(kCs#BAfEyP|W?@v4uXM>~*5k5(nXl%7q|F$jV6;XP+MO{`FUXtEUDc z?8pWz7K*&l18A~(?t#>~_|`9$ z48VQ5XC920gI~wVQq**PC}$&S%cNYcfV5G3o8OzmXU&0Ial;6Z!?fIjWi5oXV?Rug z5%x3nBMdpzop~Gryq6dSsZXJgserT{Y1Mz}c8zK-Q^9-n0KK87(U7)PPaSIJCmB;} zCL}%hLm;k@dlQ869($7EfjcW@(Pqp$ny>{_D4S_U{0Ts%tj(DCcYALNf=z-v>p{)| z*D-8>l+@9GE8j2(@FXmK?&7Eu=y|(hu=n#dWCUPxv|@!qnRV5VA$i3h-Q8rY_7jGn zQV5*diV8g$PZ z^F%eRu4@lr_Wl7(X$wo5{%mb+{r@vxAlg1c zi$TtovLi#YEO@?AYXQtpvCI@&3IyU{ z4DU-6K7M7LEaZK3an_g~-RsqtX1MQVtls~;dmAsF;wujPhQDUf{vcGEt^u9gTThN6 zN1~XkF-YC7joUxlInqy7%I8nYi2JprdRVtW%OtLDV7~PZ1Y+Oq-Gy5|=KpIe1B5#! zOdW|cH)#}Qp>YX>7@H3pqkQ4>6yAruut|}ghxl|_8ZT+o&`#H7R_!N#n%>pWeOhR_ z^17z@Ta|kF;KRfHmFN}QWW7W@E_lMBc_mEbAc4xBv&@553q?QJ@P>szu2h27jUQ1^ zX+*rr-Av^B({xIVq8Q3!A=m-BdpucsLf{JGEaHVYZrUwbPFVtGyG;YXuyvcXICgc5 z^bw^aJHNy*z>|5WI%Mv@+O0v@gdW6ywE+rAZ-S9`7l;|HN+3YW`cUkIJOys|1@v}@F7~4Ml;<2Xm^=x4D7kMu+BdX=_C3|hz zvG?2Lw4J8+IUcJA7e8#|Sin_avSK0ZUUlv#>o|b%>#J{sEy4PQdz*HfgSLzH8ix6x z&`)e#rOXLIC7Ju*{v%v5h`P^ag4r2-+=7CHH5W+&z@^-V}rAirZJh*k3 zF$;niNC$mVb*2a(w{{@60t1nM@pAgzwLK=h#r^6U_RtRcw}Zz^m$lJ!Z(r8df|MZ=L)*2|b=D;%5`Nn;f<_gtXtvk)ZUDF6o_CT{ z12GMpDqLBd4BSl~RZ2!VV0cp(oSpEZU-}B#s-TWtJ^IbZA`Gg)iDo`|vuebj62ilR z$L&{1MT5_R-vP|0);CB>Ezkp2>#dlK=c!Mk$a4yFy<48@@Us2+a%$KBFJq>s%h1>U z%(qa&fkUUqk_K7h3%Ix+@a|76r#^HAbO7uhvs-paNl?m{Zt>>Sin5y2CFXDcc?GXw zc?h8D1!Q^PrsJ}Eq_at}yw7zH(k1!=m9XbDE0s{mdwO9=REQ~`F<;-|gsR6M^76f0E z)jjRUO(2*&-_^c4U9viAtL@-4Rmb!>Z*io(21>LRto1rVPgT%|Q( zm$^2hdtbGk6&b4&Kl{;tA6R~BD0~!bGv@d{@!I0Cjo(XS>3f3ZUwemFYj2W--p3Uh zeee8Bgs;s7edw3NNgOR~5^JuYSt+Fi!zl*oF1Nr*4Yu<7y9d1?o@d+G-1Myw=`+9G z-QB`d-+vq8caobpUVcvhgfL^%-vmw@NkO0SN;Dbd$pg<1*6$j}q#EB|0(@Tswg2m_ z6-Ud56#WN3@LqS31nGrL!f6-vSo3r z%|5v&D&H=W08uX{mO^+=Gg6)?4ff+_ak0UhQ5_Q2d6!lTOoeNz3AsSDH>gjhy@7zu@%VUhMqN>kBPgmGH?=_?rZ;%$1DgTLqix1EQ!{VbB_2h6V7= z2`i^r?xp|<+t>t1cGVps~E-}8{yxRWTA*;Ln&3;fvXsh zYk4aY+YO2)lS*wA_3aWYMd}(oO3UTaQUPvoU`Y-5LuOs}(F6kVJH;<~Kn8*R*^o}P z6oV@Xpu5CLLtNkZ-mA=4y2{58kY87i>+j1#l3z#+C*{`Qb(V#VByud|yx{2lLULX_XYp8Lbh2mo`)a_Dcr!Qv`%~ z9v2jN64YR8EgN3hX$HB&U;N0UKjF!`Z2w)9$FgO>t$puM;=zO32UsN`;M*L{MiRxY z{u&FxXo2wXnWZku@Oi4D{fV0^tDXMVd>>@z{FiudYZBR~h+~9Fpe0^VyXRu+pR-7D zaa+7Y83+>NT7YG368}*}f|bO`aT&eSJ-HtdD1wC7KNE7NSGP`0@BdAhf#;j zJw_OuZZOY}c|VxUro5xla#(u7@+vkmbe0|%(!id_-vw!Hxt75yr`kEpvktl}Ig-A=~#nZyH3G@r%9}^9~QSzBqJ5if98#m!^@&l5BG;JKvAF{y5FtzL1}D+2}ceB zZfnU6z;?*uw3+I?_IKw2^Zptzy94$#@pp}U&a1T3{yXYZZZ>a^K)5y#6N8tE3cuy$ zjGYmYr@MQ%X>CIp!fCuYLqEbmMX4*)GnTxivMQbh0;$7k*l69HGGbD&Y0V(x#$%GZ z1B~qCbB^xnU#ZJYj@S)Qt-Zl!sF7|!<*r{3ljRRCPMWBTYZCRW_@l4lM={|Z1M&vd zb4%202O{$iJr>RAzUadd1&t+((MWI3sgONIO%m={wf(Mk>wVd?<6}2%(#_xDq6~u! zPb~$nUm^Z3=fs`jE3W)0vo$xK9iI3@D0c`1-8VH;x(m(Sd4HBIcVU=yc|GFTas4K` zbHJ@NXz7f%r1X=Lum1u@I23P4x{&p!?L<6y@`V-#0A_MFq{HpTl&Cf zL1`U2Aiig7Yg?aThB3EA1jo~eqLcEydazxuli%{gC(df*sTW^lb%TV}>8`Ipo+n?E zJ6abmFJ_GI`J2?!OJ`9;)Yb>RMc(OEq&P;K?NmZ+uPE54OUX}28a6tV%z3!9&+avy zx(FyljZSf{&n`QSfC;10odID*2%t&-?V8T@^AIv%`xJ<>GRZ2Pds)d2$40@=fDC~S-+saRzPO!ZAPd!B?aKFB+ zYky7a#!C^d{S~hS_CtUccIW4nfOnjf>+Y#qKyW!XQWQY?_~aqZRV+P=56Dt|j?4b; zxZOt}KPuDW6^K6va!e3J{~re9CUpc@(~?*_BQQf;scSkY$DD3SV3jVnxF4DnN#W9+ z(YCKF1nV+D_!bg^n}gZj2wBGC6;qA2#T?2r-|N!R6<=@jfJww=>8i!;4v!mX0wB{(n(IPNo*a%!?K zGgwtIr0#cNh^uYBrL%UmLoNLUzr|ItS`(}?0gwPcW>-19X}cu--RNzWJdedt7O$$N zEuQTpAYVzP?}E@rq4Zt^$M63b3u&%V|1xBO6NoN^|JLvOLma16&NJ1g3bd}{f zk8JC^?NDdsysEU}4}fbIwPG1rV@{#uh&3=~)erlaseHF_>AX(->bTEVn!^zPTaC3S2H zP!j7AMyeW)afOM26UARztzfd0vVmqUtH!;-m8DN`=?mh1SQ||N8T~W%l+-k^ zsr`t7%FkA6jnucGa6sx)lx{FD+dAGH{`{BNiBe9v11qVrvKJj z%pb6j^8kGuNNt{JQVR^B7E&RA==J)|n-FZ0S||T^s#Ra-TAi)AE={_nsRn(CqVmMi z+d&En#=X3sNF=oP>;8z4$h9^@m3!%SBYbr=`Bhfjf-1qxrwcSI;7a+~+bhvo? z;IqrxgK|l$n{{u4r_o4z%gvroUu1{Qa83TQ-PBJjj5Dn6u(q!r`7y#C`Ul&4o>vs9^MW|g9X+|^K`ff6|G7Z&=<*iWQpS4M!U4cRyHPQ~% z12KAVY(DUFEG1RWwBBc$!K~W4$FwQqTLD7y4=Pedd~sU^5P0>tTUmf^pH-Zub@^GV zpaNHr5QEuThMxsIqNN#%h2m%LqOB)Jk%xs~H%(D0c4NDjSPwV9{p^Ralt>~uiGnzd%DL&H z{tLV^D&uBPi!xWz9Yz8gjruN@BG@bnBw{|DBP64K;8jMDj)~_|7WuBnV4r%tYNqRS_K8|CU1Hjp|h*lA$UOfEfyH!b;Os$_TKE4 zwA)Y9vIaMXE9(U?E}0h;Np@SWB9*d>j7v(m0eV_)pczNw#9A4V`B~WWbXfj(duqA<1VR^`&=rF{XN zwEQa_;u|Ou{6(LB#akuzWt5;;0jGEYPcy)RVr;r1Ku=#>7oW!l14Lgb0QG&xS zZjZPK3OtE29g`W>CA0MnVwMa`{qBOS0{BMLAt2_UP4E5Ir6DLR|MIO{?4c~19%^*p zY)HoHlaZ79t{e;U#gEfss>!n#W{+*;9(&(OZyex>iexk8x3~=N_=WtLN=0zZd2s8f z%Pd-a>d0`pV-!{b%*j*LaU1a3vDnn6aK+f$BcE~L6n5#8^!GjnTQ`-1ME-Tf4batt zwFaJQM&g6+Z?LRJ@Tet&9KsawF|zVl2NPS}x?oo^O2-LPS3cAEv)|?RekK$(fYq}@ z06>%6nZ3C{;2HSwnL3V`a>kd|FAR5h*Oe!Nj^y*{|KkFT**uaXj(q{U-eKIQxCiXw z_&`EatifqheWY9+i;yzaj;4BACZ7fmOQ`BFduu46*zI z_dZ?EH?CI<9PfKoxkDx9gNcXY$bb3t7Ug`33h5h+;i~LF!B^Vu0YYrG z3gI-!K{UdRJLOC@k=hyP-Vf!xsmza*!2r;?=j~)ppV4D4^LLxLhs4y_^0fi(x!3=A zve6^q^l;M=5Hp;wKz;w)wai#z_ac_>Vo`K_vRYzmb3{rqvjU3UV@`~f`d92MbL3PGlVYQ*t$~x%*U5OT;7Ofq2HYVu*^K+?A>ME^M;Co z@^%ZYy+_Pyk@WiOo(plf7^S;Wla&3wYVQ{$w2i)k21LPH>Z?tN0{`)BMuz9t^Mtsc zFFnof6?V@Q8ZqvS7mR$;mcpqFX$=)5?kd0eEoUQ^18|}M6*RH$T{gb)ol=1MDLj0J za89#5u2Q&AH*uA@tjaw{L|p3#=V!5P-;c~Av>)Npn5y_8t@8EZrFi2#uDOFEeYy=h zif3FJffQ}%JBEJP{xr?iuc_;>*Zbf;AXa-}XO37#R&~hy|3JQbV4CW6rD_DrtrU|u zi`N3^Am|rB1WeI1?Idn~Vc2X;45Mx%7q?$k--X+1lHsl3Cpn=p_&L;S6Xl7$57K*q zP6yvahCWC>MgdMDr&4KY*$ti?%9j~|*Gl7vHOfm?Hmb)6e(Ql*AaFJhG!e(2ZnSyj zW1Egng|WwUZKa{0^XNhN3-IWI2=HK5kc5>5+{Bu28@t$h4HtWC?m?)vxVy`5rs-=J zCflInUs}d*``gjpj{AP|##2j!3N2RUJg$m~`ZX`lYnFIUSa-W`Ir(s>=aihoYGEmT zD`L(mqMW`$iO9Ymr&RXUUVM-{Q6ayNt)KT@T81Bw`V$r<})H}yT$T_e#S z98|~6YBhVPz}RSEHD%E~j#8V^|Hsu^MpeOWZNqezw15(l0s_+ANJxWp3xb=J?(US9 zmJaFe4naU9r8}g%;al7L+~+*+#~A!&Y}Q^e=QXb&ksPyab^#HaTc;WVF#nVau7FSg zYAo{m?Kgl02-1hz&fNq5b3gQ-mH|o}Aje8F^m+(wf$<|);kv0`bJnSE(LwwKz!cqqog0GtcPPLe4tT!yTUfx&3b1mZAtj`9kAUF&Py5#Wj~*vRMFk%b zR1Pd@_lTq3LzlsIR=mLe3p8&)F~Q^H=FdLUX)|@@;M|C zc9G9Yib+x^n`jfuw1HVm3N;fE`rxlda=MRV9AT($o=B=I%^{Uy&PB3IPM^J|hL1G{XlJ#EXIy;XavEu%&z zHXvW?Z*LGJ^Q?r4Z=86n%QaHK21Q3cJ|NfbZCZYS#UC|RDzN}uf5(^jl&qR?G^nN# zYyeGq3LQkHZOT7y!m@i6)2=b|EZhR~kEY=H^Xo_lOqNH%ZQf%ng(xw zJTGf&#}xC(r2MGpv%tRH4r90eazvwq0AMYKg;nj2wjG_NItZdZl}HThI6g~lp6(50 zwNq&h&awY2tEU75kU8fw$z=$*o&7h_ ztP;*6rxc+wCutjFVV~4LvS1a-ZadQ+yg7CV(p!=}& zGLxSG^b9{Ao4#I`gK&7N5t@^^Edxk4{s0S&6Vhfzr-vm@Kd#-XmjXaFQu=n>^V74D ziM^uE;#lp-+!4e6E*L6s3|(IC*m?Xji@f~rlST?6PyrgtJNHJbO>N_n|0#GfLbF5W z>TSTuEOw-yLJobS7!?$ACS|1eLin_@bFsD%IaZm2YDgtwjMxOwx^&k36lV&v-vQK> zI4Ho^eLxde0@hb8Kv^PV3k+4QIZMf+`}It|2T<4!er_uJUWJjD@ytwLs+^;8DjQTJ z9w}Jbar9w9Fzpt)Im5-pNUh&ft){Nb<`+kG>T%#oF=s(t@)c8Owk0o}i<&xO6wWMK z_Tqg96H0Or<(DaHE4g1BHL{d(5%k}A$_dr1BCXQ5^iZdhYf2g8;{!xHa=OI_i#<+L zhGY1~tUGFLO9L4L=uPb+nr z8a+6 zL*CVYD<*KuHF|^7L;3r6h(!Xctm0EGaWjmZvX66UqVMqIwWJ_4_&;fxn>Yu=jGG*F zc8hOv=*3`U$nXk%W<8J^F;37Q9gKIEbcc(QMaGozBgMK zMdX1&Sxm9yYMx|2In#V$VP^XKK|08{(o!%}X@#GM-s(w6c~B3u(@lBMO8=gjahd+#2w0aGjDTxu z08`VLFFm6q{z^Y+NyJ?Txa(xe5i#VRl9@aav%Q^?2fq8M8WZ=-b=2{ReB~ek@U2OK zO-Iuuc@V5DqE(?~gs7}cJCHkO08=lm#9v><3zjH%da0@4nP){q#lpB|GJM}_y=mI_94Ks{nB~VbJ0`_yg1ss@8nk&qddE<=D7FIy^bM2E`hDH zG6`j^M49ZW{#)-4ur)L)FOZZ&Mo#foN zmY0^g{&P3I0&PDuYsK&K!h7dmASr_#xRrJq9%<7=U#hsny@}eMoK$yfeQvvcpCO#F z#p`~1YhGHuxSvT_bHVA&1ogq;<%&_Qy#;O4Z%e6+ zEj4vVF{=}C)Hc`w5eLNL9BDOKmHZybw|WzW0v{Ube-6hF(ucwP6zyP=DZKIg!2qnYH$``4}u+*hB>FCX^&B;N*(r?wdS(B#_%VF%9T z!?`bj-J48KTJOMZAD!9gxl$*NdPZ(8vA73$nWoX|6#hn*p^Jh?-S@TgGN4?u#{g))$5iAWMeY}*+5Y>ew>FYCZi#`wOaUTE5dTliv2hz0pf_zkT>%rH{thqA0uK$Z#` zBSD|$NlVW=3c1jV27W4>;b{>=(#-Q;zi>g}YI%Hd5P=g6cU{|MM%Zj_P<$`=rc9Dg z*}vlb@>ZwmsVPvj{@b+-wzyQZw(cLk{kQVa)dCC0m6{HjyX3mdfGC2?K}%mBIKmAhRqV#BfU1e zCBE4q%i-xcMZ z71JEj{v2ei?YnQ{mPb0wj}9=)?LurER(j)`g%?1rEK!EfNjPaKAZ$aJlIZPI$k-zx zYFgR%EU1z&2Xi^)Q6@Gko?0d@+^w1=kOybrOOMB=Hc2cy3X}&^k)v|B9|b9^?XQX+ zYx?qW?rb{kQ`c8RDXucb&N8RWDXvO#Ad|%1YyGp`w?SS`F40P03dREiks&$|>`LGQb>u zpC?ME{pwf}rPOhbDzii$2-k{>>kFe?8mAkQ#a(Nq8s(WCe2FEnjG1s~P{faQaX%LTk#<$r?@;(;R7Crk@6F%FM0YUDgUyJM$-tSBfG-D{7*Q=RrBO&9A z6@sjfby9n>&d7*ls#)vOG^1)+1Dj>R3I+bPi8~Im>gxaQw60e7OQ@V5$c~_W+(|tD z#eb3B%g-G0TH4yirlx^Fumq%B&Sm#4(<|IQ&>1hVA$UjHGSY2B)b|p4#z8oS+oFvx z`t^+=KVfVB(=(zSCw_caUmQ3B1Rx0^4t#ZGjr8{AhLAyG9%&E*LS=-WJAakLODWXz z`J^P3>{{!ErPGy!S2)uX=bxtlw*h#+JLmdxB$K(`X<3u>*!e&sWsGEw&aZ7ZzMmIUer=xi2b5=dgTHuMOs&1 z|9gJ6W!e77xaX}Qdw8Q&%q^~ROUpy`0OFr-7+EL8e>rZoz@8FwoyhPc4uhpEj=JaVD#z0qB0)?B*i7V9=`R}NF z@g;QZy9y|Y^9^?X?T@$ZpcgyRBTxMA?lf{})*~b&+&*^$9Y%n^zrX$dR_kQO4*;!# zF0HD$c?euKcDVJJwlEBc_g>LVL&R9Yhgaq-glu?)!L9AEsAC=@e}xA@avfE*`A#=!Bd7UV~Ml>qDIkl{}E)k(9Hkw1OvFY1!A7?GvN;75{CVa)gh9py?&U zE(v<_7s*4Cw`QS!G1dv65zqpAkb}@lq9Fp_a6u*y;qUQ10Ll&Q`IBu~yb$Q0qYAX- z#5BUk4SE7%HW5U3H{Qt_!9p+{)n5csN2&&ZaTdt&;NjA(Ja*Agm(;?aP?!9?Woctm zdxOld!I-fXj?%GoF?~kXSr22JbxJjfN;kStS!bu7FcHZG;vTZ8X+!WnLcR~Bv@lg_ zMmXInYT&t9Bs~{o4HA)!SDR4(esdG&Oz0IZOM&LwXf=P!&-2JhA?rIITe$RcJ*CHq zX;anz`kDW;pGf=0zc8K*BYsjf<~K}Y+RPAri$Fz0hfjaHtAz-wm6GjOO+c>=0fWQt zm7_m93D7mO-+{`8h41n6@Byj{+C`=5f_brjJvWY93Yb_}sw*l)^rpdC1U33-Z6@Or zuTjr&&^_f(@79V^!oUFn*{J;mHWvNR$>0LXM`2so486+aP*DXMnY5ofPCHJ`(hQ*~ zzDX*aB=|di{8kunL=Ic7QN6fQlvOW6V?(H=XFC&5X)i&XyTEhyFA8(8iKo%U#o#e} zL%AY%TD-DV61YIrylB_f#|@iIvj%rGTcj{6brNc&_`Bg4aNy*?$3V{E@g7x&exEDOCSS-G_9 zd7Jf|-V$xo8FSKGON@w{;gPw354^`XHtG|Y_ zvU%I+*$j@f3=9g2i_u+K{N(I7nlbe%R}WcYEU?%z##m!+kvn>)7;R{_pu zHx}?c0~T_FgJ=uZN%UbNX_nrkCKZ~%IEFrK^%?mwVvaA$k9N}-cerLupnuz)E@#)& z&Mq#Vy2m{5Kw0T(z97nz`uti$NJ2CK1tH-Z{Rf(BrVm`{D(j69kI@8Lc_mT=SarQd ztDNoitd68rNwACs(?kYG!XLJQXaB)kkS-yGR2SxZ0ddEZJ+FnWTDFO%`~mbTrWZR7 z(oKS9k_!6qY9OL>+>8DzO1Dogd3B7VOgBn|sk1XM)X;DK7o%?cbaiw~+(!%sk<+{2 zm}_ck+G3NTcjU!`)Z&W^uIk@=vb81>3={~bp`t>cljVmTxHe{MAxvktuL20O<;}KM z>d^~QV@8vw;PnX+eK9J2DIpU`=@eIG52W|&Ks;B8zBOt~O{Zv2YeGQtvy5SIWxx3S zX=XbH7!0vrWt1pXsjAVH6MN`vq6;c~|7`lyqChU*5sdrSB}2IsZ&Tpc}Wc5g0sAbf?ti%(q#VVfTQB7b#C5d?QFo&6vjsAs#kvmNy41EwJ-Za9$xUWA&mpp#W7dp`>7uVV0%iWQ13s(Kj@`Ug0&;7hi5$%unF$? zt6#DIe0J-pVM~nRa(BfB+;dwW4>q;WyIlWP2Nt&{$TGF`r4kqi{;5^}#zqI{O^M)(h5{GZk={&! zl44tn+87u_?8hWRv4UtHA7JZy02B$(v{K%F(kCqnGxug*m;Byq&Fbm7hNP3IlH(m) zdmXpt?W5G|6Y9MVd^zL$vANIucvcKKjNc{x^dL``+Bb=$d@gZj<1Dj_px*u7WxxPr zNt_&wiJu5~ueiI9&t&vod?TH869wmWLIbUlnN|3;+M}e*Jvk3uv93mlCoIXt7TQfB zC{UJ_D6ltB3BspR_V=G5_<_i1AYXpzD(0J=3qp^bjt*{anl8)#(pI`a@347uz6)a7 z0m2EO$IfP<|M*9MN4KjH)Pwh4ncy)2>W@awY7N>uBqAkL%30WCWqfGqYa7r(A}5pz z`i)0x>6ctw8?MpkAzYHi#X(k=|E~W^*Z|fg}($mw2 z?2sieKQS$w-_m0B!v%_1OBZN9)%-!eUFZ6Wo0_-+_Q3jcGzPKn&B^+?b*WVXEtnVv zt$aZPZecqPeE5q?K?zB`NrojNKNmNUgr2yM&JJ2}b}-b5vyG z(UgG1UPLBzDBp@S;ANg}OmQTHk+C2GHD|kVWnEysthiXuHkm~vtye2QCTZmt(h{!a zk}(nHduvLuh~A>&xEBg-yITxO#rf9@yDT_;471v1uA=H12ksr(A{2oX81RIAf{9f^ zU+W^Uu(jOJLJS@^xdAVQsBN^~w=mWI6v^I28LcNuB0iFqzFG-&3*<8yQ_YsgwOUn# zlA19{txAx#(xcJFF{ns)u~N&As}j&FbIshl^QK)~>jqCI1X`1)dWck(2E;3*!@*xWm z`rC<{RDx>->=fba?}}Hzx^iTt9ZFV+-g2m7%9-0g0hWHCL0LLq`8$DtE}Tt7QyK6r z@MiWrPx$E7t<269M%BgYpemX=Z?`Cg&%%hu^CYjv=gt0EK^(M1Y-zssF#4nL4a3~hb4D$f*HPBOTIzoze>N>c1LN@BW5k=)}9N3y|TTv8x+Mwo{QXg>!8)BV z4>yECiCi@+9)!$c;INd6Fbw@#$~XYKCc_?J`_2dRAfFu+ZaO+TTNls&cNT%R7v$&M zURdSE1E;Bap*t@U2s7Z!=Hbi9$x+Mv3MxOnsK@c6M+1B+%fr2vq3%|to*v$?{V+$^ zyP~hIqf?Z$JBr)M5#UyuxqZvs&;L?It7F=8ORg zXZ>%tkukPu13Nd^9;GZG zbX$^D0;APRbizhT)Ca1bMYd#MZ#YLmKA3Y@5L8?SdVkuu1qIC$@~tK4Gt`3l6Y1>*_AFc?T0P z+P9<`*!mh)k}RCE%>-;FL2{4dumhiasd~UrfL`6Uf%$r!$X=6Da~UKzmg$TLsM#|~ z#28Zg>S_r~ck?k9XMP0&9|dKC0STPJ7){##x6d!WY)=I)0f%NOoB#yTpH0O}!}IOo z6RBzQ1@cU1skFx#I=0Cr3K_r!<2DP&kJXlWRbh%!UZsn|l7Ivnm`77hMK|1JzT0xp z#}Uq_5^Kt!g^PzOYKWO%maIU#XSH`);Wn@~VzMso_)FYNt59Se&VAT#z4Tem0OBV- zD(@T$qlKf+Y%^vJj`*#Lz7V@R=OZS*r9ah?)i(Om)QQTC)I4-#Tc^H?HsYVx(0Cx zYOGHKkvQf>#5gB30?Yc6pr4J!=*Fv{MdgS&Wtsm|=93q`1A&mgcv!DCu-Z_wQ*k7D>hT#B2LFrt;Yj42tQ;m>LMnZ zCcDAI09_fK)zC((kd)}5D$+4K+5zYSwHH(mG?zi zk3vA7B?b?*^WnUO%`=~zsmr^iEy|Kwg&ej=vUjYcBRHO-E-%CgV7ml_)6`@?Z}FOH z{n~L*c;<1v=~8QeW*}ovWxM4%<|#`?7WkEAc2q0!kSA&(X3#o`0wa@G;}nEyud4^f z0D=7%0va*dRUXg}f9_#J^B?&DNbcVP>BFvui84>urxodiSae+&T_#n}oKVtkb=D)D zZ>^r^bTVULAoeIdYGH;GHZri0Kdpdca}d2ApG__Z&Tg_*j8a&#QZ? zZ?!-I49>HWkuNKTvaH~#03|})caRI=?`#`S6#f&A4R^-957Bw4FhA51^sd$gyR${d z^WDr9KCx&F>3`lY&Jg;U44Z^jlDy#PBjHQOl6_e?DwKGABv+6$Ce1KP=5>A3;uhkP zAsYXaqm9Vti>jI72$7pV{~O?aWBOEPFKx_vzR)04yC%D@;hLPn2VpQ zHE3uD;}}>f`)vxiBdAUj^pOZXuG%{}IghC{!$yDg>@)Iwij!|QNyp=SFVUgHg&SHV z;#Gk1kO>3uG zIZKBiFGPF#a&d9-|CaiZKX)9UUKgO(URYSjpK*OyT}}Wv5d-S`@d!OlO^UE=F3o_P zl_c;erzxU1*l1+qx|M(bUdgi`T-vaAnaInWaN!*OD5}hp_)Wl zJjV(8-X{T(!^2K6G%!=f5q-o9S2^$!?5y!-HF>J`67R0Fq)yaQ@iS_{>U}z)ha3ZHPK?5o1;JBM z94?kmZbyP|7$o^L24?bkGiW7@LSCVLD`RWQe>p_^wjOwnMp#=vLG4)NnCX>k>oBp6 zJS-?%s*k)=z`a|7HP#V9*enx$TtmBWMw+WEc&?MNkNp?_K9vG2*C0xCbaY}9-Kg6X z-c{`EYs@#@EL-w(*7fdP_n0I7r2VMD-A3b!-xgP%7{D~%4tW^Pi?rX-YpMB z-zY3~&`$BTedsv5ei^mpX(FX8k(lSeub0gu#t?{)8)c!ena1;`Ux+1vs{G|Q{9KDo zd{W<@M8qi)Fn<#u!INauCdI~~OH zOqc1sh%$LD;Igdq7a4+9bc}KZ<3`}t12Mamb#;B4o12isQ)E0Z9l*3oX>#K83k*b5 z%fdOKuK`|X6iV^x-yQgj1TtE>UwC;+FjoMn#TPIN>RB0c=bVZm;`Q&9T;&mkEO4~T z^KVyqmQ^Z9Qj*{~;tfohMot2AP}!oK&g6n;a^p^~!u*=19Qc0gSTyRJgRH6h&@T{= zb~Mnksz?A}CYM?Us>mr)NDIC`&LGIpfv^qN>Z%dEM3LryCYFcOXSf?y%miExKx+(c zbx=1o)_z}nXj8o*Mz2M82-O|Mqy@d)GL!a?U7*s|qD(EnXCKT2vjU)++PZFb&HUS;tI_8*c-`}Xy#z?ev$H9WHUa-F zKS188roKLH7}eC&)T{SX!`M(HLpo9_r%ou-RBKl=gS#XBksoA!K_>@Z&F!%6!`a?t zVARvdG8a<~^3&o_!{x6^b9;yv+6*Z5GzG~uEnq2We)!MQZoe9g707(jLn)dSqZrs| z`+6W=+K)pX0Pup+A74t~eky%) z{YQG;ZE3Ap$`&z21XUH2e{t74f+=DER>yshFD};9)ivZxueflDTrrnWSJ$*!5Sfq+ z2X0aBaLRfr3sNvnV^p8G4No{(BB!O+;Tma_+f}S#HXY^e>1z4=eqp8%B=8)2a)B&R z0kU8F4uAUKe0Fj1q1|C-Jx%4204}}jx8`G0a8uC87wU=op$;^O+!LL z0s)v+fo9Xv%8Knvix=B9GJ)6VlP=x_4GoQSYmqb$CNOato2a!$LelTk-jl=i!_>1U z{T_P3Eusg>jc39{vTn$;^4RVVGN>boFGyQFJv9&b`e#y_1~qgR>FTagd-tN-bAsqkJ}Ah1+Wa;A2g!cl)1)pf%Di~slbF&O{H%+@gZ51LQ$BYlj}c!b zU6iJ5D58U2PId?@3eHsa5FCUW6}Pg z$fyJiQDkuc))eHn&}S7p4U{{;1rB6bfIIOLBe)yyk@;^|58Z%exZ&a93hI%mOCZnL z-Z%nK7n&Ac0iTtgemL6|Yc_RR%7pbJTWMfa=m_)5431>ZZ=QF@#fc<2Ca*Kry$ok~ zK+-t_YIoyl?6bihIRWF4pDvr@z`W%ua^Udt%^ccF+7fuU>BCUED;y~^gSkmO=m<$+ z^DUlb9yf1li8JKTQ-$JHalD9HbIMv7@4RGBMR!gsh1)1H0nXLO@BLH;nJG|2^%CMG zJDEnGMoAG{g=B}Um=E-A(x#^B;7fX~^3};raVGY|k+fgrb^8?}ICUCpq^!iI$k~0% zc0i{xrmcVvZ#AlX>LU_QfwhoM2<9&8lUPxL^1fh*4)r5Pb=3QZEpq1r2!6f2lF$SQ zP)b~%46%GaonIpO*WaSCO1IrBJui=@W{QZ=tKDn=LJ%k*0L{VmXc^Xs7+R!aS3-_M{fn9%Uxn)0c4yak#b7&<1UCgixQDGQ6^R3w{z1@Dgr7XTb;L3z3 z067ze0_lP4AXV30?_7=`-xdnayR68sOmehqY|j`%fgnDN-V8Vn@(S=63OwhpcZsR0 ztp$n`Qj9mkPwn@ku37i_gG+!nUuUY%C_8Se|l$)Jr)N2 zz$M1H#ic#CwFPdem6d>}g2JGU?9$v|1Pcp>Bp^XDFzmPG#Ue|`U$xLAsQbYxeXEV= zU%R|`l>9GmDG8YM02B?xB6WR=A%A~Ls$1gv`U_5fCA#O@)dbQf9D1qlC&-7_EM%J> zNC=ruAdY|5KqFSuAdMe{FDd#PBfloGu5p-+x&N3|Lvz}X6JDINFxiR#<;85wEr%b4 z?SqBMcfNw)rE&vHx7uelUeyGOp4Sv-m(dHUc+ zLA$zu74HF?ZH_O{UI03{d7j4wI2$;-?UB5PFHVs+w?Th0H9&9wRa8hNYhk*M9?cB2 zT1+J+(+cWY(hLB-eMMHE`2GFrUj+9Q-o(!CGby(<(6xhjJ){4B9nuJ@Uoa5$xLk1F zJIu`Z(E3t%=7==y#H0+GksF{q6QpRn{wPF-wdCHP-DsqD+Ki**Tc}vfUEE|0+6s|I zrKTyzxr+=4>7OPian@d$%t|)G8da4a-GWTgjLNdl8apFIr?RyGb1?8-KrHkqoBrNoy2id#8d@@?h z0RmX?E9L<>U7S1JF=OTfwmiT=qIs%V-35z zO@VOq3rF9b1!3%?=oikZK2->E=c<-50%QqHRi6>78txIsfx%Mo%L<(S;~lj44hHBg z7iAK`2KJZp$;00f^M#g{)=D?FFgTE)?gLJ>-v5V`*rE(zxHs)fTfpNAoP(V6U2Lyg z(cmT9_1ZS4eG-|ptO;dyw=&wlw6;MP52=tVp{$M|Lz}1Tz9Mg<{6?;MrN{A$s8wXo zTJ{%Mot=?IePZ5x#DZYtU*j~2;43+Pw6v;hw3=J$hj%DdX=@Wf}t3(O-VvUR@~OHY?7x-sC=@u9dP(lHfmiD+*LN`Y}z-LkB+WO-V+wu?q75SJ|q!_@-JfjtR1j| zP1<(peVf&$G$Nnjd!qq+(bPN7juJ|m!UxYZVJa^)3^D?#hgD*Etck*AA#X&;8u?Yh zqX~>jmpm3$_Ig3&13)b?t>+s$fqW8-TwuZI86$Y~~z=Q zaW(5UUdXJ+Qt$7WL?M8eU;Ki(j@ zj~h1=^2XAMJq`u@?Y;S@m{&bYUiB^ysiHF9EKMSKKgYQ%r@Tn%yvyjjEAtIi%}owH zt+xSX2TA1irF(!;2-*ZY8aNL+hY1!fhx-0dk&i|yz$A~L-G{UHrSrG)as%nzzoNCj z_uQ1R~nRDGN_Pc&yvRQDRvWzwnke z_Hy=>Q?C_WqPbnG`O*u-sOC1&Dil;f^PM z1iGIHz-xhWh7*G^OyX9mJAk}LCQRjeeiSC>+>(tSqGHIdtMe?zfN{?c;+vXj;e1Ch z!(4#+GR#j)sM|c!l5jQ32}QQpiN~gV8U(7pV_WaW0h_QXnP8sKaJ1|#?h+;}E@bwp~e*91D~eJI_bu!DhTb0tqD40OD<9P5DZbU%?9 zVE6*Z{Z*QK(+VV_ljNTmu&j9WMUvW}7`W1C4!To&R_r=|3P97MqWTF}T6-$5v-XWj z)K<)UwaW-c1-HKv(pp?FN%w(nng!3NJ^m>be90brah#KZJSjhh-fe4~qck3oN9OaX zc8Mb^3qr(smPT1buyyez_hZB%R=2z+7|qS@Ky09#NTWr!c2PQqLV5KtCLU24uiguC zE3w<|L9AkHlFJ&;;iaab4apvJxJOo+-0kZZb|jg*k#e_3pPrQuEF3A>QLqY6CN~Ey zKcYP$V1>Dl{#amL33n|)@llkG8CbaF6+`?)#tzSMRLJxUx?GpXIZRz$0UQc~Sb+i^ zB;>(>(lCQDKqU+`asYJzV1c2D$y%57^%*E8|K0(wUf7Y@gD*W^1>|Cb+J}Y7{e0z; z0ZJm{2~*51sX{f!4uhz}_WIjA2ciUhL5xUWwDl$lwIs&3UL>E< zW3s#rUR=<8Iz2-SaSr|YD!v}Qqr+I3bpSbR`4I#4K{DjN!_eznC4BhI=h7f^V2+Lt zD8L2dp*eWr^rw(lQR(Pp6r=WFM6Kf;4P8H1c4>wMrWEQ<;_i`=DD3usOCyaG03_<` zOEE}lC4!A`eRM0&>Z~z}Ohha5DL#h_bAiHEdf}|wRZODQ} zL2;yJ8mJaVAN9nZyeW`6G&G8{PLFj=iHM1it}k!2SXf=xmmy{a;@mX{c}ft(oj4K^q3F!Z8?t8-1F+^1t~dYp&6t z7-@Ds1nzy{1Au-9eMrwA{r3<7aGV5{0hoA}&%xS@E-Q=)Oz7(ANkY2)0UE|b)}{f^ z+WVGb3SpCuq^dej%mgFnIGH-?`!5j0%P<6W@K_}#2r#t5LmDz8ox`ej=q%}#4cEm9 zP!~y;D_&r;D}4$RZWn%?TEQnUJ0Ge0)VTKdDyyel{7PGVIb0$3JjaVCenx=i{xmqaFy( zUPd+ozZXW>nEdC#+hD{oHmOf;90`!a)n_TE@TMJ15$xWhmT&B(x>9J-`YS5m4|N;OOen;rKzh$ zDT^E9$BOn@1(wi+Lz}dwY;2YpOVb3^RJtIkGL71Uhl>eKhPvZpWL08^*n4KzSS8M= zd~F^lN=R! zS}TqnLxm4gv*7}c2Bz9D#q>~+T@$4;*Z$4YwDr}7CdDOhdw(Hee5Ml z9$Ms&0~0q@bxzsu7Y9DPr$*Hl_Ly&!L4uLjq1P*D(}@iF%94_j;jCRf=r#HOEGwv- zL7vJBE-o$?;ISHbFb7c_F$5J0AdEvrOhi6!D7%^rnZu~c%FC+U?UPo_T_{)9<|Ot| zEse*7e<6&+3{&5qx7qOc?oCykBK{F8-cF3xHwB9d|#VW;=b9cwQT^}Q3;z18u0Au4izIK3@gT=XatnA~}F%2wU_H13cNutZKe z_u#FUngEYdut~qPS#TQ=_&}drJ}nLzzPNBA^=nrY&IDh@Rxr3YtafjgmzVX(qyB?) z_Mi4C4<^`@6uZ5sw)Qx^#rWIN<;K5K`f~v&mUprY04SzY%xH05i3RTG-nr>16Jrp5uZj;88_!&)Hu9~)HPtI= zVq!GwD4fgNc3@p8p(`){v~T^?(&4r^*KWWlmWo;_5=Hg)K@T&0|B9`MqXZ@wqMyltZ1|w?;n#$ zDyKbyyptcE;`fS>;>Q+=N14d`4qzg4lOX2#6$d$qTS6!*84ac5PV7Y;s3T%`wS#bh z;%3rY+enB#;E_teb=XoG2y-+r&xOl>J}N}^s(2gNU)c^^Tttz&rR0P8^QWa@oJl}V zdPD9Rpi=xS@uuzG1B??h$X}9sT~T^p1$z&$cwftb+vINaf5mXY+&<9ZNt92Un3(v3 z>JfdR9lJf#pDhRow^H)KyZ-7{*{ z93$iXc*2TyNhoPRTF>e*s$FEY4Z9ypO8ez*ez^sja-6lZ?<9BoJP0VK2Ps}TAC32 z`D;U9SKg#BZS3{!335MSmcts#5&^5z(u<2aMAOPZQ5)hDfdYE84$SVfB~h424gHs0 zKNl>1?mNv*j$d>AZPz?dC>vZ)X`xJOFjm?~GWY}(>t)zO&<^=;k+%jIJb>2@BI;UO zhi!RUe%`z9f42u@js1NqFs*xvfs||U$1h*X=1IRDd-C=gt?sA6uuE7r{DGyHdttri z{|VBzvp1V^BAqAJvHQ45+y}IG75q{Z|S-W{sMbSBWBFFB>+tIf?U2Q3({9QzCM}aTykgsNw9D{TEV>dd=!wfdf>;~9)HddL=@GD6a~AN9Ce-@6Vy z7nkrBM;QsgYmKaL~uhZ9(MY&*~Bp*T8<& zl1U!t3#R=Au2%hMzya+Rnn%v&L$m*`l*UMLeAHKgmMI@I4u zOa@Th3P7AI;z&{Z1TPTfj&0EH zERbJ>c;TBoyr-pP+;I85gO?Fl?AxWw8DD@l@7I5~QxUygy`%mt}^3z1V0ckG;6}Ny(+&GgR)Jy0Eqfd-iEOcB_lK)9kLp8ZQY( zG6eZ~pE_&|5}>vR;;f>OMoIyIB)Dx*4y-&_{^R4^i*;B{h}}pe(FEyFnkyB(Q0YzIZ@2{=lq7+ zCu-IFwWyaj%=5Oy+qSY%lomSQ)8Iey7d>_owc20bm4G~Xpbmdyr)kVf@@w~;7)xC6 zhkm~^zGO`b^X3+jITy*qM^0b{2iwr>l(h74;S8usk6)%ia`hDVlyLKsj<1f>jE!bk zJ7a~nncWt18)`ABTT6~XUvmB1?f8R0Z9MhoD{e8t8y$+UV^?QVU&UGnlsEe6o;NKg z32+E<2o#qnd2%*lCLXy@sxGS)R=7^B6bM+a4;-2`_`V?(uT{A=w2CqQG$~5f4_2=t z`5oYywttD)%mG# zpFhytd5M7Ob#=9P&REtY8v3(CY*TRxQn*D>IM`mfjH>JrW#Z#(K#MU|j_|kkp9*6dq91}g z{Gt}TXX=n38(1`jf3BUbT`NUXiqrpHwSTtSfBZ4THoP4W^HUA&)|oH^IqQ zL~NU}qD!c8i;D1**eh+B=afuBe^xG&+j1z8oflW4`9nku?zh#ki%VG#iC4)bx8)<< zJCz@X{FH@rPDh^sG^<9b^oA!IId#}gJrS^a&>`wP+HltN%BO}U*k9+5t zg{(!oHXPfRHy9U1x%ZVS0UtwX8_=;lb#j_ApA!e!^2`GevqmMkl_o(ur>2d?{9P9Q z)a|i^ODF5lfMt|iC-oD%lo$!4&xN5>z^;`cusTX$w6ZQOU>PUF1W%H@kQ0{T_zGVQ zcHP6!?_M-thi>dDn6@oJ1sX${EK8H8U#?s}N!!`%m`L^i5%u2jRR90`cqub`g=~_& z_smN6jL1kf3CZRlGqdbHvyu^=Y~t8^i*W4Cu@8>%dwBK!etz9<{ZTi6cs`zw=Y3rF z>$>hd0A*P5B4=r7%I|)lWv&8ow+`Lhv@0wu6m{RB0Iw{M^(7dpcvLj^YC1iLJCuJ`gKLs z@^AxrR`nCcGvp#lt1Rs4-yzTA!qB(I(eL5A&QHa%@Zs3-hSQG)XQmqSy_;{{r|YUn zwmdqYtemnI46}1usgETXl>rWUf|b`XycE2G2XEiKi>bC5dQ%1zPsu>j50hs87m!Xf z`9k$eJ2uCPN~X4r>)u5L`oeyKodiI-)D=rdK$2kh@sJ@$B`)~9PAn-YdE?X@ z_5Rn=k3;h`JvVIKF@nz|-gMu{-6b5^(KW#`cn|%=J9D#y zZR^AvYorTV2f&KmM6&rh&o4Feka!M*^2#4|=Yed-X2>(jSTpw=Sa5UpVXciETtF(s z3zh>H+DIhOZoo*&ZK^(Y*7zchxqonwxQlPVI{sOH>(&tYdvnXNwrH~luX!t~k})Wbtn7 zjg)?f9DI1g0Rvk2!|cb|auy@|^yL6cekKu1L`qgxrvgSSfx)+^3Y`-DQcg}zUJ((@ zr=X+brJ!C(2FwvOQOKnzPs=5L%gq&{4)6iZ>0i4MAUB5bh zlQx9XLPq}7wsyr7_&&^W&ZRpkw9K`wlU9{lbaL*`O`X}rYF^&+c>Kx%#-fZ~W-Xv5 z@1q&V?1^~NN7sb(B$$tFcuvZI>w$xiQY>R0QmK;FsF2BF<;r;;hXZ{UZx0O}39SM< zn26Vni;YWc)l9;A!rxONVHy5Z6 zK6ArgOeqc0d@FJ;8_-a5#Hcc2nQcBNioEQO_8aODWdu^l`>0hzM{=Umpr_U7^5;`K+#`a`-p}?$?PfuJ|(Cj+;`?Y%$w~^oH+Ac5ly~WpN;*F!qGX>b>m3gtUwe zJ3%U28Vw^qBX}dBTzJZK*lgU~i2305+J_fCqwWI#n+q+3BdVL5um2>Q zd>qe`i~|}XP#*zqTuBKVRWybQ$G$n5q%!fEwT&3iKrmm<#}1}-DO%yU|IVr|4*Uom zx~2xl`vpwcfK1M)tn>JobixQvcg41X*XT>~;~Xs?nwhkHugg$-rZp6lAd0xy7j>Uo_PNPV_~Q~(drPWnDy2iw}hdC1e; z_sXfIBeB!~0IvxNXGvXLVwc!q5_>LPG=fs!NW4oYLfaata-Hn-P}n$5v3DkPKL0pE!Z8mK4@v zL5o-!`Dx4mz)1M2CX|MYk`mu_6ff6|D-iT4J7_(NrT!bXi~iRq{>&%x=G40}(=`_+ zsZp%QzT9)g$;rbN=`x|JY#MA&Qa~yoAOO6>oAhk}5k$WfxC#QDx~q*_qN)M+(Z!<* z*YjR7eZ+SS?+L#-iy@<4x?nb^fQ=`7Bk-;iRg9Rk4m8c+C&ha!5T7gfB^~yvS)%2Q z?z4-Q7reVe*UjU}xCi#%UHMJ;2*c%vt3dgs z9CycgbM!GlN>5L=Nx_}Y)QKQ@qVbs-`yr313qg*jUOMl+jZ$Z=O7#X`SFDNLy$yRY4V@q_R~IPvs%y?&;XdZ_ZjYm-yy4#=A+r1uN!2z zm`wY$W#g9Et1H8u6Hkn`3ALuS1*xL7Uc>{S3^-^nFDolA-M3(r)LIcU%nFG?R^`AE znk?oHC*rQv)!@hlTAZD7U&k>6aM~H1Ddgxce80iKzbkv*GZU2ml_a~LO}bgHEo9HH zh>>^?s?B@|1&U+K|hwizr(HyW~= zX7v(rpt+x}EqVQU3FS@uHn+H&`lN_y%Jl;Fn@SVX?l1VHCowd(xHZgOoiBk}hHc6o z>bY09o|2snthmEeleqzFwE23N=f4}>uB}s|=Lyz=^c-b?xmx|)UbC9N>e-dp4i}`q zD$2TAIe(r$qK)@z9!<>xcQWZi{hTu9>6g{tQ7n^bh&P8fDX zn5tEg^P*V4crT=1IchZRJ+<#EhXcH@DSS9`;d15Nbx?aIu8n+!rAraNKf2J~F;i&ZT3)NMU@_O@R^;-E+~e?9A3lGazuZ|kW7V$1ag)|>Z466OO8mVqprK}{36+&%IECVQ*j%&i>BYczc{vw z;sXWbdjR}nH~)v)wCjSZ_y{!HV?elWVgj}e_?@S|wAYj_0@QG*!xZQd^C#?o)Yf7J zvj;X^#Dk{S`%2oN+&J@ii&hN(IHGgNXVx&%e@wGbmTvqt?`uatu8cabHOjSh#;U~t zqkQGZ<#~ay0i5~HXG%a?; zMd}|&=FR}5sKdz2=R)(q0%X=ZKv@7@~>W3AQ1hFzvCZxm!vBSmrIP%FG-E#qko$>e4mL|AsX=5|ZhhL#?d&%1384|z z7oNn9;>ymcZzB6?g7g25{;>%t=C zI0^(c3_^FBRQF5rlSa53STx>Ear|92dorb+a5}s=oNxJ#x6}JsaV0~eXRyVUD)R!l zjZLYqi8!F`v99g`zq$)GAl&?~GU2a!tB|xBkT>zRidST4X$fsicMSY26#Q&yh-(ZO z<&_&ZfhOrx7jih3y`L^~ne=LeYsSn;;0$@Mw}SjLN1oZU_8U@?8_v#4mNw(bVww>4 z?C&@+Pi8!w@+CI4rakMgm6u4pC5(v{G(=M#-2G|lvroeMt#p`!%Fkrkf|cC$SD)iy z8TFj7;G<~gj`p(>?O?4!os!Dh+V1gj(kqC}@jTsX>1~IK{R5nR_RV>=D?rNL%{Q_c z{P{0vhZm`UYS7v`6!f%UR&eTuNVz?1a7Dg<|E|WuGNux7$e^qeXUVTPjX(k-c9`$a zY&AStM|NM>ayspVUv18?k!r=%^59%Ud^zI$96ha!JW)lBn3CN^4QllG6BA>Z%d+w| zBb$qEOfh-BK=jaE$@0wu0em_MJ*Es>ddv(Zuh?g~>cPT9lSzNxCI*EE?Zg?#2tF02_O&VkI*XZexVm&#eb26cPr#!mw4LcA(Xp)%gRKM-1hCclzE`QPE*dr_uuw}Xd65Qe&VNes>v$Zr4( z;c%}3aoF~Nr}8tm8cQrg)DaI458&0*HdR&epzp@Om-z;FPJ7eOc0 z=)8z#lP%HrCN1xKNAhD))lz*>W_;CFtARh!75lYlj??|yqZ5zyQmONSG`fvWSb9v8;-?k8j=0|{UCS4774dGS3RrjD~iDSWFkeP6YrpB`N~bE zMMfo2K5ZmFCrPbj&0Y0{_3M0h`74^vsSLag>I7WF4l&WMYr}B+t%92KMp{&d4Fta- zgVibg152{xOkU((wC_JnWKfE3rfhqMf)b;?%S$=&AyNnfWPbnsM8!7l7Sdeq@`QS| zh3ln{SG2hw)|BK>Y}Wcq7hDVVl*={Khi9|1)S&Wt=>TS$fYIO6W(KMYg7ve5Wx;gy za?>X7ub7PgO1nQi;KTH8(x{mFi@YmQBIOnJ9r{5$lUK;t3G{Es>wKJ(C;6NfHa5vs zoUxX7%5lh&?weNTend^?d+7Smv3zf6;s!T;=a+{(jY^!B@|&L?e;A)UIxcz4N9H&T z`{*secpCG*G`27FYy|5(a5|MI-R_R1)R+csBTF%eUm9@&<&e9O&We01ooDP@iZc?&MZf?#L*B@Rs zANss&^bDG-*wxDD8!^Bg8Dd=WkK(IPOev*;)^O^*Z)NJr{ID1is#JU|hLiAOBOL?2 z|HofDwB)qav;N9_?+GUK8^gy#%ho|Nr{zMLFR>~1nsW^__Ek^Gb0+LZ-U^Qx2~Zp0 zVlxDLirzwpU|$i~{S5vzYu5jFQ?Xpee;RQam688$MzntEL39ut5i>aov;sC zux)JQi?JYITNm@cmIOtgrH2QylHff5u##Exglx-o&1g`pO47o?Arb(KgM05hA^Q3$ zsi^?o2Cmi0qyj=x>S=}JFFrmJ->Lk)PMP0IxK5)@o%_A5i`E|Bg5_Ai8h!hVz5m57+Iji^QFV#Fv$f>Y9{@9rb{bQigofo!s zgF&ym@i$_F0OQq5j92pSrVNI^ut?JiG)Sqsz3f;VmR1YkC;;s?zR9I_FfwamV#3cv z1>8h4W^Gc4aB5~IAR7Z>A@Ds5^LzQP0;aC@H2&mE2>nJ3K?DJ6=kQx$G1oQRPKpG5 z){1>kfZ~H*<9pd0&~9rd67FW4Io7u_7i&gf?YG^KnuR`XR(w3_xW>RB#c zC>#K1({fnLD(o03KUudCiQzXwcw<(Hx-#iSB%D2zT%YhF|Md{Go!k~t0`Z74P@@c*xaBZV480|akoW~SK&`s%k zmngSg`IK@)6g1@Ps9aW6Aj}7vledmeKMddg(1zz6LGgoDAz1Ku z;+EwRr$@)?(aojWuX4#lnLG#Oe1*+U0G^V4lq-)4*w&nN3A=h|wL#MoTVL`CazMDw zNU}c`bGS|JF)zFH>1K$T)4)#w(wT3jr*Om0cxB!8)-lOu-aqvA@8;a5GI|8#4nOeM z1Ef2UBt)F%S308~%>vi;FLY*D49y#$RTuTxqt?~c1)bwjm(2CS|D`7Rg8?Tr$XzBuP@`6~YUTm>E;-Y48}N5B8j>Je95JdjpfcG`Pa`KzH*|JT66pMciUfYuLmKD|rU@;9I)PuZv;x=2e3Ni@?-(%Q_& zMg(Arb(nqJV(;I^@Dq#jPwv#c&iQ)wm-^@^d}E#VkoEq_J*|9A(M_GuoWI8WyxTu` z{_aEF^lEjMiP%lX3mGpAgPTiwZe9$Y+#HCny$q)F8s&V<{U(o}@xAuOT_xaQ0_geI;io9a zz1b$%TIYW)fwRJVAKR2_-fsB#6Xt>Y4OVPQfFeJ(_w!Z@auNLqm>0aSZtU4Ak=VKX z>v&v6gt z4YhrfQzCbtM+AQmY>rdhy~+dgBT#e?W{AOdb~ue3Zo#Kn2l`+_%$@NP-3&=Du)dA}KC4J7dh?K4d66{>lig;#hZC|H9^9rGY>OECa zj6<6Qv=%kp%L`8v7c_i8$pBSCkU&=C_hYJz_>HLeXDRsXZ2(WJ=x=V*SZ?)nZi`S3 zP0h5?jHRD@(C(b0I~;B`_Vx$FH)vp8#4h{YnADVctzh4Nu= zaTLqlTH!Q7br4weN`XysrkX!p`>8d6_j&=RCM7Km%t*l!>RTGxj{HABYUy`}OFx*r zfsu*i(CsD)MeUt!3zgj->1`zHc4bXpGSAT}kAG^NC%)sc<#(9~#=%S})h`c0ET{X^ zeG{Z*f^G`Ses#G|7}FDEI#o-ldM)?q6|!=T&Ha6qWS3ajtu+TL2YSAZ(w}6m!be0V z(azQQsH%?48V33gIg?}~u@?Oe7*GZVA6e*Vjb$a3cD zQflzl9Pbft*bWEzoBdA&xyQU88^jy4P`NSB@yON)FeLxT@ce+Y1!6UoFs!@2 zI7{)s<#zoLPb=Zy0Gk{ozbCK|a;QlDYwc5{=<#y?6IoBtji~EpxZ0Nem;~%|E5p!^ zYQTj^__R#1PVLdzVEV6s_N1b;05gp{$KFl%dax`HQFnIS3^mo&Z)X8|?D02+35+oo zq4^BE?f`C$(HBh!XjqVgww(lJUxpIyZ~mo%AD(qDyI)~uF(IV5@yW>d48u_R%I8iv zv#$7lN+egzEZ01IBQjkn2296z(ObJ_f7r4J@6n_A&xG0S`1)&vp0UL?EDTSb1er-K z$~xNilLgh~nSYhLBfWf}O6xJdq*>?O(YDacw(p+8$#YYMn>j0iGdHp?hTQyicLRwx zGGx)K-Z!ZF_Y8xXSq)mWHy2ZhOVV~T3`!j^Z2D0`)rzOYa) zyDwgGfESGLN>Z)@fb63$P~yOAlzP#P*t_cF*Y!$ATy~Jp;G(AJI8Ah20qpB(5UrVT z`66ZTRLfTJ{>A+8=Z`*<<}LOIL!#jbu6jKt^a7kGkw9%6Epu}ejB+=gsw&%;(wye# zantbm0b5HJrkr?YTU3Gz`y^FyxzavwN(M^#3^i$MLzdQ9!le?eGJW8-WerM7kf{rw}rOnNAyij4i`QaWM53;naFfikN< z{9i0-*7B~->E_56JIxE9#p9#YA86$M%^kaT(UQRN8{rMV_%72hSmp$0F12YFE}VAE zD|>d{!=eVr1^T6YGBTP_BlNZcb)7)QU{5MFP0gcGRUY#)D?h(XQ2qS>*+?B~w5n=$ zK@7%AV7z}z+M1G4J@X4V#hHapf?;KxV5(XGg74WF-7zrO5D#X$q@ewvx%`l3uMyVh zB&}8L{JL|o=E_?608aj=g_Es?>>FJ_9b+DyqJm7!$do!37NVH&bG9phIM*CWlCW@G z=n}&|*?aWMJ{}L1#D@UtK~8%nRwDbF$-P*YFW>gqkICeZ$0(X|U53PaTR2^KL~T8f zdu!PhId;qvHq=9!FWCH+3HpMJ#)`|^l(P1c>n&X=XY7pT$X#gR4P`iPtalPstVVZ* zZk1@LSVYP#VZq4Qctrw!jt_(`Q0U{un*T;6p5MSuaZ~Tj$G7TbpbIZJLPd7^fSP*5 zwjJO}6Do9uls9h-#Iy^(v-v+OIw(?#~A0SANO_tZAkYM@=t(!m2-|NiAHkF)x)`{UoP zFU|g@^mcVsmIGv`7q5?=ieFr~T_Mz3BzX3^*)e^_Hcph%Y?FVWzaQ5wO$V4}1U_JB zb_N4PF!^6^3wdA+pqyL3Rtj8vROP?8C@Khmg$ED0ftCFLumQne;mg10MGANfNPxKm zq}Lug^A+Qc+?fgB?Rg#EcOeFL&cInCO)ZMfKhC z`$?$Ln1TZpg!W6z=juZdj-NN*)U(zUtQ4&Da{0f1Uctr*IRz%@x9;e6cAr3}1?p73 zPEhsdkJ!R_Jc#AOgGS#9gER}+ssIqQ+AVL97UYFmyYT8DXC;To0v$7BWtaEkvn`m9<{Lb{) za0uNnAUcrgRA`Cftxzg<40+{l9tS%x6O=}n_9eMIR~CsC+HWsA>505e6sjLOG-+V&*t9M6kr--9fbSrAp z_MNMzYR6fgfliLYV>0*f;P`mGsSiEYXG8})H)P;Vi?s`nm>&Kb5Q#FhHIj)pP9!}$ zA+!J5ruT2jpO2n^K?|s~tRj6o z*27}J?*UJLbaX^vaqEWzpr5C-25ks=P*)6!eTR;3yMbOhVh=iOOT(^pDtF-Cpl+BH zMvhS;dB1<}a{jnjZaOT*UMROK9RSm#JYus)&QzDfkh8JBlB>TvGWSc3A`k;Cd zy`Vy-8M3PcMb3yk!~-eD$!n)Zb;pAf^vw-87wmdaK|j&dW3Tdv${b<2xyY6WS0A2g z53m_M7T0Gj8`jUyNaJi(2vJM{m?O0e#8(G>V*8|WvX{A*aOo46M*^bm-mKV?=o)m& zl&P-@Ce8W3Q<(ts08lt2SoHuf3M_T_cPa^1l)LVa0tD4l)6&w$@9uy)O0QICrlBDU z+>PWmHaU3BUHjbkE3z;t_;D?d*v^#d4m^R>-{5u2J6ZW-Sjt%#_Cc&1^i%V%Dj* z&FMmW^)@cK+mKJso6y*QM|GJv13noQt>1v}9*G>gZn2xG+y;}wtew-hz1O0S!^B^#)G4A;Xz-D;^<_{n+ z+!4==35ILlLr6^;0U~yc1z?MX=V3X@v95r!X~f7pGapU|47>1mJrn5+*lg(^tNB07 zrrtk~=*r$tfOE0k6t*|N)qcG3it5O{Sdh;t^xYdM`PRd6XW#5>p`FbDezjkt_XV>} zbj<_Ra@{`^*SyVv83Sz)ac$!bXg)oI=uU}Sxgn{maa_oMGd0M;SpLP z#P1+Hq%*GqK(}8E8V-O)zTn5KBb3KtpnXxG1Ex^eWw$G2z!3A6bPPU`c3mgnsQ_F; zK;{IMlNIm;{4Y*)gE2*zd=ww}NYVzZi^c1BBy?}>^t`e_`UKA5&ew#ivUuZP>lNTv z3+>Pf&y>3!ouGxhPJlJp{@@Y2WD7$(whB7eRX9drxlZReZ4r9Q$h|C%(DGQ)sCRz5 zJJd|@qPTKrh$H1N0Zw6%^WnwI_pJWHWC0c4mwYz|PzgF1q+@AN>^M<=;~et*8wr}T z8J$7GcaDAuBI&z@l6yacC}Xn^JHe&>7SlxE2}+Upfkw9C)vI^r0_%><{F5hZGi zZt`BQ=?2s81HL9;lIoY5N45HBf(=Zm9KoW8pw|rH-b*vM==h!P%$nLGa@PT0 zdcvbVT9mr#LH7GzMDib}SF_197vKKlb0SEN8>pI&*b-R?IB;YesY)<$T9AOWIfJ9y zyvITA-)jzWidkzf7ZqJrp=ntFRmicA_;H&*1~Lk!iE<``5fQX7_(reAVxS^AAai-{ zq!&`r=O!C}kzBD?50ftaX%}rIzg5W5^yW*OmJf^ItxXYaiA2oxa(Dbdt1eERPGzVX z!E};=+^EI{gWIo>C8S3F& zdxh-bomM*Q_)sHv8sfl=5KFB&}aCjm#S1pFl?TKT^N?dO2$BhH4IGbP-e9 z*Fne0b`EL~rXYREm=(B}r%5AL2 zhS=Y4S;$?|ZooO(4&NXkT2l{dww7~iXVPc!WudEYrn9mu=wy!^zY+~n9fEbDauyl)%&MGKCQW-!5pmau(0M_zKTZ) zcXe{mAcMRq{_o_W8Co#{ub%(YUtb%{6-IH1< z9?ng_-O~y8;St1eC{ufZ!w?e%Kvp2S5;Xk4rt0%AT8s@+zyLq8D~1NBR?1BpI&B5T zYrB&7Q5*a7nuT@IeBcb?+p&v%9xR?-H+{kd9PWm{()$ZacrXR;^NI(0N<>$TjMwIB z$JN8DWd`aS82)k_ZqYN^XNIvp9ZShHBTo5U1_O*)qV}YPO>Ko&3fc$7qoq8<_z!sXVixwpR=rybQ|` z5xV#$YbJDDdJn|NGfE|kKRF`~zWuFoX|cqwBrT# zg6B&qtP!>z06`3dVoJVG`{*+mqC89v&^fFY6*tdZ7qyoV$^+;4HT-T;Z~3szN%UC1 zo;;6EDC^SZ*WWc*6$DZc^|>2I>#n)!Qt-f*nfs~x%gQ_DZJ>X;t4?sWj|kX5dG-5S zCAIsjd?&kOpIj!m)N&=9qmt(pSk|Xa@RRxYx=Wt}r)7zP*>5k)#A17gB~d%1Hi~bx zsobT2R3!|j7=W6>>G6swR}g=hECw)MqX&%x_{hQJ2c&`9Wd@*(uH#qyS3{owZxO&! zW{m&_Jz#ep%?7tT2#7g(tldDq2(~?euAHwkxc%1?_fVlp{(_ZEJvkC#~}B z`@!WHpYb~s-!P5vYt4MO4vHkD4;b`(!XYk+9OIpSWUOY@3@Z+FdsEE#u{g=b3)`Se z%AIt3X-yde^d|#Ei1IRggP?n^M z?Jl)*=G^zmsfI#?gdR$}XzoFoSrIbdl2348nx!OV?ZP61*q5bOXO5(;(8k>LQX zwL+p*4=@M;yH3EoK)*Ei2GxuMHk>31T6x$2MRevpDd|LxV>gnR^{@Gtrk}QK`y1A( zWxQJ27uNl-7O7@mRh|7bVlQxHcG+%9 zi3^^>ua}G|a}f69cV@l9WEN>RpcU?9Yc%qg`Jlme<_SfjA>%^omEgR^*Z1553CJ$e zWXX8bXx=ZQM0y-3m9uzT#AFPE#k_7FnPHFFLxB?MK6uzC%EZ9UA+UuGhe4rwdIdC< zcfgt?K$!b~?Gskp9mI6C4R9d=c+2VOuV6Ui{(L^PlL7{Y-GE=ma6FF^QYKzvW{Bu- zMf#(7p(XBQ&3D<+%*WWqdtNDRkm9N4CmF01?Bk9!Yz6@4x&f56B(cq_*{|4u&gb+>*D!O9lMh$4w8f zSqlKSU8O+I5_i`LKMx|J<67Lz(dDot5*it=-I@un5|t z>0K_*5SH4{5|sX27L$2Y7%qgiD$kr>nHqm1*;OOOPrL)4b{1cdvdW_Jr5wFs@7M_*qgms^xvF~dr($OZ z_Lg#1Na=z{XY__UgrfiSSZWE`C^;Y?KiTugaAtAdY<{(ePWo3N9`%`DGCc+Upk zrov_R_r6XpF@GpP&hve=;^!I`lFO=nb(B*6EXUVbWla5ZQrI60+LX$GZSsfQ#tTy|*C!H$i4-`P2LUI1S(NlQc4lmtSB(ql zVpI02fA$)mKV_&bA%NnoVx7);37rp5N0<;hylAU52m==4JT4sCt%Y*&l;@smO~{6` z5>tLIh$=${GcO!+rvvfjHSMEWyfCw);X{V4)dj3r2?7}3Kt5sQM>1bnn0gfjGiKgr zfxTp@X7Ol>L;4bWAB<_T*({rc=&9(aU?u zIS7&5!I)wtEg08U)CTa%8$Ul92d+)|+>tFx&QmP-si1vuf=-|!6t z=UyDFOk%ccEH)jq$gWfL@6sqCqF6_P3>W@P-W}2n2JT+h>qDCeCh+o zYGn8Ox_%%ZnyN6fF*m=vP7Sm#5`u|3O8RB`bwCHs*ap%cfKiIXJrw_4;p%e07pIEw_h~)@E&vrN|_dw#M}sHR@I5`OKSBym!+K zEDGC=2xjc5THN~{94lFL2B%G5>0e=>pdIu0bP2u`QC=g9@78jcFE>lkJzVL}0&R>{ zL~EzbJ^irw61uE#;@dcoe0}%**;u}5u>$13*7uwrc)7fE0BUukpE@c{x4cNYn*%z) zD1wQ=ePN!G(kI?^z{pj6bXksAE5v0?EyTIy@W^wfS&4CofUb9x1sZYNVu_6RK z<`y9<;Sf8%^jxfMo(n=h*LL%7>z~w^E#G^fBU51_exd_>;zrj3 zKfuaY&=!})F_6~_ztYrZP0D=J zULGaqGGmrb-hzqvf|tOt*5s-g*|a<*2>~cyOxp=bpcCpd+fDh@ zm>2^|>rVRT^_C5nDH`js(4`x`maKtat+PK;B*@{XEBZrhTnG zU8^g&%UBdaVe&VhudbyJ$F)jAuvn?9&+=iM&I^g62{7{%pg) zH53QmC|C(-S|NgX{NJ5sb6dL|ryndS3X6zJmXCJ43 zo+;iiqFGJ(67o^dQBh*8eQMnaRVQ#6%k!YTToTk-zo*>Ci$Y6X5TS;Q1T89<4UG!@ zfg9!B2;iHo3o|fX>f=K;(X9`t_i)fSLoHs z6i9KHy{dJm@pV?q-{Hm@2FBM|M67((jB65eYs~FWZ~yfOzwud4BhO`Amx=4*eR=;2 zV>(j-2vyI>@fmvTj-M!u$BMV9Q@y*XXbm=H;fYJcTG7ywOD}R#f3Ov0j`|x{&h`PEd~jy zUrdCtwUZt5r?rTq~N77#1 z*oAi#UZ2i4o#6#6D`Fgz#Wt+S)wk&e)e&6Fa=&g!wu&dkDa$d_|R=dAT6| z^g}hr_m75`xPxbXJm$=4HJP+D_8nelJ?b}!taJFHu>XJ-8Bgs$y;#0pyN!=3=$IGo zE@ZeliaIz<*^_x8b8W3iNrFZ}y^5x5vD|E*);E~+9e89=B$fTWc z;rxP~?3PeKstAU{pjRm{0Suno=Whb4Q{!6aK+wnR&DO!3MKk)uf1X{@0!W>+&lYM# ziUZb{Ws%w8C#pPF2nM@Hvet{Pqtlq_H49;kr3(grtW@qAKP-f?@8LWan@1(&zRse& zjDrEZ?pv3nNba&prYdA$S%iA+*VX(|jhb9db;APT3M``WVDWy4**^H3nHt8z^RL0Y2wHrPLW5-DMZmXtt4#CBj#ciT@+Y!zEF_=uOVTJ&QG(luSFcHEI!Lpq^xs`75ntx3tA~64Sdgv#@XeOeJ+UB5zrzS z{q%r-s4!Mtmv~V6Uh|F%otULU_}Y1{E*cR7(noUO*Uj%Nn`#SQBPB%9URNqu8CRvg$p(Vce z(r+YYs@O%7iTYdxS_vCb>OqL+12Yvr3U1@t-{8XqgL|-rj z`e#4vy4j+36X&zX{ySnFqYwL&S}VjaBf2U)`;(sKWMDS0x`EwIoB;T8zXF)@qIu@ZG$!Tb`0pF25Y zo4}xFy^-->)EX=VtDgaF@6J%ROwrW#02jAbBpi_nlXUvxY}}&9J^;~FsGQV@J@dhU zG1#SLU3Vmh$&nIi9n@;N_Q%j;78x*~_R*Rhq?ovV?@&=jr^FHkk2-537I*iP@5>() z>z|!M2XH8ZaXqGeg4X-O)~WA_77kr~;yF%HFa!e=UTf9yE-WnFp?S~|*&QVXQuZpduPbCWKmy!jE%S5XdEWzFl-mXt8p zWlt>rPxY(CoqSi2z_s?{ixkHyz8_V5|| zLMiQ506MAwk4V_bm1Nlt^9)n}48uATUTE|A)90&vQXFupnbQ#`+)cyi(kRb2^q4J6 zF8&GeH_DwWa=o_vdHz06CkGfF%*};O#q%*p_b$sLk*X#OfXSdw$Uz>t;x!1CKfYc2 z*vY_p0%0YOGzKQ@U|Bj4cbx-HmvYfqDzfUo+AKjl{yP+K#(?Mr2%?sO=d&w^ZxDG4 zTy;?r>csgpVjn*8gY7ETO{3iZ zE_yv6k^)Xo@r3>DnwOpF>bi0z@XFcNXF0C{o!=Z7u{;QFi{=Xjb~X<}3~TaS_l_mV zXu1Oz9xe1OB-5<@@T>0rd`aB;RKG}n9 z8;cWbq<+A){!9PY{H3G!V=G_R_TTu*J1MQU&)28#!dkHqQUyA8!t&vg5Chk@A=Az^rY%DNdOy)%QHJI8!F(4kH3j-Df<9<8 zTj*73C4dnWJY&tD&b6yT?LI0xr2febXIF&=lh&_+Stf=-0V0M73v!8?(6I8SM#KuaxP06E_lV*AC#>%7yAkvHE(x_0$uC*2PeXQi4l93X9i|l7h#V@7 z@{;Nj=U|*?TdnwKEK9pQ$Az6Rz(xs=hDWD&fm&(6+VxagyzgGvbOjj>IuNP=r6ow> zloq(4;0DRPA`IM#k6_;im?){mF#|1URZY$R-=-9DfyLOMmIsr1A0HoAI?{>`1aj8= z+Jm|)LFF+BoRIY)3MSG>^!vcj4$|U(@n8V^9*@t*hOL8#)Yl)CPK!nuo~S+hh^w&& zVaBfE`Lyt`kcc&hh*e3CGx23ztww<(|v z9UYZFB9i_6%gEv%JeDZs1fc+1f3b!b6OEFm!&hg`oy zfBxNlcn;?uxcPP46ae|&5KRL(F0m}0&7Z?2CufmaJ45{au+KMsaWtc0iWTuJpI-01 z^c`CU7(%TKxuw&L%Xd30r*qSsnuqLR46Ez~$;#N+GScP%xzTRC+ zUzRclNn+=?{ym-TCHC06tp;*?TI7$QJSCQ~r7DT^sRrs`eCH!)s)hs{Yx=XaCvz#o z=bLw%8oO#GI;C7wB4lws(uKSv;X72hd+AJXolCf+1^7yU%}QYb6cLt&q2acq5jr-X z!$GFJ&HKOy)c2s{A;4aSd<_4U@|kwpq_>NSKve|#o3(|7*Ym2QOUN+BzAD4X!T+ek zG_t0jo&we^QL9+jYhKZlOQ+Z5vJCRAH35Z~caIh}4Et@Oy~r7b4`qf9IB0Q#-@Nk1 zka#ncW0c?8Hp&QnwmgB0N^TE9)6Ttf#_PP_FjaNegM*-MsLS{==?8u4LV0avt}D(X z4x7}sl>Ozr=X6gPUfuk_{=#eXbJOsBD>X&G2>H?P1s?B1nZEtVthO7Y_8n|Hp@Ol! z{mSdlWsBt3_6s;Nl| zWQx2WivJ$}iuV6w>MNtV&c3e|=|)1j6_6A`Lb|&o1f&EJ0VSoozDSpJH%bX2C?y~z z2!gb9mvrZI7-xR}=f$iwFVMC8aPPV2?7h$4ZHc;*a0P^1wqTV=WcxekFE|O!?yB+6 zAQKM?EFjYgdE8w^fwoGZj#gOUcHNNs<;d|_CbT=1r@B5#}Ajp~Y z%HukDke<;VeQGy&9W2hE=H*lMfT$rM!Q#{JtD;-EW<=j+97e}M3U3j8~pDeFV z-8^#dpf+PX$MDDUbV_k|)H`Kd!w8i3mC$qf^COf1;{6`8^;=e%7uf9xWw_%eYpe!B zzpm=FLkI#_NIJ_JUR$~Iw>oMxBJKsjGzaS$y73>N@4xf(M%B^zb*QRe;^8lvcy-yc z)x{64GM1!P@CH#*Ixg8W8U^{ens5EU_nm$9IqGskbhO*JdSi>1CdeqAR$hWJz-X%` zlJX)OtM!vgM}|mfH2yA0>%H*S2Uww@niS!i>>f1SLp}6r*LHYXiK&hU!_GLl*P-`4 zR9SY7@KInsiwS%+i>F5-`1OU`I5A>0KC04N8*BOzH^!!9%r%q_QRfb^ay<6MP4>kG zI+_K?GO8`13G>E}z4PCZ-!NMHkRt3*=M3w60A$DB0!0>)bmdVjbBIJhNLv;&FCUC- zki7--ZR^Gc$JK1#T>ba)6ote~;H?0q1KkQJpL@Qo$ivv}gX(|%8UTM+!!5H{UKF!T zq4I7c-j|7Es?I~&UTm+X*z-B;RWbTR1d~qUK`1pgli`_&Svq;Q1KlN>fY+!b@}fQ= zD(X8OSnC{qr}<6`le1OvEUM;lu4buPsWur09;p!}2wx5kFdRKqN?fpem8lTZajw7UO}d42yN z{-EZv;Be&3jL=4C-z%-ZCLrU&d3j6taO?31+;yEYL)hKRW`=_v!>DKb$PyQ(pU-al zcjvYfLDB<|#bQ0@>Sk)`HJeReFo5WMTvJvXx8it6y@tJWv zDnQEAWcg)LWx>g=UaDEHzSow)N>6I_W|ouz$&;==!8koRc1f)OQ)Tvj_XtRNUelg4bKrETd~6~J2MgdqM_*PQYu{S{g!Z(hkwK`9bowktbK;p z$x5+)-mjHzclm$IrR!glf4D)=MFTi}f7`Q|q)}8&KBm07S~gDuFzkK{9*K+UI?@5B z#H8`f{UoKBW9+ZU^I}|6uHqATEkB^@ibjph!maSGcm$t z!eGRbp2DlY#zBZdp>VH!8U_*pe7X5=e8~}^lmSRJa1S#U=QC=!m@=)nexo`JKlL{4 z%n&?Lk4)>qMeDo%f;G@2SfcYC*<3%VjgZ~J)44u!MNs{NoC|J9Hghr#v&t_bt3PZs zPXHDY^rDvlefa9&doU6U1ZU!{vttKXC#Xxv{|f{snU~}};c$QuM$keeh2RcALG2NM zqcS_&8hQ<#ll$vSGnNEU%yP>E!;|z|@b;~49g@pv)15NHc>p;R)%YK7oGQTVYs-qe zO6y+mDDHkFwz+D@g*pkU4SD&YHFLA~G>MMRV?F(rv7A=3Fr6Tw%h&?V6Ro@Q;Tn0( zE?kK?O+qYLijQrF4VK+Rn#A8N1uEtDNoz&cE^g@v_Y-yxtw`Zep^;%MrZ;(5nXt`^ z_GWGnpqY~|(0ev{m~vIKkH&`8_fQ`yPF2)5{Fs+%KKTB?@8>#?5d{L=)!@Ux5CRO< zi|XI7PXS#1ua&5!leWwOJ7D)CMNWdD3xm*HBadwqP=0(F{dW|_yE|g@|Y1=>} z|8SSTuXlFw^_i|r{4;1=KoHjY^xj!efJDvJWYSXJ?bz&++Fi0tzw*&kGvDr}Y15>z zZ?`dC4ZbgZ%P)%WOuD2<7N2muSfn!5ru`$tVAI742LC6y8f8?+PIrC;OjhAmG2w)q zbE^}X7Ncy+%jB3o*>-lx6dRFaxkh5PWg?Pr-^(reDO)gNeThsdL$A`br`Uzz~kUvQ?YoiGRP)~!C`UeJtfVW2=>gglWnVCBGc0ZAa_b(YvCe?gV?_t3a! z8p1$zxEHOn;yanzfbbM2l+bH7+U8a*-=FC5iozhI4a`l{O{XrGhKf4Clzw$(~CX}=$&c9-0vdPrl$zC7xZ#xHWG(f?f>A`R*ty1 zfN1Pe_#~lMa3;PAj_J4%Y`GAWIG8GHF84H!zCm}I!sht-{vUf$3Oo6Nd^NTTr+v%? z%hx1mc0^8;>Yf@*B+PGF!&JDCq`8~cDaLvVGr^!WDxe17uR9=tUxI+Je#C=BCxH8V%WxVAKJ^sH6E?{ky_Kl*+U32dn>w)NA5C*5NhlNP#V)B|{(w5xP${J86weqL)P%AqM*R3ValFocD$hxJutDa)u>YkN4$vI#b(p>uFvaXp8ETNcfeaw z;Vouc-Fcf#KXv8d+>%sFqC}Y(Pnh>oZ-6ot1-+J3$DP>NP%#2pROe9!D)BFymkvj5 z8nj4CMC>RHS|O7(EPi^idPp%TieielYZlyGcwFRicW-f0ar;aVWb-N*1(G)Q*V*GwO5JnVggu1*O64oiGj*vUEJ z8?opHF|r-eA6%-~=HQA}v=w27zf=ChAhdSTHi7D3O1j|7sN;Ap>qsrYVI5aUpb^ti zvMesL!{z?)M>9WH;}1ruMh+F;MH}-Mm-KFLX zL;F=w?jO$}eW8@elQk=-rn*I{tX)s^i)g0f!GQB7k=}$)u3Nh{D{RiTZR&q?jKU?8 z+Kx%VE+`bXem^CU4y;$!6su zGTluxievguesCY)U`}mmAS(!ki^)G4w_6&+it@9$aXWHUs6B9EZc$TN@_Dg4$l5E@I!mh5%F#r@)NZm#ZxQ^90*$&-SM*h@S;7zr8ZC;W!d@aJA_ zfzes~n}AbK%ghD&i-ddT_s<$#Gf+KmR%CM+epbly`dDh?Gvh`>BVZXxUWWbojII(r z?rHSXqHpC>Ob^>|M_ZQqJmcr|jcpn)w|Q;4;N+AxaelF#&0dx4?iDEQRk-=oV0}uu zL(Dcqu%hw%)-9omhwNL8O?To)AB=F)&t9^dkI-xvAB5R-^X--G1&~~%sc-6b5ify;dEEO&4|%dfqPLGG{k^4Jk>~D0Ce6z6y1*U7jRBS zM$ds(=;(+LFMK9taX(X}wudod{+$Hj+13C_6$aux7+?)sYBc^&xpRA!edpja8*71mAGE zCD2ZhXOEn9#NP49zj1NvmZWpBqcSsY`Y-x-!D?&?FFxsij3;5yx=Xt2MD<7BN=YvR zKb#@kM2RPC>V+^Ty&7$={mxv37>iHshQv~txp$+421d&>b^vkCc@S@CTXv1EC44YG zz?p55HHr5@pQ*Q`??CVHI=c5=tocoXfn=7x**L{Et!D=_*{_0L6;niCb8v1_lr-6c zN-15QP$|gI1DOa-(Y>OKYfy^(reW_eR?h5rz$?sJl2BT zw||8)YH9a9eu^yW?m*Oe7m?+!CVTf^PbLn(c3qX{*t1^K?nnOCX;bJ#6w+*L>=iW? z5)O9TC0J9}(o~&EOAiZ0UerA}nR)qxUJX-v_Gz?unX@$kbN{VE@r&nV2fhLa*Go3B zDxZCoIOx@|aNja+tk`Ub=CyHk$q2ddl-je&{yE`w+uFR7!5_QDeJw?#XU0~}`+cN` zDe2`z;(0rj6Nz)p;nJbY$y|Yp(Ecm`ox-q|z@F`dAX4}`S4aeab+AIVL*Z;bXr#6+*OkoZ(dcv(35%r99@56W>jA-%A=<;R}9NVl2f@9c((+4*53 zgE#hVyloz8TKH}bhd4vSIg$l*LdG=QB^o#`7N-z zYsD#=p+wmhMV2R+<&XBHWyb;@0f99Uy;?IbC;#U5uSn;ZYh3}?OH@Cep1w9?ODwn} zb!N>!9{D8rVx_0x+6IT<844n@$tba*QA&(t5vlGR=jLRBy>A8Jq&1+vbeO3U!nWhI zk<<`BK-v8{o#EcLl3156tz|(DwB!P@TXNKQb}`9(mLv9vw|hzJ|a4)}8u1nVcqQj&$R}Yz}6NUBiAW z5a!i?5bAZkI1{)AH&LSq{!LQm6H^b8WilT>3>8aKoK(f_Pa>%`mAhO(Ucov@F%40& z5cd+sldkE!H~)sFkClM=mQd`ai1?>wG2u#Qk&vRdZfUK9#A97uHdFiTQCi$Vw@%}# zS+mwoNwKCXYm;O$HP>ESVk!6ANyO)yZQ^e-fPRf^r`O(tYMshGjMeK>j=ly*_C)k{ z;u5N>`J{)~{Jrm&JPeoql&Mjd{OtxmB$xK&qPBTTzaiOt<{7=!P38ajx!o}3v1q5^ z*~$GIvK|y~8;l!1gk8MqJ`zWANw4}e^0}sEc{X?;KXF`5DZ~ZC#?1W75dgxlzzjmB z+<&x}&?opXVGsheLF|$;}^`*YM^aXW783% zRlaGzG;JXG)oKRK=wQaNSzu*E^fkr|xwkcRJqpH`zgBEWk1T@=KUA|Xeh_!Uj{E94 zzokRja1Ef04ZUUDguWEf0tA!xx`F?BEwf|7Wd{gA6Kfw34Nv)|@b~}0=;R}ub-x#0 zatE)%X7tso*eCKMhNE|?1*$govOQRE^FRj*Zyl_U|3%2)4!Wk_hm`3T1`28U`}?oG zE_O2@tPqBHQyUwbNyWdo^6HZ>;9uyyh35Trcc~YkFM-M_3QIVARV`1QK0Lnq4S-vz zO`T=}ycQB!Vs_-d+(}AuF`Y$aTHL;G#2$o;=^g}Ukc3WgD@+r+*5DZJs9nQ+&WQBv z_w+E8SL+<73c@qJ51oi0OS7oFyr!dhb~gHp91|9X>urXOTfwI&N^U!?Y6L(%;G5zH zuqlJ#kT6o~4QX4N1-d!i%0?r_e%tVr=cvwu%6uP%`uRGhi5kpN;F}ulcF0N0oQg@< z=`%`Y>$n&_rF#gHi;h$8{d0g=u3E0_GU>Mc=03uLc-_j4SfN zN-hZtM?bHx76{b$CvD<4w21T74A+#-9dM%A{W#=8n)G9_ccsTvM(0zE$ZoQ{Q-VsF? zJq-9ArIatdqc(u+?^Y1`n!BE=`BeL4O2t-3$jq1;psqg%h z!+k;cfb&n~=_u}mUIKHdg(C$&;f9>YV^avSxnfL7*4EY_bJ?^cZ6V;$tv>3lXm~5q zN7B+o6{#9{Y(W(RDCPG4uu&zD;+xO@6})ojT0O6H{AZ3nx3OaPde5*u8Jo`nHDKGN zdv9sd#6x5CF=ZZNs|#yHxH`rN4q@}V-1Vj%8{e@9N4{RVxj{g zHeX6!+#>UO4d-1*AK1~5#}gx&L)K5%f4{aa2*;@PK1#K?sqU)XYPQ?i^`K3yRP*a8 zzOVf^Y+EB*M+{Zb^BUC3hO%73(&x!^J?L1A+ZapU2@)PLquhzgyZ!|%jD)#_g5Um} zZwV}_FOwADZo~>ZDc42EDzlyQ8{U|Zb*a_JS zXXP@%Zu*N-GR8_?+@H5Eh0^szzhxc02)x*;pS)5KUip&4k-S=91X=~=CfEi$mN8=C zeHJzod9fS`TM(QLM}AGlTp3A>|MtEP^v&?IaF)S(0@j1UJ`o1(!~WT7!HO3C*lm}v zs(85m$L0QquL+o2XZIX5V&?a-rn%E)(p&%~xOgXdhx7bIoh(WSd)Q-`ZF|m^6pzl` z&*(L5Km6WGR0&4#W1*bXsAcMvRn~ktIgsS=EsnRhbx4>sOxoF9#VFqT(M_*r&3_!F z5<%)a+wxkDM7bfTm+MgC!fU3s1RS`lFimx&5Jq>n-e!m zRqu4AM;~v`yZ?&iq9w!#Jd*}chuBufAlPXoG3q#tU{)uY+PihG^kLzVbEKW0Ee=2|UFaZov0bqY2aBg_c@w$O84_agu zi0y({qZP-0F!z#C^}}JAOw#+IV%w7$C+aTp5^+ATE8&$or%h=tD{*fvcnS?+68k)7 z%Tw+S-KtbN`FIf1X#$~HZ-C0ceSA=NYUw^P$kHe?&8d!L?Nk()drOx$f!V6Ef~du|sv{csQ<%uqIPFoKST*i=dzJ z66uP5en;vKRWzgDIw8@eS-#2S1 zKDfNDPU-WLJ6+sB3Ig&mX@ekO1~{?PtQk6ozK@y54+)s_`q_}438^d|%yQ{xjU=AG zpbk+$%W^oazx&|i#RI!`TKAx{GL5rrJOXC_W0EzB5)xL5HAryG6;HTxKWnSrsM+j! zj^fy3#XP;%&(6VOWY-j1qFlj}9sT}3i{2{0GX&tz@p4XN z4LE{;dt0AURej@_NM#3@4Gr*GyGHHvsnQ(Y;&6MVmNVW;edM_uPI@Qri6YkmB# zz1p)Td~QQT7)f68qn{&kf8XC$7g*X?n zIh0#jwnF#BopVv#hILR<(^UD@^@$Pk) z_@2}l`t#zwG2R@*S9Q3#^Fqf(R4TE<#SKXe8Q1jffzr_jCVT?>*$GEsX$dw30{n=V zX^51RQQDS25Bn#=I+<^iDUniQlj7Z!c_rsOVmd-Py&3^@vkL~w)(ST+nlbgogxWt| zYVcj%>aQdvSXfx_`bbITs1JMqQv{%dK+AQ!`o64ZkCyshl>Y|747}!~rZphmk&j7T zc`Od^jOngDGHg>|++!*W6?-Fz9FioR>9|Db+kb1ljBTS`;5gD?xo$jzBtD{p^Ymxc zZ-IvfwJ}NzYU!jP8$Rgm|GDDD6)u+4a{7x=etBc_J~eJqSbMH~vjx}JQ?;|6O6-KC z%GnRj5%TONOH94xgo-b!?N36zBw>5uX;BAbQk^TZ0(QfO-7QM5i5X6p?&=5FvYMiD z2gs)>!DmbYUW5KA>5HVDAD&EcCpPePn^eldBvXPx(~E5mT1nDx0YBJJt8fA@4;-Ux zx)AF}EzOOvq9q$`dgA8Td@ggTDrFy4u0OKSH&1YGPV-J}MQdv)_LhA=vvi&DxMPk& zqBN*R19h_1aUV9V?Vl7MQMG@N$teU?YC8>}FQen*W)2RI__Y2Ghi+(Xq<}P3znXxa z{?$~2XFk?cW~qJ*W~Sd5&Rs6Jz{#@~6B z^(~XTOJK1rb1u#thKIoRjGR2Vp68D_sN%`7=J}{i?`{=&&q8kJJQ{=A_%qpqVX}h{ zO&%{lI7^c3>GBKPzEa{eah`}i=OgU?Bz`dY^8T6{DEbc>5U$p}-466e#b;U3e;C>+yZ= z`}V!xi&s|z2U$mdyx>@!u|*H5>z0nXW`c~4PrLlCGUCh1gPWP5duZshw)}BF1Cm=7 z`+sbhR}Q}`9zX0J@idyef4XA4kv{Wbo}4V2;8{ih1B1}Ga5r#J8=F?5r)ON%XZ-yc zdBsx`(?hfDtIxqT@@1u9qr#_*+f$vJYT4F0P*yq??BVo722m3f5CK@829v(|T~}yo z@j&8JPToK4mINBq<&rHGl|KVkm5I#CGlCKyozDoi;h^eC9>Gq$M>J67>S`Y}~ z+*>!BH@`N_rGk$_aTV|(+)3C;N^O_6iW^U5FylPZwclT121K$^ZdjGEZ6xGin5RvQYFi%(vhU4Yk&xOJASEKvA5?@ZU#0y_XxB*o%p#( z$%4Fmz0dZv$K`fN!?}5^?uH~{zE1y4nS5@8&s18$>hZ!PdFg{UJ~umFAoThQag6S9 z@QN=YTOzqe=^|>EX(KZz-IbL?$b~2n?;oQ6xSp2#!}z7x`@W}DH3~NGWNkjl7L3p- zFw8PiPkHO`Dy$DOgK$e6p~e4pXHHr$bNtb5LlnCB+Mj8lx*d&uG@ zoi!9!#^Z&+Uy}P3;Jdfn^J#^+wj+|N-kmCW|BFuko;$Xi@RvUiUd&eWA*WV$aN$!R zdi-=a>SX+X4Bt-aB6xmZQEFw>>hU28|7Mdeor1VewRpC2+{?jQU0Zm(W+RhswA-gM^ioE4n{C zJiLWkgZAIUY&#E(8#rf#SG9w+|9|ILpF#N%v?x6S;1dB}7?k$bc(h$_F-Mi+Ps%0N zLwN{J!xcRD8F_tKn$nyaK99GpA);Rm(G?&M3JH~Tl=5#r)FJP{+(^xQz_U0uqoZUa zYwuS(ZL34sjd>C;zEA9DQz5u~xcvHy<8P|5aMT~+I1jY7EqKXWZ0kfXjK1jvS~--{ zHNK$_S>S%4OlIbW-E-hM_^O4EUh6&Pgv+5eCZ(3l+Yauvs9oGs;?RZ{hE_(}H)xpO zzjd~z@xp~%3OwG$b^@~|FZR64sr^2%=fuPA!!xCc5gkaZC5Nm zgP7`~AIR*-4SzU$yzDtWV#3GAJIzN2Qi=?CG{!5uX9D z0oRo0J*hL$&H)OO%}gHxfrmJ5ao3nsQm3oE*8ZW*YaEt(e7#HmEgR^_5e$ID1L^?z zTi{+ro~E)?j@XlsIHGc~3hv+!fW&cGNn5OoAK|Tuq;sQgPof}PR3oi z3@xWuTKSKy&O`he$yOho?725Yo7*fCZGO~q)MGzMH5T7ziea*aJFmW1gM(H#; zdzYls_obc%dVlQ9gIh#Qry;wi+@2_8;v}s$Yd1tkw-mn75^o=RA`U{Ao_a19uU@#^ z(T#Gzz3UgZ9g_3<50haKD~_gQ)-aKquJ~`8SnkcbJI}`WemWMMnIQ?BS)FkwGcL8b ztWJ|he2ngI6wPd$EU>CAb{^90eOa!jm-D{vKw-@9fm=5DlTVy!>iDwvMy=zYaL8t< z(I#|Vsqd4LOu#P`G6z49OS2FUFlXF@kpsZm%*Sl@=O?dWKNQbh?y68pYv5~j zr^=;`YITpNX&m#Ez0SX$>KitjXe}bkk=+FpLmfw+DE7BQ<{E7Z%-tK8(F{d*gj~0XoG0lX;Z_y#>kD>a=w=R; zssGSo8Kbw@nc4kM3ot59V%mL_9ds#!$>5?*AY$(qx$IOs-r$)6(FEHXb+DCt?}K1+ zCJrS{*gdn#D`RO%kgCl^isp}6Qy-N7^M+piYD}A!cb!Bso^z4Hz89{$9H(^Q87?I{ zcw?3gGZ8T>6nz+e9p+bL`Bo_vjHPKJke-b&s+!kbd@~?@5aHhXPJNI@+X#1(YU$8P zbCnoFK}-exfP&>+&QCr(Bi~sO#}Uo~FORa(FdIIp03P|}L$|q*E$tj}Q_r+;fUm;u z)W1UHPSJe%hUPPzQ26K7?5&>}EBzTO^wClJKOR}cvD|u}E3eSMiJ1Pwo|BBZFUJt- zr%yB=ASt?oV`vm`+A&+o-_048fi0N5O9VBi8oTe1VXq|X)ZLI4$_GcdmsX7W{@J0uf}Y<)RV^W$l|JD@hwk5dNxpuov4;6 z6|IvAeG6y^n^@Jx)hMD|7J^dkOr^he1(*{?#x~S8@lC(x^h6O}Fc@PB8Z6b?rkkN# z)tmQgNpnh6J!~Y%4W{jJefeE2?I}W8?`3k#9@?I}L7CDE=jD%jACqwee~_HNLI4D# zogeHl7v#?HWPMrHSzLS|{LOE&S?wU^H(cuT?;ls0|D-wk5MaFc$M|gq|B8RN!1xlS zr7pzc1QOoe5JtQ2cTqJu+?jCWd9L^iW>K=A)TP#+VGO00&PQ1gE3v_7Mzo_0YR#Eu zksl4K=P^i!;I(M!`)YL*u_wo|)j0I5<#3CA&wU^hbp0rPYUXCB!H3*PjW2IGCO&hN z{9+%fuo|FvJ$5(-L;5xQ&*KpVpAEvZKhj5>opu*;)1~}?$TP^;eFn37ER(AJ&b&M% zOkcTvt1*X7#roYpvjAZo*zGe$n8Ff3&FeMo$0mgTJpk*3VAFUtbOp#pQd40}@ge__ zpY|Co6}$Qa30;5QiT$PTzX_yM1|cm31tFX1MLoh@`|5}gA9+ub^IVJ`>MmMu%l-|T zr{ToRjVaj~mU};R%3P-S^uC`C;Z^YKLAyvxhV682m)aTiW2tk&!Q!QwOl;Rer^><` zMY1wkc^nmiFX|~z>cvXm{_ZoY)GW!aqN8H`n4)|#@v0EXTc6R`>sgd;Q~i>yPMVFG ztMX=psO6M}*1pgF+=8i&73OXWdZ(n@J-TzJ5P=2STUo0uo}P!wQ&WuvT%uFbvD^%~ zl|5zgomgXj`djtLi6oAbXbXEjY!{EGb|YmmgLOV$GZx#CC>YOr{VuS_B81|0z7Ciz zv9f)qmyf~6VTzU^XD{LP6VeIi=H+c27#N7y<|D_s+Ug$}$uumBf3Q)QuS)%=0 z%QyRD_5)sNBH4j89B>10K~a!}T*&?@WxE6_w-&@V&cXGUSg$7Om|As=@;A+iixlGU znut5HTfA7MdGSLR4M$(BHQgX_2w{8j+j9Ih2+B(`M-0-@j?qX$ye=w@Q2z(#@ zh-x9}q@OuQXlVo4)}Td)Nfq2juaY6aYIM?lQyBQABq$n>*>1Lfm{Rq>vyip`DJKwV z^7e4bI|JY<9!*cQ|0?=vH<)w6Y_#Vl43BVR_pv&9;|;Wk;KP~-B4$H}idv*rsUW30 zbHvQ`BL4q;aic7@D3nu*A**YGW%**!$zrWKhSd2A^PfA^l({rAyF<&|GHz~8i1^sm z-p4(J;W^0_&2z={nL=w!x{CayVtEgJB&AbJOfl~AaP3|)m0JmJnt7~ty-LAg_SByk zZ0L7{`x(VwC=<0ysn65=azjxxzEpqXCq<{Vt&rBM-(41FB!PnONVozOeCaG zN?a#v2(cPdDzQju-=kx5pHyY5em$RG$f>Yl>baKSxHF-5>VRsUCDZtul^aa47B(Ze^|VN>Dd;6J1XksPY^hG=;m zI8-yeLHsKihn&cB@;av2>O|phpL~82Vf{ey!(%gOyNeYBAW0qYtABhPZb!`hUZ%XE!D~bk^S=oyf*5wuKtBaAxJ>1!5clAexcg0h9vG+YIK^G%WcDsO zYi0g3<>H<<`E1Z>b|ia;iD|6sJX&93e}`wjzu-(Ws3Rv!8;KWpV)L@lCd`Wqy9GL& z)TiDLrA7CNr!D9H1o>7hmuFOiMXKJW#a5x`>+)_)dxa=h#2DAsHI17ZPR=OL?FA}6 zQ;vGPBK;(7w(DAPOnE1y<5uY27g^Jxy~1p_kY!nd&KHPtnUGrU)NZ{AY9AVJ8A6wn zhBgEH+{QFx@0Qt~hkJF#UY2JcGA~Zbf-IT4RjW%VU9XjHL`g3(p;+}cTddsp<=1It zrs+GW0ogAGQ+2-#K8zFP z$lsJtLP!?&fY5vW&)b<}k8}?aQM)vU2uMT&42*yPs?A^a3zTR>V|IZ@>c_M$1HcEu zb4%F{+BN7SA$b-dT>Nj7DKu#rg0DM|MPI0_ zri@Q`)nXC}{E0$odUAi$da%T-oB3;mX3PgQo-fgqjCX`;p0=fA7E(K~5!8$Qeto~NQc6e-M?nBtWq zTTftH$zY7SKCv}()Nt7Vk(ZGDY(9&Gc{)fWutZ`1<^2V{1Mb$~w3~F~X6W@(l&|?AO^TX#Z?LjJ*NJznTh^k zewC4J$@`av6aui|CLMH-cNtK=8*_o=Ancy|T@X*~boJ*XsuVbEHThAYJ}1w`-jEE{ z8+`Z?qn181RYDg$#A_)l%J!*>#12~|1=zixC5!fu1gOXX`0e&-$ZWIu;-R*Sr< z$Cn9eq|rWsM ze@61y>(%|f%p&LWJy)6z8jHEJd^*OL;Yf=T)&Dc{BE%Ed@aQxqi~iYZ-iGJQNmC^j zW|_P${&>u8tXTn-22y<%S0hg$v2=3vh~I4iflMQ+pY9{i9iGJkxgDRNV^O8&=x&f4 z-d3tL!SLy>#wRO{Yhe#aO`Qrg04jk=6GC0Ctn(mu37*G0Fgt;~mIxEf%%-y@pTlq9 z=(|n>cj-582px3^zwzI<^~{A1arPSqES!PpxuU{;MAGf{)r`snT2wI7fmQX4-q;`J zZ{}Qz#nhQ$^o75fnPkOL5c_2Ex|dqvUJ^okF<{T=@t!G-SA*swp(R%8+e~VE3O=5A z(T8M%dnQEW;{pga0h)k)!ySP}#u&t&KFQ#oUWhaO(GYEG*1P;`8pLuzW%9CFdXk%` zB4%v#ew7c9r_ch(k6tEX*F0*7F%lgxY>6i97L_ji(JM1}NQ!Xwnc`WF4A00-AsE+1 zbB&_UJpb18JNe@ygFvrh=O;fgbseKnF!ecn#`b3Td{XVbvP)4pJ~`^te#})i;B^sv zod0{J@BQJ62l~P2{)}0D)+ZN)FC-eLAYFylBF7o8$ytDhg-Fi|GY|D{GFsZ@Jo{;PYfN^S2nqdWiJ?-6#Ohu{2oIDTlSbk(U3jWW$yQ z2zpZ;cv5~a3>z^8O!+zo0V4^*;OPX-^?b2=ZBVwE6BHR=G=KlT>Kpl}iip%$CQ7%F z(rC){I8*60vE}XrUW065dh_@Y{%KI$in9idLVdG?7oD!H4%NGj*Q}e!_rP@9xnJDw zF+pw7)MwOG-(ktyn4Y~yjY}UP>!sUMdCz|YZ7#zE;(5?epOzba#J+e*bLfhuowd2* znRet>v^_w)_@&L`=^c)^uU@0G94D)uK?vM^shkHy8+>dB4!wIU^-RL683Uj_Tx#-1 zyRv132kPgF(=u-D+kzK@9vP#$#2oq;;SJsoI?{SEWif|7uPcv9yQ4bwUJ(t>dd z+-Eqt07PZ!9rJ<==1STDYz0I(xg2eoxKRDyA-$8)3ysPRvFhJAGtRVIclej?5HaUq z+8R@GSd_fEe=mvu4&if)s^4hu#iC6XmXl@j>oKJ)!yxH&@j~{l81dJ;%SV+ z^Ne4mcordP&9WBln_ga;%=PfE>u7WwO)HBIc|DOeYo_0dd8}sO;V|ghlxEk#vUFpz zX~qVD2-znza{Hk=)EPG2U|hdbP%`PZ`x^sUZZIO0oO$4#%+%oW?>3#1DV{=$$0&vb z9X{Qd2l_>a`%7#qfkeMwkGxh)&IhS3z-(9aKcq3vcM@)h*7WXt$Ak~?@gWuTEiC)% z=N3<0dNEo}#vL7U<;jXPFaw(d9(us|0j9-J9pRcolUq9>60CF7vD1V`W4qW*22w0g z=)sBl|AD@B7+V&wjE;~%wK3n9BMWPDSFhCe4%I1=?~SK0nG}1gDSRj|7t2y3WmV%z z_UPe!9Wj>(bmSb9Dij;E2QpQqT+04&$j+lrMKj!tHrW039;Rm{c@?U^k+{M^o;Jp0 zXWZSx@z?VXU$Pckq}l@%DyxjfzSWt8Q53r@ADP9^5E3HQ-nZ}CkYC%^G)--;x3Qz) zA9r1VLo~{)i}4NX@%fc`krN_gPRLL>VTj9YdWQeJ9qrU=L^6Si={D zqtIU{{oA;8CDu9mRWmTq?eSh%=$) zGtU4v^n>>#r?0U}OlSfYYxf0Lc*Bnej7xDiFDVJm+ex1hS4=xE&Z`o}h$_$`bza9< z-j^@wV>UB1nws98V;Zk_j=VA(tN3!YhWTp+8q5fd5X-7BYmYza1lrVl)!u!!mu3Gq zr58qntMyDMg78oMJ2;S1FBgxS1*v{>sTO#HgbtP`e4|^z*ZF8r|S+x5%82HVy2^W#VMa13@-Etf9E4 z`XmB$hA36hy1RBAv0u zvX@$U5c~AuajGqXlbs#1ygLB1hp`rN|3X@4T{IqBd6o;7-+%~^?ZGmyx3D9A

7& z4vzo-N@Dd_aPS4K7Tni*_e0!)FXcv8@Isoj6eI^+Z6^V}0^wuuRMAJwVW22*B$z^V zWe!?Ak==rHQc*k>3~u%sUz-CLP4Yi02=cc(O1?Yl zA%^P9Yn)}C>e^Y<7E@=tw4K;ShZVHMmyMPz7OvqE)A!{tEtPW+-rlEKtzLA2#hDk9 zXBz=u5Xv-rILbs6!6>J%Lt$vT5o(E>VnV%lafVsgPQL4M^n`F5vMZr| zg$93`bt#n}nNI#D;66v-{L|W=;bFgZV=(GWU1G-u^_w?|sTXCv+R_YI*|VS_oqUoJ z74bN4SIjxPeLReDpwDs;bNjS$KKSB*cyWLS&Cr0o(y#uhoeot3bu*E-r9d^7uQ#|X! zAk!-=xr4yic(-Yta%ShJKz9<#uFS!{oTVZ?HSSqUTJ-somqC#x*z_o=4ksq1o4dJ? zm6?w@SXfGgXAjID{+3*ukXZj~BMYB_&~P1Gf*UTxbd>7pt^|KD?^u*v$-*P4g$38? zQ2v7h+T#@yI3Tm;hOJo@(^Yeh@o}iTr^o(y=h>w9r6+8RsS^oT7KPw7ot}$a`Cg0_ z475Wm+&axO-A?it`#sCGW_o-U6Wc(MY@lLi@4K{vXThby);di_(1 zS$SNdeBUlbCePc(rVK;;6o^;*)Hv;ZOy7>0R2}}*DkhhFZnymQAW6!+?h}H<%bk=t zmp->KX;$Q;$iVq~(%oMSq^s1|xS47~NlvxaPN~roX(+lQvl&J&zot2=QMol;GB%~z z&dpUcl=X@7dCjt+S=*((CmLYz#@1nd82Lhdqiqkwt3#YT za|plp#o1$Dq;<7S#up(~@!{dGzfAZ))E$oW@RxFLol$wXp71E!4comKTm9t%D@Nss znB?@ilxROQS_}%zd(MNir7s2~>nlw%k>EEJv5IzIgaykCF=gi4a9FV>TN}o?l_Y6S zwE^seSz9uFRcWvnkx6aHyeb;N?omF+-@f*-L$gh()_hR>f#L6~0 zCh9`o&$Cy>?EKw(wc#Mkywiu(Y4B1N`~nLjSC5Ha?+dK2&RUHg$2av(-%Lbv+|KAd z_0d-rNvC~ixb#8MLqG87)%Bxg;n(l=tT_SWYZt$OkMwOA%7Qybpa)^Ki%7aEoO;jzdE39xrPXlYhC%3$Pp^COcl1Gt^Q19vs%gGUf3ibk`<T+1u<7DCx;T^-GEv!ui~&3#X7&`{lKh zj#VLCBo=gT&YCU~=OMcLNaWdOqu!wbR9>wOSgiIq-O))bg@2I;MIKCo1myGm!GwwekI6OHlY{IdPU+)ns$- zPwDmJE!WN0jZMZrRZeI7L*F<1Q0}DIZVW~_tPQ(EBiRd_qk!uUBc$?P*~38tkMHw8 zaMcDJaGJro{|b)nv)KBTaj^&N@fhVL4~Ok~`A`KIIul8QR14JYU=ji-t4$^?H^HDn z;I9Ie>rwd!)8m=Ang%AN6meR)jVaSA565qB?oTTE+Ec1U@}fq?h{scIgh*DguQtfM z6Crx^I&j5eWNAzP`|N9E;%#x_i%l+jcQhnI^oE(0kg>{pC95n0?13z#sVJw>HZdVb znXyr|%9(I}>q|c`ONlHNggMN6- z82jcr??KQlERnN_>|mt_k`H3VDf~4;tnWxZNC9!x?`<9?D>@=egv2wc)HiRoBk$|I zsG@*a3`!T9b9nyyR*sVVUR6K55R{MEmfC05jLZ&(WSq+K@~=BP-1UZdreS41QyTIO zya9Os0jo$hZ5Al2L-g@E3IJ%!#zS5oxOalt7X;B!o?_Pg!Hj#tfkywN(GDz$4`sSa zjZmtxem3??$%na5#ayUJoNby8tZw7}7%){nyOlg2NjUCKa)^jH>djDA8YwGKdX%MjGMEKVQ((j+IW6M@Azy6H5Bw6p5?wd$5A|~#aJ1B^iza6 z@D8WM*XVeXX_5b%uz)UF(X|W2%t`<>Tn~VP9-woeCXV_YxB}s6`yKL-|G)T45GP=td*b8g=SP+6XpT7b9JBna z)8_Yo_05S&P4WBr@%wYC`(pz50|G5I@Da=^lLTVnd5|{&B*4B-6UN@fI+q|hiC$J> zBE?^5D>k<3(bDsHLOeu!59GP5*fDYTbvy%7DH72s+{b?hdUk@g_@}_GOLU)dm{ro= z#wx(3xlMFis~3g{uQ9^kYH8_RF44XCWtnB0QQR{_hbcA9oi2nMQ;$-M|&7c4q$kLUa>c3Bv3rfWn4d&+&g4U#Iix+4etQ#2jqne`*Z?P2CT$ z>0p3;@%O#0u7N=T7<)@J!FdJ@GMu}qQ-O4{yQD`wM*z>)TmJvJ0Ik|mY-k>nU0R!N z*d87tp>O1M=}w~8Vr(Syv#jdSPHw#hb7dx@{TFq+e#%H35l8L>H5aL6CgVI^HC{49 z!C@)8v7P8^NtdbjSbF&@Bb!I+Xkv~#z=mx|g3?T{%1BY+)=cuOjqDWL^-O>UJ$T0( z7t2Fnr#dK*4)qxK^{D6>_s#KAu?k&rvp1Zofz}6Q{y92kF;OwXG*Rz3`Afewi@pYZ zqyqy{a>UXGidK!h78BFCCcdU$@zb?`k8gw-+gzm_=4_T zIn?W!qQCS+4j39YxW;Ig2|j@wo{Qk21${9D8uiUeE|B?57@Jb5m_%ow^skk$4D0)3L> zEo{6PSN7x$=0TurA=R-rh*b6<4;;e!O8Tzs!Zc+(Z6+ggpQp0%D6qR4cJppTCVIGs6fa=;(Ixgq7XIiCoe z+PaJEl)mt{j};`|u-y1{kcS@9UiSN@1^5KNlfQjIkNg*W=|A}NE{yE-*y&CTEkPU1 zI50?({#$#`jC5xR-%`UAZ^@gUeJ=Cz&-W;g$j?`Lal6oT}ow$cNC zR3b~0k24$e;nPAsZ8U9$u@e*ZV%Z=yw?Mm0txV~AJyZHHp8@#e1Td9_%*$vE7-A6@ zw2Jy7UdSDeiIN#=v5oh~XUu^h?oNc-0rsP3f3DH%@@OoJxfG#{<1n%;Ueojs?^FfNZ*Y&IU13q! z@f*36#3Ui^SPT`G*@&^kW|fh$8au`5+to6wO{#-@PxJ$GY_X6Z-+BFM_lpY?GnPhP znEj?FR<#{qe~?66>i3C#?J;_+rk{ppTg}Bz)~!)CwD-+jBFw^$1KwO8yS z-o^RyEQ0CUA^55V19{|mxyD3BbMYlC!QH4vypD$CCM}!dtY~!VKwc{6#f^XP$=r9q z8VxJ0U}})6uT;GdxV~jCFP;felZaMJcvo?L>0^2W8!Xdc(;WC9ZBbDCZ4g8el7^1@ zXaxYgf>&6ye-&8TmplI5|77IZAvVF*VzK84Z*SHbd(>|8O5v+m&}Mw4d2qdZu8VK4 zJ7=V8jCWi6u6+PCGb4C(tOW25YL)(X_%BW0!yn+TzlSSHJ1+a;wX-Dec|pK0uVBK) z`EapqS>cDVv-6m6*St$0CHbL%7}%1^QP!k#sAP$Yr97wl0u3&FklP9Q&2VLG+N2~n z_CVQ<*sM#7s)otY_ba3rqu4w;CZN14^I~{$E2uqhOt@`M`(#Dt)+=0wt_XcBci`@bIpiJyw}$kr)SPju7Yi7 zlmT`Fk0ePwNieec2VMK)5j$i1LgWCjv{Ju*zwLuc<`fYaN$xYBx~Jl3QKM$s8&^E? zrc(+TYWcETz|^EGMNB=8;{8E@)gDGFWnY|}Rz;55I{L2&j648d>oYOlEoLQ-B#J*(CCk&P^$ z1-N-ECKF%EuRR39wF8!2OaN2rt4RcOt>cU8N#IfFUT!z1H28P-9PT?WptODNy?Q7c zYzQTlKL6jEbMyhgG68!cZ*002W0mCzAP`j>j~DL%A}?6^W1)7KiA3aDGPkX$cv=<~ z0e3Ml?H|=<-(`q;pygXfxE@q+lTHfz)?44rl|a{a0|0ZjIra-P3Y!{>$E$7wq-vgy zz;9Y65WJX5JZ|)J%ZK8WJ?JX23u2~l$76g{^!UtF_N*;si`&$Q95R**r95L63628G zjEB0%ggnVqV>O{us&{2E(hJ(XcRHbGl&nE_%_sW)DCHc}oj+c9XdGc?< zFcyycg#M03{AwUaR%&%xXqU)8ET{KzAhF-l^#p0gSPMWi~+mebDOi)>G!7 zbJ59uj{XG^E_XdTEl6y#mlKVA{QRf0vBLM6W#H_3V(6$-Z3hY%$cEs(U3>|`5Uwk; zPWGh`r{Zs;>o}kVHoUxS8YszumoQdqT78VQ|6zsjgo@dO)tqtc*@VvO9x_;+Ex^F> z#VBy92 ziHM8a;_@+0<5%e9l(P)4#$8-BS@9=7H?nV1g=XXT1gi3sgfh-YU@-XZ{4!6_t4XXIfk<3Vj;mXGT zhkN&Keep)i90RUIpb;3&vS0$~$}>;GJ2(vm*B~=U}o(O&=a`n817Ma`>Eh-OEAs;+ji9ce=S+^W~9*#gNBC2JyZ+!wFg%-2gOHtS-NOo`jG$Se|PH#Bn681A)h~F z0!-?pECm3ipw}5q3arMSu(J=^IZVP1_Ow;LJF*Pbb+sSLcVwDC9R4&mWGof6s~^2z z_MIrY)s*?U#Dz!9^2HG=;=yCpSYnImvtfg}Y3_V^T^_(^N|F=9OoRnYb$(7KJ)^GY zo{QUII}=knYnvAS)Mi#~u--V9x3?`Jsj2gwhGi`ojTOT|&uNp&dQ{r~Qcq|xdP>~_ z#pCx1mtMG(7OD=RCcZ>GUw7alnX+Et0HRTNeC^ox!A^Bn6n|vkzgvn_kLlUkI5qoA zQy6wxjXA!OV(?V{IC0Io^OrUz*$wK3XTQqRi(gD#;MiOZ8{IuqFtquxb~FEK!6Dh_ z;?Na&ja%t=%^D(YJbKg;H>y&sxxxZ?cn26Uc`RudzlkICxgvR65RLpPM3++KBmXRM=+X9$r?QS=q?fP}W@vmX@?sM}JA}q?cj7^9P;M3+RD!n_ z96Y8XPQWSoV}ZjkB$9S1jsI5;u8Bes*7SO8HKoUP*{kiGu(O>9IA}rOs{fByf8?v! z!;sLXeM>C}b{j8}-rE93Dgdc&rA8sML%9-v%`<<~9d|1weT|O!`>>#? z<4brurKuj4AWo8@9QX`vv$nWRKB@S4_%HQgKu!+7 zL$g%w=(-H5^5Y49kokFB>J?J$RI8CtZ40Ywu2Aj`v@UUZ8w_fXOL}>DJ$i=aCzE$* zbN0{R(fqe#-ggWCUN_=Ai@Q~hKzzLmSToyt9E&_v@jAC>r*7`2?b23?SnE@fHgx&L z8YU*_{gkenfc(!w=EGwMR9;>23d_mC@+;pP`b_sa;VT zo!3m_F#9`*=*SP9=KqbLooceSz^N7#-dq+Dq3H2@Y_%M0;)gAOVcqqtluJObZiLRu&ON`gN-nki;hhpMn68|(rCXH`>- zD9g}&HvC<zvDjNgC^Y)J<;VfZldqOlS7&Y8K-vGH?r-k0_c zmANDu8+8}DRL)iQKv7#{%Bkp~#VuEwe#u#=86WvbrfB~sdx{ETVTbvTwT6~F)3oS= zTQWD=xh&GV3ysVbxMP!FTnd;FVK`q_!O$2n^VBMN;Q7gwfuR6hOJq`kddc2fRQTWt zo74sSf_w6VJ0&g7JVOq~j1d!lV)r2|9FZo6OikJFdikAmw@JP7h3!aKr8)4k3X3pj zkCrpd{n`dQ)PQ!Z69@k9@C=hI(KG=y>^|>w-~DP1xILNjZqtqoJ?^Kl-ESgK=Dnv> z0HG|P417~8urwTAzIrQ^e$PVk)hjrc0k|$~hfM2(F~p)3-B+s0s3t{4(B^99cikFF zD#`f9A1^=sKRH4~*M)M0NY`&(0hCc~wKlTfwQ+XhbDHVA=ty7!wHvN9XhEG4ZB8Rl(*tuL!|^pMf8YQH-)fc7qtvH7 zIg`W(Vw;EQ8co&#wRov+#ct8j|wydj4V`wW>Muh|eK%HBi{o^-?b8eG4H z)}#~Wgx^lL^Djj*@fsaq79dK?sAWKO(;a0S@uZy6w0Me=aAF=DR_`n>B2He!u&iMd zPD}wF;)@7oha#di7q53`9G^#fkF)51Os46JOFZee+`h6Mx58I2rFqPADSZ9XPkawk z#HcR3eA76$aC*J!6iEKxguG#vW64Ie}fQ|T4U^+8%@LVXp@lMmF;1QQ8M=eIGxmV1ifNmCpI(~80P zXNx8drH590cW**({bBu?&ePBjLn=5s$GkRrK9a@#X;w-yXkQPX<-?TeEn1;vaC(+l zoVeA#xj(@sYgbMGMr_|4(KvfpTq04?t8*O4p}jV2nnsM~VHqAx_?*}6aKa+46TD-y zId`T@%#Z-@^WRW$>v9dotEJ_~94&9o9NKp8zwmszct;v6=zEECO5M z-#`Ry$2ct>&nTX!E*nuAyJ6PerbG zr*$MLjgS@B&?hFXZ^@iCGoZ6sghQ}5h97c2Q%!RhPIK!5bQ|*27}AWue90@XCEpQm z(vfH)p~x!%sw3$WKW;oJ(~s!zwNjah`*hVDn$84ZxuQczTWNz4|NPaMHX!x zl_tjW4IFN&6PsyQ(H6v^o@;_16?a;XZ?RDTD%Z2*YW&cPpeTuk1k`VIXm@VPH_p{i zC(8_I`$0gP=>G}B#&->-=vJ5R?voM#AzUgpubv=DAQ1<^AX-DqBVo|@{H`Tpm7?@)K z5>Y?H1ANdBjuMT4(_*BlX6V1X@V;ClhO+V6(&hL^s5ieCd(iQ{&MuGVDCaxFL^fz~ z;SoKcJvLI|ox-uvjW%ffdLb33C(3|Dgv!T{V_k@VgktWpAx8+e zIOD{N!V|6WFZekNUj0jUv`EQ33Bg;kVT~g)QMDSM2e+@D4-KNMDzcl1l~m2V4LAjE8~|)2G`<3TYPfPy zZ5f|c)>$BwlHLv8RAOgcVR!{pVdLrN&g zGF^#o{(AlsJZyOMT+}WniBc#+bUV&V3ifwv&US$b-(CCPrVX<6w?I`K4*E zeZ6Z?z{>eEu1(eCa}CF4RzM!Er#+qA*qx~jy|k@{esg5cA2;ZtA{G!>R`IlT z`?2d^ydRsC_BA$CW0HjVn7sz0Qw_9_{Sh$DzU3+`IsK=WA;2BjGl4ZmG8u7X024MZFHgVu zQ^_GmZJT1Qn1ZK+nqs{2e=AHd!ERh0ukIESd9Z_kWx$y)t*1C_N6<7n9+so^ty9B; zpWn&_Hh&Qr0$!=O=zZy<`N})dj zPVW<9=)?TG*l*bjaYvVCzCE(1xm~SxRsFcv21-Yf1jtFe{SUa{&7VC&Mt0J6pz$Us zi0Y5wi_EH!uRwdnU!#T7UCurD0rgFhFh*YMR`qjQZBn`^U+TVDquvRXGtl|fAdCK2F2T(+Ur&v( z-~iJ+Z2i}>-%l-eciVS82x;!Ht`dwsu1yzNw_iDaIc$I2`A79f(N$46k0#fJrXDo( z$hfJUp(VK@Y&mv7+l>wX1Jr2xj^(0_oKj{d>_;!H`IQ{!Ti~{3Z2aA_EjsH=%cg#I zWEYL_>3^?DUS8g=fXCc%7Rq>d@aa6z)R!|lahA5kjVb+xWpGJQmG6C{uF zvZDx0gKPEkaZe{;HI9M|GquR(CG;6HYf2;AO&KF=cy<6EkHFkqI9)@9m9A_j>Jk&@ z(`EJ!M!L?!(Fgii+4P)@lowvI~(1O#> z`ymowu<0)vi`%#EJl~8XhnmC_OBwz7{VwZa zfsxg$O2;uver&Q;+N1iCxw^u_@Wbm8%+u4;T}_Uq(V3bVoPfnDeasm0`pr zNIPi1Y16hHFn%3epKQAYVQc^^Y8O8Ru@A0@=)p|aahrM?>bUwOa2uR1^8ZvVn`p?7 zP>}!cbp(tX0gL$D8=0COkQfZZ92EncY{2K-*xVFlUI%b59fk<0Y#AvTL-*Pm%9U@- zJEmb`%hdFASbT!D?$a~Mhw#_fuCpdKyw_6?cN(M*aNa+tokhVls<&6UjKp;__-^Fi z+7or#Y0IF8t~b3(k{l7Q82--Qu&bqcRKQS!;Lb2g%wY-TSD(6mHS`mHOl6J6`_{AY-XHd1eTl8vba-k2dSxHOm#Nj7Lo!P zBWL8`Khn6Jp=1Hq2D%sRt?l}Y7WNk_(Ede)!DF$qI1&ic2q!A>cA0B6;Uuj;ZaX>i z<--C-L-Umw-L<5t_a)Y0ZxL87RK=879{t}#iMaL&!f0FVI*;0oW0GT??>77j9TwJa zqtWGMR97i{hE`$_Sf6xUit&*ik>zy~!f2}Y&m$k}?XUlS_0tkh>(yt>w;T&z$yT@G zg%t~1MKDjzKsw+T3oR4kCc;{qWlPH8jS_zmU^YNBk3~+*n94V4ZD&d`^*+~(Ki>^| z>iwb%AOr)e0&q8qPWoFk z%6A_IqvTB3+|y9*gNE-Tc?P*VhJO7DcWe*NdF}Nu;*{bW;E;j_;o+ZaG>?OKe!YyZ z#JkGq`RuKbt4uD99qc}h&azNzsn1x!Fh?C}vE`J{L#*m|B1&h>oGaYDIaFPvGG~qw z*SV?-I>G)l(rmpn!o5bZyihXzu_rfcdF=I1;o|V7zE(2~2sxcbi}2ES2e$44qT|Ci z)2pGydl+{bpWopxT6#h0wdgN(KMT;^28C~RSQ#6sH|fX((uUd2#%@xTV0Mi@Hd;1t zO5yerzGS-=et5kvPCxIr&i)JbZ&#*ffrgZz-f zoXRV4+yav?Jqcl6ce9B3;f0=vb1|w7q8bjTE@26|D@0=$2fR4@w`r`;U2}WocY{8f zn-{(-hv~sxG7;!%>zFAJkGVr1!FT(UUq0P&(Jo5icF20}P!`j@PR9Exf|Mmg&vPU& zKw_3+IV>}cO=Oqb*J8-X$n4eu?nIKhbz3dv4XQ=SbW5u$%O{Fz2`*&dal7#q)74c% zsou4A#X~892f42XucD8tsn%UF**5XZ_9~#O)r1Yh3h>WPB6jwDpJnXMeva^BzN> z8%agIW2o09Po*CMm}I66Q>*51U|#1k+(Z(=Q=TjLi}yM$x@u5Ee*YgAVE<=Ew#%)6 z-_Os3BJ)i;kxf*Fr&S`uel7YHyuZqG{D~zwQb*EqGbkB7VT-J3X^u$Jk>3&)JgEIBPK?-@^9Xz$aFYMt=t=qF z6bh%5fk4yO9_mji+&_!)&l+&Znvo;4j+L*jm=3W>^8en_*nUPx%1kbwd<55bQ;8Wz zXQ~-Z*EG&E!KsY>my2##sdpPuYGq-dmlGq2@Ct$lh5g|w`cDPRfA9E*6>UPSjIj9v zy?!r+a;zaezPx(>Zwh=IF(4;PTdq6f`yyyXbyxEq!z$W#8C zM;o{3(;*+GXK^Y*i0d+U=e5{y6fFOW;m0c$$QNC6s1$k6uRlnA*N|ua(5NkI*xV;@ zg9k%|c#o3S(Nqv_@v5ZM+>{K-5|K1Xp?$zueEf)PSbY*0T>rZ_-m!Ndvg_TM6P~I^HM9RRK(&_OG=Oe3 zXq;~^4TyhgL~uG}pK8oY0Q$=unXkupi6gAXQ5QookNTm0$h{lJ_guM;iTS z?MO<-SaEyrQI+ zh~9MlsG%JraiGCY<-6*8Qo|y3R>gu9kv=R*k<46uwhNTL)K7(usLkqF3+t++zE$nK znxyer>w3HPI(6lhFyZON9GjU>ZDCc;$YC^K*!Guk;ZW}0&Q%ZAx zOVdB3=aXp)4ur>3rhED45BrAQ`3IZ!c@|4{|8?$a<@%2^-0DZ&W-?t`heJGe6M%B|OjsHRLWGyE%(VQw3Z2vaZ!WhrRGkb3T&2#jYiN2EORzt2Zl!}g0kd&r zej5|xZBOz3j|LQAjRPTamxfiW$Wd+N2iUcIz3k@KRw$qC@2l*|_WG?8_;_n7@XexS zdbOi(hG~E76SGG&L!(ZoBT6QerUoBUi5~w zMsDq41UX_F12nZwH8MLZMiMA~!x9Q^3WPTTB}g)}?p34b7j1W_{O3XyZ~bL=7w$;W z))?La`)^iN`rJq3(+b`HI#fJw*o*(tSMiSYrlexOPWFHIX}y2CVE-kzreXzlmaLgU z&q%*P7U=I#+YEWt53D!HQ6BbyqLCI&64}SBUAKplzVn`@!8g5ZK-fm7p{7-|(@?9? zE+3>hfjZzIX5{;?BO*_|r2JpaYqjyIgseF5I=WG3OMC&i6UJmfeb);Jc3%e$!6P3s z!6X8_s8N=F#WU{BHR8V)RnS(ZSNvtcNA=P-<&%g~iRRkI@CVTqdG$u3{JQK?$TT|I zPN+AV77Si~jEguT_Pow?7hJ#5P*?2T$2#c1&Y^FwIgR8EzI@<|J^Z+UOZ8%6vGqyL z0A4R*V4wVPJT&}U$g}YIf59Kcjc=lYKMd$-<744U9Rxu%OvSCOkO@r79V%BdxGK&M zc2f&6T{`^Atpcy=JZ|%j`XetI+*=<&=c+6@t_`A_FL3bUbiL6G$F(M$3tDOzZ-35? ze0{lo0W;0O#>d5X-RWhmH0V$^Z;-CrI`r`Ctb^CuT<@!D07|&M{>*Zypu_alz8yxe zJ+2Pc9(~y0)%l)v{dabTC%EigI$gDU ztzn`LyD}SQ|3baW!ZCi>B>~lsP&xoSR4aVz`n9!t!{!=k+OybS>^+GTT}fnJ@{w(l zHn6NT)&kW{Ca;pkNUANp_PJma z*oXZiIcDd*_ES2_mOeYA;eYim$cvZhHZSFp@(CX!iUba(5pMjpW!3DdF7qk?_~~n< zkEVi1A&&_@i`npI$9(A^$@3?UyYBEVTYH*CfXj6ja3*HkR{`}m(5EB9)TfKA0 z?#rm%x~RwZ&K6c*dgPyG1>ydg!7o3EzPJ<0a9MW5Sk_rTnIZ1i{Eu-p2w(goV4flL z1Iq@8_ML2cT!!^h!%%$&K91<^S$B**#eUCIgaZZ`Y8#&(7#@b9?Zs6Sv;2q13FkrP zJ+kFg81s3zheF$tfsMossQ?UtFaB&1nhB6n`N)n zdT(xSnyY+3)__5xmq@0CnOXiJ!kWGO+*(nN{~kEPqZJ>DXM8i=;V*I6dWts%HG=Ic z%|7|BU~qnn+GYU(&{+L3)T`6grk&oX5rl8ZLZhOhfS(!}8@}`MiY!>jU%UJIbCll| z!N%l!cBzL3s~unbz>Po`Ua3OoIQV=Tt93feVE$W2Tv5w?WVcN#3W_!EPbewNlO4@# z6hn`D-FQ6~bj4J>o3<1d*qn27c18c@1~mu*`_9Eo{KE%T)Vg{Tcc=M8$rwFxI?P7T zTB2+vzu>%xvzr!hBA4{P9eUw}A1Ai#*eel8Wkh`GSm^c@m%G!>gOmy53g{4P>@?3d zd^T1Y>keD^?5)GNk6eT6>LF@dB3*QC6giMnxtqRasjyzWt-T63yoQ~ zbbb-PCRU#k;45-E^sp~`Bu2CpTJCtOfOts>{%2GVgw3kZsfeh8_uV##`8bQM*E?J( zR{T4l4fYSNy`F8 z%6SopG1DSnNyuew3OX%;MAK(*YuF19&JUhp%Ps$&06D4`6|W87r!eFApvP&H5E(bQ z|0t_xN*Fo2Z0q5X70=%FLFiX{fD6ntRX_uv+R;tgx7H{3^#pPD<&1-}T!Ud(i!+vz z%VRY|#PZJ+jPJtqxt9+MqoQXHjQ~YMf6X}Ydc|^aI^p*VXMC$ z<8N?}lv=P1YEZ(&O#l83L?{A}1b#7=6aXt>e#jrQ;t>;DIEJwnkWo-Dq#GP^Yv%s4 zs5J~w=K!WFm_2d8t^z<*4NBD-v}{%OciWJ#XsRxAFAh@n2dq`AB*NC!2r9D-M<#cp zD~q_t)1+^V{s1{3q2cd9ZyZ!b%2dL$47rYyHfH!bnNP20vfWP~XLG}+v_P415>Rkk zAxDD)w|y=cAc}=-_}RLGUVSDQ5^?UDH|?2L%o@4H?e@R|Nec-z3V|s19EAC z`NPZ57PU<`ZnxvZ0D+~OoMO?B&R*!mkwe%v%FF6_yn*v@n;Hnjv*h7^07?ngxVPW# zDF0Klxb7F;Ft2BsMOSlo=q;X>jl#RXozO&KT4I9dB%qvlpO}C0dMfCRl}P(W1%jrP zB^jO7%eBzOwRoI$w1ZPA5@gHacuO`)jwIrIpprHSN?JSd`u3-0DCB-!xK+xcqo=_} zG9~yJm6j>Ycv_>n;u`}-Pu2@PYb7$2-AVkOqwn-*d0V>Plg@3?;@QFNT6+vCYmWYl zKtC+Tb-qw&2$iVDvSub9_Y<<3L$THSE~R-3tX-X=J)?OakM(~nYGh0w{;F8;USEH{ zJ#hHpv#~6IGchm(+6W`BZZ;)G0jpPp;@bq_+g-aiVJ1<_K;xv}<{oW3Rq1&6P&VML z=!&Ck)2m|qZ&O*XU++*5D@*mHhjIi{17ne-AWR+Qshc_ z2HM!~qZ8*k%BHCNY~l@TFUN$?d$8Be^ZAV2x#UiMYV*aY)C+O8UtA^R3p2 z_}mjB0?))SQHw9PJSY4fl{VcSds?2;r=eT1jNKA%_w}-a0$#fzAMYuwUOcC(#d6dA z&TXrVm%WsjY-DWg9Dpxz6E~YoebJ> zwxy1j6_q6;<#=wg2)|FyQ?=?M*i@coA(%>Hk(NzAA5Gj{syGi5JNYb2-eQEKQPbtB z7RVGI*KSp7p!B!DI)}j{!1r@&n9ze!n^nP^epIXdH3sJ!A$?TB~Ntzbse~G+HN`W!qERa)Mp`W8H-h z724<{f?_OlngH|9&W2SZ?tmXmcW*CB2hf%_0T5XdZ{7}F;W9JsD21h9y3vs~At8ZE z%==pqIzCWEh&}`W)WjW#2&;8<1#Lkha8IgfYHISMWLO-wHxx)oHVMoQE5;|<=^_bC zBiNIQyh`b!u3JnsAkF70P9IQt4r81K9rg2|EA=RdPTrlkWJdw5!~E)t%@-ZKFcN{J8K35M6J5K-Ecm0VDCT> zZ4J+geGH)t=avX$QD_W7`;mP&qfuw&eBN!|9VV$n%fy=pPdDP;VgCN6RuEJiPlysG zj#~04SLT^;MA@*(My2sVdr%~0)9j<;1rK-<-o{HgR#^boV20FB=Ko_AN;2@_eCxfi z@`)|lLFXIkiC4E~INchyS9hi2DL`R?AUH-W*`XoNc{6Epw`FTaoP_Dw-m?(^)NM$z z`RB6e6$w+IpqZzyyjYBX7&)=gwKQFDi>4iLm_Ra2`%c|=o zfvf!9_Fn1*A|C)t(b%&em*rF8pG}vScqmevkw5Rph=nZHH+bVpA?%_;4_voG21>SVtMeoT|L$oE72px zVz2DxC$+keeLs6K!pAmlDOL7JBru31*|fsMHI|M)u+&SJ!DI$?410pt%~EBoxtY8AYVKdL}~c*Vi1_DT4I{ahycLYVR@OR_=zy4wFWo z&p3SIBhh$WCn3CWTFV6bd-l>`TaJ1ssk?xh3!l$g4Id><{HT!a7U3~1MWO%G%Rpz# z=l!3$TXz{r#pM$qLw5K@k3MG;7d0VC8;<@)Jd%x;K85NLrA*3WO8P6_y%WthVJoGz z?TX^YIT(ST=`g%Y)r06HZI!4Hwt*8z#)7nt4Qc!9X_{>L#PxJG52XpL%4;#C+3FXa z9kOzNF2%oEf1GcwK<4|kD;jt^Wc^CcKC*j)@(|Fo0CM*_7(|&kDu~s#w!Y%2MF-h3 zfWz@2%{pEa!u;$NJ;N=^+1^ZThL}&oKMdEzm`4Q_Qa}7Q@$SVeI}^5ZK7UkiO+;?B zg9kr1Zxv-;2rMcFy|k^e#Bs=$F;IhG!8PZ0+md53>_c9kW()CfQ=Fkf`BX_8=v!@6 z0z4R#w&tEVOw;2NEgJzCZ9vqXUY&lFW}Fy?yfo*+E1A(uqATN zZ?l8^7UhyqHK)?$t-DQ)q*dBcCJC}GDZ0L^ESJ+a!!?H5JRXKu-hfnCj{)U z+I{*aX**EB2e?8Xy}iACgnApeL;a~gira^GkbmF!hTriRD(oCq4n3*F06Xf%$4PzA zQx1Jo5xT%5sI-~3aXST}Kd0O#_4Q%)k(1?(gsv)z1U_#z&vYy$#hoj)o08Y?K>BrR zcA9t<*^MpL@uiZH2W6N)4HR9KbOkD#;!2X*P~7qxCy2TykOK?MX*)(1U^DK}ab9aB zgh#{V`>a4ZmA`+K$IUik_i$cPX9|rr6CS|^fLehYOL(gF!R+mg!|TG3BQ1%P6?KAd z)HNJUPa?g3e>4)9R-xE~?3Oh%c7{97ws5>aZ6=cZz3c+f4rC9Yg!2>X&j_#7G2?7x z1k{`!F33t9u=?+9v8||Gv?SrnJJ&DX@dA7`i0F`tddqa8Pv+b+Um)#oFN)B6%|djt zOEFvY&-&!Y&Cm3N-}%2QN3Qo6aJt?pqb}3AE8Ys*e0fhoB4RfwPPZP@gN(_xt z^X<{zI-S3YJwjt~d_vqEcs+RMEwWDEu%Ow;*_6#C_~tP^vwJ+L2aI$?XrF}(-zPSypI*-p9Wui6qkQ}i7yLr$yNVlkhd z#zoaB?jay%ASQ1)Tx~{68---p0`>PY{mhtArns=&*5MbYQJ0~Ec_ek+sFIUcbUxa2 zB!B|5-WAhGy=#gmJSpBq);L`k6crRDIkNn-O(UbK;uWRZFRQt+EL-7Y{U>I!aSnc_ zwQc1LRXuud#Jr!1xjbs|BouYUZ1ME5q;9^C{r#FCHb1lfH!ly<^n{1({p5S`PGd5nzN)K?kMTT#iTEB6UcdS8@3 zuFx8l{OOQaN7H1#BUjcnXX)K}F>@N;vtL2*BeG54&v~7eN^UD!(PFWN<9PL?gSG$u z#Dxr?$H-4x{M|lF0;LcjFZ0cQ>A)HZ7idHp?1L5@!IRhP{}ikw!@)uUMFJPV6I9V& zm;!eQw2f6XKQ%&##A}0DIe$k)3a!83Pv4R3Z|D-ZS*-)Fmd7yZuMtCuA0@Z6RjWizrp3p{ zXGwBkJOcY|jGp>cxgVN4Wt8L;6naIJ3e#c$bpXFhzdI7yC$4~2(S1-*U=9N7VCU(> zOrXtuu?Z$jfJ5y45|ZGWv9nleC`q>y8r=G9Z^V>f{OQxDMqx(!bDwD?Tv^4fo;CwQr7E=O{^+5Z7DK#l}e z)VP`uPjs2~ZAY1!@Yf}mqUtctjelrv26=_>Tf}^{$lbfkK8 ztaf2muot!1C6O0j*qy%17^&@N)3aO`PL(CXDwo)QExc~YZC$J4CL7u`op0*dZ~XP` zr1odCg`|9x5kyA}z9}7nP+eCrgAbT4++OwGBb<9$dnW<_4X@*B-$`T%@dJ;i_YKGO z60>~f9o}(fN5A%gPvStPu%GM|9ziHQ$Q-o9a$#Ff_K5vM6p5;COuHao{U;B5TN5&P z?aEd_Q*k0{YzuVLAV8-OD+1*D*47I>&!4bUD}mz|Rk#7aft5 z2ZfDlM2?16_U|l3fzKNtKH&SisE}7oblPhO2fa71m{_v^cOMs}>0Q;pnLT=;#f*yu z{(APgJ?jrd3EdOn9svwsfw7OXb-cGJB7z4!`alu>>_!>S~oMU;H&fUi}uXV&%c4Oz|*)o!+yx_pX=KL1{Yg4&0tU$Sj?9D!=`2M zbeyJFC;g|wMkKf&>e)Wl`vXPiuNB8T1; zynylt%1*3@M5K?$`-D5A<`TK_tBt0$LUb;KFbVYZ_voI6`#FuIoR6~hcErfi#{47F z|Lx_c*rIOGjQ*hXZ^_60z+hcXuSZ&0D8wH(DwioDW7|)&b>0P+4X@gqR(WE(UQq9y z7-()2Jm4xtJn-EkS_17jrfY8jxCtM5Ulkg0J1nKyb`{`%`^WM;oaOKK;vcU>9vsZ( z(#oLDuz64is0*c`INN%L9B24Hu>F#l&n)@<-dlgrb|@<${gcf?4N3z1^NerS9GRUb5N>e(T2AFnl!TJ!&*wtC3CDeD$Dur3E6a zHa}vtFVf#V=-la^$QP-zw26h#qr+(>zgQSU0>C~cDG4$9(+g09-WTCeK6|>aAl;4k z6y+fxSyD+rGJxGYpODbx%S%!HH$gS`u~9lugVlk=G9VcIIF|-#YGu52czw2jak`yy z#0}Um`51=St=Qw;G=Gi7_#Apwjva1K(M;&ix%u1me3aeSyyh_9-cWaREEGS#k&-_m zWj$;0{zwre#*fkD9QM-T=Io|Tq?7J`3I3De^vjN!aJ3~c4`Aq)z*bA1Qsx=%kCKRi zKtq~K6_8MCXvF((o7b+K3}CiMI)orZZ)Pq!M%USs8`mMj$tEkKjc)2t`#%aV(Hyex zKbQFl*Jh7{&*Vy=JO4l}$u}7iqMfgg&~22zSAOyvnG56c%2Cysn5{{Pf#>_QO&nHU zp7L%)LL_DwC-F!0)#d*QH{jg8I*S%Cw$B#px~)ZU!pr-z1b5Nc_rBM!*RT}7rEt@| z(zV_=8h)l{{PYR6+l&XUE3lJ(%mJYG@^8OOGtMk-5t{1DJ`9c?hue}rMp48 zJO1tSe*YOqXK+O3oPF=L*0rv{^qX3q9n`+Rc{P`00lEsy#z|0+*5zTZ_67zD4V+3; zzN$IVTJ@=pZwq{F_wj{He`R30M#cZ~9w#|Dg{QOM9^}My7iJx8Z;#efBK~`|#)Pu4 zvDH`yFq@5MtWR`_0F5-8^T~0;=w}d)^adrVal4}-{l7~^NVUjf$AJqla_+Wh1?DXR z5uF}a$L?MLZ3pCO+(!|4-L8iK`p!uh4&5vB6I5sT42UfM*XsT^l?eCFascXTsk$jl zu}w>K&F<5SV9Dl4#d}i%LOEa9PXF{ZrbqUW+BHFUyj~)$9mvRmm|q@r%@lRh@)ASw zSWx`r2rN5Xey`23UzIl_5QF2+|4|IO+jRZrtC-tmJHmy1z%W;LC+Z{wc5juxr+++V z?XmenR+gADW%Mka<0T7-IIM@CS}-6lP-NvT-j=IDY-I?#XkH?7P+d`+Bg3pUYXUu$ zYh~>^p|+>*1m8-++UZ(s1V3IlnuKUMXLI}woVJ-WxZ&|lS0_I`5&G)SYpxd3NdL1- zEgS2eCf#L3nABL)OGGwe)r>LrA$)DNYmZ5DN~^hllT+q*qbnj&3*!g##Vog5 zKVefLk{Z1M1YbV6qfJgzcN5rI=V-kWRf|veWK-WOaFddfI&M~(C!*zKr@jmxWl)9x zkb}J2aC5AX1lw5QZv6?!*~RAh&@i*(-Wr9^)%^kB^ZgEQFl(uv@z6K3r8c8SMC1u| zj0TW9FpQft|L2=M{gs&0&d;Gaa)wZ->Ik!(1p%lOiL)|b+BR)0EdGXphBLLn*9mC~ z9_fK#GoS|x&b4?Mo&Kv@I_l@tD(gDIonH8Hq(fGjM=of>t)kq{rWN^iQIXGNNM6OC z^H49+<^*zCLQAf1kU`xEI3h1as8mpvQgfczM=E>$O$@fa zVJEO*r`&r49mc-_ZV2g9Rg+W*kAc0#!afc}(O#kgoQ+jlm=NC+*O1Y%7dcIx;eB$) z^GU+*Di8IV=u46*V>FxSu=_uSRCcfpPTw7NGe)+Ca;>~Jiz_9+bD4m&p-LyiCV#pV zQeW<%{(F{r0w;uinYqwz-yG_e6sjp;UYHmwUl50a*C3ShZVQ=jxQB&2dmMt+dGS=3 z!h@8CBWzKQ;%1)HMi^i84RibeQL1cupXl)u*!Jf-|8tUmQoyZntouHiWykdi*s+Dz zx39YvfNj0czv$IN-xst$;r}tSc*(4;NiONiQH%Sl4SWnhwMc`S7PA(R+IAK0RyK8T zhzHt7JCNDn(5$`t!=(P+^CN=+w{3L{rLJz_qP(olJhqOg%or6N`Tx(o* z@8<4%%I>{Ay4~^29?jvALl9wO8*{vs7urc`q(C@ja?~@4;NOYlEogc6;DcvJ4VhKa zdehm6%wzHNCiTm?ZuZu19qIT@pB*(btzlHpLcUjRj?5HwPO z!ZZLa;p|^&Sz((-Aar{Gq zh?dgNYISPe#n(n!ZQ|SE=c5H`9K)|0p5~8K+v3SEiO4(1IYD_jg9f>OCI=Umjz<23!&}Dt{#sJ_G3q%8vqUWrrX!XCrez7 z+NDC($fBeZ>tnPLF7Bt<|9!M?-@FD=OJLHLAYTMjJzyc?tR;NaE~s<|z@Nml%*>+< zKQe&21B6KbNLZRHs3&fCo6~&*X06P#u<+O>9oh@01mV62>T9>*4bKKdoc!5P{e{hq zrVQUiV*-!8#5cXqi?#4>oG|}c4(aJ0_1))%y+-J%M9Rk(rMUz+&xPNQyC|0jQ1`A2 z9Mm#y>@Z7#SIURXN7sG4-2bj%jVW)~MKzZ6)4--5Jy{=$7x#158|wns>R*8(aF>yL zComKDPV98})l=Ck4Y%v)>@sX*F&b2o4It@jJL>~PFgd>Z{+SaCK$=j2b(LH1BRL}z zpw@r-TmCnr83Utu^E)a(zE}6o@vpoDb<% zRl~mLc#iM#?yLB#DNbxNayRr)dHC5ByHr8M+P&&J?RRti&lR0aA*N+2gpW=iRh_ut z-9v^0rhfjtHX?0kGSs5~U=gN(4~gcsYCm{v$kw3#IAdD>@zl4KYD=XuFZ%$PVc$rAO$k|z0}ci{zw3M%EF()P>hZOvEa(b9`WMPb_IqRL5Qe0EdMV>|gsKxDyc z>8?k+e7)+yqs>O@b`sLerNAqd(&>&5@AByOJ=1646Nk!Zwom$Nl2$g^Bj8>i$UhQD@ z9k6`=`NJ*d`OmFa(AqWET$YcJmN?;SqVu+XZkoQFh4scIwPK!`n+ndIq<1!R&e2+# z~b$4-cl5_xdoJ(En&o8Ca^QA+3~cR+6pwx zV@u2i*xB+mpM8Q=(tcn=Npk!#)`{+ht3bH@%$q$faL@09%F;Js^~p2*Vy z6{}BS9KmB_ljfghgC?T@Q_{pGZ!$+$&+`Jvq-{QjIRPI)i%(b(_5Z5(g$zCnz*Rt2 zb9eWKu!2IkS=xV%94sK)fB@KiZQ=|r$6#%yU1&Rvbf!bQ$fzhq2HbfL{xL1vPLVR_ zbk67p`5P~7W8H}hLjG45y{UWY!FyzlpUKSqJ5dq$zqx)DKhk%*G3(+dK%L?XdgK)~ z#U6dh6>|D{kJRD{4H2C0I)Qr167SrF7uXO8XW2z*Ge>yl7S&Pa&#|?p@bZkd-^9I0 zN?i+~*uN)5!pCWP4f+SQo_3C5ruIUiA{6)Fi!N^@wrgmtDuoHsO851 z<2C^)VfXuCb(6?V*J$S%$9Ew-+v;3R-5V2>`*oe2oS|t%=|(nI(Md~en`nJfqd4!% zx2lKY^#&63#x@g;%nd??3;b{*IE6H}otfM!BIhYQvRJln$xaBMv)|sYo2#nkl*5iPfSoo4V#)txRt*FN*z;D=VPS~4xIT^6 za{D((VHZ3U26(_U5=d@PNqGlAR1%lht=+CI>g<^x(Ls?WVB@ej-!S1Z-TpM7WkOww zg^0Tt;esMHMsUcr$?TwqjHrw3lF#O$Ch6WQ^tg?G0e<;YTtOC*5{t0)n-ovTIrO5d zci%90CJCQv`W;T9Z(FQ6JbS;d^`E+tzg-h2zV;IvEzRHXd==J-vCeiot|!;PzbRI~ znjnJeI$+3eRJDm}@y&-(P;as$Y=^W6fLoUX7-0SY!h7u|w>YpCWXaM>xgtb;<@&P| zwJSy>w9AV^ymRMDnde(()vwiviB6;m+oLX0m?!j;pRNRCya|r{TMfdG+Xyv+&?6~E z#;Uo#W%gVW>#A`ZAN7PXi3a0{#$1ls5MBd%+4>eD-458F*_GfLtc<%TqfB%4tIIR~ zncyeZA=dm6XK`Cx54Z5u3BQWHEmTHm#$88>PpwF){IgAxqO?J;k}d<5IE6g1;(JOY zs$WQ(A2#u=i?Qh$P#Kjp-^W#$X%OlP69i2L_vVU)CsA$(v2FLVZ3H@f7@gQa7eN*= zCbayX*dFW{4QSC>;}F*1?IfHHx^Dd8^C33-wohO4!yoK7nJ0Lk<+MxZG)NWN7i6WiGR!WskohIu<8GuwdIM?`3`) z-j&7CbRs@?!_bvZ=&aL2%4p62rir=E?7=W8(h=UZl}mO2xh}3mY)HknkT)*ML0dJwKEU2AokVWWC^xl*$&3QP0oIF7uqF1t= zL{{Q}MAg^&D}2|& zEt?xf6Z*QmM!mZ3H)C>eaxreH3i6k)&4d+B$ayGHRsl&HNH?f=NF^*t@5-_1RFLx1 zeaK7>H2gVV&0c+otuPs!sa3#^*RllGnta*yoY9^tl%N*O@*U+&TIqjcXdF{4n+Y8a z-kwpam|>wgeq16EmvJHBz{6lPiL3r2X^`!U&k;@Z^qS_qp{3)0y#7#~TXZ$gA^x2I z)6+Tw(D3(P_F64vTxT-y1qz5(!3GT|u3)Nf_Zb$TR&t9)s(mPp?sF1oft-A8rq>~u12fHmXKi6MfpAhT814* z)|$ENx)TgzjfRhQGIP3H-^wkqZ`E%U@h&0Ip+QZDq0cPBa_W*i{w6}BhmSc6@^+^` zp`uCoq$%{)HVR~96%nU&+nwOcvmX;*aUuG z+*Ih-8Gv%2TDo0NJAx6!&j2xd8n9?dqtP12JV@mXmE!n4RqLFn7`aL&p&>@KsDD4f zuG->6KIB1y%)-qf-H;`g@%cM_+}Hfis;o8a-FuI8J;*(;NP@ywIcGXgh|vSUraDug z(V>H4vwOo(LAek3=XY;xw0s8HEhP{#PpvPM5fOGLaN4&7U6bQ^XdMWGZimA#v>oDZ zJ80Dr9IVJ3)iSQ3mCx8<)g^j_Y)!Pev3v4^hvMJMfJ5WUArlj$qU~Y9e)SQ>Kcdwe z1R-?5w*+RPZMPc{8Qjj{xw*Mxy_St|z3adOcB#`hoBqEPTxeS+_S{Ge-GP z5kO!B&_()kS7wXvT=MDz1Fe5%u;vKrc{x}I(Q~i9wfkiNW~)H49i01<`kT)uATOXE z;s{Q~%F7zG&2q;-TCk1n?__(87fq)LeSvi%ls|!Mcu)>6XE7JoYcJy~=}(gJ%QrsR zt6Uh(YNkii(+}Jqh?TZti9xbbnC3f;^rH~V9{<%xQ!PJ~9@`sc7CR^b{DwzEd=~wm zekgj3YRJsgipVBXTWR~^f&ki(j{>i8=mz690BQfG~(&HiO%>z>L$&Occ`2!-`0<}TSpkiS!#Kqf6l|3 zrRk=v7}>U^W^it>^o4Vj=CSM(%(R;%QX&0-@^U8rrEY?lhi)(YVb$2g#bm8E9V?yP z@p+v!QaJGoCo%FhtFzk8Z2X^aa=c5*u81p2qc1T?iu7O6ZD-Esb)&A}qUwXkANM8w zUlWK1zv8qEa}jeq33|gtml(P=Bw3i+R+&S?jG_DJPK=sFM$37@R9PFP(Jtn+d(y>q zxZ}Oiy6XAYTPo@Omr|7yrK1Xn*WIvovsVzBz;kF&P*93II_I%;W}-?7SgUZ-L>mDK z0BCGM`1Ly_Y9h-@P*HZg9GXpRG1ahhsVjWH?b(2N}-$9ic%C##` z@t2^Mg3lcF%((8DIMfJNLoXzTKDjYuj4OOKTjHJ5m_b;64k=|CqRDk1XGLTY&Sb*eonT0$|QO)ZAaePqB}tN}T0gfjw|-CXAa zu?XB62FW%{*=eccZ+&I~C07`|)mp!aBBYd2owRo}zi89H^U(5+T-Nmh(N#j;SR`2ir6IT zx#Sjz4ti@H!pRIazcGF3X_)$8R*?~4rWnU7eF_cj`^9jl4E+V?(HDFtz~5E98+aIm z-ZCK9B`&58(o{P25xhK59A`o9z(ap@_Ol9I?T3#v=8FE!A+I}SRcgcp%XF!@K0H1Tit|^EKf6e&q-~3lkAKLCEu*zldE&v5tP_Q^p})am$NSq*(9r9~%H@rvCr8-| z`N=`2NA-T8#4s=8`ZFxdmI6;m*N0Nq?1Y&G3h@R<{R)E6oXY8jlGzZUBVh0EvHDg4 zgf=)jrrNK5trs^HGREgS(>G(hx`=v)<%=#_lXLK#H-xA!wXKrky%IXlgqpyfI)dSu z#TLNmIM}5l+W2tJ?O%@Mq2`h$v-3KiNBo0lq_rX3LNE0uC=FjKo29&N$Xp5e?;BxK zI;HH6buPDXE`PzQSR|h=K(LmdBz_S2N)@%dqIvD=0HOcC^I)Ge^Zjgy(*Pe328csD45km!oYtM2g(C8VnI%pEOHsH-CZ=(tN`{EfY`Ab13G^mr$DH>+}kX0Sauk?lQXCj95;7 z6?=xS>Ak*m4KUJpb#<8b;a`&9@V49S9>%bYOx?nf(U+}rjiljim(=OCh=gdZ^B~@W zGt4tv@n^5OIxFihX+E62e_}Sz;?XGQFCeOI5kY!N{`5Md;cM zwj}=j0~R3%9b;VD@qGHbj5agOCu8aYLbI;{5YhKE+a#eZW=y$L}Gjlxd@;A*r)GM^A8$g8bP;?~n0epzfAfF1SYmw=Q~) zKp=%SSA+#V!q4Dj@!YUhD|@`B(T2JAEQ{X>?yWMS%q0T`hhT&fQ7gLAdq+(je+njR z!xCXz)Dx!m!Brm7?rVW--E6mTfq~s($)aXKH;+(NBYRPh8NPgHrfQbK$RKP@DYV^c zf`fh1K~|YVk%PU4n$ygJ{kuq^OQS;G$gzkr4CYabnk}@CF~?hAhcOg($G7gHtH3R= z^Zjh6ahPiGZjojH8&*A+DC2kt)wI0x+W0Au$8QulzRkr1fTS9% zl7Sq%MZ{C_-Ag+4u=NLoG(<$7Zzj*WX*?cSg^V)wpJj^A9QXcOHr;D}^(g}PKj;zQ z$;s|?y6}Oa@q!@w&x3rYz^wPvtg{Qobbr_WKNnzuP!W4QW3!@hsu9SoT@HuR!c)S`B^KSAeHP5dmn&c-H) z5nQ*0p2OsR`I62VnfrbKO>kyJC2Ejm>VgYZa2cz({N&|pS*`LzojAIN zl!%CkZYy=v7%p7oW}#LC04LdXB|Vxl&(t1X_pE5+{4hDqOZm-hSnsG*2O4U((%lok zgz`1d7APu?<}FB2h_@USLY9BArfX@Xa>7kYHUxg>4^ULLV(^u&Yw@dKhW=au?DJ41 z$U%GtsQ&};c|)JlQyN2kdt=NFzsNk^rRuW^)??fJ##nlTK^3bIOS&PaUP6LdbEtvi zH_SO6dXnuJG4~fT&zb@+yYp-!S)<0JWg8g7wKNZt&K8%WQUe!hHeV)zr0F*1W(zAQ zLY|Htax^jQAMp0IHc@F2{n zAzZkNJYKNwM+?7@li!9UxDF~FAh|27p;0_Xg^u|y2fuJdJPR2{lZj>9(6iAKbPJ5? z^P5%K;&13h$4VeM_rLH&BLsnFwhSl|6mV3~Zd~(xejpO^WBz%xl6^Q}UC$1I@g>QL zjtu4pz9d;zIz+h#T1lbf9M5nFpN@WgeYI@k2=PW@pt31$=l9l0u!=B=*F)fUWi-{D8}B3H+)p*S#Uc^@yJJb zsThZ|{~{h`%J?2(xKzav2_tFv>nus{eJ#*({Ca7Z@k zjow6wgQkEKy`L3CoC@a(7AP5bco1R;#gfAFz7bYYw10l&VoQsy{*7;WaA0L?OXg)C z&=8X`B``D4qF+Q}vtZ!E)aS)0t~XnJ(4toLcaHw`Joe=Sp>(u*Zx*7KLzZQS$1TR% zZ)|g<8W?t=3R;XWCLvF4U87u6)*sKi&hm%k?%*HRJiC5E`rwe&wQ~(m&vmBbcM=sfcn>YJ+l(E>8S)5*OcST(n-uB$-NM4K}R}TQp(lrzxB_zor?10!s#acDE0X zoU1GSb;nLW;#QacI$aa%(eVlSTa8QRj2Edoo79<2nj}pA$~_0JdRfcg>dvP`y=y0w zztYo)EdIgB*IVvrk~UUfp|GW&ODJE~y~C}MDT3%?lYQY9F(8;@rhusfVOMJq9S29UXdbjNBaKk!sp@KYKMB+B<896fyDHJ^#hwR+nSzukI!lKdHZ0};9jT(J zxjB601Z690YsKXip9XGfNUG8W&zDlHe2}XGrdCT!%gC4*$Lm84U}HCLHB%Hh91T^O zXz1bb-LQJ#*Vfyclhxg`O)(JW2&OQ2{>>uH1R|6(i0H4*!%4w_lpt$R`#gt~akv7qD?IGNg z#bk3O@8iV6g`*ZNlWr{sB&fhXJ-vGJj=^Q=#55Y`*5-oCl;17A~1FWq9je_GnftX%s0*j%=Ou z7u2)^jtS1RLsHT_&et1DV=axkY4DpBFCoTj{mcu=*p-9zJ&zbn0vp?@gQ>4qx!0QQ z;_V%ONX5s>zxq35CFOg&YmwsEo3IUj&X;Fho6wGW32gKSqi1QI3-H6mes zTEuZ*L>t@ge)p{a{#{+35$Xsc$57~n*NzQlKCP_qMu_3tiM^T93q_1fF%p%RNiB-Q zhz`}dhaHnS9 z6p9^pGG3CB$7pkf@EwKvGEzR@;d2}zbYP)-(Te)ob<1u3dMioxUYR8DP)z1g3!}?5 z8ka+Ojn-qswlCFI{FfdFj4#>e#|O+mtJ$RbcQG+)1E#LBdBUJTX_IQ2i)sulz5y^8&8I#WG)LA=An`6DJ5mRf8?_4H!!e*GFF8nUdOft2;-Q zaX@~n+a9_@tm`$cY^<+zZLLuxggFRN8X7|uE1W$Y8Xp!j9jW3zde)N#UZz1}-7h!> z06TNC`HqBJ;8B1zf^0*#28v&aOE16rhWmha5ikNrc;HHqcZT6S$1uHU1sh;Bl%B6B zWbxA>_#+CSP$TP=&j=zg&28GtucvK@=#8N=Yke4aIZl!9v-8x!rRwzYoH1l3((|ib z%(|e%_8iX|&<^{|!AP z^(#%+aB2{314qk_@eVG-5?ZoTTHlTXG=3PZ1PuXheUoM#QGYN+Y`r106*|e*-IOaOc zi<>FjTiW?lje@R9kL6bp5qfc4i~C^480aIAC*+&2Q0{I8EYw_y zqQjQz6ev=X)M|h39Z+&?Qwdyo5^8v|{-I1CMaBQEv+WRY1QP7;UQ46sUO1tD9sooe ziPmXDPowk)y{4EclL5?z=;ZGH~)c9LL2DVhJNR0`4P#MJV)5-cF#g}(hh`)K-c(_RRTaF2mYuy$C*1(-%+lh!*WItn=Eb#4$#zx7&tc~@EhNOnF*aWuhbbORijC3UC5o1@wR=PNSPY5YX-n_p>V`?Obb_7@(( z$#I#r(0#~ETz~f^-bo?~0n6`#AhY5diC9P>T{3`A!A-F-w0i+$VF2O~tG_26XjYT_ z*WgSes@BeLt@nfgqeab%WDbGc)%Vpn+l0GA1Sr5=m2O=XSxcm7s`n(<6=>UH6}UwWS=Ue8M-F_W;0 z%Y4sjtn@9nPl&!vpeLdu#UImmQ0=!5Pw(PXLU(~KUEAYbS zWSotaq;u;F9SfleC~oqIH(&;b&@ta4_{YIw1D)cPnBXq*zbMuThhD>P!Up~BK)Em7 z%xla9I5P!GLZar7`gu2B=qsGwncW6Dm2+8Md@~RC@6|`u%X(+RNKS&E(y6nDmCI(; zSJee@d+k~h+FSF+TaQ{zzzP*hzDux`>Qm2fU6xvtte}?CLBUa%k zWtWA1D#_M&Dq?W$aEDKUoyJy~p8bgqZ?klFaAK*Hs9r<;R;}w3N7Xc}w)J*#E4v@^ zpO>~jHXUC9{dEpxaYe_xN;Z8pA86ekm)bf+l*-xG#UDQS#J-QfZj4`K|9k3e4?XKg zgU2nIH_6>!j!?7NFn-;h@-ISy4q-wh+;5duWNpK3|F{Ko(p0U-1PpKXvon69VcD(v zGxK77*5@=Fy{H61tXInGjjWE8Qc@Y=c+do@93~9ML0a>^S|*4lAov~ z^;sV7Kb9%5_RKq;iF^MKW4l6MT0O>$A6Ctk(9dXqh`7YAQ-*M8d?J%B!jj1o5paf9CVLX0ua|q|}%yC$~g|5+i_WsfO zBDtIQl5#sHKotSzU=BsOda(kKi+! zB+K#}X-vuQ_IvS{lhY5Ef^aBm$f;M|u_J+*c~nSz{p0Fp zP429>-L{O>Qfqmp!_I8Ela{3GT_eZLw#C#@_BljnFF0@H!?Pv}x(+JO6MtGPJsu%Nv#HxZWDN1 z0dhk-E08;BPVC$mt@0mw2k|SfuUoVR(GZ|}>D7z~W#Qpjq?exgsKHK%<53IDpzQu` zh>5~rfTi@+>HAkaFLpm{-~S3O9IYIaf#MAkz22 z1yJ2(wiEB`?WP>A$QU{$GE0AJGNJ7q#_NmVnO4^OU~%u_Ndfo4k|k!v8tOeVxMGR^ zU$q@)?WzZX{t1BvS{`O+VD_qi{2a+Mr{Aj_k8&gHpI~uHOvli3%NVFl8My z30Ta;>J&QVKm&?bc0$p~Q?y)N z2-elI0(he;cFcc;Rws++MSpZrYX!LN`e9DGb!6^5;Z7V;Z2;z9HR68H4LM!Wv3o?M zdF&Y8zcw}_(P{6Ho_zeu-)Yadzn%UVz<1L4#kW{*@DKwLc~3c8V!RD%4Ab{o=WxFQ zJmSy${rQ(^;rFzJ^{M(wGcal{0}X4YZ9+sZ(vf%mLJY-Q&k$S_+CSFJ1iWmUA47j8 zbtejtN#p6)M>kuFuTIn!Yrzh7^`?{IVOyeLB0#F<@MC{<-VL02Z}Gb{E$?vocz(;2 zJdN*>d$0_vJH_wNfOm(VaUA{|njM&4?;}j>)T9wI%=s3VthjpIPET`#V81VYyM{p@ zR?QBq0?SLEZqj6~-5oF4YN-3^)!+VGIqI?^3gh3Wt;!dDU{CfTN&3E8qSP+zFa{#J zgB?58Ov)C@;Du=lR9vatb1HR6Te$pVd~a#OJH$-3IC z0d!&H)3vtad{wy6$nAp1Ct|NWUlnvdH9Mp|wEn=s!gn%vHE z>Mfq(;W)nbd@i-ru5PlC0nS|iH|t;cRQva}d6_WJpevM`Weuz% zwfQBi%cS#EsiG-GrN%iCdKBp}2*U6cr4^Y{5PP}|B4)ljG|T3ElWu(vh>(DvnYL=UmThG310fM;w&zzS zQqTpzBo_lB7_|I-1h{C2bNHuMZuzadzUkn--NYdL`h?S+8_0FJv?y5^INv1Ec1m@4 zop6iUue@LB52KUYnQi=%ag%Trc_RCs%1^3F{RU?W(@H`XEsFA^fc-uaYF6ZiugTjx zd;br5P(RC;X?!l9pND6$cCG@RW)Etl0&ig>(vLn2UU>J@oy2+)emv%trap<47*fy& z>)yzzU+Mj$zpCW=h%phJXhpdXNf@m$vAmgG9%RayO#vX0a$nhtWL%2Y$#(RL?8t^$ zJv%7=>LGyF=kPcBIPVD$d}iMXG}Qh^M00=GUHeA=YUSZgqesr?ve!C}Jkl&5VFg_J z{aR9Tv|1jRFZ*S_`)gvq?UcBdX(WsLS?qp6+yuizHA)LlA?Zk#=i6!Y{a?3FtNtTD zMB9p;P(6jesc=U?7MSdsKVIh&f1 z^$Xw`K?w7yVSI6ND#;Q;ulVPYlW#ew{5ugpb3|AARvuQVVNDGVou$oj+6)=90rcVn zz|S}TD2F19X=+B%5S5h~_r#K)_S+kJwWXx}P6}lKR_`@}n{*c~>Gi)yt>!J$+9PfK z(ruUCB2lf}Z!sqFtAALIS7-qw z0iFWy9z`|RJP?9zQ;e3}ky&AUF@7AAoH(9ZPzOn|*}gEbxggCh^VL|K-TIXCJ? zyO2qo1~29JW;xE46^87G`hE~@2wb!EzD&9o#Cmk}Yu=~Lp~jqYz8b>gP*GNUyhGn% zrRUgt+u zLIfBSA**cqlc`((<{Hq>YK(f=E?l|Wj(NX}!Bc8m5O~Py| zno?i?9Fn%BCY1Dt21I~UH{_W;}A9qRoPe`f2 zotOD`lyKt2G9PtECV1?`HTEc9eFvUUgZJLsYW33`LCCYu1P@-cu+2h|^03hv79qs% z42*+tNG#WlyBBx4*VVv*%4R2Ln8*Dl*+w+$Qys7l24BN6C)a8#dp zNhn4uIg9J#Qz3s|0oz1lIRgcasRiYn578xW8PGFcG^$wbuUOlpF(jy>sho3ic`J<+ zy+kWqibIf6E;MAX6FK_wq$D0k2OLWTCPA5M$kPyyRpRhITZI+A-T8sn?ZO!utGMxS*?9&7!APnwWlTL({EIZF@{ifge z`ySPE{$6-(xgoMg$C01@wOtU*yu&1_sO4}W`2o*v2XefTBKA_M2;&hF=iXabv({m} z<)4-uDUUkv_4!_xFWRf;CL!rkpV^!VwhH_Csgk^u{BT}$pjT6_#;IX^$chVSvGI>= zc7LxF;Sx7oP|69;Nn!o@7!U4=H_#Eq}e}EJ>e1%q; zSG2UW?|?m}qeeH2v4Ie%K4^UJ6>xF52V*}8z`FG5uU=zN+sM1Gtc4S&Q!4&OzYJNx z`+{V+0l^nYwWdMS?2j#}Affn{#CmOoIsXSc@zy%NZ_>WvC^Eob#Fv?qut$Ry zO^N!&t~?p-gwy4WA`gi&`m35W2HZEuSW_z>F#!37P2Yi8pnlhpE4*OivnK`cIwH1V z#*LsFJ&*gI>ejN2Dy6EyorXH^l5EApgXwNqK{8kiM^-`HfA+I}62Er$)gLYiY%yp> zJg|l`b*%H8{41)`SOz_8YdZ@!a=zo0FuD&HGbSJ`9bN^@#^4`t->6C}GGG@cdP8Nz z@ZX1m2e1abcFmNIat9o(-MDOdm7Kgws|I>{tVSL7$~+}_t~k*B7)~gpQM;`r0s|x+NMuf z$0NyBjmv_#9AmSzzpRCN{$bujrrTyR zqAx=M3g-K_F&yJb{Y6a{;{io$k8>rN#QnH@`EhkHgkfioZ9;CiQzBO?!6oS~P0Cb# zr*grO9v@W(|JXLR+lEAVMaSxrF6G($UXR~%D1jPoy{9Kn=UH5@A?Ff!cH$!Mw-fdJ zg<8lg+rTVkd_o!algzf}=UoS+%u{4JOX^x8M2N|~KPGB9vA@-?v#)HM-;rNvAN}6P z>5S#qvJVg4oA2jqF?gQFfu$%yq(_|r1*0qK3<-w`MXc-T8^|AGlwLaI0N*I=ORl;; zXaHAtBWD%=15zw=IHQ|=U-8|&b8gAqL+Rf@j5MUv#r%D-lKIduNl?x zwTPu$ff7M@nQ~iWUV~)uXjS-^Y zThJ3XQcj^nJ>&V72b{p}-9*oF?rPvr$9jRk3Xykk1^CxBJZj z$l6Nd+ZHSgNT0{E_m5j{6L%;7czqhoe-%?`AI54uuCdfcMCjSf6_UBwjMrix(rW50 z+IG2aOPmThUPA8mUs8cikosyg%kR{|{6xpham13~ow>J2lj52RlSlPMXmzSdd2CZ} zMe=^?=E*bKj6{LhXvkRR#Z+IUgXT1wgYbr!p#B~r7qL%%Z^nHS<%gDWZ+2}cc# z*AGe)Si|MPX+$m?zN}O&^E&N<2T59X&yVha<_4e){wT#$=&xsViRW|pz(+erouR6( zZRGr%O-5!oWZX20&y^LV2|247jH@pNQr)YOY^*|G<-K|mS*G82%MWk2AbNg?ZNe~O zR_A^Z3t8iVy5BUqeP#Krf!umr{>?KRjMQ)K)tV+{RA;qZUoSUrSNB~qx9~%3X>Q|Y z3%w;J-1y>F3^Z!Mvy-LyFhN6!9TD`+{6LmQ#vaBHCZ2A|5QAhd_uA@HM7&NA=(@bs z>XK)+#O-PV$ngiqeZCl16zD=u!uHMC)9W;OXcf_@H;B))Wvwg4*L9(q->tk_*+v7d zkC+6nS3n5hB7UtSU*r$-aY=hi#tPMg?Q?L4i_M+)_D;oIbxd{vN=-&qw%PL(Z<%G; zQoC!6X{|dY=)&^j-LY9WMio$|1S{OBfT+UPreu67Zbr~8e(Lh0|Ajz+`y^!CjaHv;ZJPm5d~TbzE68 z`;N`yoN{vXM8A>Lk81~uB3k#Y?d%z;`^euWpc}8O2HHE;jNn%sPKZoeF$oJA11KC54Hy(JxHGd%bG za)mTsiUYd;8tSHaDtuQFZ;$v4>9Lr{Jyw5qnCl^zX~D5OUxnB^>BCwTS6?t9AiEj1 zQ_i0+-ZPx{9^jm}Aqp~eJ@Oin$5{<@biD!taw#E1h12_<-Sv1$imLM=@xQ6rG<-7^ zL^w^_G-7S`v4DjSm>K<`P-91p2W3rDGct_5{u`u=u&UeJ`OuHt@Z$@~XFu+@^vQ9L z%o>5r9R4eoPm<92!}~mjWD@)SUgeV-g8jerqMlxrQ}OpcrQXXb;an=T|mPy9D6G}x=>pL>pDs9iNiIei6*K-PaSB`hi4}H8UL$v?gyy- zZ8))hHuCN@eJDsY1dr9*hx;#a^|(CUrypmc+5I0D zqga1sh8F*!3I9QnFoQpQef_B~(&tC%ED^gFPe2D<_}ogRK}D}M=ZI)zOC>7@%HrZ8 zZ3}v2`Eb@pIMG0WN0u~mG3mBRmdzVlduP_y=XIgAvHf-n*fg27XZPmB_UqS&r0JG+ zWICeLb_SU`jF$-L3_X04#*TmYqklZFpLs&#mbIb7>sKas@b91b0l_)A*bJBLSKfBD zV|Zre$i}>$bE6t$yb#Ps@r6zJUJourLT8t@wMB)mi&0TS+8B)@UBdnsx=IP>Yb^O@${ z4-~o05-k0CfS_|wLRGTjE81 z-r(w4uda#bL8w=*V;;C(YMxF)GyfKK7kR;zR4wGAZ;?0N?X+umxoeMBIuD6ljTFmh z;7r*}jdkd)+{||v-AwJbt=Uez?cBz5lTW*zOi)(P^9fw`6`tAOeb>51Mb;q z^Ou9vH3i{rfwR!Wo>*Ra&WLdXpO~nqBZ4#S_epdqu5PoyP?d{I3LVCYjYQQ<_1*OU zqv@KXDt)7Mwr$%sCpX!)YpSUxW3pY7?V7B~6Q?F)vaQp}#{GWxuG>G=s?V z><5Zz?c*HC>5A4g;LaE0>9uT|y>{EPN!o9xD2D)AvR=WNh%5b|kJB9t!w0!7z7L#fol5NxSHK+BuJP71DM{nPF| zf*A4H$EY{jop!9>pjod~LmxKghsu8QuGsC7>?1y$RgrzQNx&FT#jXMfqK^W!+(7l|yw#(Bs6tsv^S zaY&@k*Xg297s&`13K;{B_g#=7e?*K6PUMWZ|4H2m7Ipb*i-j}wb9j;lgztntyvw#` zGOOItip^2%;$Zb{`BkUj)C9(-y?5gG{?WYra)*hC`Jh`@2AXUNX4!Gn?<<122=mwn+NEZCj}Z>XnAm1|F4AQr+B7@rlv=7;?J1C05dT?%?*TH z0V?KgWx)d+yqs;4nEx_Qvrg<6`T2k``@bk@5NMUsD?e|S3;EL}82Y?>FrDDU%k`M>My+IXREKoWV-B_wbd8Bh1ED;+CE=I8I+s}u2SoE<}Ggy! z$PMOW8#$vZR~&yL0~LsWnb1Xj4v06nU9ou%0CDf3sRI?ZypFO1sjf}QV{fhZ@#L&L zfW5V8FI-$JiDs`7_5hiF7uhw!T6`qEdb`QYwpOm`01NxRo3?km#Am}Ene{5}7*_JR zSl61>KImtHa^YyO-GW$9@dFdINzG75ZyEeL)}7j2j3b)e#8aiKh(%efb#nEsz6lBIych zXSqk7#$CRUMCtvAE(LH$XTzLMyl>moX^!voppl@5^#t>Rcug>Qk-{BUN-(I1op?@r{=JYW? z28l!6v@Xl}cAu&Fga;gR5JxnEINkX8%@`g&M`PG^-&ua)UOLYRrNd#)*Tf zg^@8^teY;aQ){ww9Uy$81zu<0-U@p`AqknGn(9D>kn|LqaG|gAXREY24^I;32uiD* zI?vF6r^G@u2e4xK=Csrn?ImMJeAYhp*uBT&feqdp$c4wcsZik* z2AXbx(mKF#9laDY9P7%t9kAG@6tqX41f=^B;`h zo-4O!WS(O{#6L-E6#2m1?bqq=&F}tt&jjb@d2#frO{__o`Az86{gaO&F&fxLvpdi6 zbH#)4kik-lX#B{0u1N%KO-!RS<$zvR0Ey)!~@no!i zHt@r{4k&WU%t?(f(WzLxVgt-obrq5P+hDZ6&R`;t)WLWT7xQ(F z2p0zALAnp`sV{tscLH$x5VzhhkL|Z+ z)u=$QMfJVg`ZZbxBqGEf_32ngu$)vG&VK5Rj7ZF%{FSv=GL4)H%QC|tRJT1eer~70 z&)7y%W&_MqmQ-I|2Z(LgP=^?w2+#q`PzXCRg&FJJ%uFvsP- z0TWse4jxUeQE&fmIjtJ5LgDu{_ln~nRK=R$KxTrw(;=B5supmsV*RK(mi3xm7 znjajJg*YUK_?GMX02Cn5d+0@%dSVUXao{ZAG=dR8IS??fVfqE*!+q!^@kkK6z`R?7 zu%oUJoq6t`NoAtplJhJJ&(r#!0%`)}!s&T229YR4lrzmU97mavr9bHV!X`g}owcQ< z<>&%1NByj=M}LLm=i{^Ei2&Rt@9u)Bl8i;i!Cv*&+#R8ebyaD_BAorpkAUh<-_(T8 zp*?yp^X>rm+_6B^c`ERS{(@zp`FXdP2!vzit-wxC% zH~wi^SG*;0!a!m`KAM6t(KJ8s_Im0ix z4S$*?#=jd)ZO&-&j_5IwtrB@a_Y7=1hyd#Qmr0e!jI=DG=M>W|M(A zB0&>}4sdXuA}+&D6)`cg3JAzE03~rUG`K^%M$dM$zyy&!r(N=+f<89A6Yjpn2Z9lj zsL`y{5k8FNjc#7S_d!ckuc;W{-d0{p(f~vZ6uk#fjQ4MZ^^z$N7}6CP2)j?h0CO8H zBCa2;i_kK}emR^MuE==pAU)Q)>+KtKyWR~eMuVY6R9o^~+AWf}V?4|disfbq>%PN` z!{~2HW+8b{KjAB78zs4yO1rh`)&hM-zEsQ;J_*~kuPvMj>tm5IYtV0MH_Q@9)#?y) zb=0I4e^|Z;*<=l-ajlctU;ivU` zDu90v4@T)GbHk17vFUm0q4c}Zu}40w`*U_o{y?Z?Y$da@GeEN|a)w;9I*%7Z(|McS z??1auCwgS?!#`L@pWx?kF&@sfJleW|;FX(ScOaa?XEm=haoN=(aCH%a89vRQ_77JN z>Y4eyt#zdZfW~zpztf5(m>K5nV7$OiQmykjq zIz~ogeZCnBdFjye*0xDj>1o}mwe>kY{wI#MvrMttCNXTYQm9DLJTqS?|Jixbkg!So z9(B-^-ulHrHEhuPXv{gG8r2#XNB?4vTw~X3+|^M$kL-ig;sUZczg+dXD?7I*eX8`4 z_+Cj;Ui)Qfba?gSM6Y^5K|`gFjEuHj4KCjT+!eOQN9hTt{Qhr$=ftCmln)R%kS@a^ zB*{l{OeXee?z51mY9o=oWUlOg8X^aAULsUruMis>```8+@ZL%85|wo~#ragFb-f&I zkvyjt{U;G0$Tlt2sflM%@ghk1gY>3X6a;YyfIdI2=pG4O9u-h&%x%d^2RKN0Dp*~~ zZDyhRA=Al=Oau4UgYeK=)tJsBxK`J{QLP)6PNEE^fOqOL_ z|9{5bN=~EuO)W&qLLk089mi>eZ(e`J_p5@01h_8?_eWj_;XMWN>T8VH0Qw6Mu$Vh6 zG!7^s^bAbM2(JoGpR8a!19`>ghoF z9gy)l>_V|Qo41phErNG0#W!=mepS(7Q{5D??_9dbslli!q&mh|eb4?mB1B)}PKv_d(*TM~;+g0CHPp#Vc5Nj8?eKf6G1TjIJ9vd-xItoL8X>nEH9gu=zBhY()0MW|rEO(*r%Gv!j{ z9Whe(uhH6B^HqD7?%N1E$?uxbN)stvBx>V+kDb7rz?6V#heVPMT0m z#AO-5^!jB;Lr|-dD~ZwhvRKi5Cb#Tjhpz$lT756#Ygm;E|0|huaH$0%wM-+BU>F6$RdTa)_6}>QfacR8;O*F$7Pxdvy>9)IRX<)yKR^DVbn8MF zZX$NM$HE{k(})JV2w?K{NRK{j!ISyapD(0(*tw^xdemTX7U771j|cOLhd?oD($TuH z*5b=wP5lSaJ(m-HVVaP=+C>(Syb}YL&B_iuvy*~uMz@i4G?k1Zjje!`Te+Vv^o)e1 zoOaQDwL8~5y1oQ-q4yKUn)#6*Hr4IjzgYLEf1hxX_x9QDmQoYG1`KfNQ#$?6@gxp2f(a{FT7v5;_k10#+1}S0r;fVM6 z1g_ajn`Be_!#!|`aRPRAEVOM^KeeLSY4bmn>BC6D)js*(CR+NH^!GQMp>{W~c40Br z20%ZyQrT^sfmz1nqi3s&E*ael=QSZJ%9{_^{{y`wp*F7)?5iR8_lzF{q4x?vCQ;dMy2_@6>P1iphXT1!WR(&$ZmiHs8d?3K<} zZPcf0SaB0BQ0gxNF&b9IUMuSlJ-u7lHvv|%7UE5#`eP#ps5j?jSXcMJ`vu~cUI4LD@yPj2zD*C`RE?05^^ z<(X3ZZvw7MN*0)L9oE*g#@Al7*e$d_4d;8eKFrH94g(sor8;9<8=Gv?_v-*WeDVU% zb}BfC#uF_wi_a1$`=SS2yxe$q)0>Ur$W5-OAAiAEbzA)l{Ho>iN9hnl-RF$uUe#e! zCrmL=cg(RFcgA?Se}$AsGMTGao=u6pgK!5w+Nbj~yfq6(a$aeC-_Y86-m(Luqjcjd zJ0QyZsmxW|^5TOFS}(F2C8T~8*I?tJU6IP=qS-W^A&O53zhgxeOSInS%I(BNkx%U3 zcIp?+F^U|&=RxTHp7!9Di_FzX{WZMqA)Kya^cC|fQ&hDCY55aQT?8cjHzvR2Uj}NC zxdY|D(TFGFWJG>s>hIzCPA|f(S~fPHHTxnx>o>l|J+#MGAq};C9rkqGy}a7x2yvbT zi{5B=w0xL&FnoFFQNI+XqT0;@de#o3awE3p9uS!skdZ<_PHt;wH)IIijQP6OKX?eFxK7_W&F1)k3vskUd7HI>A*!Tyo4h zsp!`#$BE?;(#wQdLEux3)wrlpzl0F-#)L_YqODEq6wweoo-I1Q#z_6V`y`eRPW@{Y zMUOSKi)ax|1F~`Vk}M^x#~$VGG*ic{OiWt~@rGceZEgmF4N#hUjLogTgCf; zb-MO$a5sIY%7(hCtdUXxj61`7S0;;vRGcJzM_*AKUh$}equ(b#Vj0i zwIl0UpHr@R9>wk3C7NONbG$_)ct@@UhNPhi#9H{owcPS;72duv70;bEEMq}d8iiw{ zagSqY@rqqO=Udjv(7iW!t6}>AFg#;+ta-u7sSoFy-YBC?fwFK;4v<^(UbwP&$Ysxx z#(?dkrlK;*1Tx40Xc8GnJm7cP++VCUeC+KbhRD#d-~dr7zIN6Wk z^7P7I`NfPy`**ihCnqpf0Mc+KIz_2Mp?n^=!YsPm0cIYESJf?`SxbQm2^(wsk! z2ng)KUMJ&~jfOLISW_R=zI&U|cXviqt`B9+t|uNwvcHUymQ4+ZjH8W&U*8!usJ;2$ zAp|`jHH~S1J%~EF${#dE-Ng1=M>=w_`o8sGV!~s5^D>3XASvmZM#98ok3X28q07b5 zP{fLc0m^RcKkb;|U3)Kkis+CnOyKL2r>9K7h&wr{ycziN1>iwI;QOyIRyR=Qj{U+&jvYrVTw?MLpmo zpQkV%Jr322^{00*r@34I9kdpEoPeh>K#YhToM4+saVUKb1S@d0hz_lh_fCdRL9br% zd2RL%o)56BINU#N`J({76d+HRQ+FWBY-#ht!)WFi0;J<;I&z05gkryj*81SMOgMfx zf#-hWbITjQx!^5+S9s`&3=^ywy__~YL9ib&qyrj*?G@$VHZI77>tLdcf$zn7)r<3{ z@}cT|)s+;=86JOWktHtGBGOMOm7QOR(O!kVaOBs7dn?1Zo6cX`U5XqVQ*hqul(Fs_ zxIRT1wn(Okn*&jy{ZY}E*Ylpz`Da@!qVv*leNa~WXc7YX-MHN{(4rJJ;(L7O6D8WTKJWmD6#_a!ErDq1IG zKquJg;2&I(WgY>wA@u}}%`(ASp}=lnTXICvH3rD@WyZ{v9sxl}6*-p3(ym>YpzFiC z1Qq1zXWI6kv+Bl4kL2RnHvmDAY*wjg&S~w-@a)=X2e`oV7CP~30|Jf>_^4E@$)BM* z3X_llASpVVF}9k~>c}btlJB5eF$V~0g6d!}#=W*vxm3K||8vQX-%uqU3vJs;@C&Cd>gnJn4+AC4lTpI#r(h4J$+=Y8d=~b3 zhxX@O2C9J$-AP(#yrFUt6VJTcq`_tc_J|deFb*QKf>@X)ye`p9%L5=r2xEF(md(Px z`>LH|@{7`!bcSy?`h+*G?|c0zw1b3*2uZIU!J zsJ=+IB>ISRt@cG)QkI6G=m)nv_C-n zvlO)PfcD^ez{QwN^UIX5-T7lLqz>E9%i~jOJX?Ik*YDoU2|R8O)6ETw_y3}AE2W=F z`1!;mY7JxfV@2}4l|HxpGU!ySGAf=wok=vPl`VVbNf$);q*$h*3c-$m#vp5gUCf{+ z14|zKZXthJk-cr&p5%qQ>E-|0l-OZCQ-IbF-@(*SQ}-CZ)<$O}nVTWg@pt#Ie8h-v zG*P=$$Y=O5Fiww()B7S-G&8fD*TmM_GVbSu6l4UlWlOfQA~A6qAD_KvY&F@vejvz$ z-EbDrb|6w-1{46aejra;&(PEophSTb5AGgrl%;k@2+a%Fp7Sx!qhvmuqaLKtpJqAn zvdca_GFn|w9itsjnfcpHL1j0$vKsEjSWJx#Zv32+vZ1@I{}AhcRYmxQG2CkkSxl9b zxNj!7hu&|)>bYnpF5tIkHN=<#=dN6GA$@Zn6@_n3uTs*QaM3kQffOhwjUtexRPMq# zY{VufLbmnhTQS-%nKHI7W_qvEu-`BN4vk4BO+1%O)0p=1@`B!mYOIkI)EjceAY38p zM;66nV{P#G8eO(R>vlkbpKoO5W__KtwPwd-cdyQ%

A>E3z{4R3aV9R&N}%zNGUu zM!YMIe%j$AuTE@uVDT*bn4UKPBYS|gqtAy4+})Uxsj0wB7KT_KhGK`={WvH){LuT* z(GQl1m(1DQiBLmJQo47Bp?b;QAIHFM9t-xcxZh|AAZI*xMEa8`7g9^KifX7fdAGh< z8nED5TKVTXiK#Z5R2VR6GG?5#sEGTm8gb~sZkoP`hMNO~UVK{{;Mk{)TmSg+qf*?K zUv_BB>`$B~?}o6SWvmgtchFu}NZua_RMY;hdtNJtOtW`-n1>I(x%_Sf$SBySx$tZi zY+(n^LAVYY^vO!i)PkX|SL-Cs+rRL~e?DON{z~|zVp<3LyYfNZ0c8x+7PAb8n|ofX zh8GA`!Unzi!~J(2c43y)qe&(bHW|el_-9CBho9k6_pZFRoX$OjHXa_8=$gTg-XgvA zk9(Wmss$1_?fbbP-glud&z zX4&qQc5?7GG^?|7+7x2XaREjzWvVt9n-McHe2Y5A{ch>Bbujx;sjw=!)8EcG@EK8# z$DhC9gNcdW%@_vTycVObAGQiiGDeKM(J)ui15e|c3fXthb?71}P^*(m0!4A5gnY}G z$dJyEw$n3$A|ey#!?8wvo_TUN?mu0eqzSj`Qzaw}bH`AK&q7Jt*eL!PPVIyzQ|n&V zzmb*qMsNO#tzs!KqMzm*K#*4cwLxMF!|l*850_6;w{}@B7M%Tx<9lOydkC%cW$(`O z8ud4tq0&2w6Cp-jJ)gPx%Sv@_)PHX!$x3vDtZ^w(^Z0AJeJocCwo*Z2;X2}&_W0_(U-+w4PjBQ+(D zgvvv2xYG=zSVBcIV1By~&}9{?SJ^qkv%`#ty)9r>!(VfLu| zX}~4SC+Xnwr4R@aj5R2G8Y+@~=3aEphE%+_VT>zk^u}+}plIOE$hc$+44#tv!0Yk( zuzK+^Nj3`@mq1T@8`V3n1byr?z{sQXzVkWkBjqK&6E(l>w|ZTzQ~y@-#FvH-AY(8t zvJtl05cx9m@9^5}Zb$Ow#F9gD`Rg zA@P%3>PDK6dX_b@LzvVo0+k9!s|I%!zM5?9LeLlb46s9N^ox;k_=4aBv4uah_1UbV z@VScVFs1)B@)#9A5+r$=!f)`d5dj4vU6p2(VnwX=rl{gTgD=x6+j1yhXBa zuZ8|KFv=*YQaEM#1MklVGWpw&ewANKT{kYPGZ^0D*J|R|NuTFL?Iu06=`&DH@yXnF zP_y4qAWT?fMUqLJj=V%l#f*pRpN3-JVlOUe^X1hD$l(h`7wFO_=bU+~bgLKIOlvnK z7hnKDgzkp&g)1%`V`5@rn{ik*@L3a3F*Acc4{17e8+Ln*Qib&QETT&V(GB6TYWi9C%5^&0ggB2HRw8zq>x7!Hh4ER!t;A~;YqjpC;R?b`o+$VB3weM>E?x-zTB(G2 zh)_eeVdk20D3)+M`z=n1a^RA2jve7P=MZAYWiL!KuH~aTB}DKlO_?($Mb40<{w7ZM zLcxAd$O)^#ZBV7*f${un21r@#Io6=!SNMwD#62KLHyG}c(W)Vufl1(=#lji3uKXn-XJ<{xYVwI6MDxguezQ1ob4{ zDU(i}XGQ-giYDaxHuC5$nVHe*_&Cy2FW zk-P+16u3Fi5H|1EN@}rP4-Dntf1$!~E8W9r9Rqc?UxNjAZyS(C^`cNO?gHk32nJa> zIe>H)&(&x8o#B!6s}mZN1X>#ym4Un*OHfaQGfOFD`eB+vU6E5nq??@s(8g@ar;n-& z9(P7mFeUfIBn_rf!pG9L8PrN~qt~_qUI3+OI7qM~BO`!OuXp|tlKHiku0(2YF>5!BtZ^KlDoEGZHPJ}RHf6;D)gSh?_pv{6HmX5q|NLd)m* z)h`|Fh!vj*;xZ1FqndudH2N7&wlIg;*Vz*^v8grFnNKON_Kst&mztLw@ow1$9?dhEL)89xxPizuQO3{T;ZE0Ved4^*Apx_l>Z;Jqt2fg*Ppa=)aRsGNo z=Ok5{-QNZUQDth_E|eDbO4eDf7k|`u=J`n>+su9gJ%`oMiNy$t=j$Y*iL5jUE+cJ6 z5oI~Mk=f1_)Sc{GOBc_jbU!%CvLuZPi14cv@!z5^mB2fS4*9hiI=mfo;U9%nm ztPTiVV+JY+#70P_UyS*4?=*mi0_p;wj{{O%fi;ztrR8N))KJ^+m)^wpPx6lkNryoT z(r>amZ!=PFGiO(~WblIYn5YGpj*vj}Ru0|W_h5XuBPiu8{~C0J9Y`x3q(1+&^kqR+ zq?`QNTm06@^8q{fLs#s%X&!y%trCb%I}5TaI;35IEk@i#4;XrW^2>um6(^%kRw6NA z-f216H}r60l?~)gFa@)+y*9~H5)hHmrH^rVn#X`Fk`)`JLAZE%xxKEzv$IgdIm9B_ zIk6&J6_O<9+Myr>Jps^Ew}{Q01WHA?&}nfY{$STDuC$1u)G)6e>3SW0;Q1=YaWmt4(u!b z?+CrY?f95%{l1YLj=~7hV)}9vDS)%yTXC)Es-`HG-Q$MGc~@fz zX8Mpum``sn0?WaW>BZGv&v|EBEt@02s_w!YjE8Smh{ecIvL8EofN|n>y8*!=hv5KxC!leXTe%T<@O%s z79&hGb-YpKV8Z6*kZ+QCEyGHBLi1ntoBYW4MNf=eG3log?yc04NyBv$cX;3M7xP81 zDS>%(`XQPYOP(>BKE=vSisuY9L?x#X8v{;qij{ERv}zB%VEPl=8(E{;P)M5&TD z@$hhYb+!20KxcXszQmqLX;1q|@Ccgz1S&Kt#&8K(DJ6?@VZTCcFoWYjCgf#nm@kHY zZ3Xi1I-NNV4+%oV_cqGn3ZbtHgx4sFyrecz>_RlNA@ex({!%evI@EP(Z{?irdUX_r zEZ%<#nN^afDP2-yM6|!N1*ND6T{cJju}mx0k@F(NXzCu&*3H7HrjnyBegM zURUeA+J=1Jy=Rv)VD*le&66`35QFK+df?VUk6;m3q{W1)Qb@2=(b~$}vZ&|S;d{sQ zROG~k}gD-sTZ44RXFmebCJxu$#(o+iEeOI%lNQixy zSnu$V*LA_WT(XQ>>>(r6hfG%-;NzrE8d z)MpQ->4b)v##2Lw18gSM#fw>9{aD@zJ&|DY#MCiV_0{DTebS!n9hIj;YvV?RSAG(jd47M2>=)(MYT(b8vGwNk>ff zD~(?4<|9GR^_k}J0kJIU{vNj*q>OYo3#Y_awgSf~k*~3Ne9Ntnc^@7UBA9A~Gw*p6 z8j2B3Qg&awUmrPZ?p(hG<{B*N!Hz^i4n= zY;b{i*JnzZFEwJjnUy2Iy4;ZhK*L}DPh3F!!OBJ!Mff-xKLN`RfJ(@hBjY$ZH-~+A zcm&j2k*rTY=;K~n2ZC6xJ_h816fMh9`U~JjVWV?3+2s8uwsZU$FnJ3uAD||bLnmRp zgN~>bj~;C5H?>D;gL|D2-YJHr2!5hBeozB$t{gh{4`vKYG~M-=eV`H-!U<*N$2$yR zi$-cZL3VZVyY-MyL&?dCn5s0F-Tb!ZJSd-pHemly9M3rO+4E+1O@Vz|6$v~zIzM*p z#3w3v_-wDW>W5;d&g*s{y?d&b8R()n|LJg9&pW z|2JE5Bf}LBPfdv8kk;bn(yRv6;J7w&Sw|~~0@#9hFEfTJhxn>e7VoD;MfD<368yEn z)X-qcfa5#lwv$etuuM{-L!S(}59pKQ1dg3=$RA;#2Lb&D@kLlgN>eqe5*Gh&PieIV zI+leKMFxMnVKE*_P_%OKG-+NrM+6pz()Vp%LV3N0(`z8lMEtH#Oio`zHF2DxyuFaiiP$Z?R+RTo9V;0sB;+lAq{gO z@J%-_9&`*H@*DPdILW!6O6CcMmC!Q1{t$OlblhT>W%q102Y@`XC4FfOlayFS^h}&J zmnZN*5Q1zoq!B<^-!g^EXg8dhy z4&UzSstKiS<42Y@^`V7DmC8ul$eN|P|6-yqw)%ovupcG<3Vm6MzCXupEU^=`TFNHs z4P!DIP9wL>R=<4Fwv?;QsX-CKI?oKxKA3QFk0LYp0vAhxdRMZp!KXbjn3OQU?<(5s$aqk9 zPr1wZ)&zVP`im3emU{I0mwKI=fLQ(zWUY+xg8;|{5C{~|f0lRiWBh>O(KSS?MjP;9 z*H8?h_)Q?if=5l32sSlpGHV1DX#n=~pVgU2(a^ zY-g@8_8c)h`Q=faA>C}x+ea`wpbRz|#s5P};A(BKNyGFCH$0e9u?M|^U0NiZpci`* z@{f{L$_NM<&EgJvOyAuKu9_hPxf`Z&@8WkDKEjp~ruxO!eI{qxk5liCTyQ+ZEtZ=HCM?P`$C^hF2>yij-p6o1p}nyF2*Run#IJ680ap z$`1|{eLX!hAV3C?KBY73{sJyhz?L-XB1lKz&&5;_gk?zy@T@mG19FDTXz}pKnj0E8 zIP|w??jANXfGXPIgz!O8cw^eukI>zBclo|3zKB%W&5o&EaET5z!5TUV=N)v`g>vj3 z2G9~LF9OoXvA*gSim7>T-Ec1PKD!gW9bn{Wdy5CY*D5cBA;Y{$cc649NCb(|yc)<~ z))S4IGIs}EW4L489eZazACWTBj%gveNSsLmXfdZgePh-@{YX-9>4q~l3|o4m2FvU@ z9;P#YPFNnA4e&x}qo?qi3l-6-f!Gf~_pwsXISV zpuPf5(rdyAGfKYR&8E`I0Z1M>t~>O{|F&}FKQvZYuB3ByN)&2V zXh?pel+QMD_TIPFa{~Ig=T)Mu_xpCn3{$ar{WO^CqL4$vj*6k*CY*Yx=UFvTR%9Qm zOUdCinX<{-n_iq{e=3%y0R+v~LUZxofP!8I4K~mb(*e=-ySu}&II*;Re8n7o?8zOPxTLN591?ZO0;eb#)=9|>8FSe%w<&R^5h1!I$KI>Hq9ONJq0>e z6+NbWo)|Eq`b#r41f2hyS_cIc$tX(&hwaD;tW$Jxo14|lYptD}P_`a05i(ZdmQh1q zdcjSDnv57B(jqE!d4R)*W|hwJDpP(ST-J#*p>v2)lDGIh1~HbfbHm_|ZPRZUhEP6o zMPeFJwHd^g(wY=H5^w8+>x;{bvF{)ZpCf+;HK#d7OJLRxgK9jzr7dPGgtPekt2UW+ zr|DN8QE?y1MQ{G~4rP6?XZWWTye`M->x6-Mii}b}`Ai-J^oehwcA?8jm5H<#cjtX| z^f3fKLo&=UE^KVtvr)6F;A#y~_fw=dQ&kgBHu(XBKvFjv7Y_1}7e2EVjI>-FKK}v% zaCxq-I2$glth3S&4w@Uwu9PL9z9PS`jO90{;^nke3ZIUyjfN*x4)Cgx_3s4@II)`x z$77$E3gyu15}YtaKnd02P5Q>m*7m-vh^*tAHPbPgE`@;j zNhLb3K47(jf{y+`k|9q6w9f3We%*{BH59v>_k$kP24}sXR)boX%TA4|89R{xhEoqA zQ3FixYU1dqWl9vO#l>8?1p+C82%twZK6+D0`cgqbCqSwwmO-5kU=>Fzby|AH#z0p# z@6ZZYju6Ixyf7`YF#UUiXrMmwxE_94HRP|pG_qBtk=nhrT?dQZF_T)LVd&Dg(2VH@ zDB6pV5SvvA2sh1p)Z2>RY-x0^@VE{5F zm8{h$%CEzKgY;z{nm{)hQt(*kWg&8QPLrnrm>={xlTDp%e^bk7W0EhdT$lA{M37H| zF9u>d>?q84^24?(SFxifCLuyxPmG;v+Gifr6-ra~Wo144E?Nwn@M9VJq-!p)2$j6Z ze2f1UWl-S7a`N$w0Hkcd^H=$83Yl&JIU<8F3={x) zxYH%SHL&H%>g`N+;`}sT>p>EEznjyKi9;<$JmlC!~hqzmM^&nnr1YK z(-v`qz;a|%RN#L$##LIs{2tim=jQ?6p>)TkI#2@pCj^>0it+{ver$g$t1w_a)h65v zv@DuTsGCr+M#+ys2YW%&Ql{L;?2*S?v&$&nL0&ET1)a=Ad$UjVYs*3AjS8_3#vc>T zE_!X~eb0{@+B=HX+AvwJ+1BQo?O5~iKTD_CzCR6Wq z!B!%mdFp+dbh+O21Ahh7Ak+na&0X7lcLFT@x1Z#y@&ly-a zHJcL0kM!PCAl%!_coMXH3c)-o;6OnfboH7opS1&mL?-|rYXDyYl0rpELt)G$k)qY6 zO8zsW4+Ieb)erEhK0Kt$$uWHKq{(IK*91j4AWOsF(zh`0E{jUDA@BcTZxnB2P5O-W zvGsgB?Qna<+hVNqsIO7D95$Q)R?lPcYOX10Z5|iu6Z&?fb(c24BJZ^MJ4q%;r3OzevrKCjWXR=e~A}>$sigFhtTxe!tUo&3|dD+lij?pb>i9;LLb97?D@9 zLV4!ooGB?pMFME8LtP&p^Xk2F*Ud3*7ai2_M2U(QaV#Y6Ux0$@BS(!#>ox|90QkxR zPTfk%Dvh`Mh~v!6JchM)$==@^e9j!u38qF8vLhtkWhr$#yG#?JCR7T`#X=|IESZ=A zq++Kv64ED3_Gr>(=g5hT`3nWw82}-nE(uNS4cR?%TJxjdEhMoaWw4y>gVUT)#2E>S|r(> zXOTP$?LOpFq*0|-rKJaSZ9uGdjc)z!iVyTjc4l!dW5(v;EyulhspGJhN?~dTKLn8D0MJHp9|2Y8+O3TJ zB`yP>ZDR=@w=)LmgWtIIlUvq5%F!+)pQR_%J8(qZ@-eNNLVG1e43v5b`>Pop6V%;i z@b4<}VsT5(cGP0CMrtfh3(R>oJ@yzVeK)b|n+cU28%p#K(b`smFA!Z_*rVr+OinG7 z2tqA6&cl>Ir(R13vT@{3?b>i49sBdea#1i5KjHSQhiDG(%|0GUqV|y{Rl$bc#LB`V zMJ*C2c#W;C-&T9#1iq8DE`NqoPmAI%6vZSBHo{dCHZirnpn3-dA!-!0lNDxciD$hl zD6o*piIrS-rKRXmsjy(ur%xuqGYwOLE(Vg0URsFaHy|Es)Ji6%rnrQK$45rsyuj-_ zfCI0bxV|yPVt)M&5sb7p#gZ>L)!~)3`?KjlTg`EN*YO>L;$0`kF?(Ynjq+d-|0GkG5iq60{ zA;3E0`wbd6PJ2Y`TQIcMoc(_oLi)JwGLthWKmVWCR}sM4;D|+(4{u=_r@Q8Nnbt*?Lla!U@`METn7baVi)@6 zAGMgM9};h)q1kk=CExEq79?5ZUoRYeNxlUGSVPd>COfwyM+WL4tMcOuB^3mCtE+$# zAMS-$oDHCVRoObKwk!gUoGgW*-*uWLYc`kPSims#`I}uVi_6Ym*PO=%S@AD;1Y1EaXsa{_cL9p4+L0h$E@@X;qq%i(=8<;74yfN`-WgW7he* zhKPy~W%=i~w3@LFT3Q0fxh)o`@s*2}-B5Dxz;oPsn(_iP+d^0F1-uK7U%IPQu_oRS zdhU)}x^84C^GCUphs>Ob_C@{ZM#g|{-2Ia#1-W9z`8Tv=jsF5!fzVCBHMU|Sk2~6n z>>u@_!Rei^DqL&p4};n^_BD5U=oWI}=cFFO)&HnV)zyBusKO-W#6TWy0J1y)ii!{e zVJ3><{}Gy7TV;yW0C%Dgz}jHr8S0Zjd;PEwX#~z_CJi1mqnsD6YMDi}LC+Mh`YGD` zeJ0J*#qWp+tTc;h)WA$mtHt8P0Bv9>TY4j7)NdNiDk?%^O5yc`KH}Z~7>6ORU%PO* zTLyr)-0?b2pV<^&+6~A-Ll>=T=rjY5m3~OV7MvwNE=j`gl+W40WBN^F%eZDCi&v{HivEIzh zBx04Z@D%{P=J4(`(Vwio*S*9@yp_mxX50AthX5HZb9Q|C1_tL@71AhZI*|F__U68; z?o6PDX7N=fmKsWnAbl#P+mZwZt5=-z?x+-`o<~*XC-UX+?|XKO?~T9mIHAR4$-+H^CWjtj0QV)? zo+%)0Qeud0im1Zi^OC{mnLpF^aVPfZ0PNWC%e1TY$A6RbX~jq;S?y>uS4SvCp+=Ro zF$#JHuv}c9KGJT z&Ny?=dEdR)vz`^LyT^kbf`Ii$0bfTOkmVnDV;vlhoJOUz=G0Gk1H;fpOJbqTQ>oQW11>UqJ=3iIZD! z0CeS#Tb{0U!Gc6+d{WYFkkhZ*;hP0;;@W2td5}#GHtnQzMQdjpeUtxavZbI_M7&D; zJ_7IbDjNIjJGZ$tzeSl=QR$p#cT%Sh6Hh$M-4!8og?;y5{qDLtS?&^9Fqq%yO5e*N zw!fx4VQ5Vte@OH{ErotyAH2spIT4&vw}npjq}OyaDUE%)oO6wRsDje<(jGfU z?)c0&9ye__9_O3Li^(PW1LRcPMUk-CfBSw=O}_HY*k6P1cuiSkYUz;*mbl~T=55L~ zE4gZ=>I-vU{`NJ-iwB52^oVS(A2NZ|>@Pb4t9f4(iy}zsQx6DTKZ$#?9d`-c8nO^H zsNTzpcc880hOmqnWzbcmhVw2SPG;Mp?{bl{R{~->I^eD-q8jM6uMNx0JU!E*qoXH} zf2D0Tsr*fX^mF7ZhQB_ z9X}D#fvw#ukev^|z@n1@RfNGoa4DXiBBn0z&n4dfQ~(=8Z2IR-XGgawdUbjAG_)#@Oc!nm?wn$^((!%T zDR32Q`y^Ppwe!TwzC7n2KYlE^@%-xfF9w=a^KWRdSg#kJ^L(TDXl%B=1m)MRmP_29 z$jD^Rob`I}MA2Fm*aB9|^-tc#%ZWXhTs*9}LHyFvXxsu`RgkU%8Vpn{_7c>Fom4<3 z7R_t`)HAtl>ps{9mlIip_bCCr8@5A=3y@j}FQuh)Lw< zUTw>v66~x`c}C*bu$f}Moq!jdDe~rB2%<*?8}v#*NEv?$zzReXwI!}7*;K2Pi)423 z$+zkLuKaQHjAWHno@jFb<)0%D(z6*-2QhzL)HvkhC&x-(ajjj#O$p@JIS5mIua2sr zz@S{~27U440BBeGBRe44o% z1+0Mm8ps`JQwqS>wu_f+H)TEbc3O`lg3J8oB-|r2EsdbQp#e-OB59+RL?uYQ~1_9dTR!{6TE2vf-3}*}5YRx3|VMP^ZBkKsamOni*u^zXln4k~7_+RNI zIT_<-Yqxyl6F`as&}Gj*qrc>yKJ^bg6FrZ~&pzFJDHi?bpc8EHx(Ye+`NX)whp2<3 zCKY)@gYIGi-b$I_nvN0XQ$1H^&{_4u>g=9RvRk=RNk?%v7QPhw*7@ugE`y?7?_SCEdviPQT#9tR-9)LvUY{O%p_=4|dBtxQ8M>86bEor81u zK$kml$Ip+pS1SO7%46E^cdb=~Z`WXj?{*8Y|IO!9FHv6mTMpb|1!jJ_$J3vlQ)(?W zkm#M*y%Kr5KaffpsNp zhB3;6z4gkKPC-QR?SJA4ym>Wt5QqiV1fHNw_hsr+Qex-hLncNF)=5ETDO!5u^gg2m z8}WnL@~Y-at{%P`X`HZ zzq;`sCp3`@JLO#=7l4JxX_jp+KFLh(o-S9hyuU_?QHiqhTJW;?-FAK6RmVFucierU z5UF7MSU_w|uX3BzsXQKhoT~Se_$2t+6V#esqhb;jh9kENi)ha(LQgloF+AED#;`=n!*7cNZa z!6hc5ZH1l+#dz=c>5N-;Uv}f$8Rb5 zqK2ai8dBK)Kz|QEN1(KZQU2$9t($Ide@A;57tSm8aEw21?l++<*-I3K5eUxulY5YI zf*CyS+~cU)e)2q8yc`aW8py0z*+&xq8SZaRfYBE+un`p%1;w(<+&d|2sSAU<=_u$*A0vK(d8$>C#zS0M(j+$|ln+gu=S$$dq6b8}Yp zoMU8WBCNrbn!WrK2#9MiHtf=6Pd(^|XMy>|cJZOSJu*ggq~*qGC-zU^QxffiIi$^A z_p?5XtA1Mg)=y*9&{Gwd6b3(;tmX@EezyRHJ1j9FATu)|74a2hL$$&l8S$y=%PQ1LA8XvhzF*MypSe6IM)joGs;oKrg0UL>N*r0Vc(FOR|6(P4 zJ@7^FcFq#%Y`-exQj4Pmx`pLB2bW~O-u}_z%XUo4S$VvTv&(8NxrR3iZS3$!P}T61 z^m)tY@*FYs=%S6BBMzz3u>pg%LAgTn-$kWWBuV`-VXWKtSLn#PLXc|wLB0Z#YM^OK zDA$i%B3`n2h^Coo3$->T&)Kk@F}5e#tUkP7^2WmyKb;@_f>(rd(tgj9RWK}q04HEq z`5q7K(iiY?{k8Iop8(Y9=++ZSj6{*VeV8Ok*)6PARkFE+Epbx{z%!fi+gzbE2R40k% zs2FI^A#^hfo8}b;L54i4N`lC&`c$nTOQe)nPmK4KH$ry)Uw*1~s6%MN*&1(dY6vg* zqSNXt+Epyz$z*jlBgAo3cCOfX(DqRy6uxVr?7_@v;*qhcGbQIoozzIXqt!^@sU_O; z{DDGXky0R^Ekq?GHnEdZ@ zsBDP{>f}6yztwMSTH7RIBUcLr1{z$P@mYOu$c0#Zu>=2TZl>SOt$f-E*X14ndh#LD zgym&DZf>4tl8LijjrJk4>AH|{Qs$*g55erotub^nJK%b66UwKjM3XrGCuoE(O#X!| zLAhA2coMwFY;3$B{EI5(Pt~X8jkVnVt}d}rq`$@rOe$!}w!-8!4UMH)Eb(Q7K3PA`39=60aih3xNqW~1b$uC~rY0ad1SXxr7HzL8qV zgIs@Ce!nM0ieL_Rvg2nf=np@|Mo5_9O5LA?@W-{Y(mbw>Ydwz&R+R?teq(jE=9gQw z@xk%a>$N3xlc%Y7cN=k?>A#5hz>=so1#hf$S$O)YF@)n!RjK;ashR02uh%`l*8$Egp`SYROd^_tm{@hIcNoZv=m{0=7XlTM1jSb)Qi0SXahDuWv?S8GUjx z5~=b%IG{c6`H0;w`Sb3-)XW@-3a4e`eiUj`iE3#Vrn0F4Nzx&aDRayz^UNZ!ZYI$q zOFtv~F7zL+Jp@O&`tgrf+7xi4fLzXL3+3_g(f{|gFiuyrYyNc}?l0B6PVnf2uz>_}|yzj4kSWWh7X_Lwu7i``sup^26&^v?XtV)YQDlVZu)0ENU4=bt*(*VZ;m zPqJmaENb`8JOuR$)xU%AXR^xb>TW=D0KOJDk-?K6;4R+R=Stp?^$Z0p%fKGnG_M8J ziJAthhCV)R#ezOkS{PqgCEH6Y6A?Jg#wx52A!0w}H-AX3XcRs*;EeN_T)r{J$n`DC zW^v{{OzI$vYoN}*Iz%(=`%3<>2)AFhw%ZmZQlZ8ddFSfRQfjOKzMwPFFy}|l=%$}m zk3>GTv3);28@$fWdOVX&Fl4bd)#)P8nGF3NH}n=;aS*v$WYp>E(I&~wZG;?3h%@PNOUTgwl+H2C>r0n zyN^vb-$q2RBqsi>x{R1RZK)dh1AsavWX*lOGr1KFNPw3;H~gr_4Uqn2BauH840Z6vtf?*A6CH}xc?q!(%fll&~rUE zKcA<|LN=cdg!6ZIce@7%R7io|Ftp)|ZzCpxFy`mlj+NnOL#^s@JfnYs&=^)9Z zeEyI9meDA%F2o}BmA>C(-D~`R;lxR##5G~A|3dL{M|L^UXb_48O!4I@3x+q$mqdlp zNsQ)S*cpdi7x~3IRazF%awp}?BA9>{WdnuZjE7XDM?q2hA@69;7DM=om5(J2C&{E4Z_{^2Df2~QF_=Mr7}k?3%y^>%8A-o)cDyK@ z)0u6C9ts71IuqM-lP8JcTlU9;+E@aEnEsF}|bLJZFt@|hC;dVvBq0T3aVEBYLlc}2TD@ZC0<~MTHDPmei;f~1v zzZPH)dSAG=T#`lG5@o6vrfc|3_@`A#2ZIAQOVZeZjWfYFQL)kSvecdzWjt+LL&)oW z4&Xokg9FNb5G@0U`#SBSam(DK{Em(sKoN7KNy-LPt`EMnhTq-a@12}jd^Yq~4j|!7RSU{ugE(P*z=rJ0z~g1? zX=V+^91ZB7gi98KL;#4AF5Wl1R0Tp#^Qs;MX97vsUMF{E>E14(7CcTXjGT75{W++^ zs4lql`)EC>7Hszo;-gXOIny0p!65ilHncsWU6bRRZQ0Uy$;l{04LtL!t0Gsk*O{0L zBr2C{JDmXg*Z{*PJENWHGY&8Y{$Nx2a&NIa5se*nZleEQzMD<*$BO1>h2lw54g&B2 z09HqmND=w1Z2fzBg19~Rm9-(obV&|5#;p8hYit=zaEQ=Huvsi~QbRd+G3O61GH7hW zSl@C`3PiPE3k|O<*8s2onV>eXeRq3>OjTp$UaFZRy`R`oL9soM+ z$z6||nCNIVCOm+Vsj-j?lSW=IEg+^FeVep02Y#IEZusl#Yt2^INS(-rIfi7me#5A} z@C1via`Cp(wN+ZkGd<;9BIMQ&f}wyV4$+?-e671(aHlF{89*uE+h~I4`ABdb=S$2~ z(txwi43Cm863zC8Yuf<7`y}jh@p~-d$q(L`^H%n6-i1RFM6LIXg^p&i0>Nr_ZVLasL6-UbHh065Rrtr6`$$lQ`fVd*$ypYIaI@M4 zHC-i~@cEr}cXB}L{tM(&$Mj`-p;+IEjS)>^Qo#4)|JpkLesfSclb}c|hZBj07g?Lm zY(34`vbZ?+=(AwK)%L)|r61IOx%tfdRJ+@Ew}cu>R{J>aaYCRnf1z7thN zUb{Qbo>|heiB|PYJW3%rP!RbskxmK-P1hg5iV2}8q2oCFT^swt3&wU9Z&}{HK3W7M zIJoHmBM9PxLXE4CTx?aLLhc|K|5tGW>NF2QemA3CsiM|)FK zxbPv*Y)*e9pY&jwCNP_DQ}<$~hm>-v&Y=3W`gVVac92fqk!3*a!tb<1Pit};m~a*X z*NUO9v!$4~tED@>Sv|47+N`F&)$+g7I$bim@*`H42UoFXV{IpDj{e%rG38tLk8{i? zSO+VWY^RwRayubRYM+Z2y96O5)v0_zt>1HfIYzC19LzmVzUlCe21f(fqk)Ms>&LBK zS<$qm`eKFpf$sC-A0WreDp?jjhdDuZA$s2)UG`6|amSs!Q<>ls#fF}f7rNRT2+>6B zU%^qPe1@fmOHABfJ0X&(xoo_H0S)|oxUIKG0Gg@zvxh!D`dr`KeE(Q#SqA>`-z>t` z+1Uw|rr0l}xyHeaA>&5x^b-M1!f5G^WcUljpb`2Bc zcSIm{ydgi9M`t$g8<@)zoYk}lql6_dSn6dnVZR{M!yWt(P$DZSB|5dG`3mytALf8z z2FzRLe1=LNyo>yPMshPu+;Ck?NZE>fSRG#^Ghw4=vm?WQ=(SO^P`kXkwS9PI-AzT4 z&{G+IzA9M$O7)j6*6`2JTB-6OlN^buPBcm(+14i(bH7)M!W1-*#29eUu#d1fp(x>Wfzn8Bd;FWBc8KUGr3I}&&I5FbYEmn91Pr= z#K{H&c;d$IR+^pI7r6?K;)^8E6AEhKwDk4ew3bs?swyixZ*O_!8Isgx_uv}CYC1X7 z&_GO)rcJ!KQ|WR)e)PA>ON-e9lQTU4lw=%~!(16)uIJk=m|ME9sjUk%^LfubQ5fs&% zJf_EJ*YX_x%CD+(K#JrRt=IZJ~1*&*|7sKRic-w z3}s4MfK5LCD*1ShkJzFLArDCRz)d6hcD3>x^1VDuH+RS1lw$}C!9M?l_oMlL|NgDA zWcW+_z`mb^8n3c{tYmt=LW6$Rowu*IwDg8PJ>+@x_^qYiE~?@(fr*)L^o6Y8sxo{@5Vl zwY}Rmo&pZzObKwV|Cb2plLdxn5dV{wmS$vWiPQ)l!ZJauPUf#*c?oVdFz<1=pOibf zU$NNOw0*E=IhGG}2!k4wLM8+q@q;N``zg=>sR^r=@OT$kX|YnJWHuU_N7>NcMf8sl zZ31YJwc_(^I>gnM#6$Cde^@Ezr);7>Q9j%hH0O5B;L`QfPYbM9HEWm+Ti?xn!4CFp z-J)FeP9wbTW)@%@nq!($n9-pLw@5MLVt3lDd|IR@c3wAZ+n+zvbIMrq_Ti@Rwx~ISIbChhE@3vGT9_Y=F)~gn3QMHA2e?l83?waAj z{0=?5uhYx(jJdeaY{RW`Vsy`BzF^3SSGAZi&J5s@V|=+ zTh!*!pG3Z3yi*$#aJuj-F(y-@^~65t@n_LyDZ^sWVr`!DMMy|7dIQ+omQC-8q$w!G;bFC)j-_yb)Fn+O>qPDa&Qi*v&e2=~w($ zL9kF!GmG}g#nYa#f1xw*`6Qxp%|}t6^=%yoURQ_xbRH#+#%`GHTuGW!41Q8E24~0G z0Cd-D7)hzd?K~mVn$IHZqPf1;YZ&5wG_+u{c#y$#(j!m7ar!`hLO<7a^t{cm&=PDY z&HRHYu9U9BgS?13S-$G?9@h7EoP+y=r6$L)pgO_;GG(EfIUx7uQocQYVwj7E;xrx0 zaYQvIHmOpS4Uyd*Tbv!!A zzLqu-$m0w(ps@5j0ai|yVSTz`tR-?eX4qL4Z#Yu` z&zt>wr#vdfAagkVmHwCP6`6PN#viV?*JBWIj!te9jbF(aNG{;*mweFpelu%8)_Ul0Ge%=1h8CnvJT9t z>B23M0?EQkZg9+}jD?HXQ(kcsVL!YdtD!lM6>l#_N}(}YXpZprjr3)veM)$bwnZX$ zI@uZSS}ay-^7cJ{)(+Y3$qRnb9AHBHz0~?S@w#H6WNW3a^o*EHz?A)c=voepY3y9~ zE_`%TzM2C=@7$ZVOxAE zms-PSM~8U;HF%=fmOG=_q3o9J#UQfvAPCrde}rnFLf|xt`$UuP+CCx%)K!achdf4c3P=N4TXlz{9Y4o*VmV91lD2UOS zA_BBmC_V{6kuJ;oat*I;^bjNqW;I-hl4t+{JA@=s?@cNuD)Owy*tJ$l-8XB6Gtr?xQ3$)Mrcmoo+cp{*n6po8)rb*hUZ^_^bBY@Q-r) zt{Eiz8flXX%8kA;uk2v9zf~!3ivK(4v_p+4-nbua40Px(q_$8>xsi>a_^l_6LItMx7w;LLPQ=kOi+(>#6L>>Wc5z16`yub0$!ja74aYdVI>!aPE{ zar)#OY>6~Q1dSh^#{EKFt|XV_AVAC^^c$@W2W>WCP9phBR=&uoRt>91jbgDatBXIS z%4K_%>7pe!@H7@wntZys+Hkstn6Zd`rRn-#bim-7pP8BcKFFbnA{qPTQm|MyO2=bA zWHb{>+#NlxbiiSsP_Y%*beZbgVplxgwEgP}51x-CUP!ep)9ZKJvG^`2Yrvvl(jjkU z5_Bc-``y7+VvdLQ(i4A(KHPx00r~7C+=hV^9;>m?-zKKI z`}L7(lDeXb5<7?BumWrQ;Q23<-@o62tZp}(_oS$f~4`?u!e_Vu@ZOU-}OGvl`j`cKpyBbbHngI7J|>@xIu!?)|>zi8cZ2nQ`X!J zXt=U8@BM2epewrpV=Y^x4%~Jc7-O@uFX`SbTR;g5!VD6n3mm5kOX(nc9-?lW4->{eBq?`RS?gxMX9IDh2>Kg96SyKN~EDhVDa3o3PpicD# z{{YBQh5R)Jz9Wh68paB??|nQ+`!q1ec;i#fE_uP~*ysAm`0H^WR`WhVI!qOP=F!x9 z@<3`z&fwu#vDE&ldJ6mO&$Zw(gbNPu4Zry|p^e=@m0zMnEOm3-Km~>pfIXsSfMRl+ zb(n*bD>~u7@N3}Knrv~?Uh+KD?4EM#^ynDZmrR0lx*^uP7iyDu z+4b07@19MsJ8aGN)>4Hwi zrjdY~&dk*pSn+nWbmb7{mKM$_)~~2(uj)F!WI0PQ>1N(Tn9tq`dO0b=F>7Er&EtQ= zG+m#;geE1BtIB?7>*xI)JL1}jAEaa&-=_f4AlpUKVKv#PVXi~&j$=!cgcRR1ku0R9 z_Ehv6MpJ-8dWPs7k*jvJ^o}oV0a>f+X0?{^#eQj2ObocterGteb}cL{$k{H)Aa{PV zJ@Jf3A%~8-reYnX_`zV?8f$lK^oR3{kx+$ZoDNpiL4`;*-N3g@_^j4(Z)X^+#&+hn z=W`~!qZi>NNNiY`ITafgCA^Y;ej+wDHd8iN_F)&plc*A&fUNT@2SnG-LY)o$OQIxz zi<7=3RWo@czw(gm*<}8(V~4|mD_&7q5$FUP>uM!y_Bc9IQa%Zv>$X8kP&Z%g{p$8B zLVEUrd0#u{NCz44!z1C+=EE7;N)Tre5}Cn1_X(MM)B7y=?U8jct`5$R4C_JS^Jb23 zcKlmFe9B=wkoTf%D~=lqmyQp4_b=@Ggxqb(gt52{8t$O!egOUgVxX$|*Te@zzTVS} zK*)cchCj-lPaWT|`)V<9U~NpGT9XNQ>8$ENW(A4Y%!HdW4Bn_F>Ty9;g9Nb5pt~Y@5 z$c3Pc>#AAj$c{S$4CE`GJ0xJ60^-sEL{w+62%y9u&&2(ehhZN=ldLGtAxD{JioWAO zD1`|orX)9oB>5JAXPV6o+8~av$gH4n12hqU3wh^Y(b81)U}8ZTlFjoSqxi*$*6_YS|)f zOGRt3&7H1DM}&&%C#$|0gLxzX@$Q4k#TjC_VWISHKb6567VLQV?reWC%bi|yTKI@q z%+>axyNO&ZD&h~fiZRRg?hlZy&S=-pfV_884r(k4&|oq-wE4%JQ*xeRbLsc4M_9?1 zR}2~Ng7e-)vw%_O2*PWPUAI_13(TNf?`qQ-QO^oNZ8_l zS4`Z?LGxcxhHIsx72_@a2x{5_SMD$t>D>iD-3(X=f)4AG!2(|{(ovH{sDx$o?hQTx z^Z`p)*r4EWxPya(DI(#E``WYrzKTl>H5_2n0}7&_<>eeaJTfiI=AS>unR3Vh8k%8? zqYG2haTFb%91TWVMmnZF2VfWxAO*YaXea$@p$)>)-`r>ujevP#)c3ju1i%N`%vR+1h9tF(R+oN?6Qu~> z&!L#g$*a5b%XhbT5nvpps{Ew~>+QCkeaM7G>w6<1lr57lurqj(+57iQkQPipyu7kt z#*bJ4Ym_W&`1FDC(iGK~qvv>jad9K)weVVhG!Z!WI6xC1aMCpC9`CZ}n1(qGey$o6 z^%DW9BSu%pdLR+HCrjY>&NXGJZ<%U`qm#$!a|m$GJZb|aM{0$D!QmPrw38AgVIcTD z{}a&zF|1kw+%rY*FyZCz^clZd@p8GT#fUY;znohkEa@;;iBPVqB|vFh(1A7iRG~eB zC4)MpC-+c?f05I`et`g-dJWY3U!A&dnyDX*p#C8C^?(|XzJH$JB$|E%0r79L9DFd#6ND(r_;ZuAbH0YB8G5x9|L#N)`s%un~guP z7h7^?6x%sXXdsk47;jS`wWcGJj~8ArUU7Gqh!w%PxZuK|Ca&VT)H=;8rvP@Cwz zs~IW>oF~A1w$@1w+--+shc{ou7it3k+kzF#fHDUVefo~jvJ9AL0FG2=!XqFhHTUpH zHJzA77M?&aq6$P56UBf7>BFh%KwiNiEUXNWiA8bm$jC@j^KL{s@3||US%4*qWRH)7 zz4nwVJT5c?5R%kBXK))Uk-y0@WJx)(srSqd*W<2kr2>;pBni*%C$77?Ij*EH26-zY z&%SG#827K0A)8#tYW_@`NP7KgV2{Nfc~k>}oV)}?mlEdKVYMo?l)UE*5t%8m25)eC zhA4aXj1s<67nQaoam&kell?M_`+c-CptCYb0mW%siDkh#u@$8U{_Xwt;QjOWcnWbO z$(lghud3t1>I}0VZXv!L1fR4q2hPUJmSZ3$7TVtU1^@wx0=o2q}z9vw|Z~{D*G7gYa#; z?<8ANOIGKmZlJO!>*onA+4mpkm+1NPTK)%J@F)VNl>``M!i!3WLd9VuwR4z3Z48)4 zD+2vww8`?0M&_Yg$+$B!Go*{vf1CyXN1*TcgD_wq%LBm?z+)PM`UVKVz(q}lycV`~ z6k9C;O&5A|b2Yv?J8&3+`m(C5t`^6Ddq?P+KNyY=61H^BLLx~5793MJr~eHM6Ar@% z#i!pMup5hu5?aKvmyqwa^4SGg!n~r(ch_0-B9xTMWkk6O5cgxCeezO#pou1|Bo{kI zk<|J^z4)({YL>?7afLFJq_Wo_mcnI*HlOiD4#phLqG@YLf$G(5So|tLwa}R%;!$GL zEZh3~ul|1iEopd`wTGSehR%4$ZtXXMJep>}(nJ~8V0uHS|7)bse!`IU)%mwT6U#bE z*+4Y5Xg$S(z-VDFL$ZjT8xydT01o*krc?78SJOP#QNli@m0IqOnhwb+duP=$C)KhE zd+uZTXC(DL@};c>QD!6?SyS+3tFR&ttr&0bn&uPuIa2l&NHr3OKjPy&uQ z;RDI(3r?3WPrz2&986k^TMx@()wS4n!<+S_*hbH?_%xDQHd|g3OP(e>kuu8p?p<$m z2G58&@jCSXeK9W-@zawq$f7g(@+A`x5>WjE18JF=aL4m`{@88Ict(BWKK}84jZlJu zS|279mbCPRn{QW|oWq=&CPJ76DA0fZo`v66lDeIx_-4ue9)X4M@_>Cjhc8~bTy9fo zE1jA}nEqR~%+w-^=LgIuGUUroCc{Y-cfTQE)qno+5i~&696~6bcG$t~ zKek;mpQ#y7{cPtCp%9rKcsLo2KU7gI`t{0w;-Q9iJOs&moE%Rt#J{xw!(RiX>e99& zEIXD`0n77~8?(tQE%VvQ07OXa^l^*}K^TEUBw{$$*v&!W;WnZjBhZvXj1n{9_f{r+ zxT_m=v~8A_y90y-5GYL=)% zWzy>}ESq_Ihh=4DP2PwLy`t3ZQScWESZaU>1?VLX2KH@d%^8QisyAfIpA_Uo2D)mX zAYcwyO4=!f14wsXN~^O1wzpl{Pk!?06EoO^w-qm4`-u0nI!88*VinV z?GIOFwF<@VL3@ps_|Zz<;p^P|9EE-FAhcY5Tqn94o&pTH6_^S+?f+(wV74*FtVjTM zhF?5vCmBGb~4(Iiuj!;3=E7CgqxFT@_f;_TJ71p;6mKDf;UnZ}dCydtT}q zKwh-+a|muZrXg!t8J;ubH+D%cv2l@d?JcM61~IFbcXKF7)yVN?kG;$~ATM!)h+bc< zwaOkwq)H0?e=Put>Q2F(Bs_~y8(27BuHU5n-<&-_41R>KPFp8uWs!j82YCKXZEd5# zm`9sP5id*p7>#iQciQv(zl}elA^0=vx?juFA13y2T3XCNIx3Kh>COYNRf0?xRW5kz z{KydfFNvrx%@Me#<0>J6;`T^~@EZskbunXF$AY7LqAYTdEHm+kd-iMbFVqOXaX;NL zy5|T9;6SOpDY+pn_n9h5q47z%$Nv)(hkAb4a5KNKm|v|H5Gv|}L2Opr+d*bheBybU zCgy!|?-M|bH5VnN0q4|bjEbjC&ZPQAIVx84(2dn*&KV77F29e|W!_|V{nu2^XWzm) z+6d!rHWv{j^}zswV3ew84s$=)%d-zY6mUlP7@@J*FWAwVYql`&W9g)2W8W0-jLZyu zSUm&XUrz#RI5DgR*GNyxz-&d@rY~D4AT&VzdoSWi$0%^XRT*5kPat^x!OG9A{4_E6 zDCp*i-FBwmKz05FE57EO^0@23^_N$L!|0hMO0oP^c2V0-CixGTIHcvEoxw0bY|s~h zP(uD3WOEgTd=r}aK1rzm>4-SR+w_a)ZL8bbKvWwRI36S4uvUZpATT$>#^Q=MGJQUT z6~Co;kuoZz02yBaP$Jn_g%=gkTwiB1y|0{A`;>ff0Uy|bT4gfA(i4Nfp2B?AKnWU6 zc4rP~W>^kXkivKf8)MD|1R9tXt^)&{o_#^j%3`^Gsvr2Q{jW>HWVD8PJ&48_&w>;#-o|M996$TMZJkAsEx!@bH>EYC% zKOJ#c@htCk(5Xy~B)rNCWEn#K9}#TX#AsN5DB%UZs@%hz12%1ywtLi-6i;|eE0Frle zW6N|#S)#(5*^|nI!%1Sc@|&U9eO*V`p2aDx7=kjAe8JVT%15w91w#a zRD^!ddKRCw`+n266o=u&PC__`D%t5zx*nc~BJqHvnq&(JrWB^ylyLL&?oMa`dtYaX z@n>=N`#m^`$p{T)^|wUV^<3T=>Aym0t+fykoxYsCHb>^t^*I?y3tz?8y^?utHt=K0 ztotu(!SN>h_{WBxvj-ORBLuHqe17rC3`ftASK_F)OQo<@u{)-+w24t@v4&CRHr^Q@ zOI;~(9d;0`^k6?5?R|9D`M-Aqd^@%d4mIH204*sXj0-req@|_7Tr10f9O$n|>rAaG z$cQSKEDsD@_#`A|4i2&H)4~&bXvy;bWT6}y7T;y;7@)mzJu@`FQ8}5(jHy}+yOhu@j=Yo`MTimvN7hfY#BTsm0a0etKW2pzk`4=u*19)Z0 zV^d4?A-^B`$ed(SYmTcQ;~UeSutGU~YAY58KN%Yb(dVtVa!!3XYMJ@tzp5Hww_2Fd zx!=x}bQu~XG|i?b9k2BLTrz!-ifqKL?69$%W`-k>q(n4YU^pNPJ9;pAmx@o+K>owT zmFSR)wi-Ei^t%720+MMxgt$47@qx7dk>#5{70XW%tZ-S8)HZ^N*!g69_KFL5?=8~O9y={?OLlf z->wNwc}g=qmzOOkk4FhqRkhigXBn-mzQQVVOV=<6`QG%JVe`|F*$<7t6LQqkiICJo z3)q!=qx99M#=g5~{KOpT=+-FWRw%}YTf0iUpZ)bjbJ7Ifl`$;L;&wztelD1E=$gZU zV)}K<2D&)V*4wVB8F|ak!atudTB^=lo=0BxrN{#2m7bAa8QHeqcF!{5#4y-+c|E3X z7oD#KbvSkZ6B{PnGphj^TO-IP5Jy5lK)?{s{cqdL&Fx0*Pxg@-`7K*k`bP>l%Fi7y zZh(2KLOxw4j(6`QfmB*!!OY#g;q9U)BYup$7qFfz9Mkf^UpL?_o=nLJSh71K2-rc& zEkP1~J2v?n8Yew|l^*>egp;|v5(9XMQurNW5HtR;loFF@TUpFcz7bH1!KtXCf+=MO zhP9W_-DP_d(qHw!FGEr@cra3$@l~{qfZSoF0ZOAX6$Ex%5Q2f6QPlx47O%!-XXYP9 z_bkFTwG1-NB z4}x8rJJ6YNcBK32^Wm6#%{B8S&{tSq_l#Z}dh1v2m1RC-H$Sy|+eMiaBwxRKgQt!; z(i$^T53zp~nCe1U|7&-7NesN#DQM^RCm$^4tCV|wA1uf8I_qQ7AiEyCxffE22BaE$ zQ0vRM%r6so;0Ji6L13W(GufQxDzEk35ud>S=7dp#{}LJPpuj>$928(~UU-7A2mo+E zEEji%s~@?jHr?>DLl}sOkaZ_a+q&=sPgBY9$>eGW5dIbESE!Xv=O7CtA%aXiEJzt* zTkfAE=mSZ(jG9z-)D*5lCbuz4mZp9Spyf5bM;m`K5G&wGW_x$GthT zY6oQCc;unUtf3BJLt{Wg=U``7HfTS|o|gMpu=U8jc(y~z#bV;uvZ3-2_okuAu#yVl z{pV}=ddAGyo6a_$Ti$yOVx-;x|9cdgDOUcfD3BZ*GG^>t{tMKDlxW#18_O_RrpPf$ zhhR@KK?pHikI8srZ?d&4`6}oe){IK^QlnAXs76qBtR8Qp$9ot2&TXCVUT#Fxa`V%S zu<_y-fmW0s6Jx+2x*@A+)psP%0_dxqL5EAh#Oe|0xAWfnxg?dsIyZtCF4rIO7X!ZF zsNs(FMy_TT_ir=f9LB>MRm2aOg0Age?V3+z>hq;80);zR|GV&=72EW80Nv>Sd*An< ztN|oDt$``&d_V3HzEVno5y62tfjKz4n_I*8u6d zQnx%5#us0>%s_k8m%kSVqBcIJuIG+sp>D&-s~x2`5xVh%)4?{DR$brt@7>R{JqlNl zke>GTZobdq1+N~>F+)a_v@2oWN%|2Q;k~<-vS>0v0B9$rN*@!W<$gb1oXPX-e#uyr zML}{S^)PkqKH}hmikA-;MWz(pA~ueZB%Ch^05=d z9^w6KZ)@*Zv0nd4^ttk1??w;Wut7Rg3+dGsYnxZGa)>B9XZkl>j@?{jbYhr#-bMe% z?W>Cu84c;M3&7OE7iI6Za^P%PnsWL|9k6_Ec~Y}%=3-6#P(>-6drF2z6Fs&n;`-nv zIbJ&k+a2X)c*{iQwFSyvQH1SS{%MPzf-Q7-B2argVH3>wY6dQOQf`|nR0Qu&f$se0 z9wSL$Axf$Ed1r*=n$de1eW$5N#(eojfWC(?vk?1k34|z``T6A#@z}Eo3;VjX2uBu1!cgUl>bB7Z%Ne?dY~`G zTfQfG7L$Bgu%fX!k9bM>ux*6{4-IQbjgE(25z1OF^HCBlqnXY3{>H3tNib{1}^ zFT|jJCN(WBZ`!`9z1{ca8;v&W{VMuF;5+5CipTo>p~L^9=`4flh?XrJ+}$B~a6LdE zxI4jvI|K;s&cWS-yF+k?;O-XO9fG_2o7{Kr6n~(oLT1nG-QC|>>q8*MFMZgd$RO;4 zjR>GX`hDK9z>ThOm&Nad?5uZqkmb?q?nh}yusuAH{hg`NyoM5%*ErNH%91Roj5Bs6 zvp+)DPsfpyZ=WgseJqRz@);qPMPGzN}VpPez8lQ!(E75)2#Mo_|`e;(gwqyhEPb zYz2AHO0!+_vMB*ftQct9(Fkj+{f(uI%hX|$ua;&kDmp@UUybg#s&A+1I?5EHfjb_7 zw5W<$*BIIUCeZkXteN26;;(~+=JS!CKRofymHEaMirs?Da?2y8=+uL6uwbzU?sdGi z^HOs|7kI?~-E?uz;O9z}XW-JN^5TCqsOd5#2~qN?bNKel{-g7U6kAxqXQogkkxaH4Px`6|PoGK!lTR*x3&bZ1}ts zeTp=GfKN;rP8mm00(`$Wr1^)SQplsq@{#Az-nIK6Gu;nQ9}p#T31T!kYs=`_DJUr@ z*}-r3``JJABnJlfTabhX_*FG%^rKjtQ`V(0AfOFNjIou|j31*Ke$q}<*SPwv%_GYM zjYay%fSP10xPcFae17SCcIm?EpkjaHxt$R#Y>7|#b>VTrc@0SOeT!eZ240Qd&Wy$Q z4IeV?`Nwxna^40*IIiyJr17U?EVIg?a-+fzXMC30wm4 zK;i+wl>iQ9dm}ida{wG%snaY{s0@Kx*0m)}j3@+1g~03IcJ4g*ZPq%*4OnwlP92`_ zC=4Ik#D7hqHZ!6@sszS-)gJpE;4W=kY2Ncr1?*CJG_lz{-a&1-vDq?#;6`;A2PKO0 zf{XVJ>?du|rK{2Qxg-#GsVK`Aa^!IEG)`P~7!mj-SnX zzd(pY^1vwicbWtBs=Qao!#m=u*7LZdax%dgK^u&DHuiRr%fi^VdZad*QU?5E?#!XM zwY(@vLB{F^*DN*H47t+Yu?H0TAnO8F9nn8$QMC&hrWQAxhpP7ww+O!3I3|F1;ro^6 zS{lB8C6Nw%D?H072m6s?xg~?>S{Kb-Dyf2G+#a`b@>{I=BjxXg*VTE-ttkv^zZcbJ zzY7(ACaoKsQx5H7J0U)Da`G+r_+gVTt#(OYqJh95s%V8|)YFBi8Q0siSm3fNt)4fE zG<0@Otf*k(oAh=9gm(YHDuwvbJ>QUHMaH`n)V-4)$N_wwOy*5OySry7PA(r59{rV_ zdvUT@2Fx0oSW-G#&2mTw-0Pp+(c0T#_}875yLn>X4k_N zn1TAq6=TW=9*AjD>{J}mp7cpO0*FvEya~)e^7M2f;LU*{uAdj^zESr2>GxzQg)RLH z|VUkBv|mDz+g7>!0wrw(2NtqQq2fU+7Q5;JZv4lqEgfQ&`Oz zNd}K3Foo&hg$%C7qn;_y0e5yEFkrU#Wc;L=nx z?kR;4PqeUG8f-QE$5P6}GaRg9giNEA6}wr;xKv86!cpLWTf&&DpBI12I!FAJiA%8v zv4maJmo;f0M%77DS zvkqz@Hc)BA#bE&2;zDJF$!n5QQHYBKS4B|P=pL&C)*$G$+t;W@sB8`pV$ImN3d~Hs ze2P{6Io?8Tr*#~#!meJ8zi-kZs9GWw`W2NxzX$~L&SA%%y9;g}){_Hwn-vgc%!+5h;PT%sp8idtg3mKx zjPJx06_s+E4$_tdRS>^YLE8B-expn@cxDuUI{e+BN4omZuqy24I&&)a0w;$O zz1ZH4W-Cbe2Aad|Z=Fdeyn?$b!#5z!V_faJtnA54SgPap)4z)k^ZDE6^FL=iV8F<% z-!TS62LJ((UA@kZc=u3r0Ytx)}x-Z(x-q4T(Thqz8|2v+*k!X+xuV%whe(dPql=SqSrp{Muty5es zo7K&EpzHRWU8sytVgK!(7xKI+J2Ozd9(rBy_ui6!zYgdind9lW_deL}3G;Hl_Z42D zbDHHt^QSmjv?>9v{Z*bc20}-SF-_5z4PXzviOr^MnrNE!%iD)I@qX`+;)_AD|EHbl z#M^moj`{8RGvW(`n(?!z)Cvt(Uh1>Q(Aa{=0E^hJ~O6@HaEJf4pF zzVY7<61GQWF|b&^7toBmy<-Ir37uDG5gS%8Ewz6pLpIpxp-80C24%QYncP{D@8D4) zVi5|yZX#+T-J*;)kfOOg3*Kt#s|FVGHFHgZ)GgQrFA?@7)~T~26gkD|QB#OCDau## zNfG_C$Pv3u`$6YizUOH86{|bbC%ke|Yk7bd26uM9c|>fE*RP5`#y9$bw@gz{%SiCi z_qOZK2u7C8VF&`x^o8|O`%9y-MK6-VF4~B=O(uBQucH%dDf(~80!=;`waso{M8&0s zu%XR1q%NQC>&80I;u&NM0%@Iaw$!v+P*5R!GUSlm%|ScJ7g@AkS`Y*6F<548{n4# z7egy6tLl!9%f0|}a_CgKf2tpWY*ICFD|Ln;K4x&Y@WcA)oxC^@IT7aYt=sorW%4t3 z2G^$FKWVj6poc!OoBtdO-)?)cqY}LqE0i}%9jSc^n@qtTS@kFilg_8n%uy%uf#so2nO z>f>+aM3Pz1H8gRqCo25Wq(Xjg2=baCs%fm?()cW0m&*=|$#zj^0sTs%Y9s&~X zNy6H(W#CIkFMxS4vbx|iqjaRbq_1X|r7!NB5TbJWoCo=nrqI^zwuECt$&_U2c-Iq{6Q|NNwr zkubyFUzf7Ktl$7^ReQ1&)s!GSXI~T0eOh1T!m!OUw)^XSl6{As&NA@~+De$l9U?;P zkf{TA^n_*!t$TnsXh?#`weR`!OtN1Y%K`(7#}*F&H+C%G@HAyUn|*)uDHZ_V|6K~c z-3DF2Ib5x5%8GOCrqVPXs26KA0NyZGzWDOhu<+Dw;8BS`ydS_AfJlePm>89zeL8H! z1Q{xS0Cs|f7M5yVqkxxR|1_heI6|4oV+DutrT(4t;r@7@~+{DKi|K-2CB8nz5k2c}U4XSVv?3Wl<;%dDpjeR~Vzw zpbgUrgZ0oFc369b7V60Rtn!}TdvCyc9dAPa-*jBBYH<1rlXr#p=Bb^i>srd0J z=DByILJTWp@i*o=s@3!lQ!Qu*vRQc=26n$oFWw<6W9Bjj+4mkSrNlj^RMY&4D|5hw zd}0zk%`&xRl6drI$K#W;0>S$G`Hp;Q4pXAW<#3#l-EAJc%Zw!wMEcDN8eX6VM^v;{ z)6KHT$lD#IZ zE#@mF%hy9=F%kx-_SfY=-u;8J2sZ8PoAWCW>8?g{R?_=aW)q$!4*rh|%8YGE+dW*$ zs~)@sF6Uc$Dsgn=WoAmo$$$D&6kpl%RD5z_^D%?N;}9ZrdHBOIFcAB)gaV6=y)ip{ z;TIUFAGQU(P2CL2&RQAtUvQYow}knM_3N8wxUBy<+5`FP0Q3^D$4Au{p>K#Gh|%`=a|w%a>Nit!O3n* z30>FkH-KxBV$OP?zmoN2%q&I_0@h|DxER2=KzFf1S4GiTmi!Eb)GXTEkz>+Ya49_f zTkg7#hWCYvkpG%%XZA%sIU7|QQfI`ktp58}xo8$Pwss_Vn^zUwe8X*rzSRWdiYuYC#RfJT$UeF7I7cW7N#9VhWDR^G1~dAohW3bu|)H3)l_ zOcvWB*|eAazVb|Ve@)!juX?+aEH9^@pJtEDKJ-WUwX5ZZ7tgIdNm@If)>rF#V zlC>WA$LSb$4=H>nyd*-v_63~u)bciVp`BE8S@l9B2F6zLNj85Cc_1e3jwk-$r4fU+ zISbvu!Y3ZlT%eTwDLgK)itKqqTtOe4YBy5z1E^=J2|PT++2F0Q&wfyF34**PGCuQKYbC04R;jt~B8_{Du|Tyoq5jDdOj$%{_Pn91yZ!{I$FbVgal0Dla^bXw7ZGaK&>s8ns9% zI=bW$offCC2t4NM-@k{}JYAQ{&U1HIlHZONIPN05pL0XpAiSE4WH(<6eHcAI?|*(e z+B!~Tz`UKHd!aAxes1mo+x?R59{dJ&4Pm}q`0Ub+t~+H@1W9Ir+04&J>Qx@QK)Q|L z0~^X8rn8&+Lt(63*oQq>k&IK`&B}vdcE~;Nj`?(@%t@|qJc_ZMfB39c!Tw~FL+Zuh zfk4!zFP0Q^p!i2a1z8J{nAnCZmvT%<#d1v1_A6%8E`DlNe3?Zc8$QM+9&9Y?qEE+9G}D2Zl; zhxG4as#>!0ZnoHz+&%F4_+3A-wsVXXdDx`(gJ{feqQCRY9}kqXByfCZRDYXB53(B2 zpbQxr=jQciurD%(I>J@}1D^v#F=(T`DJY;bh3<*yPCOPZ)L9NPi<+q# z5sUpMcNFKa^dTE|q~)*n9q5wjSYU2a=hM{LZ@G%GeZnpx1g?L5v*`0wasFfJp}O%#-$dlx^`?VloKc@93_JiTl3{s*!*0!LRwWSumt)I2`(5f z&Nw;jygdNHl?-kue!{$3142!soR#@Qr%%Sn*}LTLcP)s!8(LmW`G1k>1>MY}CY{uL zBy`nSxQ$=DpXvew2m7x10P(06(SKx&J8_ljm{}y!51Id3o)>a}xt6i5Et)T|@dM6~ z$;`UjfRP^HVw{^G0`G?oNw+7A^B^F3UaU-~T!Ia-oJ&iZIhAu2P-z*!L0{et`D|2Txo)L@xv5g%3hK0;j{4wvA*#Ds9&be2Z87t zpptuciM+oj0Wby+pn@YQm+pIe5N0HyGf!B+u7`Hvpm;MyCQvUtc^z^@0l@XR2a)d~ z2|v9ACIPdLs*Wo}Kr-mM;Tf~mzQ$r@^Z230_oAPfL79|xe>DjmC=$7CSvMScB~B1_ zYsJ?RCdyElO$36%@tP^n223pgxDKgf_axIR6`a z{hgOsWjF>&?wnJ)t`qX1SNO;a{OJwjp-hyF4HQ<4k{SsTw@gkk}V zSqE`MMCA8Tf<<12F+Jv3bh!=rKNf;%xcUvhaiF6xW(MbOaB7qRUD1+AG8Ob)hM!J) zKuLMa6ctU%7aHXKy1~%^tXKSLhq5kh{zq2rAM< zbOiOo2Yl;=pn!nGP0Sx{k`!n{$w7&QE{qB4_J&`_Nq7`@(ei6epruD4!0~*FT=*c7L!TFu92Kwc>s`Q;1D!aX z7PqiuK&14;J+;*}^Jv$;G44rGScbxX=4t#DgLSk0)KHL*&5q5CwTdSZp6~#vE!!jH ztFrzFv9CE#Bkp}vIbEaLu7ck|`MA86togwJO*U5G$8q+BO-P&UyhWl+GCeHILk8DT zvo#fi2EKEyPu6Y!9fu-O)K-^9>xoWIy~~rQ+h29Fkcs|#cc|gq{bk8mvr(i-Aq-d;-BOsI@^Tup0_85WC7(|>=jjT2<UPqCLg@)U1F@{jq{;CNh~tF;Y*o(>UDU0B`Y z(&|J{{qQ7TZOO(kdkB}08VM{H(~yD;QhU&PBmD02kWlVv*}(n9x!Abw&+nWl36UyllT`H_uQ+gH#d2lr|K+Fd2#=| z;Qi0O-kj4=v}QA7)AR!DK0mOB1J*0RP!1reEgFvKdt!b86CG06Q;Mc+@oa0sF{#!isD; z&47dO9f+Z?f2{o~T3GEnN5)JU8!dF5C(31w#3ad@I>lyw`UzFGd=Jgs0#AcnW?O^~ zzM+JNJasuXf1Hy^1Z;hr3;goe z&Y~Ox*35Pn#x7tg3!Z0Sl`J5EqD@4vFuAU6nsF6JQoE%^w~$e!N3v{;iv4d3BA9BL#!9VjgHL zJMj|;GRByK`Jv9?!YP9Z)E9sCyHz%N2QYp?*hBN+hROw>Jm9Zu`LbCjAR@GqzpA0F zZTyuxWYe28zLrS7oQ9z{O-7hADO;yJt7oNego{@FtMHZV5hOBw_{PvOf^vU@B zrubCd9k7W}lMR`&(7;FC#)IjvunxPBmjlmYOWG-S%tuB3XFF$?fK4bWTtT0A(=+$c zJ8mz8B@%o<_2l6GdmcqzF3&zeMtlcHfMJZk*(}k&Q{$r{y8#lPSI#vD>lfmqjMwA& zFVTlCyiTn#uYTzl*#Db3?N1o604VN^nG%fx zRYsB*AN=4|O|86zW0c-K2xSu3nP=hax}Iz7tl}Y4b~wS6D)gA06pwZ=x*HlS)YB`3 z5_a=~*T!j|Sk5|sp2Q;qspEhFGvS!{=^OFU=iO+r^;kFStsb7BGRQFDzU|x*gc^nm z@b1>@P;Z9gx7MfcQA}E53x^DST`<{M`yk~C2OyOxJcz>cmS>?#--mH7tl6Zx4z`9m z({zs^QYU_>ffA>bTlOUc!)4@~j@EZ2QV+N@!>&US|CtgAAYlx?FB~{3D|daKS`}0~ zEkNqJ6_3(U9SZKE$73Dk#UzlvM_F|E@^zkoV3jN;2FV$@@<;jiUmxA3SrEr?P(W@z z?{?PH$(|&KIvZH(idZZd;Fs(_p0c#Y2>u^7?iJ~8cjuoCnqAzW@|g^C4xQmnP8)u3 zY9YfyMS?|rCi%H-nGn74x%hUD-Bu~agpF^)OLZBl{JXs}0Ajsp&k zj)bl5AT+TPeGh(6^2oOOK($iOg*FDttTZN6S)yHc9KYZf( zbX1s>CD8=mjh%+piWykMMJ+mDYH(MR|vj$bVbwbG3n6{U{}-Xhch?NHieIdjx` zEcc%8uV2aHyw>(mUV}3f{Luw<@QSkJons7F1^1skDY{t6I+GG~Jy_ePuO{Gx&E;%E zW*a|Sg;}pf#A3S|eQYqPuI;cP%?hBzCn5$s1`uNwBixiCvz4L?v zdQ41tnL-^yp!W!XGHK)U*LsS=C?mul)`n53W?sV6$B>fHV&Y0=z#51n67$XR{$3k=0CT__PG;;<5=%0~D zUo-Jvlc-;^McYU{-2^W$-l_UmPZ-(R>wq&srEcp4;6U^W7EI*?a;1beU;A96h*S*z zqPX;-zqj@lXmdax(X8iEzQ9OW!K==Q>JfG9^ItgNPT?)KIam4gt(>T$%v%KqJaHL`_zOHw?ziLL&;ZoXp0hLC)=HR3- zktlZa-*#Zu+rGw0M8u!gN^W0{HZjOaV&GzHY(d_r1VcRy{jA%CP zx_qG$U?Y+w%zmCO6Wpc!bUVh{UU~OTI`5Ii@Q*xhJjD64#&6|%Z;&~F$0srIFiUj2 z+R`xCV95mpzKPHW$qC!289l=oAiqGGNTR3m;M(^kTSLhHVYk|dJm8EzC-XxpsXzsd zf9~n`=>u0l^tcNJW{W@IKJoAJBiw(xITzGJ#`}KSO%c*vvl&5Maw0g`O-PE6@!cNr z{KS@0MrBbLsm>9}1a0bz@WpuC-z3R^^Za{KuUJviN9~5rjKJ0^9+CtEZ&rUjj0aAJw!1khK7r4}h8f599(nDG)yd0Jj>9 zJf9IOHUCb1c=<&rE-lWS%-dM*L@mmh4nvkbI(2-HR*G}aP?`Px^Fy}>l6{UHcQ^=` zIf-HiiGG(6!|n%kC4f_%z1JU(Yjc(HK?-OLM8Kbxrcdaj-meGT79e%yZyQq2BY%WW zVyN{!mxCsEP@e#lpAObyObFf32Sr7<<{>ZBte@(iP$>W*0MLUhSOa?vm*^xeHa?7~ zdkbQFi$!fiKrABoRiHu*69jNu=Hz3vzXt!*&#C3^5B0N~(IdqyS^}(|pBPbF|#V1t9<{Eeh^njmpaByhHfLskH?^1p)6OI&_<<<5H}uO-#gyKsY)lE1yR@0r6_3=4C+^5ZY$WS)pX9albBwCa zn3D3m1aS{Y2EIHE3@+Eul~xU;RR2$jI0*xMoK>DcmlEhUS0t5n$b6?_r_?OKl~U>+ zV&r7^8@~s+z*!2zM<|1oHR^-GgXkMvTVhfd%Kp{1q3J7uu5YQo6CJ*di)(clKQh5C_jpfG zf8s+GNRbXW%0MNR&DF?JE~&1s7b{+IUoVTdBORtu`~P)Vyl^~qd<&Rc7y|hwz`_H( ziM1-&*x3V=5jXD9oM|{ z$8LlDwdd8OOhFy>`kAZ`caio1wB&$SQ3d{xpGJaWBU}I?5RaZLd>1mhyr9%ac4L1t>;p92q2yZ{HxqBCs)Jprwe= zZz+w^yPt6Keg%IHPT(>q_$@6kBeWa~UO^9$OlRPgbfu>};3Tt{3sbv;zn{QB)1k;H zRl69)R1-9IMF6UZ5m&G+v9{BJDy@X}{fnmGLx!b03)RI;r3hbix%S}eTmlJ&E+m#= z%V#-n7~Zlq(0z(V@K=VdZkh8*p05!h?_fc(jVdpN2gsK#?j3Byfzz#Krmb0H$qEMf zFV<2z*{Qo4GHyD`l^8AF6XR?54HQxm=aH%BVgx!Wz#CqU+WX=O zD0_v?H!K?9{XbZ87slwTZTEW}_TO(&sg9$l?+YKG-QEv`8DsAYT76>k z;q@%r2h6PliR*eR#+WRs=0l4q+kCDvJRdPwjbVAYowh1RcfRc-zzr!-Ih?Yh)KNve z$w%`4O!hdZ-Hobx_*UW~g9ZG-$v~M;>MD$SuuzZm3(7CmZf^4_TzDSZNWBXt;6-uk zHJ(>~Jf$BOPdX; zqGENkOUMZ0m+n{RgSteD9J!Msr-13C0<9Yn>+hvWqRO~II){Kz!f1k&gYBelQ}$b$$js$vx>E3(HX7~APY?Rp(k5QtUY&}!(Rs|*SC>eF7J{bvC)azkGWOH{Y#*q)ZSMd4J&bGI>*p0)GUtM%;f;Ft|HJ48B-- z$4gaBzm0Kmd$(=pA;+jsemz7|N2cfB(BW#tn zTz?PC_M_zpgo;Q=0*|8KF@d#Wt7Hm1hG_lmCgX;YYN?V%;P^*#93Nb3zla|t`b4b1 zq_~~(@4sY!wow~w81xZDvTqx{d3*9=mb`APQk&c|3kLANni(80%_lwts|h3KA7WoW z5@jezxlIAg7hszI;XeT*68aaRf&0Rkz_$Tco88B6`8OW?KquP%WBj;jobo?EDS(7d zlz{C|3%<24p5n^^8R0Fp};1ia!BhJ1&@dTp7AtvOvBz$oh z!LC?4?_u@0QRFkiXGIIaKWiSbso`{@K1Z-x5~0m80#%vkDTzjZG>&ASh53hb#r2bsuHx9iM_r2dBC1k&4K&Ff&`{Yy?kj>yi^aL3W>A1vw(I2f+1$c`XEq+uyk-1=OG{Nwk{svYH-mkdJ^^gkFY#T`* zx?-HVQV2VH!56`6JIkhNcyqwnG(ET=L4JZ3cC!Nm5?p|l0$Q3-79X~RrmXQ>Py((D zO|;@h5DT#Jy+1|Xl4&RGGWe^?qdTFTj&q)R^0UE6+ZGGWjw>_uV>{j&^GZ%wu0J&i zycP}SSkpyGLnp24h5R*2uLj!QvP!MmCP!YdCUFLy32POonUo`+xRE<#cfy_I(a}V- zEKy*2q5K;Schvmiesrf=B(qaSSg}Z!`%D*ikYL@R>dP96DU+zs!URO;F3k2B$~orC zTFw|$nf{7IrHz3um(JkX9~#@269!&FCJ~reqD?mNp15Twr@Fm4)=W0nN2Ml>LKtSf0t^zCovuPeSb3J!0t0YBcS;D?u7gP zZP1jF^ZF4*G5fQT!pGMoB~zsTu>dV`u@@Sl_+lzw`t?M5kmLX$+7RqVi>L`8B=geQ zc{5V~TbUOcmOy7t;Ncz6mj5%#$jpTKm#f~~+zdq=o^T~wrc|4Xyc8)5Jz9t0)SF*>SIWV)BWtIvp_M8UDKMfhyr4Xq3$Q5$KbqRE8P|gH zm-||{ygmA{PQ;ODv!Da`1+Po^rxnmssceh&I)!U6^RdQnR_hI<_iu>3=c4P0L#=2E z?k6co#ny91e~kb-V>KaE*Y9hyfi|EEB8IW}1%&`(MAi+*eM;CDt{XONc~3&8sU8J} z8`1!T)a&**4lXWVa_Sk-S8Os>O))jw{pny1x>2?VSaLs@vyS|kyc@!ve$WgG{iH_B zJxToI7m;|d0s7SWJz&%0#6#>)CiDoo=O=@}_hTwf2<>%RX=A$bhZb+}QG(G+xnxJF zxfQ{-xsMRWOM-!kj8f{&#f<+`QBiXRFfseOWHGm-m)CN14%_HTqfcE!`A{!c?BDs2Zj)-=&=(> z)Ds>FgKKXan$hOxB&C|O58r1WaQ49)Pl0ZB#E#!YRmiv$Qq;0`jZZa1Cj;?_YvO?( zvVyOl&}#g}LxnCd%Hz%2j{^+*(|CG;nDTK`tcuPa{YZU-|8@BoqydYB73Z1v^VR0w z5K{0^v*UiSM=Y}0WETIg12FbynUQ;f61BDS^6vmd0jR+YSU&&Rg8N_ejA)9$>Z>U79npO$40 zs|o9$le79CO*}x;vwq&Z0t0dc>*rBI9!HV6jpg0^=cuo)N_fEB0OjkcjhwR#$a%{6 zjw)s%i~4|2J?sR*0jGa;4jXHqzaUWCHsqx8M`R;%OLa4T9hlwdFBR!+Y*Q2Z#a~iW z0w-jx-n-0{ivASgK?5W6a|<_ilNT9~r-xrxc*o&z9#UyBUA zx{c3DCoA+lPG*q}$0m^A6<~RFNpsSxy|o{jekK=QXzsAQ=kT;lTT=Hj)xS)2 zAErTM9A{b(nw4!Hxka)q#Lv9OcS0e3H|{#q@+$BCg~FSXsX%TnI&4&l@2cl57BmZr zhFw5weRrSRkbKAGl9Wo(pLCS?PxYZ50eGJDyg(kRKIQms9xyfs&WQf^wdh3^w(}r# z3-RaFWlAglKfa`Zi3pHMgHJ#JLG~YNO&1=VZE<@&OG~$!E!lf?^gKtagiQ>+Q|w0@ zj>ZA|-1K_uX_1JyT%ssZmmgU;h<`m0dM0+Vy0oQdn@FO&jS!`N-OcmO_qMA8Q*>Db zar=DWfQ#cwoA94gP`jHh9Jht8gnV@@r6H0yY14jOp#DkOCH1 z>}3OO?^>m)oN^-G`x%e?);a1kI$RQfaF6%nUvn2{Z~ywFjeWBc zeEJz=G$*HNB<7kCbaiwM_f#bD4 ziP=0ukVaBO+Wlt{7rm)I0>1S9)h=Iaf4aQ5mmX?2TlA(l*?N?Lkfxt z-2i%CgA3i*?j7|rKbp18V|A>T8`eDC5N5~6Jet+!%}4EdOg%-QDKcZ5iO7b_Yn(%E zcL)-~Hs|kkPH4_qL-E(HYy7f0JwJQ z)P>vUjc>DU^BILb2wgO$Q6$`ulGoD<`#pt_DxLoq1xum~&{$3DW!`uNlafPgSw@2J zjZvMT6w+V!`f7mu2~ZLlK9FXLMn9X~Kg(B$4UFmzOX#R+Xrv3Lfu!Ab?Eabqvnk(1w8asW8VbPjV6@O$A4|;XI|3C5O}+@qgS%4AMVyZntCjy|@*g)saEyq2D0N(B9kMS|kdX@~EqKVEMtj$s{>K<+8iF zu}9={Euf*a5Ok{PDBHN@H!kSTCzY{r^j301rEN3lMEC6EVNl#e9Kj{LEcv01+>bE| zKH)pLv4dlbmd(;?;|)q$#PxT@nO2)>*H4MbFlL>nj<*fS%S~3cl8Z#R)96G81ifqH zzSAuQUYcyTrII#c4u5}2{;4Ub^#^YEOSwXop$4#i9(!Ze#=o&2;~yQTo$jRwPi~rF zU$J|z$?UbQ1w^Z4iskkb(wazW;`;>T-Ax6E8@*HGfmPUAHhXOM5a{FI1wC!&KS?@d zSpq4byB%|SK|LK@=_Ykc1yUCLd3_*hb{?1L@!Qq0y~US^M?6PvvuXpPjh`bh6W2LL?ls%oz7enP^S|2zRKOhS6t$h!TjO?fE>1E%(o!po-c9?=H zvs!gDYE8z(t$NUT1E)o73@fH_E&_s^YuwHYy|j_Gkf;Q!ZdT`MV~6g1r3M|(&cTt} zSkt*z<{Pb%q3K0Dg1iA;6O--jFAnwrQS?i+A*H0<}UdLa#~o z9wux;347}FZh+4Vj--=iI=xMi*6y+g2KO(Xxhv1Vpu@a{Q;a~*HfcsT!TU>r56~~9 z#ntMRdG{1;*-w8$Lp$&=-$Kwmr;R#DjcnW>&Y#^nf#x_U@xiN;Y%HAoHo0|w<#~wm z3CNUuT?@r?T@r!Int24tF16#AT+hRV1tK4PDmd7vAHahcMoSYc=IB zok>T}e^wwm_9c4EWon8U@0etr1Vvah4&YtBYIrkrnTinJKY3ZxPri7CSLqH>U@Qt9 zawguc{JViQH-_2EGE#rmtUZ^VWu3W=cH~2|9quULvbZP<9DB4o)4zL;I~@1^zS0z( zm7Qu4R5+c0G+PTbcIeL%eOg7x$k!?-w;=1~5J6xfmDTDnd}Urd?+;yt(?D z83?=pC+FAb+FP>ii0r$Es|}CxRb+Tio_a1XuiWO@5F7}ut!dDVM z?P#<1x1KA*#gr0|xBhkAt?@sVo!me7Hd-6R8&&k<2kg6Zq<;l~pTm0g0Ae|`awQ4x zp0)S0uN(0AKKC@7i86lhk2=w;$bd(+O%sq^Mve^W&yUNbAd4OtXefmKyHl@9u%45E ze;#l6P^B19`cS5i{|mO7pQpa{cs1D49i$BUE*s0-8;W`kMfyD1Q71m!vYT{gA*P|4 z*JO+oZ7u9##Il!$ypUMh7N;~c8D%hg)oW-ofB=FyDbK^9dVx~kFCZV1cvJ&67#EW zC%j7Uv{g#uEU4X-``zE5zzk2=@LNic3^8Zp8>e7&C?^c$_q~8n{iYVicfQ>%iLR## z_&SR}LOR6e@P;|FHgrndInEv9v*nV8(_IOe2sbW_yxDZe6}}ZqvGT-u{&`eQ`r23? zd!h2OVg8a%L;ZVMotuu2ouPReE%iAbFX~X)vtfZQLAE_$ zujJODm~oZDo1MqDUt>3AX0#s5a2|eoi!%EBu8^KnY;q;iXdbKKcE+h|G&b%@-jMjk z$g|)#6j91b=h;-bMENS}(2LMzMfWP}4R2EB=h1<+(5P1O(-vaw4XuL)MoU?U*Cg#m zKC_`jWFxX8hSL_=pUq$z1JBPr!Ij9=+5_5daMsr7m0*9D(ld|e9ByZkJ$4Fs36y#I z@HL!vQk+|U^bsbhPobZsD8QXhv+;q+2ne>AwM;4BxJKBzw>$-AW@Z4(_{P$2%cm}R z$;6JBm%Lkw03_CLgkg+qc)({Q8FB*ETOjpMdr^g1DuWLFyj(>a4tU)5P6F%}fK3YA zU015oVsXnuDQsJsQ~QFGEo7DU9U>AYNZe_VkW@lPCC92 zISHi~P;AHobEAdh>C?N_Mtza1uann+O}R;(rhK+QuUKKv(K5a3`FgHanRlV}a9X#v zqwNxj5RbSMr^uw{$)@dmk5`76-MBkdypqY>m(G=P3I97NJdcpFT*znaHpbplKbog*NR)$;g$u_h;2T2;PERQPrXgsH9{!*CF(a$awH_ z@w|VhNGcQ~;M!n3mK_}O@ZdGyHU)ucj6|7kCq?*>rm@tkT0g#B5k_pS6`=;L&Bcf` zc0^uGqu=Q|)gGo^UabXXb(yLyb&e+-Lvu~0JK zrzEMoN#)*G%JQyP)=uNh@TM8Re^bf2Xxx3fUs~wAyHt zF7r&T9S8ZD@H3cg+3x1M9cZ5DK|4K+;IXKxfx(O>r78m<%2LO0}UMgJy6}g#Sue*!XEhj_dS8UZ!*B2qzVgKT3q1l z)3$3*E&$S+nwbIN9r(tfdFCnj)?`H-gi)Ye+J78{GZ2M~60bgQ@ws;C`ZKE+7HO()LZBEb_jjc%0x!D7mV80%0`IA z)am?+hjK!E+j<;*%EJ=1)kdv+&y*}&%o6qRH2K@;^T#Fq_TBrm05!}YSoLCzq$HN~ zE}!OQ@Pj%A_P0B$cs(v3#Tw^4n(O7VGJ67~Ml%ycXwTgfTd2W6rcf`6F4lJ$HL$lw+9 zoxg*)7TTdPc<{9r^x415q9;D#CQ?EEnBGjbFC~96N+^O(3I)aB;`sM_+K+i%3FTZk z${Vorb(OKw0Qxq@|1Kc7!a6|HiGwBFx*xM{9JCz+?wMYQFy0`0*%kyqUR`XFBN*pC zqygqvSM1Zo0nz|mOki`s#wJ>_7|3jpl=iCVE#ZlSJpV%*Fk?q8(if;iJ6CWysy+it zU=bdID&**4+~SNjl}K;JT!`MM+*bVL zbKBq(Of2e1sGzGucQF-vf?4@%t`B#N&|%-_?P*fOG>1VqT9{-yN4Z$wvht~nU=7L% zfwpGeqLVnLSyfl`>m?7JKxEDX+;^i{Q><>3m#4J?mc~0-2PHrn3IRhU}!!Xg05<9x%W* z1Wb08R#r5zFF~;KLy!om*pir_UNLMY=?G26gDwY)&*gKj9a|9e(gAq2_|maIaHR78 z0ZES*cMSg?DYkG4x*`s1X8UKg2(z|n!g6(h#%+m#8Ac8S$)H!O!98M;+9aAM5Uf_A z*f#5P=PEySlWw#*Iq@1qm`QhT5VW+8?1VDqjeV)nF!QqJol1MZQ0 z{`#b{qFmC1*S40-BCJc`eZ9u@=NtIqMr-ykR=@}DRY)BZSZ@+;)*^U3ByZGoL+DsZ$;_6r~bx-3TZslEvfwJ;BZ44CCt z*Ye%y3Un4dPQ0Vb((>}UPw}&=kKn(r`zQeGVf|bC1s|=IEM~3SI9b1%cUN&ufHzDT zu$bg2Vzk8^8?xRH?cPfy=!0e%^s zchvr(b-wj4cz01F>-A@LUJ>}JT+y)m>o+1km#dSlm#Evs+nuBDdr?iWkPa|qq8ybH zth#8YsyyzgKzt@nf;pR>hvaN*%!MI)0wGz=CRWx%{lUw(No92R`8N5R2#Pt(uA;Vd zW^MK&rn`-p3$Zg%ywS|?RP8t<>R}hn;>!56FT4_Ewm+B z0W8QWXHQ(uZML1d#Hhjep91*?dOF2mR9h@{lZ)<~+g?vZyEB;nQtjnU54{hRn@Me1GzrTESF^_As z^^UeZ<9afA7_peKf$wCeIvR&;9NjOa1bWuiq{@N@YOC z%{~Ck=&KNL5mR@a19#`wt9=CkrnR!}_XsgXRF$O+q9Z1t{QA>p-}z8k2po4Z-T89#6{0gp%|reRIgwl(Eb#qUYwG zM%*hp?;cLoIltWa1t63qIj4l!~#XPgBPNg?CAF%GYHGR z$TT!hz;<+lH;feZXs+oZDTL;Y8b-uw&v}ULeeOUHq2u?8_nffrR+;Ia(%C|@YQNCL zRXy5qril!6+(;c4IK$`fBXnZN^|$4qh20o!bS3A^g#mPhgJ3c?f5f@Z*z0oR_jRF? zwzC2IB~z}H_kDxL*GL32zVR&Q1eaLDvA#w1tcpQME;~fomF^g@(hfzX8)r7F)&rM= zzs7=8Z?k0JC!j;AZc(4*e7z@Cj%@HRSXzF2M2;1H)^hT==ZNr z7fwESm~UN3tiT!XOam32mHpSWMw_V=6`P;h4(pxX$@bNPN}ry7my+|Wko5GvWFO3% zPV1f$#7}{Gb@V_gjCV~kss>F6Y0y`lY=NBR>=!15>Gig1h;HVCqto?Gu&cuE*q3gS z+Nhi4CMF*i<7d(&5l6#Bsz-CL{ad+kS5m>GTF(;?DhMKlbAY*BQ3!qC;8#~yf9i*F{8`k2f(@7t$HvB*MIQj%i>P@3zFX4LoyZ8h4?q93 ztZW9|A@sMe=uH&}jjW#%n*=<<@;Pr3dujI6!>Gt}-=q9Z{O=F{&iGI;<`lG`$}hWV z-5bp&A(7ok2A=-)i9$LS_5RTK4cH0Q5bJ}A@>l` zO}gaKI3JXmuun!wGjWQizLwH~C95Qk4%Y~L9q_Q%eWu!X3kUs6*Kyt0W^B3x?s3x3 zCnfg~(oMF)bI(0MV)Ap!YPuA9*GR(3N@l$_>8uI3K_>}%#3QNc-l95%h>3FezAWGz z`7S3WAHN^I4`{oX3lU}0dngbmCI{hzhwE#?89Rv0RCOI4{Uu2~7%4l5B@nr*k9<#r z`{j<24x7>jf%DKJh! z!$s=Ap6oUaH8EDe7Wk%e{-I~OK*;;ZbL%2Pv=%@1q2NN^c*ym(+lyiNRCHg5@tfJu zLmwjz%3!h9Z(HiU?Q0^I4&dV?Hh^=Q?+f*^lK%f*fKGrilPBbTjser}>H%1U2kJJM zu#w8ZI;Q(oO=c1d!HeSzXb;Fou2BnLT<75$4?8SKsXE~Q>>$2G z1G4}dZxoaMoZl>s12V=u?UK1>{i>;r%J~)1YE9;Ej@Gq3%?66ZKfUVc|2h@c<=*fdQK)%#QaBkD(Vequ^@@S~xJMCGQaD&*hTshCg(f(bgok?iDHk z^{LXVVy86CDoLFotJshe8*ay}>u){f)GB&f2?XrUlr zKQX@81amBtLj!zyxHY_(h3Nc-wHnxti#LaB)7!X&B#*K`kD;`#T^vM*|o$j@mpw+=;eN5S9<1 zwU>a%Fn6>lkiK{Po%d%~uz4k35@W5uWS4Ruf!5;I7|C1fJ71UU6rv{w=}j!ac40v% zbJB=>(~J5I9%$2wDF54})PKeQb&hui&#TZ(haEU?s;XzBm;&d&Do7zbJjH~K?Y?DN zfdjpajW3j_(-D%@E!lQU5&DYnFDU)Ps3-JDsJN3iuvPiGoR8L6QQ36ihwM5%Y{2@_ zH-*TgYtf}J^A?zum@GV*FVs-Sl@3C1c}XG80SsDSQ2zT~*!TU6;Ed{Q1Xtx>4~B?1 zk_~)b?S>Rt<8vpscHBhMe}E%)qyV&YI%t>_z}S1tGU_@C>I-uMI#Z)otg$!g{xdZXAfE`W!|X?ZZ0yIx}@nuv<62yZvwo7*hu zmLww1;?bmJZ?5pxz)a02k(b8aNqw`_#6->p8f*w&_J3tLIbWU(#H>3WM6=ie`rB)7 z=~Yf!WbBLQBUH1lJgTyeJT@ihSO>o`a8`yjGTSj@RR?}U&pjAu$!*dBIk(RZ=eXo z)JU@`)DHLZ6@pAToGun&8@q)B6;{K9v8mAxTT@M|O|QcWyzk2$lM?RMxko3Z|6d%{ zrjjNtu>Qk;Ox!bqS&?A#!w6(`tN1=gEkBrZnjL%S)j02HUI z(6NW#@}&+lZgg+Jk|>Y`~bF+TXdM|T@cj(kzi zT(3^h>XV=uKERs=Fpz^@JUapw0@Q^5UC&ayu(fywKi9dkr}rERb-1JBlcs*gLv3Nw zWlj$BA`U;gth!Hm8!|aZTW=)Lu{t6)P-f#a5_P|o#IgvGx8&L)9cnXEAAY--hOz_& zF8apb7f1i?|ys^ToWRw=u} zfJza(Yb5@KV;K+zZmkA7A>oXN)$f4PDuf<${yy;9c}XL!@>A@SEaVtEm{gXsWzX)K zJaWunbaSM0ZD8x>19~O0VCByc?@6haeDwAOqy1(PvstV~nymzwMoL>a57|`IEJF>O z{61DKiSv$ULoc`%I@~QC;XTS;Wt|HsyvJ%B&!9u)R#hz<5cW5mxj5y}LYRVBcY}P_ z)Wc8crZaJ9?&PCM6XZ>e8Nw3gmknVw>=Q`vf4`2XZ>=xM{k@|koSSg zkIZq12E>b8lx26!AK?B$a3>RHKmOiL`6w+!#00ZI^Yn4l^P#tlxEMHvuJqx>Pqn#5 zF<@VxLOH<#(kZ5IpF^-Z0Hyk38Ez41jf?2xhLgP6*?{}+7I+$|j$a6ubAkI#uwZIt z4#vyy?qB%qrYid zlRNLv>$@8Pj<97a7LaTOP?oB-)1C7lthmt!tL})d1j$K4m+zn5diJ){6jn9DM6A5K z^X7pA7k|l#>Zv^mTFz^ulb87((>CG~%jK_K)ZJYL*HCK(2 z7d*ciW4tS)w2N$nd9EoBobpev)!@KeI*hS%@L86yDtT z?b6r+O>`%2^r$wyH~?}{fpWb5DE8%HZxUIz;_r9bxk{=$As9aGe0CABc)okIw~5x2 zQ)aJcL9=@u>3*jaxC8GV8MhybYzTIv)IuAI(p8>M)u|x(05GopUt1)iR zG5a)IJXvLoklXpG4Tt1q> z6OkTiyp^yEMlaohAkvC>RlRs)tF@H zAo0&>9olGRs+W5}%a*^Sa$`#o07ZnU@m1q;Bd_Ax^dJXFQGfW0H_OaxWtW*S1*@fXDDmt%_!x{44s*dhowvKBUXyYC zFCb^SHn7A6IPiwZ)S2k?4}$yj_WQ=BQlgvz+~iSe*LvPDav9q@`c3acmCe@j^?;9j z5FwX4tjqZc#%(O=TihG4M!%-(2DkoU*z^Q_Hi(GJ6BGDH+gcUi9V8FS5|sGd6MZ~Y zY;Y1m_KNCthSk&_#qm2wOpp5goTn!6lE|-mD?0Mp=ek$wCNbE`<`FG%O{8HB^SGox z?{e0-0Fc)Ph~7h-en~F4TN$wlad2^kdS9(&S6*koaI2l6wKPYvOca~pEtm`OIC_qK z>s;EkV&Z)p5PGl)&fEU}^hN#D0CO|ZEmGYJruMuakLv#MNa(2WUJdYjOb^{D;8C4w zM%Wq9aeA-cH#p4{=FuKFs!l-nFTmP|L0J=&Aao&6I@H`Pts2>y_#Hk@(Y)J4?8!%<(9{^vQF zzU(h#BF^iQ$NNC)~Bw*@r@o=0~dq5*4 zW((1U*gyIq91C>)D4e5YO@Eg)eo$}e0tkZHW#@LK{6Nr-aUdWBZbAOBNL$wi)hJ6# z<&7h@g*uY^Jpfzo(n)=DGiamJ8)zv?7wNZO2JvulhgZ((6xK{>XI7y^{vtLUq7k#?0r<4Vb_W66I_Yb@G2OP|zU_>2ADL;yZ< zTgZ<;u?|qVaJ|1+pZxa0YU6PtJDY$^NCUx zqKf+W-V}&0c|6Y&C|-~ikTb107c$4k=Zis|c14B_G}B>K3pXxi@Y7o)K;0e5LvheplvhL~xJy zNe3$g_Jr7{9{oj2#WO?39EM=2Y|!~U^Y#xR9oht1j&!J@y#9#a-)xT$erjcJR{$$J zn~#6*#*v3dWHm8fqj_X_Nr#yIm?}PF>~HP`Id72#xv1(kK^;cH!>?eHXaT;EizuczizMGx_8V%LEzBpoSyWSTI*jeYTr3uUKgBXo6Y6;QrzWGG`llw&gd# zaoz3G+aObC&g(qDXSx#!zn^_`D26qJn*GRtXC_+bk>=+(uKvYi7MK}rp1036l+c;a z1`l{r_tmf{>Y}H9xUeu2#B=dpA>X*X=8KWt@>ViRiMCdX;H&cgRUU;*))tGGWK?(L zc-8sJNa+BV>-Q^7_oT~{N~EUuMWq19$DuqYsoHR!J@ZKO&eqBJS3&m0@&R5gO?y5l zW?=GD0sq#$xC#xr1`f4Ox&&*8oX8Lgb1EDzLuuhAG#g}ZKsx2>2xrO0~z&tdtnDOZwmC{&SAZ(Z(F8`3lLu%)5 zrVjjP0x^k|x&N@M%Rk8~!BaG<4Z)k6-dOxtv?o2+8(;Ai*Mnpb2P8WbyZ8j4S|h~q2=X> z^jv67nWDck)sO;TfsGg&cKK%;61GOV!w%9Z!F}JGI-#=r`n|Oy zbAd*5VwFBc1ts2EkZGQ^RoSk00m`+qE#6A_S@^TN5{rUZH6oJ zzdkpDjyjG~us~%Ox-jK}5EJI(hVy;uoeFe)=ln4cP!m00t6m#iI=f646F)kGYh`bb z6aqB4ZhsdT09@o3EnvY5;GhC^qO_&bjkd>@!14(hn#vb8Y@~_lX~@*eV(U-sD$Ob_ zz`64Qc))e_J3KX`^IcI=Ncz_t-YuAvrTnSD=(RCyP=?TnZjK};+cW8n zgM#`%K}DcZPFPDyl9bRX(tu{~;0$GK|x?)9TuEhfa8=L|-RS8og+jHRd@%_T` z#E*g6;ApRy6&+Q`EpsUCac%$#&4JU`*NK3}-P8#*1vWuQW z3LWMN&r~)8`HJL>jH6a6ooToe1!N1tpG#5!WMlglR`))XmBgDjGN*Te1JAwUXFi}M znfM=l?~u1y*q>Fv0^bp7J?#n~>XeXBk4-`tYp7NoZ;L2m$TQsa@o1nKxgXP40D@xC zdx;a??qay$Ilu9KS3QcjZPXuNmy(I~b&}`WN8Q{zp!od&m)7> z&USY|1vY3wIW3cQw(|#-GgQw-*CK20taZ-yVKX zy{~tkcRMZ>MJ#>LYN_}lhb9)Awn{p7=VHx-cTrBY~EreFQ_dFl+@QWOE6<_P$z z!msj^al_d=Tl!4dGzGzZVU8SS(2TS5->v5JNz_;MT=>{s08Qy3IH`H6 z5Og=8S7Y3c)K(nnaKc(?(z-@Oiy;!XUxqk>jtJwv)>fg8KH&sAO|vtf*0G;UmAaK1 zSB;3va!0v5jydJNlXA9H01EN7HH2CJm~9ZX5WGS1TFwx&naF;R-EIRoSj{pmW?$V# z=5hCjDRANZvk|3O;V8EL-V0cKBQOl=6z+sFL^%CW^&dt=Stv~g$rhckSLy6ff!Cp!n&R4O19;3Sy#s*3k4HL_IR2nHqPP-m2 zjA3eL(ioK29aj_hHgLz(z~mgPrRiPWC1cnd_8-=eHy)Jx7WrD(z21w=(h7P`=MM3f9A$05(~o)S@d@3jW{X3#~h7VIy_u~_B}z07F|hR^kKVf-)AxB={sJWo)X2v z6C8Yz7wodQzm#L}*hU3JbI`eAg-tce#A{~6YCZQnEC*f7JVFgG-X(!0FRol9ODeyU z+D7lv7iH?vdtBP+pTBePCx;1hyXD+DPK5c|&SaDzCkGp+1vx@r$HaU+9xC`gW+DD> z23w-;#hd!aKJhj&G0P}F!scIBKpOksr>Gr=Z#Q4r)UZ)u3;QpV^a-ioHUVQFU-)y7 zsU7D965SXky?-)ct)@N-z;yNj`wy^S`pr4*Lm6W(8 zm6*v32&YX0Yg8oLByQS_RBH<**FwYK*}--#Ob0y_NmlreSybc9?1&j|9a-C6E}_Kr znbs_XQ80a;9MXjn$*CV|=zq!#vZ^`7+CK70|DmCi6tnO4LOoj`=fm-LFmQB8w>{Gs zcoqW>ox(u!gQLj`UI~L=$DY?;Z}@Kb7QOjQsZJNGb#2MazOQ?sG_XGZ&CI#Om=0HT zBf??)w0lYqQ?W8qz!WJ&FaUh%rP94Oa>KMZ*5fWQxb4zdnCRFe9_UW?vDK zdrC^zHWhLV9WWPv2|@*}RPX2G#H-NfCMs@yvWZp4^XNC9?i5D!n(c7PloMq2g6U+Q zatT~K2seeOdSDkVVQ_z<#%q6OO#sX79bm2BrsCm*WAFSGe~5`A9kL1xG)XTa(x2P# z%Sv%oV$k`WFXWwhaPV!%|I0v?B48Kjsz;Ij=luk(BnJm%Afgcp5I!sxfw*}eqq;@3 zGo_Z+)?*LBTF>aM514rEA_4+q2jf{exw$3!)mLxNkVaq;dhybGZ#Z%1rc$GV-}5i_ z2P`ZsASQ`RL?jXNEcG$qW~*D9p^i=u{1LPGKt1-WoeMnyaEO7RM1wz!5*Pr+3HT!D zSIYtgo!-~FqEvy7;4Q>j+Br;11$M>c)(SwKRLRDS*+h<3`~IQf+)?%P&uFZ1sHrnP zAod;>_P^(dDPbJFSE)V-QS=u<82KBlubu?v7EbEQ-?ks|dGCBa+}qWv4nC>_XsTKbyVc-VH&1)Ml< zFWTqx+u0QJEG2byUv8wC@8K=2F}$^y>kmSkqPJ@=mpN50M~=zwS1Z9gJ7VvFU9p%v zJUy*68VRj-;sNZHgVjn2ANQa|8;Y~ps9vT6n!si%1p9d^C<_WSPu(f<&_Cg_9Z2ue zU`w-!NH=eNmT!$im%h5DjaBqvgE_ElKE!B?QFOh>2ab>Cwi&0DIv&b8o0F9l*Z2FQy94HLKB{qlSR`-4sDj=J((*bIOvv`I$?Ss)eVlWabh znf3+(ao;bZ{U4#oZ3e<|)poLJag=S;#rFk)iHF$!Ajy771NNoK8b}+z5LxH3>uaH z_MS8uLBOPRMyN}ZQH?c=A#2sFj92j)BO(Xy|?g2FDbqhlegB@7dax ziBkDH*>i?i%o>8{b@TQwsevs-ifRnRLy2_?&eCl7;RCwt`0n4W6RsYiE9@4jCnE%U zcwJ9#DiO2S*hX>W2QMI=+Vg-RTS9!F<9m1oE2E0k0v$XaQ9(&-{aL;E!p3tiE^%2S z%Qwx4Zfv!t`j1{~Y#dag##W#L?mGaEFK~5+G|DpI#sfk!aDsD`q8xdJctzsKe;$ce zW%S?lZ4Ti}v1UQ8!ETV}P@ z%J}C~szF4?fwCe!=!!Ai`4DJiToBr;Upe%R#A^M;Ro~=NNr}easQ2lQgqS=MszR#9 zEFpy?3c5OYN9X5UIQrHdm{l`l1IUgg%i7IRk_j=Qs%dRu0nn*}b(h-EF zk^dk#>C{hpHf{A~;9k;BW8vV<3?oUq2{FNqDeq1i4vXFU+uG#W?kPG3!VZwOXn+>a z%^B%9zG-AvBIgSSe>1O~02c+Tl+H@OFsBs_3q2Ysnc;@vn$?D)t`1(s;9qcM1E_Pm zk7F4HZB9}c5--d@xRWcHOL(O_g{F9|=u<{?$#FX?iJBl0j+Jp$@PQygJQgKjgUEcH zmK#04L0aQ)MD20~p}ETgiJRmCRem$|w?U=+{=D|EviOMcUWq*a7cS24-*g{>GL#4B zKivV zib3LtpTt`Kh=9AR_C?tyuLSGwZ_J^kasFNhuicIrUxE8t4;ZwEM=}vI`}~4*JxGM>xjJ$P7dKQ{cpy(kGFf6VpY3;z4Z&od+O!(r|bjB*jcA+_MWG_ zodkAkU>W*`TMSBfU;0$&Ix9{~ogDY2T_(f1`CnEMM^zlp8u{W3y{b*>Y6cJLc8I0L1Mp11Qv)F}jixwAGd$$tuR5aNEP725-T0Z*odo?|XN zQ_*9!O{uIX{BpeG^f~nX;n*jafNP`zf9t{g{g9rWl9`nifN}kE25s1h1(iowr~*ZW zFlMcO#=0#G;D7@xDgL&07ypr{{&S!;Qd0U9jtmXKfTxSV0BPW0oUM1iKOCN!g+=80 zj*pKIo%jRNmBS@qsz0Ex>RkI0O9-jGruNbJ$5CJ2nqpiTL9=<+VM z_@9ux8Jx=<3xL~07*jT@YBf8sNcq#oUSA%UH4L0qC6ggXW1vtiHiPF7O)Kip>xjwe zKzOBXX^-;y@5th1OfK~YIbXifR7$8~2H4U2)GEF(iG3+Co?2AM9Nlf4Uoo+}05=ZH z4V&7azxM(jkeOy&%vzn#uX&fk;{TS>)Bs4P^fJbC7mw0X$%not3&#Row&X00&d#JB zNsc}BWU7){v6U-e0yRCvO93_{`gqyhPPNR0tLHY`eHYh=nHpv4?3YbcA2|HIk^trT z%P@q;itov{ZX&+#;#(x!iU9elZ(DtZ9MfkHfz>6`zhxyllyo)8FE1wv4s_8KlR7sI ziDxx^hWAk<<@SBQh6;@Q%R55i!Eyh)GAQ5Y#_o~s#302h%=)!&{W-Hqc&RM z<6lh>Yfl$i{viMr*87n8)=<6Ud!QX6u~DqefGKi=aQEz z`AQbuK_OE#+ zNvH#41L8&npfJ&7{8k@4esI-uYqc--foji%@);&)M7IJ3F!BLoBz0!oSXtpsCu~d@ z3JH8us(W6|TE3rrf4TF{m8TPlzwUJi0V7Q~+MP)WUYOdQ4DxP^3sM{!_(5CX)~7E> zisoge&4dm_Tgs#~{BkL-NWc%9u!$;IC0)K8?%iL)l^nF08f`7y(D>`fZ1;1-HJBu} zY{_oJ0+wpq$?UqwR8hmSkt=&%M?UKfZ{onauA66uG%a_4$!IuZs#G9(rdPpM6dG|> z9(W)CU8pYuPk|*U{$=Sszvz$6V_Qdm)})NS&6^x&1yc43Q}i&wJkfkl&%j8jPV zLx=Ro8-wq-z<3ByM5{O47U_pa@_G^g%P+N(3cVPdfo45iV3yxFPe9X4rbg&5-Z23D(a@0dQBS4^Z63S84a`;b*W* zF|c@jrhafD|G|q?|JSKlF*SoJ*Dl1SB5f%xTlU`s@N-k-sV!G1Jg^rN<1YIC@|?GY zQc6Y~{^+?V8mL|00+ZVmQp4idgi@j7=PiP~^h)mDaEX-1SrGQto}z1n!fTAg}owV5a*W%~ZaTrmUdFOp{td)rdiL84z zZ4LZ5m&(y3CexaedRJyN>4ca&Vzq+e6j5*oj=wo^4z+jkD4F-D;C7NAPS>w)y1)L6 zgbCh5TUNNJ7KcmB)1#>OlN4Ktl(_h8@t@`#o^0!lP~^0)f|uWM#4aJz1K9D>$>jxlsa3c zfMgyX>2bru=IvRw+;HdV_Jo@V)$7iStwSKweJE}V5VQ16o_1YIe{Hg(j7VL{slh3v zVT{z{bhF@&e;f2P0%ipNL-wdN>yso${L|zB{|U7XF_j;RLfXW}Fg>9aCnXSy`HxQp zzJ`&w8`7l52HYbbG$pDM=6L~0(X&TzO=17 zjRHvc@(Oe5qlp6OjU;Zr6g50RJsSCD&}gyY;x=LP3ojeK*L3*C-}k2#zRKj!p{Ig) z)`^0nFey^Vr9aH||HQRB(J2d8mEW+bOAF&gXpMCf8{yZo{xfyo^2g?UM zn`xIeY^Qql$jbE6?(iM0l3Fu_!lK_3W`BAUHSB4Ghvw&j~hJp#xhvu5m$pnJ^Sa@P@4Nrp=) z73ro_37gL<@+EWtyLaI9SE>CPhTOblHk4$l3{zL^5m9>VRw*AX{$e08;VH+;`-rt` zH{@-RFaxd}at&3rZz zX(P$Ui(&kahXw^&k)*R@veSKa?zS?eCxh34XeFs6$QoRYRB#CrnyA)3%J@o)1YMR5 z_X3wVLP=?rBy+}G>)OoXp|UnhmtBF2R{w>&vj%eT{TS0k^Ek?nfMT!M_+gv0{?2}C zN>4N=rV#`GG;;!3*pF6|kt6pruPNPPwydYi{$;V#)o_aZN7&nCy;vb#rBupKXlyZ1 z8a1Rf7XJgd`Q4-ybrSkMoURXBqSgu&AIYEB^3YLarv1{=m7WlllZ;#l;sC@&*;0wt zwQlvtZrpefCprU7q+}>SW(HPxfWQ)p<3Z1ul zl!-?WDCE;%7!LSZVbO$7k*q7+nxp~_A@IO=%Hrc&+x-GCdFCdhw)>n5?360!Cc+gI zJFMe}&k_cHm-4y^^jZK& zSh^%VyiPjk{}B~&`VQ`T%)fi@hY0vzJ2qUE1*NedfT4HbW7HLLU-3XImSt zr#!<5%9a{}0CzgkIlAu)hIczf3L9MpA%~%?rPRdyJ4OEjb%Qwu8KcsP_mNA_kT4-R z3AF#<1{tIloyWtwkV~&27N)WxT^&DR8LxLl3ZN~8jMtdozhrOp&VQK-pu)tNsbv@{^Wwwf&7FyRFk5B;h5cbp?}xG_g|7=gEOLdw?X8OqL< z!{R>Q(*%&&9-2@>8Z)WQr+T*l4$DU+N?uTceFens=IZzyFVZ>)+!vOUv>@O^EVnNn zm|(#qV3 z?vIzw2?4?tG3S;-o6@*X6el=qP?sAFkV}}xSqYmyUuH9ihto_e&(kyEt+W;R#wkDD@rOESvfUOE(u1$~q^N&67 z*VL=EE48aKK9^f8dI?`kLoT_wf_nxdu4eDQq*3pwtWql|%v%}?Hv+pq04o9TTy+P7 zm(Hx`*UnlW4Wa+D9IhL~&&Ze{=;3?u{TRSN6Rb1QxYuFp zh6u|*(SM22&d8|)-5cZDP^V|1o^Wn4$4hHx>cK5$U$%Xf9()gZ+*e3Wm6Qz4}=L}7?RTjl29 z=GZgMK~W%xj@Gl$Ta}Qj{jwybbe2N*7E!OUw19dzJbPbaE=Nvl^xXd?1flO?h234x zWb$gZ_8tFq%w^W(71!v*EYkxQ$JJmDD5&mW03Pm(Y|=&wIOzjBf4zh(AqT!a`q$m* zRB>lTB|yL|37Dx7&!d70VW}9#R^nYX)vePR5~pVO4adhlTAea8P#~}Qv3;ulRpA$Ll^{jiZUfB`WQ5=GdYlS`4TsF7D z{~fx*KgN6s5qfdX<|jKWR2?BFGw#Mj>fz6g}ST^$Hy>o{NAa9uRfcn z1q-QCWpXVBKlZfH+`n}u#h~@xQ(0zMK=HL~S{}k`Ci*{uhPGNTI-~CeNWf zqQ+PXksa@h#tj?w)bqwc9{w_yOPu4ilP1tFcMid@g+?`neo*<`<3{2)*PcJXXW5Qt z7jf)d++iR$#Yp>BuaiCw%U{J3!c^ySQxWKdrHMQ!~ zJd_~RJSh?eYA9Cd@>m>0j{pqqM=V99j7Yz{ohhsj97jog^c<`{l@_6H)>KuS*gwqK z%bDgv`M=si4S$RZ%Xj@X@6nlC}vD!TMq&+sN{_eLRx>>~cficCuZCx4 z#F5Jxjgom#^*JDjQfkP0J_aS|&7+>K(VfF)hAHO*%fJMt7{hA(4}Rgbmrv|knm2X6 zvgS4EpbBEz^W27<-yB7XAj^S+0YsVS(p9akT4YMU>-gDRbuT9e9h;JCvy-{OTr#?c zpE$}Nx~iA-_wGrA3@uO3du1bfwOk<5P9;cF+&SnkGpO+eaTP;!W$$6w$2M>UqP>t z2g?G)>x{p%=Lpe747AV0Ie4ht=uANdNtV<>y-r!%mcPa<3+;Qi{^e{(?L;D70p-ru z91KbF@*z(nU>EZKe1iz=|Na6NvvF~8c@cO5*gilC0g$A2_|^@0;aIb5jDdZvdZ8}; z>ZDRd*?NZbSqAuu~bB=bY!0aXiU3d5(osM+H}jL*>vQ!}>mj>y1y z9I4Oul7ynV+K6ZC^C&@!kWZUX9 z`S?UA*PA-k;knWh;&m?}&;Lu%b+yQ8`zGX^qShq?sD$)B?dZ^Wq9K2JeLADs4#raP zF}{Bk>V|`N+Q2^M8uNu{DDJO4J{C~H!&D1T&~M<6T!tT~62Uv^n;R{*1QYie5ht>E zZ@$wbCR26D-u)=Fa_fO>WLCSAGdgC58^9IRRJOC9K}OP!wDDu*mhy}EzH$1NL9F@L zj`D}2hu4DbSR+o10`fjSVIRn|vwU*WOoN&;_Glg7kKuI;!~3XqFBz+=6H5(b{_a?jNDBEw=kzL)~2vFdU z+awx+=?htvDhSvxQF>FkAEPf2!{Mu2ss?yL0G^~j_2R71uE@5!hheMB4(jEmEg@^= zTfmDdeqQw;1sSSiQDFA&!L)WFsx%}$&tl1{p~OlTsQU3|Y2EKw{P`nB6X~J7%*-^q z#r7MHPb}p*u+rah zjYp;Qbef;x=pR2VAb?e@RYwdqI1VgeuC1M7YP_l~?zeq7hj50naoF#AFuH9G zO7Y0px5uSnjd&iganZ(}vPKdL5ziaLB$lRMbA=|Y^Rhwn{mbt=Y-zv`gYKArc(Ybv z|L^IZDoi0@&btkjy@{Dsz>ZSz0dB#UzLxSQZO>@VX{|HN28XK2jppRYX_o0Ynuxxl zKTZczY9N(t*oJ$iq`)1ZO+%EOOV2Hta3i-Ufoe^8dHKoi#9I(l&F-I`ZM_GCtX_m@(JU`ugKb<+{MkrHQ$gqwHx zb<<_uw+Z5p#2SH<;rerif=c|iD{;Q4k-CUUKSOmUO=C-JydlDypGCP$a5nVw&cw|z z5_j1x?a)U{ZNp#+TgTmWm8QNvZKjiAM-^g~zmBJW?E|#C$Dh6qqvi~}rE*xENhj9z z-L>} zy0%9MIZ*CAw#0xn#Ot%rtXGKuZ8)H3So&-0F|#D_+I$Qua-bI&h~|UV{*#k6iELq? zq2W{(kF(8i5(+1{pw3kY8|$sNug*c!2f8SdwSx7GIHYZ$cs>`a;6Q9nquA?^`Iwdr zd!2gD-t%gGjt(>m3k;MZ)f4nBqv?y#_o_kG+1lc#@pE?zW>Y14?&tsM)i@--&`QF^^0$;1T!c$ zL&wU)uG7Of3R z@~r+-)?u!>vxx3XRj6-pv(NdIe&N$Y`f)e}LlOhz!0KgOq&1aEHG$E+M%9`A;(5Q? zyskC1v^rgMg`aMWxw*MP8hhn*kr|dB2KZd$SU;qzk>9cr6>q3T^se)Ao7Oa%m8#|I zRjHOu_nnjW%Anvm88Mk$o>0kJ)@gGrL~o>le%&$i6l8h_yJt96?Sk{0j^D2Ze;z{z zs`9r^ zY+9`I?);<^_Gzy~#MJ4$Cc3636A!=v#P0z}=4$l0LN+0|(||RG4g3wJsb1exf!L1l z<&?npJJ4aje#utKra@OZ*iE3#2$UrNGDZ+uv2{72t>nWq8VR3Hg$M&KT!^@#+$L(E z0dWbtmOMx5Fi?m#U)PYD+U9FUBe7!URe>VwEhBCry$W%db=a9bINu)kBm6m&B-cwY zTR-#l$$&Mn_FIw}D}F9o*uLdgc6=1Gp5uv&Ad_p#+Eao8uY@2lljgudgrSRp{M~Ha z78l~XLX`x>@ODbY;~>y-4bBJf!dZtl?N4|65|K;ov0*x|wAum~EAp?}CD8~o`F>w0 zIBND!;S3cvysS*iptw(fN~sLc@?6;eyYuZD|0Qw&LjxqRL5n1iVYtuFFgHvqC6NS5T3Dl?u?XaP zFOEUERlO`aYhB!=ms7e|0Ij(*1bt&Kv1-R*GHS-7X?>@2)3YcEJF>UwJetyUOdMO% ziDbFty{g!H}%(CB~woZp@U)FQuXvj=uNN3Ca-_77)_#c z%)$D&e9pS*HmZ_M_)*t33MSK5CW(n-r^HH9r$wPm*{duf304>lYCS_Vl5LJ=wiP5n+yi<;;;^p*5*!2OXU z_Eq_;h^V%hMc8GFxAK=FFB+h_eD6?%42wy5+#pP7*VfdqyWQzHXzvr?@ryPr6s+X5 zUHuK+ENob)C3)_{2kq>Zap5anEcr8j(q~)GLE)7#Q@7;9!^02L`j0sJ-lwlR9=2Ej zaBN4Sr6WFbL{3cBcFDKr_UvqFq%`v30$2O3;R6R|$D3Se4(yIPbn+scU%;dEI?^|} z+Pt9$U&dTDuo|CL0^bLjvj*?lcS&^yR9d(^)28Yjr0V; z?kYs z=h4^PRxNw$u?s9bmLV7{E<~#SCTc@IN##YJE)1~QYUhbt0N@Yy%2SFBPYfN5gKqLT zrvWpssAO*rYRBi6mg-`T86aPae=gYkbz0|F4BX%ak(}T-QHL;HTrBYD8|9~ivk0?1 z1XGknnJw)eQ__@=mXNc=%|r>;rPk7}RD_T-a7eS@5|f6vW*5a_yy3Z6pSP8OW|iu? z3&7e#I{N`s6yXTNUfBp(@syO}D#W(`IMJ5cIX z>e(jDW4uU=Im=G6K`9e5E~@Tcq%oKB`ND}unO&49V1i!pXXuKLROKy!*fqWE=d3He zD^`n$&%0Y9hbzWv z=XKZJ7Qw?AjV0K6&^v$0)`agqn_SYIc0B0sZmU8nzdTR)LDXz>GseSwul#bo7Sio~ zP{!6J0{zZA$j>5ymuZEONxj&AmcKZC4nH~$;BR&RjyU9w_9QfRcFk&-v3cqzcC3eb z`UyWsEuy@I>K+42B$4-^KL>F@XI0yLz2X0vAtc~sy^q%>Y*h%>vDopm>IY_0+^E+6@gFz*|zC5*jb~K$od~LE5la zhDRi@3%ujiP4B=>X#Pid z_$fvAB5csN_AlFk6+cS%2#rj56HG(&emL!K^}PHy8clg|HZV=L&L{{q+fU^aC5LW{ zs;mh~QD=2<+g%kl%$xfW^7jEHzKpW0A?`gHxm;OT7mUo#%_U+u;!s@h?hLZLA6gNoLv+ltpwksyzsCs&!Z+kt0DjNqv38Jg^|^*EpRoCJ3Yd zbZ$+^5ld3pq}J>u=g0(S9&{+xX`7mwhJZo|uje`8rN!6KTZ1X!F&pr9KKNq}bwGxnccc)%Iwavp)&1 z8D!stCS{lZ*s7R(Er6voDHc^?W4Ukvj- z3`)9!mW2p)7=IMeXC43MVof=K{ zE{bht@5LzX$S|jF#6I7|md@_?IE<9!_zr;>3($^KLyj3!uHO`4SIqpBX>MrXnH?2k ziP*|b1Ob);(k4h)-uaqBsx>pe3P%v}kAs6g61HyS`1c!RbuW#mg}qr{VluT(e$h4M zTd6`N^@^j=)7M|YGAf*b5w)YmZaMAxMTd+Dvm{nlLB9@=yI_JOl_%cC`2$yYuJkV|F0>2kxIN{DWu@`Zo)dn z?FIT$3})*y8_@>wEgwgOS0iwefXmh8K&;p1**i0X3ziYsiBE!aj?}#Fu?{I-F;ud} zI-8aIHGucck+b8m>DY97ToP{jVi<-=xtCmYL9#geUHzD zxZvA28kahWi3@w#{spdPg+kZT?<99M;xoM$Tl;hdo)&)nujy~Ba zP#O)fJIvQ1q)}7!UbyCi!CIe7mqo}xMgIHQUxTKXHu=oWr*KQ20Y|nbA&k-RIL55_ zIL0G`hw83|{{m+qWix&@ z$zH}#1|{hAWZlf$xYgDdu>yh=U|66)Mb)ZKu1=nQ5ARN2dJS#>$E#(g?|R(pepUfSnK_ zHm=6XzE&;o+tq>)<}8Y z(bt7u@1bJ4ZV?I;VJf4qDjTmokxj7Ucy_v&9OC|EO0Wup*Zs47>`*U4-EjX&hs01V zQ?g11@B2q*=FoV|JrCYq%mMVtN5%9(O)UzHZrYhf1}a9adj=ga zuR0k|;%}m(h5yTKU!lW6GcYi~iHX)u8#y^m6%*)C{4cP<9e!p1c<17KQ9wo!YyecW za-J?qz^IM+MZU!)iwHu+qJP721;NeHXcgXT;}jvV7NeaT~wTWuF(l zt*8tgxxw}Ibv5kwKtoBTG&6TAeU~_bGM?_k9~;N!SaY*|1l~dka~HgD8Vu+>#{4=S zCg(^WXq|{~9Ty68%J)IICVq)B#A~_nbn(VZUOf#@(qK)C>%Z-jz$E5EV$?Qw2MGxg zs0FVwiBL>1LP90FL{luoaq6=K@ZqSLJDUG3t-pvEB(b|uEw2YfucyzdJqs&*n) z_#6DM?2I#sKk{r#`HC)AeJH)(%={dD%RY$|_w?>8s6%Q1$6KpVhKNa!QW;9lenXnE z_c;aa{#i!yF!#=jGlS`;^DZt~jjnzk0i1g>`(=w;oC8kjweg4MrAM#_hS2eD7J|13 zf5tRudF$nIc3P8G!N3;H}U0e@p%ew2;))*Z2MXO9)QCdRZ?p z+bu0E062gT3SgqLuGSGp)k`&RQmmV~NF|OK_ETIWjJxQd(b5O_{0MJz2s$u6r2{xC z*E`z@WKlY7lM=T$u1C*t_F9xJZ|bkJv2ha#SS9Jmc$+# zaYbdZakq~UMM`b|cCvU+nsG#elJI%Zt-NUb+dm=V3r(Hzv%xa_jSuQxi*lrBk&eZj zS*G<_8P<(%V2P)=klkt4weOA(}574vO ze|Lvq%csJ?5+lj+^2P+k!BE3uY8jB@eBOgkc23Pa$_ptJiL#w{sw&9D;U5cCOB^q4 zq!&Za4GG$r-NQX|CQb#@o2(p8Yyx|j>d!>;as90j z5Z2&++as~1*024h7f*)Uor$gbR_m84hD+V(<;AD(RtN!k`PXsyu1iGDS+A0=wA5L& z-sjZB*{&ueAfolZx8!Hw++v5-qQN%xjwg>6Ll%2?2C0!}Ji~Sl4cuE#Pl`A8!QRV1 z`7Mr_7FKsb&#;H3lW2f`VS+PD6`bEAnlkTFRr^&KV0=2WlE|R}iQP^@h1i=;d?_g@ z1AD}%(l{(f;+>*C1e&Bu3R6k0EkbX7UjnD8PU1Au-cz+aCF9&FOC=mw5(TA1IGd|f zB~>n6gL#WgHHu_$i)i(C!#-rBJQaUR`2(ZS)uH|anmz#;MpfoyfLmX9E~Sg_r(BZ( zM-5Wo-ZOacMKGV|yc2=!L)Gkr_W8Vd&gs8t1`uFYOf48S88tTe1-k9f`cwGaaU|^I zWDa}YKMDtR8W>4HvtJGL)9Zc5=Oj81^b)_jaEglPKc#+avc-Q?fqmSMh9MSGLA#Rh zbaZ@5BC&OkI(Y4eVhK5Jv2(vW(5H(eowma9|AslGrAKo{=}j`RcRBYjRhCxtQf_2`v7ZrYLG>I`A z@7Z*T&9|M1cTrix8pKTF4#W-~7F9=-BnU3dwpIPp=HMOqmY7OwLh&sXAIGZR10S*{ z5!tKmTW`#v?_zq_h^FD~<+&&EGAL#=XpiLp_ifY55fJnO5w|NDAqU5Ct7+W~FgW=Z zBJd>(FT9BB)G0z7DfIqttRwsuKS|Af(e8Y@STj8u-lpDc9)AVpuQ8`%0Q3RSKoEEd z(7WA!d-drr7D-P^SrYh0$X*ze{K?Dx*(R5L+y=Xq z;+5m`gL#e@D406~w0t;JbAX@ba$@@or`4kHaO)?|l@sLo$QvPx8j&rYVF|6W?+`Bu z1WDse6ATjYr5S=J=!(J<(>UdFr@O+9WsKpoP_4{E`wYB9d`-2CdW1$)o+!YWOu9M7H6R|Tcq~xRNC)Wn>L@JAL?=4yh`vYX$~Vcw3-a@a%> zxDCX7Q-V}SZOe9rH7-yexynvqvoQwJLnRk~3wM%@Ls~M##y~465zQ>V$Va5jk@jSs z^7WHwSjceABm={ptK2RG|1(&`egB5ufiA9<$0Ik@f&xYjgzJd{X}qN`*I!+|T+{Nl z9!**CGd<>Nw$2QrC}K9=>tnx_O>o=pJkhn--zRljxvtG~*}q~Nwb?Yebx1m z2}fNvYD^SS#;!yP&UQhqQEXz-O9|3S%@#ODUzPUytA1U8(X&1AJ$g}&Tq?!xG+jIt zG3iHz*rMuv9PfW|^Rlj8ExY+DJup*EhE)rAJK7kz7hcVd1$c~w2JI7X4U#oQu@%b7 zbxa$r-iPJwdz~?Ul@>t>4<*>3kF!uHf4Y?qQxkXor)qt87znfD2_ ziX5oV-Hh7#b^~zOnJS>ys7YmDh$}Gm$=u|Srg%lv#y2K>d2uJVlUyxgg5E%spFGpY z;htQayb#&(8%+tuuB!JF67-~`dga>(%r2I|R0%ik-)&6Ji-s!pRqACAw>i&zXk>zg zx{Ub>sht0&mKKaQ%BpG(l~zkLu-jK8Jn35&J_$bGkda#{@$F=N@{4#z`0P$5Olf&M zal4M3d8tIVL)ANd|I_xt-8@ zI6@N9J2=TeUVTLQvu8ZTfrJb+&Sl)v8|{TE`{qwF*wIq3SbxIy11lHA_AotvbXRpe zaM}Kh{5{VtSA=PsCxy>ArTysN*c#zXb*MUP7?VX^Ti~`7WBv4~l7V>qN$@XnS z5AJ;p9ZuEux%<$iPfIgbl)cZqBB&GpvBetDAufmc4dwiB%c~%($exr+KHTQ*4ED zwGTIF?|Z3g)sf(vJ`zsfAK)@H(ro`V3P^AxV$%7W{MmZ@T;}jcW4+vxpFi1b|M2x| zH;X^1^H)N_1$6vE@3#4>OMhQ#gxfx*IWiZurxkoH-$+Xm&-35l1$@UJ^Yc(g=r_XC zA^Z)bKK_5END8Be6x!dwsO)`UOx5x@fr`KC@8T5I>`*9CFW7H_yA@3Cl|0jt-eCW> zNdAsFKJ`Nq$?Ign$+E-#mK))|^Y|FZ+uu?JKgH=n@cCEkz_e60&!j5bnrE7`nNdyt z_C|z*b7uOzTVWNssF@x|QOuBCPLk^!d0KZ^6-r`+aTlc5uN*@JEBCWJTg;>VP6g4% z1?F9c&Hql`V)dWy^&G!Qs%Kddm8v)k=>9=^^*|M~=iHKcv8br(@~%MQD-G4)Eo7bE zrP-!KVV$@BEfix)gJ|A|Tpi{O8QH4Yf+b6`j<~J1-v5{Bx6%O6j}f-~qw84O4Pyds#dE?u^6;Y z`fP{U`-GI*9;g0|rfWo>^Km3~jYcvb`LT;XR0y`7{PLtnzemSlJ2hCilcgeF~;}pmuF}t8A6@ zW8H9;O2Bk7*;9WcQxoYHI1_=~bOCCDQ&}P`_#a_kUT?Y_3Y_hq7rvQY4R{1m6ub(X`ka-)E!Q zfzoFnf!_hq@>j706;7Mi#oZ}Rk=f3}ToqrKgCLZMm*W|0N3nqC|^E8(3jACZ{7 zJ6q;82|cwKdh4`c&#*swAUWa>E=0yu5&+iu_+=hvjqlVFoh#BhF=}Z5-<>|ZfG6;Z zTp8OXvc~Gi;bQK_pSh{eo6cx{bhborOihq(t)jR4NiIPV%hbPN3zbV$yf`{_H*({o zHZp`=xIs1-=ZUsA_-=pMM-XeHEbLdXowpr6MVMqv0OLBoWG=#unLlf)lD8+GJ+ZlW zPUV;NYeahLBP3%fX6-p)r1Oa2_A&mkp_YFJ*E(p&Tb5#_< z>*2=#CW;MG@=e4+xzN&cO_!m&jNOt7G&9xC5$OX=~9TDpx$!p{REg+6mVj{ zCMPG8u>y2wO&uICRz#kV2aTE#rASoTk5wzwwY0Ux5ye`Twn6Jl4SPd`Rjv2#RM;P}Qt?BEzqqB^T;t|3Ix;=Rcs5HK+=Ufz2*gO{ z4rVaBC9YtF6AN_=eep_dJyQNdBG`7>cMpRSs0kmOFEe&AkWR`xSY2s1e9BuHxzWA? z8$Qmcm(wl%&-5Q1ZyCDZ%ze?I_hV$l8&CZXnw8LRB*RF@=mKoZ}p+8j1~6nqqTJEnzu7ZCNz z6*&U>S_yvBUDdl@qthW*(T=Jcn!@6SrY!Hydat1N@{@{d2|*sI+=(s<4CqNZ+g|FTS$JF~)(q*CwR%V%(%*X#HM^3zhan)PdXd`Yd3?{K_VXaQUB z{zw3rn47a<7C;#Qhv*@K8GYs2hHXR@6RtCP**rviO)g@ka=$%(LK@T}{~VK_xyb*a z(0xv_9(h_wQu>lUJH~A0sUtk7X33jGItgD2}wYxVea-jRJRISh!Rlg!JRo8oo@}PmOSY$dy zjjBgw_4}LGN30xeE4isA66ai~hUf_ca2xoOoQA)T3tY%%&(XpB(6qwP@MfK)B<_gJ zmhWG%hI{RqnO!-qw~|*OTj~F5ev;>F&@lTDhy0H<` zu_AHFC5E19^+)#9TH%L|%KxxP4S!ArOYV&RaSLetND2T(PEUVS*U(_=I~kO){m&nL2BibP$jH@3!0eo?=>Eo_!&AY(RSDSK4v{P$EOWA! z`A0k9#T8JxaWJ=h!aw2|1p24(+Z28-GYRua)%86Mh)L)B47uQZ)?-Z996gd%7*o zjQ9WNj$uJ5#Qyq7msHUG7g(~6$3r`iY87^hODbzsc7pIT*V@?F ztMC;QCF`01hwLCCe`oZryfv9%MRb0t@9uN$kJ7%%hi}($dWN9XAa+hz=c7DnV|VVP zZ*`-vaMWaPR^*ZqH0lXwN81 z-cn~5pA%@Gy=MyU{vuMG2p-EtBN9mlD7^Lqum~8{P}iJ;zz~cddsovcbocnQNY@0q z%Cn#9`$y$f=&+X~$0%2>LF@Q&Hk5B~W6xIbGM#xe$7CORKbt^H%f&rxl<*44ts+TE zWP~g~lU-^2i}eFpN63L;t|lWO@@eYo0`a=qhKBwZ!sqGwE1;67f>-}jld&pR<#o}Y zQ;uwy__F*U)5Rg(KX)ZP6(sqrt-Pm1{!`M!eEAWx$MLGK6AK}a!VWFbwrxii`G*_k zd`T4?jQ6hSF`@fQJ;&Fl$&?3Z_||rLEekipfe+6s%UQxa3CnJQ&)Zp0n6yZwAF0YB z%D-3Iy1Y*@QSh>kjSWAYOEB*f$QGh><=Nh9pVPRvdXDp9V{tXsx9PFA4i?hW{~AAQ z_$fu(ad=7P{nE#SfBc%g_rH9o&zA9aA+Q7Tt|a9!V!k36Q81)5iD(ffFgIH)9kDg= z4GqX;lm1TbyoY<)?<4X>r+&_jBLza~&h|%KegEEv`<+W6D4(wTzJ~E_;$RfcqqA=4 z_wR93me!deohFaIB3CABn~nR;KNuNmvNm|DH^7&;pK50J^T0T~qp!esdmnWyN_fooe5DLs#ysS-9Z=ge20qpCiGP@ATGudqmE9{IjRm z=sFJuhOSj0xo83v&^iS$u(7c*Y(zc^UcL7+o&p2{MZTRv!L%5l*8b{vQ#fz}F;0s* z0-XvcFd;B^7tx#SBx`sfpIa`8T;?4)y??m``d0jY!7I@jazay?qJ8@YKfxQn3$mk!)~kz2P#=YW)s|@opYeD8gFxc`%t9QZOBQpsU^H~?|X11dk?Da)g*tX zty~VcR2vqeqZjv``2qT=f5*EXR^z=E5p>}=xpxtw`AtU|8?Y9U8&D61{oO{=p4A; zUC@KRp|7Lc$ZZyslrT_iEhwdp@M7p|N4`+kd$A>pmyhglqDd6R5pfzFuf$|K%R~ZJ z=0dz$!*f@bE)L(tX`w@e_&yvI*qFr*^8{jVTj64>gSawmCmzBgZ%u zocXin#+xc50e{)GXxO5B;G1g;$wK&Hv+Y4Ld(1{u^nE*8e|YvL-+r0(u464Da-Fu# z-zj%XKpfPo8i%l*dkoY(XurN|t~3U4WxZ)hFUL4Zb7jswRx3av zQ-`x6pQrZ5{lmg`xv(TLO4VL(ITC;+`tT7aW+QjPVs&>H5ezveS%F-rZ1(a{B-{R4 zdgg0Q9A9;Wpqa5&IMckl{+3S$V=sVo)KOXYJ z2=r(VM7h@i(^3Xp6k+U1mn;5hx`8d%s_xU$h$FKNUmzfO!zP0h3yY%djkfrTOT-W- zS7g*MZo*!@&>xK)=r2#hF*E3+rI~{BDHE`Tt2c@*rC#@op+owZh9j7?VS~Dy0M~qB znR9dwKS8ewPe9Q*yES5t{i_g|a6E5~n{0&xI0!%!rs<>u@B4SkWH|*d!V*kLj6LT& z9i53^|6K~gwRvxaDbP7~GV{p}NKN8gAFuRp^v70rbch_%V@{M~Q6tu%?hVb7t&jEA5X7lEg~#-%8H52kXyjRNg}|VPU5vgqbMSRe~m%~LiygKTO4)S z9l~nE5B+UH^hUT^5{brce!5n}K2VDfFG;cJky^F@Fdee>n>4q(7 z)Xdmek~y+aGj8yd9C7u2P{U2$w{pTFci~W~{(S^a>9kcm);Xy4sh3sDC_qwEsARzj z*VNYOSzDt(Wf}A&thX8O`8afWw=Xd7M~K@I9=59zM}>6jO$zE00I2(tPq*vL?|$5N zZEtTM=N`_AF>#L0VM<5T@v77rHee~h?SVe;QcE1GL(asT`iO2_ouwbCj;m~U%KU6;R2dhCp4f?p#qG9lE=r-*+6Q;}4xOPP3 zg9)9nE(%+YO>?$YI?Q;VHdBlp6E^y&Wg`y9_|Z}sz~FK?z<-Q~0h7<;-GAy;rQT=* zE(yrSt6|(#yay~d5?@`ABO2l5P*FBBf{}qhajm+xg{Wl=3gdq}X|QIx6e14YYvkZQ zSZDba^vZO{f-2)0OZ40PS&2BVuqIPPE5d;35HD{svFBb~Hvv3Bgn)T}^RqWaK&;{v zM3?{0VNP=+HI$PK9kfRx<94X&x>ViIpfhVwDlTXWS0e+9iY>!ancpV_gR`k#s2D*6 z=-Sl|Z&L$~?^zW%REVzxS=h6&84@^`4_)7Gfc*hoKRDU7 zMn;B2lMWchjvKj>6xM4;N!c7nB^y||uc@QcGc@!Xln6mTFo^I^HV3i(>|f$(BZh?S zs^z1Ijl;Ghba=sZ)Q9{Em%{%&k0p8f=O%8ja=Y*_vG4rW`v4{utU&n&kS8wCWQ;lZ z@p|z2RiHCoV_lfh=~xky3W6BASB(cdJ5?(g9?!amp2?z%F5r$2wA(C5Rj3m!xD`x< zMdJX|taBU`W+4@fOpf>Z6@EGjDjJ$`L17rwe`hHWlvWxYHsEcSnqSSjyxf%o#2<{2 zsYqB83>1W>7Iu%H-J?kwm3$Fz1ZP^An=5I}REKM#05KDHEgl^14JpSa9qaf{359d{ zH+!cPFyx5nJ*c_2qNUEI#t_C~@mhj5%r4H+YKN8U2@6h2+EU$F$=dm-!=4x~y=xy4 zc2YbtOhCy7nv=mSD^X$0ND5OwnwwvbpZ}JD{@?n;YH*i-?_W~(qJXyo%`_jSAkKr9U%vqT)$Vga zVp7sRJ$eYX(P>6lnAuml2ykD&e>Vd8J`oWSAi#nIzb^;@?WG%u*-REv6#|^K;)_8b z=87q%U|uI9Gh?oH8SpT|E5A!MUmR_Eu_YluzX9J)`R>8-Y;;tCn3#BVb2Ioh3v!`- zyM#4&{Y30*^ZBo;hvE0{`5)+dd=&we;&n*%*seTH5U>aHGps21UoZ%i-bEfr%b8!seLK z|2uv|zzEqcw}yXeur)L{M*x)B9$>7j7q+)-A)Giyo~Zwbo-rpE?{=zb{h&LVcpkjD zGolZpvPa4l|Fej))s(VY3yB*Jd`pQ7Q@M@0RkK)ls@9x@#!FL=zGPr0YqD(0^BOLg z|15MM?X33iK3@8Tjc%g`lApEF7)#PLm;-i97&C*U@(-Z62}mWteXju>cJSa+*|?+s zGee6Esl#-s!vJ#iKfVXMe{<4}2F8+rEjGg2qNMaB1(Tr@2O<3B)Ux7WfDh5Ei%+=) z6QL;`&rJLvvADy+k9JoqdyT$&vS=Kn4t)@i^n~`f7|=%Rn+4Iu>lq~t>^7QeRZoxt z_OSKhxnNpxdfG>uuiKi}_501$%9NeSrmKJ71t-Gt-p3mDVGo3ZnCdnxA5me-KnquX zD$0jM6g%|Ay7Q-+Xp!Q217M)KxjCY!h#E}2K#wIA>H-Z9#X^#lUjywidIp)zl(F9; zlMmHo&P@w8`839Dn8a%*P`%s}8(L#YI4;=IBr$lU++p3-41KS)ez%F>333PB@x+b9 zYRZym1TlZJT7tpb3m>v*DdTdPr9;<=J!i`MLuY<--=?3rg}LuM3b*aLmhS0W{}pg7 ziC|z%nBs7wf<6YdvgtW4maz37Hy|0{0vJ zd--|x$K@sxP!gWMR2Yx?Z!LMi)dV;xE*@U!DJ(55EdcF7)&S6z*4Ai?FTu)`i6ry+ zbW)U3&bqOqy)$6X{h4GjRRDN&{wc+Dw^^85n1F#@PC1Dq3KIh=SaNZm(O)12YvGm6 z!quERIvhAi;r(labQmkwhF{GJe-q=eO&(txw=~L6WyWu`BUb--4L)J)i;p?o0#D9= z6DcVvzj}bs3Ix&MLBQwWu6U>GCA?J7O)G5ym0hso0Pp)%!w9G$f;R{)-{x>N7q(NQRt5if7F) zo)4z++J(m7Gr}Q=LG?TIy&lTm>1AHsZ9bX<=M_9a{Gt35am(MnYoC_@N;6)$O^=1! zXj26pZUEU%bcDIf&boW)8ByemRN(uwlK3JtRcx%gaabeNqG$WfRas@mi&e!6XIxe7ggARlrjL5NMB2oD9^e9| zv#)-F2Q>T2_+of~hX&UoewGh1zFyNNK|z^M4}8*psYaeA<2qq>KHkSrXVl*=@B=rFq>MgA#y zAA#wh>t?-p{b*PoM*bO{1KFRdyFo$o(g*J8M%a2m3dBX&9kg$yKzd&`9f4if9fpBh zIxfPd8|Zzx?@!llM*?E?*k3Vb->|@quT{l<1^Vzr(O37bT#aC%CM<8pLc_xJGFY_@ zeSAnjdH~)E^j^NC%ZiGMnyY!pZqpdt_xq+J0&>q23Mm)BkgEjFB|Ki}1f_VilMuXTzCF;Her zz*4X@GJHvag9>q#$90utDagx_3^8A8A2_9p18m98zyIF3y1JcS?5Vah=i~i%o!V3q zs5)6uz*Tw)>Y6LN9f)5HX_g`asLF%5uHL2}H#|&_OH$bYU#ieO6PucSUV$mXh{_0} zoHRfgyCy8%FR2_{xgY+@QekSYNGKn~Xw1F~hpzob3B>*3qfPaUpBZgUobMYI^9RF# z0SHZ981jWq?_%lX+25V@L!CP4ZfImZHl^OK6!+P1Tl+}X{rM2u_aVRV<*}{7)divZ zhkHRx4qIrueDh8>RS3j+yURV%ng2~UD`-PgX2gvL12VG`5fBi-MHTc?8n*_)xTOxZ z;!&{V+Hpam{db!SOhhTbB= z@Wx=x3nK;&$W|+sz)o?#y|->yFqU)}t}((3Ik>*JXwVl9)sjigEvytBviVi|05vlq z0ViCg(^TGbKv@{VL(bxdGd6>^`jJ%LOAfpOM-@1?L&*#vJT~K`X~X_6+8+T8yPyaU zIuOe%D#Xy?4vvo2H)2JkfD9gP^W2`oxWudra8d*A;Oq`}s$;(b;dcDU;S{A*LOx{u zNMyJ^RVz)OWH#@OfqSp?fXmXFgJIGJFUZi0(-&m>qZ;w!H9WlIQn6gLn zg}$G-p5OBdr=RtGb@s0T{f0D?RwS_He(h%oc*_6mRi$2A1W-e&xlv#V`Ohz40dyl{ z)X2~f8W`f=oNr<_R%^$FB}%5mKu=#^#*c-2qhS;F-<(YBw)lN>jo-f;M{<7QR3M5Z zLZX%or;A{paUqckm&Yx9NlFnr4iqCX2}s@1EKIlXS zzyu$2Fvi=RQ>t_eM)84>PLB&8_vCTSoAv_;0Z9I@w)MO0j$nmZhH3a!16gm#^WTf5 zn1VKE@f0eshS>|VL7W2r1<-ihgmz$(CD`IG$anMg(N=X4K|wEF?Pfo-Q~^xX=OPcH zVkm_vqXGyG^3WGU(b>xZ;oA8F%~LOSb*jSsySe;0P6H5qu1uJ$xwETp4)?Vz*;*$J znDhX0?n`3LLzZHiC7U$Bh!OoNY@WJt0f1W-@?QL$A7OeHaRA0~e1Zk1&S@JOrkDK- zhIgWfVwhcBLmeH;{cLkka|&)E(%{7<=%tY(0#o&p`~j{a6cj*MZZ;E@0R5*iYzqaf zIsh|X)>pGf2A`T;i%uy5-(%*;%GFS$#kD2+B}N8-$GhYq%}`gcF~D*^-hrT{<=FgD zU~A>v--1!}-I9OHb*-gRNU;LcW}SWjX9x8Ch6oso@nUzg8HWL`-23z-{Guc!PB6hJZn|OE-d@Tlv3DA|xpSH>apQ*iH4#e#r_>2MUnlUQHUWOwn22Lphm6EF# zY*0>?A-?ehMGd2fQ&QOX@A1b>5tJrcW*GNQ?Z*X6wy|4kutAmkfSEhf1hOdhq54A^ zo;nc8j2+u64@@}Bx)?6Fn&db{%1xeQTo5PKxd9AS%7EK&<(c$hsM}I0vKTU=Pw*hT zS=D8C(Aj)naGSdN4-dU>t2>0i_sSV0~|`hKTgYwK`{0+r$ru>eYFLGmhp3= z$Q6)%g24zlIf?61{+r%5Uzx?mC7K>tD7H1$8qff26}nQU;HAw;{r}bU9pG5+@Bfdj zkcWh_N0Chqg~*JG;#BA$qe0mz`>`@I(^7=Ow?SDIiXvM^;S}}YA&HWe?DcE;@3?=TTys@fI>BRzLyS1t28j^h_&iG* zxgxIh>jN*ve+1o2sVJ?Ir!WwoR~h5YHfI}bOQ=8C8g?f7-q5|iMZVCSs@^45)}Vc4 zx}eoS{{A?s&w$B7-iN+beXGiO2^^0I%>%_j7 zGw&UE@~e9n_WMa?(vf;zXTHtTPW>(S<05(55>NWUUJinR(7h%JzFps(N2~A4fp})g z0Is03D6*Z96N0ppFrvLBW_)f5)$8uvyJO@H-n1=jue%(d*jy|qu%vwFw7iLh;}lgX z-gqj_T)ZiW7LDcS?)rXOT+v>>Ip9HAvS+22)QPXZUzm2rCvfkPKbbaS&2*ftEuxZ{ z^eAxy3e};-0)4vx0g`AdEj)03!*ab^#iAPhu7DRLTXx5B8F1PpIcHmIqq6DL7VU#WDZDQfVl z+e!0)#}%gnlP6p}Ef5vvSj7MNq*|Jxc4o+fmnTm>tc#4Nj9Zs7Fh`D}&wi)f+)^+x zo_K7Kl8FiiZA@{t8m07I;g&d*XLXHksV`GMc!~4g>lKgt6;tIT#z($y7z$pp;p=Z# zza1VJUlZIHDmux+we!u~XJG(u!dYIjc$+82Tz6G=Pa(2mVpK}kC?xf+@yeM?M< z@t)%S)(H54dMQU*I58*(npAz|fnTsb{kVj_>>1O4O(ZGLZK-Wnt2f(XTl#m-5fuibX{;Xa14 zm>-d%1+Uq5R??3S>O|4Lq|N%Q7oWra-M!SBrlzLn5B2!SvLpk8l%onM5J%u1+gD_T z#zcc1*L5pt`wP1CpB~pQ?~R&RLeX4Pu$htWRepm}540Mk+$J%~VUZ$Y( z${($s)*|E!@xPQByUwJj*&Yu&59x&I=iz~!J7Yed2JdP-EpWAfvbm#2qqawdv@f-s zF64*o)$i`rc^+a)EO9vjFQix(TV1r-1I)rRB92yUdc4dWUKKGj6%tPC$^5V4P84OW z`RhS!Bt42kFN?>A0#EqRZNMQMV^XMEjLDa4=dZR;wNo9QBa?S`cUO&3OT92Z0zUqu zGFymG-p8V9XN`2D$49qOX{Tygl^WX=ZXQTcThd?+?~b`zHq}{@{%!ZB+>hsS9=TD~ z5Lm1n09a~yUz~sOh0X92xjpW0kF`xXL%z(V6F~yMJ2VlmR{!YKu!vs<(}&6g16~4b8>5wug(_{50mGmb9OHAr93f@&BlSE8MUsK0PjL@ohF( zByq47;Vv;+r@8DUSNrJD_zI8R5FM$?e|hd|v+unpYrFQD=vyygmHs8IPGJ})mL!F> zQrk+h(_`Gs|N9@gy?=yy9`6l1NsFTG z6|T)bl_K{2mgvn-VmCeXTNK`Uh*Sdud5BcyX-8QGvsV`F?PbyB3eSkH_|3s+mLw&E zO=SlONbmlUP-&A#UFW)Wc850YHViN%!d@!5KD;&|I^{&{h7{W!!EX1D@LxKav@x#Z zep5{H5$rPrw($md{xJLrBq%=MugiOh)Lu&6+a>fC{AztDX|PC4mt1>EQ)=vC=a1S; z&ZQ@w78#1JlkRam+49YLPmdqGE5KzgSb2ecY4v16JnIqKV(=r6RqcP(DV*U?7_u1s z)PB8R)#;wAWEsAHrK%{jiXog7Mm;O{j%PzL^W(COGqV%bi}N}hDl~$KdO7612gAEC zw^~q0#OdtWvtRzsVj~!otPQX7iDIaJ*By4C`cT~)#(sfE!QaVyBkTOblNryMEV)xn z<5Y3YQZs*)vP~m5KaaPsuP?|$5F(CR_5K|{e7O1kCIE(7S`F2!&ei_Nyt`VOlOYA= zM|oZilkon^ODd_7f&`0aX9syzr%KbGH2QFj>s`HvUdzcy(RWvG^%(^$2+h;xMeKD} zwZmt*=*wA#r{)HHUy}cQ-Y84E95iN0ryKfgdUF|dP3ix~akaRFnTx-E{g#mln8EAG zx+7u24WdVW2Sdcy8Ryy7X6Vhfzt} zgMOtx&^`9i!C*fagomABNUCKC&+Msca?Oh!&>RTfXL8(M7%Ymc%v`|h+O|LKF~o)% zopCHhAr33UO|3KHSt&!lvinNu3x1QrdZTVCPn7IRC^^(=#HKnUZ7n*)ymum>s+z5-e> z=2!OaD{lvczETxkKG!~(zk+O4@ki}O0*#*3Xi3@d``fr(-m$GCYq1l?sFq-z=|8f?>H^C`ly=Az2I0Xi3&IU`i zTN7ln-Bv`23%NK_$@^u`B<1!&p;A#vasoe>p|aXGNy+BlRt{P&OF3;*)(|x&*HE~j zq`Lj!3II}f$zFnoP{+`UBHNDEGZ$Phx&iv0ybRGG@XV@pwn4ZkLPs+FvU3#JI66Bw zHcA0Asc<5M^K0}P-;K0Nj>mo+9XC&gAAPlHCV>{&)g3lH=`kSWQJsfqLe=X}r_BhS zxpTXm9)*-(kk;5^GKvXFU9#tCe;mJHpSFkgCl#cr&y_1#F-K)Co(lqus9ACdYCIKv z$>ItAQMAyNo15sS7%Q%F=a8e+oO4g(X)r>>!rCSq8-7%V>DaOR(ifJS$qosl>J?KBdB@8!F>Pk{zFghC1HqL=3032IGEekcY{M$& zcObPg%CjK`RGnO4UT#wkZ&R*#C*dbGH;@s;Tu5H+fHZ5dFpI;r{tUQRCWR&=aT>he ze)GWnqcU%&gE7K}P@vwZZ`U{vEYcdP)c4gI`mDxZ+NYj>kZ)Fjc;v`;5%u$E*(X&F z5PueO;M2YFRji z`v+>G!Pq(xl@=uEvolAo#5li0y;r_O*VD@>+PE#}Wg2-H%*1OBypjluHypZK?^<1& z(+;1WpCIX8rtQ(~r@Zki?9}i7ZTfwhJAujhzaOxzsl*fDcy9?&YV=QtXotGmeRkd3Eux>-_P0x1H5 zbCJ!poFcta>DZ#WnVf>k5v}+7&_(4Qj1Z#OqLp%h%JEZ2QDEVVzcgE9DglQXx*}rGBR;j=H+c-uY&dM1t2lkPqhsRp^6`gf*DRuSurYzS%M8yz?hdV1{!?$_@0R*X`q z7h!S`7#*D-2%H!g8FBv7dH>+$I*+VfIl1RtwW1%mI1PdkfeS_BQO!K+n=+z0sIOi`>cH+PTStdlV^mG} z?6|(Q4>cnc7DcKBE3+ zIWA`8mu<%xfvmW!qcURGo9^{FBP`Y$`Eb9Mk)w3}kGuY|*7=9eL|Lz}ZLhDpT6^(0 z!#<>9K>I#R9;Qe=vEqrsn!sCpjzQKAr;IHKA!pdXNT|(ZFu_Q|;@?dYMn=!-176$x z%1Z2YCrnc>MLJzzSX$Kve1&ihn+(U{M5|ko4M`${BO@_+_M5rP#S3N`?Z!5&*GS|9 zCh5`;mhjZD+qO|x74+n3MxJAq{jQaqehL-!YJ$3#J=B;NzGnOtV>spS_?INWSH+)A zq6b)?sD)G5`srJV&377v1?YVUL3*XsmEVe@8v5%ucg99)OA1?Lb+=x;iS?%+J^^y> zlB#ze@72&gA$R!Qq}k$PbM4&9-`NI64gWkn{_AU8>zQ4bw08PZFZLSaZp~MoAott6 z^k%|2!vq6u$OV2BqvPt@+qqzYl537#4nZJGub=p6??K@U7p1>OKYDgOH}CsA??xaj z)C;TPZ1FqE+uHv%4+@cb;$f zs-AxEx|gunv11Lfoen|97A?{FqfQH5*CgxeW8>Wma(_;)x_C)sPnX44J0~?c77y-D z-t`hdn|pzaPo189<9ov3)9S?~LD=E0Oh1oFo)*>eFD@)pT3&hj@f@xH@i+v4zcVvM%_{;hfST`Aco*E30dpewU# zLa;`&g00dr{d@Lp4M2?AYMCCeiYNVJsx+vwRj2|LijT@fVmwJ%VuV?#fPmtGKer;JjV&2oGVu}=|>JClv!LI(&P2@khg)>^H9>{-KivGdr z0JRhw=4%_3kA+q&Z>nw4TGUz48TgoK7DyE6yXutKdtUi(ZavNh??Y$CCR+d~=!|z<)@`fHmA|;etM0LBC{(`c{1KlJ4OzEc__{g% z6!jW3F`Q{Gw8~yr0}*B$e*Tm}^?M>yXDVdz$3wg>#CK1@VGClhwJ-FSvM{;(u1R!f zu53Yx1kh_+bwQN3KzHe92**rY>40z$`|tpbMC!>d_Y@8edABQMuYr^BPk~C7A|D3I zFe?QLnq|v%B9sgFCQOOC|29+zRof6)kh!VjV82GU4#RZU-v$#%5$rG zp9qS1;F3Il6)^D5{@rE~;xngweHy*)8rK?^QcdI6XKRm4Mb7;~9o9C;C~@ zl0(Mt-}bKT{5Di7_K5l0O%FX)-upfC7vZqtnCN$!KO;2hTE-&6sad1QV;*&HnCs6! ztQrjwf<8$F5m<;BA8~XOPVq}jN{Z$(pd|fWA7|}2H1o^J@KF;9EA%zG0iI^a)*7w85kW-`PbX}ZR6ET!gF+6D%m2e36Xk1E~& zI5*Y;=WNz)a?;&VmypRTa!r+DZTkI0v_|@-)KQH%Ek-#|8(go&5L zKzM+hMba+QU24Cbyy3#~DepB_{#-KFz3WE)sP^ACV&G|*TS}H2_PlHO;q%P{|AP`# z`26{0@0VH?-dV@afJ$_4`!{@#w0gm!*%OTeiILcTOs>vmcc6s6jS&ksm|;&%TN>j|4v&wrT6&k ziEO~{{A)Q-jhz8TPMA|6cU+UiOM_b;yNBg30?>jL5^zG*rvhLieBU-br^SvAUGbi+lk5U+ZcTgv( z`#m`)sx=o}zx++8_&~^vYe*Q4-8jBDHC%Q+$7nqzUMSsssUb z!l!0Gson$oI;>oG@7_gW6JM7)Ifu8Wpi*fWLG!5Ae8aZ%_N4xy_xi!3Cv{s|bU#cV z0q68HZEYjvya;rqD)muZd*Q?i6Mf#^u^*WSS`>7TbQJ2WC{%p;buk|=&Xkz`42i}Q zB-nBc7v!*SVVbMv}16%j6kPwQc&#r34=@7%(B|yJ+%@nnbfkzWB0d(o@ zPJLh~en3G2b~PADxP-Cd_^xnoU<=QNSZWYY0F=b>Ca(rBZpAweH(1lR*mgxH?-=kB z7X;B59UVdrBtzKiG&T4%tYRFMz4IH6P0#>^mKMfDxywh*nOXz zT{NLt=fG2K>c^rJ9r%1t%zhUk(UHu8ykE7yxRJ3d-kl8$REUvE^HmJ4>Wt++(FbdMsfqHX~kGnVsSBQJLcRu4-(!zPZ0l^|dpTTpx}G zxSB7kq!R9cIW5IvQKuf1h`8J7T7uimSouqd8zIDrcD}ryD}#Up_erR( zk#&((Ev63{m>U#yMGWpnrh}Y`00R%@VC+Yv+)Oqtfxf8~MP@9|zJZ3TmXxiI4jhwR zqTem=*#z=gI52fo3;E5s%_ofMn)wa$Q1}APq^{1_ z^w}(S!yUo1cN>4~h-<(9pYk#~12>pc&ue<+TTwiO4Ao7BHgGpF@md`u&mPC_P$bYZ042RM+V1spE5+-7dSn4KX@<%scT8Q zVv+FrvBT&b5jZ*Z?|0dp;d^i3WxF7Nok}d%<+i5(yCt|;M905Fx}IZgS;ImcZ$9pps3zH*FSnFq$y%aQsa7(6?LN24SS)6W#JBZ7e%*9gLF!X1n8l za6ebCjHpr`aIH+L8mFgI?1DJ5r~i5ZO!k-FdwdV_+IJ253&au zT7(-F{(N|hO57k!X16=r!_x_P=HbnUasW!!$n@%=oF_|Fee>du+$qLoF@(GL>{LKk_^?mdWF*`$PHM#Kn-# zykOm4kGmib2PY@5MtW#ie)FXTtE=4R5%RW{FeIY4n5)Wkm#QhK_1Z^(_uGDapky%U zb(Cm5B5!X#^Q=a0LeqEL-p!2zY9M_0Z)a!K#(T@7u?&}~r{p+M4de~`<`t^1{hkh_ zUz}K*IMO$-21v{lPWqWv$vHN*wsEmw^?l*Q>duP6!(mm?GfivY()(M6CFCm^P7juf zN-x@rwSD=U@z)~p3M?S}1MfJirV%^we-;CQ=Wx|=ma zQFYy@mt2SEP(1+~PKk*%7ngO&x69^8Z$#zAs2d6!T)>RXyCD_qJ`lR_-$sj2STU=1 zVh&U&$aT2cD@DX+OMf&=1 zwvDqyM5=%Xq(&?12|cZtLA5M{n9_T3aKt9yX`M%> zDhdS&z-$I!G!;8Unn9!7k1}!p8Zg>_7~89^9u3W75JS!JqEKHFH5uCTh>PUAwH*s@ zy4ho_W^w*7iRAcz-DSWOL9{}E^`RAe{^_R^)(&cX&Y+P3RXp8H>Y6FX`YQNTQ~ad+>vNaX zqPhpqet|}A-U*W7sEh-&V>A&UsM02~Kb{-F93J2RxXm88Y+8TS&LvP+`=<8Jw+fXl z=|s%L>4XQ3*}_n<@2aSLkM7UXRZHiSOB4OBYYgG;Okqyd{)?QfEdgICkw@v?eJR){ zLkp+nRrf6`RBR-~M}w0)(#@RUy8?nQX}>vAaTO;SOGMyGOYHx3FKyWP-r>x6PL3Dq zOD?0-Q_rmVqv%XKqeM{UXGufiM(_l;J2*ejKXxf?s}p`8-=Y2!tTt>T$3wsH+Dz%s zKMiKBr)M+?tC&43dXpBa8gk*tFNI1v7y{&;yv@_v_hD=8{rU9G^XY>F6eer%(wqD? zRb&%xfW0rQ%YXA5&l5e<_y)Quy7Akc}==reLy3B-CUlso~S#_WIr2PgZ4k z95P#3g+=N=uMRFT9hA-HbRF8_r&1*yog~aIA}1I{Ox612zy8Fe=%NPE+_ozj5?8K_ zD>dr0bxp*b!QEPg?FY?ym{4sVk=_TFcyT;7FTS(uBEA!v9z5YV0UY;mszH;B z*iDis%F|l)jvWJ)b>>;qA~`)!j`Fu0I-cZsVMU{3SGfy9C{%a0d>Fsq{`QYrSE<;| z^(mK2;gf^Y=adSzDIxYFA{v<20+cSUXrq$!T3ZbUUF_Y?9Tjvq515IqO_mOah9Re&o0ybR)B7Jc}YsCCAjFLm%q)=dS91@9fMWj%dRIoxY zEaDrKOfUFF>ULz68=Q4;ci+Uu7Sa5*CXY?7IsCLWg!y;RB*e2U#XQ~oKFZIhJC!Yo zyv0T&uz8Do4KBQAC5bR&s6MM=>|4<>8kWGg5(&^+DBb-sYWC_vNbn_Akg*@+6i?v+)`a5xtfh0}yA! zoXi5Fun>k*9ryu1JZatS>27Bu0WYCrW4&)Q8vv2O78~O0**>_U zrn@Ey>4X%a-h*#Ka}r!M|Ls|jx!}}Doc~;xD77nSkfk57!2v_Sg}UUbxnP(~IFcM3dak<^YhI0MdpOCzgH`XBvg@CV zTiN>Yu>NTM*C{r&x-@YiSRr*M9@HJ2$&w|lck8rss@ktdK7wcYrTTZbO}1L{%U0=i zEd0-9+tFi8q;J!hPrN6`;xU{Z>1H*>a^UhII=Pp|;j$3eNTF`j3ZB?Av9Kl3{7Fs? zN)2AbyoRAk(unQ)EK+SuGu&E}33N@nW@TpAAo0DcK> z4?pu#IR~}m;a>Tyv-MxqU#sBqx@H`BeHx49zzQO=Q7Sp#Pxmja7BaZ}QF|?n|4(Kl zMdafo73j_wi~vkRvPbH&EU+^q^l86Lz{(R(K@xC;JTTx($dW$7!$gX*9w2>iR*g#U zf8bK>b=QGT>zAOEcxp+zQ}-hX7IpG)lFH;D8uo>UF;;xk>N?Gfztuzlhqx{$P zZ|uKcY|hi*$b_zG^s5~7sIdwwe6+1T=fh{#U9Z5Dd$xD1yQ$bZRmE884|QIajwQfn zDV4-rH-R_iUfQgu&c$qL()gS2aCYhgjtQ(MH1S=!)~IUgm!baj2RB#3*1eR+xf|i2 zXeeyI-ZM}cRC5r%H-BVZjK%`kb?DjI{sa%9EwXTwpWjC$GBS%&nFL!S4s+11cIM%A z7>ryPC5f7JOnMJ1UEiDep0J`>=G!1%Adgz|&bQz_ z<&CpYNQq9Ce&B+JUe1DZQ^6sAf=r(WLmQOD z1DF^cCUp%8O!-rO`U|H%<<-b6STR(M!xO_eD3Aq0%^O*iera#KAU!&>Sh#uT^70ek zqft_HAQ|MEYp4i02;9?Jc&Puy2CNB8<%P?g1Xm+Up8arIp&23XW9n}S@mD?T4D{Bx zz@L}OYl2q(%LBY|U;Txhm|{k3Sd$#?I~L9VuR*Ck8^$7Z4afydgbXT^CWK hVB_a6=-8Mh^SZ95NF6N|auNoT3l}bst3FZEyKv#k(1i<^!mbj5 zR|KgSFIy1T)2HfRq2s|cjoGJuScdz_WGWSZSx*_PT>Nzswzk4 z(^)@X^uW8xOl+r9V^a-la;pTK#VV1@;*{2;V-u$ykDP& z!0*ya4|N?A{<;!z9DrtfUD$SHd+TAO_l$*XQB>Z>_UWR_X;@YkbKq9S?8frP9KDpg z<@1IuhqqexI|aUDF!@_FIN49`odmf9=9Z&rf`p8We*rcMu5@X)IrOjN?^tn7XuxC9-UoF3$yy+b(cFXhL7pPpVA(UxCG(w3{A zzeUOxLNyOj((M=sI`ueRDL;*BIl;6nOjg?&HgSNjDO}wop9wk(kUQQ`oI)*72JHtQ zpR6&{UgS`1o0(xz&jP&w@+Uzp5UAj3LL<$o2+(IwBQDF913r(r?fW_2Hz@V z6@M~cWc-MiBb-WoLWbNV--_#_lrL8R~Bhw)XAM2%7xXRX{zJ#VA$U3A8 zGsLD1;6}Xy#(Hmn*F&f*+KtsQD8nW)H%%qg#0n&`GfNsSc5&KCtYO6~vNr3Ih4(Qk z+|pYpqzUgTkE&ypc*e7x^Dv8hJCy-G(*Dg-tM8V;ao>Y3L5A2Ti6JQ1JFSmQ%*>V5 z)$PH=l+XB6OP=yx8xEyXh#=5I@0(2sF;S={Dk*rLA43FGi$|HM+x}!1c_$+E=5(D~ zFs0o71uL?gz(XGG9J!_y(Mb3svh_PEd$XwT7A6-OiMC8MkL5YifcWmwj;P1XZ^%PCaubl-|aKJZ(rMPQF361`Gz?fgdWf_tmB8(2cG7pJnH z-vV26D0kHNnHf&akx%APbuWfu8O7`T_V`;))?9dc^$;eVjB_6G4cLkxo6TD0r9pU^ z7WGh2>`)GLa%3AB$Z$G>fEE;o50dLsW-A>|;Y%x<&tTaqK*=o1JXbNp#)+7jW; zc1w#=YVxI8g6rP>zqysnJ&M(0) zulODa&UYG|;33^SJw3S5?shRA1@8!q#W#i>5zQ^BRoF!XXT1$HzL~mpCyN4@hqm`JoqNQbEb5jVU zg!@GeaP0dm+`WldtQCul_rq+QVH4AN^nt9XrOpEHF=YW#uINvB(1vyKT@`2xk%;VG z^G&{TqD^%2EdLA=9=COXzcN#-x1<;vRC4ZYc?lcT+Z zK9|5dZ0Pgsmi?KTkC)2hZlm)U>%IQxs)NFW!Zy7%n7R#{sNFjAxU{oPcNjYMlt}`A zxgAl2vB+=MU5-DB?ELutP%YqO@A~4I=#qSsl1*>z`#6z9O14HW%9i3W4DAQrf+r)} zq4K6C(02nk8K2)FtobZw(sHg zGNk;GzjhsS_zAM$guwVi;JzHu$w2ykkXpnk;p&MIYr1rE(bUn~qC25wBD>u*@ZQ`T zp$F5Lz03C0%B!oZZ)_$fW^h{r@^-@SHhL{i6HiV8QhE!Vgzx?N&Gw~})6)gqQ6Qtv z&p2eC=+ju#$cTQXU$5B0&2o-J@@uo?#?UIhJDU255?xBy9TKU!uNkEa(^2TY8fG9c z#plRaULP<*sM}669py;<2&WKHI4Mn!ysX8*(p|n8J3YbY01C zC4)6%FB_cc2IbiXKPzh6;%+zw%?vj-s&q}P(4ih zUDwekJAF2mE2m#LdFyxs_ljn;QUO8&|2fFTkWL8XNzHY3EH3sf7|7E4DC58X#^UU7 zLWA?>Z<*8+a`5{jpe1;zuT|D^Ir+(nXD`oN#d*N6u^pOxrc~@I1NH8k{B{9MmSf3~ZFA$C6Rj%PA5B*URB8%aaG*8838yQZnaHMg$$q zp1#EnXxp!(FFQRR5s@hSxxgp7G)q5fd39r2Hr$xUVCy7vvG{A$nEQ@e4n~9=qzEX` zzh!V;v5fww2e>bv)X(1}zE`r_Q%aeq(_SQz>QCXCXV{u?F;^}`rZ}d;(?XVJJ=Azm zoF+feUeS9qe(@Y}s)=b5aglj+lys#<#ZgtJLK%G({guY0uKgo0FA>(!(I8#Rtj<0e znJcFh`|KM2tZ2I!tk7~_@_|#otKhGVNw(^PoUA=Q7Vvk75}em!E%UUcy#{K`2YB+*frzsxg78iJK&> zeJ(>{TUs01XD>4U{Or~AwApW&c6-G{P7c*eEF~V_(T_#RXO48H^Qd7My@gwA&gw|R z{KssS5Q?gHGWf4&a>hbO{&BKvIv%0UA|%S`Hgu&u)tS>-74+kC)pktGtV3SYaPgDX zhY%9K=a#>QT7>q^D6bbL5pW`hQ=epl`z0wTDJN%V?cng#wKW)Gga?K(KRi5t?`}R( zdCx@{+`PTH%h_+9r%D~7anIAN_MH+fp-lWn-bV+uY@EydAc3h=^t^M&eW{9(h~)YG z+Jw;5J##7-{OHjH%D`)B+!-TgP%5Fq)V<$vlUB%$C21wuSI=sf`M{6f_q`BlY~YKZ zxhl+#^ISsH)hQ@^#rS+vJN8|6_KO%xK{_4kE7H=^9jY-~ag&~E)5N>8@8|?Ag{PV8 zsLFx{6t@lMn(UCq;8^KnAOEQL2uHydz80RpeN7)i5k8$eiaTole?25*pXNjV0)xI< z0)ofS&+quyP9E34hWX{w5BlyiKH5wsRyTkD4toiXD63(SPP*W6@cn5{nj3!E_5)Nf zMyGjhSY(FO{OsejJBrri{l<%1lHkcD=_;htpKpG{d8B;0J8sMpbZ~d8Gjn8_N2R;l zf4`M@b$#_lw-6<(Tt{H{$iQJj7qi4_yncI;5V+)gYRj9tH$fTH zi{elf&xq=3r^DT+W(jy7nG~UMw?joJ&_R_~(*#xbwmXHUoGD@4iSjYE1If(DuPbi4 zgX838nD=+uS7&4qTpyWon6~z}lRs+bxVrncy{8kTBU>u5seI;dH^#q`&?fUBWA-Sa zdm6r^E$SbCua&md9!A7T3(q*Pxy@?!|OlJFTtRv;v9MOA^*LnFszL%TChU&$Ok>Z?40%_+5agy*zugwS8&eV| zk7_1Ww~(^#Ph>l9L{gg5o4GqG>d{`z&D(Ue2?C@m%8D4{74)LFRKZ%iH}rnPGI`99 zHzfp9S(QuN1Y`89Z51Eqnl!9L=6(=bWtCfw0<~w9DCP+O0BrcOG(o z;;y5&YFs!Y)JbbM$iG%KB2YP559G@cPJ+&GS*DcL^Dylg>SSFRZ^Nb+G`N9sKI_cE)!qTk_ zyS?pMt!tlc_e!CtLhRLod(R6w-2T!VH(fz34PJP^xbjt)q0lWEE z0X1mdDE!Q-hlD<8B0v6C3@RG3aQqRhvz!;#Vs~fx72#~J7~r6djW-B~FI$0h%UdTj!yfm7g81@i64y6c(#2>=pOhpHhe95o zk-0UpZGyK|<)3E=!I`dfYU>E-sXL@bAcok5GssQq|7s*>QUMWTttNm`g%`2QI!LEAK zvskyNjXGT-N;NS=;@b4PcKaub4@}o|V)L9CictvY#9O}Hss$g_L@MR$ZcNxrY1(v) z#+*I5ZP{Crs;N3DcOeix@mt0YL=Ioa?a7R-n!2UBH+$Tc;NoF?z4lYPvE%4MwcKp( zACZcXhbmWxttb_BqVe*vGa}>=Gqe3PE`x@0ahd=lFjd(=q0z*YEE^khiYw@p+vnZA zj$*b z^Bl$dyKAJ_kP%(!Qp(tnQN2-8`Mpt*Qp70R{Z4(W4rOEjlNf!e^a=`5<|u^;rD`g3 z!0Zl$jpKQ?b`Hl~`h6PV8Sz}IuZ6CAnI+hoB!3E-bn35x+Be?OPnU`EadF8(;h&W~ z1y{(Kbj`>7XQo|qTFc~x+Tf+L2!)l^*5i!UK&Q>i@dvepo+oHZc^%$@4Y^S?cL5zm zcsX_6fbD}Rlnq?mw8W_N={MVI@e0@T+iT>*F#+&nUkWCX{|yA2 zd2G$@zc!?WE&b?5?ln?jT+00^5#hWMqDF%|>AYa}h^bRVQxSvWP>n%~X~-Mif*8#; zeS{gmdp z_x0es_a*nz5k3#JYlz?jbI}#Kg{S#}4{$!g>8QD-rHCGD1%{8Q?%#@w!8rP($uIT5 zpa0Kr@=xf7P?bMX*jE35xF?~fZz zp(YKQYBarDoE_5!+?Hd?3U`$Ucpf89w(=Q{GPAaYB-3Z9sWOAy3x z+b6&3g@`EY%JR$Zv0HtnTS42_Kl|xaXzw;NSF#2*kr@vy@`T>kWyqP+P<^9yX$~SL6;f5<&BcDtCN1%@-cE<#d<5oo<28| z-C{vwHN;JhbHLpnw>%Z+Ba7SK7V*r4TTcCuw-{^leO+$}6~0EmM3vzsWM$VB-NUOX z2tPPKucK)&Ev(~4uzTit+zLC=G52gLQKXC(4xR701-stY*b36U!O_o1f35m}q#5!0 z(6uphda>Upn?-KHQ>xRC_}(bS^F-t@Al=?t&_{usrgS&g%Qr z)chaXjPE>bGXc$YbaceT!lDNm%Q^e&pHS|2`$j5t0(30GbYo9na7N7I^GQH1Cl}d8 z9cC@fd3u|ZK}kuD{ZN=4Doo`2xq>cHMY1wZ*Ss>l{29NYftNBSWX8jexj#qK1zIZ9 z^)u6|-c&E;*7!>ayH=2_p0MyO3MlORtD3d8ax)b>0j*$ZoPBy2!hyS2kJ9ZGU748fm{)h{ZFO!C~FYJv>Q0A$)yesaarr;dLB*-vWvb(DIx(b2M1g9 zR&A7q0WIDmBIn)K&>L5oH9cDW3|g60uqHJn_SXdd;fb>T&wd|tzi`e#&sHY4u#zry z{}}O-aZ!a(q27sYz9oYhR58WIz$Y&J$OVkVD!7d@o{?j${R zEVv!IZpe%fSsD=idT-T_W(CijX9DHv{atc%nzxZ;#KGZkg)#P}SvRePf2*}H0J7l# z1wbG!Wf|t@P-Aw=Hy{2d9^3*XablBCsa0bR`IE{|)t_lUk5{ph^L5R^u>Rm==3vUn zd|qkIYQ1{g4I6%>CK4TSMunx6b;uANzVi|VZ~IXD8l(vy4PT0SO78+`P=s&brKTdr zl-|3a##R)l9AOjTi}zueu;t$SR|i2s)7drfA+an^s66{Lsx%4KOi|(VuV1n0?4X)bA0cyue^Tz+2>Z) zelvR0iC2t2(`~zFj>@wJErJ5f4RBjH37o=x9Y`ghX!|n64}SLwfQFWe{KKUFi?(Kb zZ{)Rv47q+;!@&0s1_Fu1WfmUw{KnobeoB_eu8}6+Kh&LWPoMCnq8i!m3Vp)x(VJjY z_7p@dO>bvtRMM6L+(*SsyavW7MmZ++*H~6TwOQIjxaEA~J@s@%?i#xJOy;jL{Gc>b zGHuurl^7>8MK~V~Y0Wsb^4~*51)rtk4d1^dDiu__sjSNy;+M!_D?xU%A2vco8J4^y zspjCkx(*_%M!#R-9-Y%beO z6XWXXsf0mU)Zf?Ccm7e=+SAiR>T-q(YiE-`=+Oqv?MB{zFxln}4yCgPdE74q>0CEj zI{?M=xI;kSv!WG4nmaLIOSI;pa1K#x`c{5`;92q2cO_>LhW zenS5jzGAd~5VoF~AF5M1&j%oN>BoVijUO+WUoxx7i&r*gzj)esTailxZD)ikiZtRk zBn!VRa-vjA$=GqPysa{`TT&Y%2If`pF5Q^IztZ6bbz^krJm4re7`c*0Zmtw7Ft)o& z+*ZATs9v6|Ilik?pb(VDM%04WRUtu=ByG#JG-EKnIEN`tnOav%Uh`5>)x^f9gz=u9 zYbq)#s|12oOnt~7q2b>-Vsrfs)rm6oep^x}Pts;c2IUO)Bxl<47<+v^4(siv;HV!~ zeQ~+Pu460WI~RxB>!I`>>$dT68f;Hm6(5KJ1Dl>@PljUce$D6QpJYmqAmJfT!6#~! zjGvye@0!=8%Zn2cYfI?e7gyKB&+1%{NhvjDb1Hdj!X)BUM*@ul>p9eK&P%L|qxCYR z=y1%ii9BSN@qmBx?YNsULmh5RzIpRk3q&=|9A)(-cqrDKVEX>GM3@V=Xe>%qW*j4Wsy5X<#+;V%K>g-yG|aE+I+nLl5@pb z<#D4&qtD0R5N{uR?CglhTg~D>y+5RGkwYmc;pz{Sxany|fB!S$A4dZ4cghbC@wOZA zih#ygXHhrm2Mn>U67v!-bf{O?*Aro6pRY`*WFIB%DRI!0Cnq*i>g8A zxk>bw@VBRZ(5PuAYR6L0SVK0w+nx))=Tm=}8}q39dV(HVxMDE^QLIR45DH@#sPl16 zYR|XJ%+5B~if9frfSVS=4n9)l;kg(rd{*Q67H7X9G1fH>3~}*s7N5!%GC%?X40OT7 z#N?ap13<0MeyKk{fz37W1wb?g1?9B2D}qu65m5c7Ol*oaS5r-cZn2$=E^GOu-z);} zoeQ)bI(xL0KiB<3G9X7)a&B3kIdPolfG=EM8zG#?(M1;wlR}|T^s!;oK7R{^p&Z^# zcq~TWJ%?~>p>Mn&_?VB0z=GHKNR-dcbY_Q*(h=*yTPY~=q^16bYTe&nG^>ifW&JY+ z0*_`h^>&APc%|?<{2J=;6VGF`NmFs#<9wfN zeM3>N5gkLzOS5!0ImI~tY^y571M zyaW_2AVh(Z!Fx6-*}}67I)?<4TErjFblLKiLe`OA`ahHSywqX8f+s;10vVcw>fOox z?Be(1h$4u}QDmO-Cg)!FYI95PG}bRhTcskzc46=>=N6AH_04X;UMC{vU|^(@>D4s` zc+aMO%IWrsseS!ZwVfnP3JTW#I1?7Vrtmg$oB<~@4$y?k2ueir>R>||e#`ajSn(=r zeOh+QervX$MQQLhPVTPLla-DBP_=hJJx~PT`Jv${-+Q|gMT_qnHD!#?d%R^HFNc+_ z+h@G2US9UqANdlJp6*qcVMm|eDyT6pefE0!AoZi1VPV20QpbSY_sd+v4=Am4s_{GR z#azb+0Jn&!iresa(fyVQT1)kr@an^M$M;ml%(;5=Kxxi_1>WckZobR+k8CmT>nDyk z71@^=_47O{YCmhU%(Sc$Uo`iLC(e<%eHx$x08raLO(& zl%*n?BNe9nMsM%-F1SAsElHMQWHNLd2{2E&i_Vey9n!zGWAG9J@id!&TOX0?e~Paa=Qv>-UA$_{6C=c3 zaC8)|dcfDa(XadVE*R)eLT-IH`PD2G#!d3*(7nFHzTIA8-cyP^1B#xY9NM`_9v(ti zZ)O8p){c&4kTqLFAe+?bs?D@RqO)8HaylA zBd#F@VBttM84Gw``Nw7f=LhtNo+G$G$Tn?vZw{&XQAQ(i!J%;qzmv`sig~8~G}Ezq z5`w8QK%BFdl9;7Y<8Yxjw%7WNVuqgKy|7_X#Go}HQx2T8jNTe}X^x1{DyR}<%`ii#K3nt;k8xeI zl)GMLBQ*ek&6h~iW|oI{4sce>;x!*lB>2{?b>74Y(Dcu0XPGqkc#LN&6Ygmg!_8>L zE<>m~uMgFyGWfM2K6=Uj-SUjD5KmGn!Ws3D=eG>yX3L&EECO4X<4GxCF|L-M%&vN4 zcW;-!WErXaGd#CUMSiHz!P|LTKbF<|N7jbh%s2Dw^5v58$LH#GxoqTmfVbD9LOK%K zhz~&!P-E+)%7Sja|F^Cj`f(|GLhfzTrq9P;5zoKuY*RZqId$#tmm_a%=v5Qn6!17C zzReJA}ZR^xlHsgyF9(3F#u zbh~GOX00i}U}=4eBAT7vB1E4%go5YZEWCJxd1+tpr8=|9^kOc>W8Tn9V1|-m&`r6O zh5Salm3opG2)XQ7w81LX2+5!_W9Ie0q2THDL1%5}S|SD^+c5Z=P#e``ig(!F^!_$9 zG*rN9@h>JlpG|7}r0Mf6+vgu_aIv}ywDkTOq8Z4RZI@I@vFUL8Hf~Lt?{)PZa|jPBzQ%?U625tsLq#3N<1rd~*6-IN7RZ^|aztKaz9FpGY8 zZqQmyz3;jlt&2S7&FJ2oPoaz3xVgmXp+7$Qf||p89RW-9)aDv@RNjTF`hC5(swX`k zu*uVr@kCwh9lL=Cu87^F{rkGqLJZ`(QKzq8cl(4t&OdU%n-HcuumX3L3_p@gJ5IIK z6xIjJH_mir&V~X~)e-pu4zE3HYYLP<-jX|7eXu^;G5{P8`^Q@Y0;O^)|9$$gg0Q77 zx^wm_yJZ8lRtnRK(|&f}Fx6)&6$Q}zN&Nbz+oq87a$0uweA7p662SChhv+a~97bKw z1+4{{E>)P`H{wstO<$;|nlf%!7PAP);(ckL?IL^b^*@|u>YE1+>2mXrkMEs??hS~M z$ex`ZxH5y8;YC*GOJ+0LKrb+4+y2fBw9+NG_U9wnHTCBuW}KK-nz~=66qi->J3AUS zl0K?m_M2@YH6tWM+E0anQPLs(J#r>w%Yi|x&nY9U)m4dFrQ_sresJrn(w>kW?{EH< z67Yn%u|lm}R>#rm=!gwzK4_^5)a?YmKm4?AC1Ki z|LzESS;vA%(!~S;U6cV|yjb+F#V{-a*$6XbVoIrhC#DjQ{>z`0)mo zHL=`X3$H)*sQXJC;Nr-lE~-*v8}G#3oaYGnta;P7&(Mbco_IebzcBDlKcZ;hl*(tR zqyTD?jw*0qEUuFIS}CVhN5$6AO#yxW2vSbiu!`o5KLNR{IEJm5R!X952+ zS>K(n#m8T*>x2N4J9y~Mx!hazVYP*lIQSv}SEz|9y7K|o`x6ABj6s2EF>fg=!0lXs zW9!&cz@X0CA)>1LhxE$uS(kInf!fcHI&4a_lbo24;@SIvn@-%A3x^-<6U#q8>teC+ z-@MX0m$)6AJl)CfkbJ`-_R=ul9kmzd;!3a1*sz!gj4{uKP-&)8Z=9RF-q3GCO#;0S zn-~_k4}pY|tAOzzU1CNyJYZxuVbM2aLG{6cYyfcA_!Sxg(+o(xpjTe6nrAu;pqiN+ z8L#{Ta<-uNdv8G?Kx!m(u^4yL!E}sskrWml1snTz=1CDt`h3xAR4-s|1kP)&D_ye^>DVNjfVlOWm*YU*ToGuWnl^6}&|1 z#ZM9{B_Ek>*2m$SVspF{F8@nK{`h+SP=o-hylwNdH-T@259}3o%X!fHKV@c?s+YIW zk9lK}%)380GtDM+A)=qE+P2v?q<)%~rDR;2^@4nrsyKDD=|!i8lHME&OxnG4no;H& zY8BG6C3xUmN~*s&Qz>aV+qa(CE)~9&%@G%QBwjE|+Wq6LUWcwmHja*2YB-5wa9I19*oHXUh!j(CyXc33^ebrT2k`mNp<@IRg2^nf&vq zqxR*p7yp2E9X!cjs#L9JfA=r=Rzdni^PIjrm^OgqPw-Sl?sCSAk-pjTA%eM|M#CukFz! z$_C%FtyG?7T-YqESKkz)h~P|Z}EWD(TsY3|F`&tKl8XTV0PO5A7OIqFx~&g1qbENZS#H+6f9EG}0o zg89p>KcRqrQGLNlHC~0Z=Jg8C@%hXGJfEhSKIE2{{vL$; z1RLbsu5)H;&bVUK53kJ(LbXx1$REMZB<23X^8bYeiv8}78o!|DgcGCp6ib0oGU_9m z;UkA_pSS*&k_(wPX1wi$HWnA{T}VV1N90B1eK}I~)1E+jw{aG$-pEg;m~*k%$*Vzp z5uQR!X2Kld<_7{D9>*}&fX#g!Lcy(Gy` z_p?q>yiQ_9d+QTkP0Q03jPcz-pai_#+7>t?a9}|PsX;wST-pF*4nbM<&(BL>z_`~D z2?iLZZoNv*KLdG(sMj*v;nu>TTG60 z%}cZ?g%v(6e3u^$yQ<&xG0@pVMdo|iEJuxleFhC)f#7W>o@}FPHu3CeEX!xWeGu2a zy^$ffFq89va#%nvyqI!wKyF~FBG+NU%TlqwJhPnem>^C|p7raxLwX`k(#IT-(#Feu zAzKHkKHkokn&oYol&u}q>Wzm)?i(#~N4=JaE5ge?cM(wwwL&Ppbp3JMW-=}R*X)P}!%Chejww{i@kP|A*ueQ^WAKLG-3VI=Q=A^@A zSS#7#F9y`sG*Fk;*ZD!m3Mf=S120Q=cehO7@xESv0rFIBC-J483jXp^Lf@}_L+GHQ{M&j}~F<^syA(jD%^)IARjkmS+(1-$L%J?&yEy*PRXbEW(KM*;I zXmU|TRCR{x4&vI*eNBuL`xdQAwOy;{hUN)|7H>Mv=v8*v6RP-(kcDAV-nn=r^+CMr z4P}_M(c?tUUp`vtA3EG>mPcRCU`v9V9T(@Li4Q6K3IwO#Bhjw>IX>)Gg@kbTPKnzX!6HvM#WgJS%-lTWoHg zf=sF61GYg4958-XrTpuM`-3G+aKm_0g^I%+#@mZN{m%t&$6?F2zlbArVe>uz({10 zbpJ8-x>5S>-}TcWn=?7`1axqwruKpFy#I7xef{lu#VZlx>2uFNzo>j)P4m7yG*WQt z0TUVbCm<-QCOYw7sPmxx%Ye16T!5@(VBu)_P_PpS&T$fP2TP{`pzU$@{vK$VKwZ#Tptn~4v=~DyFr#3#gAQ+^g4QkGB2$3FYzjrr zy#Jp-i=aJpUNKEp$lsiqzow7GNMkayGlyknz&tM+B)Fw_d4~2s9yb+k&Y(8_VgPS7r&@94bfE2!j`o7Gsjq% zc5|BUSw=B-c3wET;HG0%}v{uT)QCFlwi~9Z*wtC6N9h+=t-XX>j00Fk9!d_#9gX*wX9vKE|LsYZavf$QvA06wO*ZE zo%V1t+97RV(OV{z0oYsQ-?5I{1Mz2*p|M>`WdiAGrf!|r$8qSp^-Y2zYfYCr3*#*+ zvnyTeJR(LO4?Jp)v(zm1pHIIkTwWBP@Hm{>qm>8E@{cR2U)rGMniEsE#lhCjJ>WUm z-%rETx;$Ws7qDD7KPzt|&;zG6N~&6gUT)Tm(~ysBZeo7D zqMoT_5#A2!pv-_|mR3f)_8>xPIgrx#Z4-j3 zH)OKM9Fayzd(K;4&$P#ayCp;S=H?YA07X2V32)McPIzTt#WX#3GkphITji=dV*veK z4!QiRww>V^nCy$8l5b~F_bucOs|eNFVir9TaXeA4Wd@ef>qx{<6QxCM1&`B9Nzy+i zICWqJ?R;^aKl9@1>CcNM2b%&Ecw@Z66k9qh~70d)U61~j!au;f^xwJ^? z7@quv21YoCBD@q+%WR#ehv5}KIB>8HxC3WigSfNn(eC}1aQKsv5EOLTDcp-^v&;h6KFvm6K-7c!EPi~dtc{LPCxc(-=nm7RDxItzE!-&~L#-MB_ zuZ6d$cr?izyTXXb9OUB3Voh;5!fggDS4_@K0T*o3I0x!5DNN5Y z==tXI!rrDu7{YmfPySSTWO;ivSZGz^G(?DqNqN{nDK~?EDKCA&nH|9I@0@xPa`5FZs5L@`s z*tB#^i`^<`OhJvqUgLHUxlZV@c9ZX>`oQ%i{?f(O)%A0KKZQ|>WvPvv1pq4w%Dui- zS=BvWrJ{d~XZdbR8mwf*Y#nhgYJ@W0Gu3VEHnX^_#I=P2hU=(k$Ns^&;|Ydw_8o8X@Fqs#!FI=Ds|qV1Fl)`RTiZDz#d=_c z<%#)$pi43`B?)_T1x=B)8)ELMeRVi!znxY1ord`l6Oh=HbhoFv|J_VDPrrHCO9wB0 z)kHxi^GuoMr4mNzxO4Xn3JTjX|MUvGFOW+(DsJ@87dT$TZ)i*@ff@bRgQ<({0 z!hLkjfGB>H{-*Q5q|82ryg#&Oor?cRlW(anP{&FgzwNg-u;u`ImV#1QH}#4I<~Qi3idDuZ9+ zOd7}YJF{t8HY(41LFy);D(_q|ZeIw%m=${o96Hkb?r+J=Hnx4H1A?W0Dd{!5M~T3% ze^`D%MS4x&l_mL4@XS!8GUUZS&Mzk)y7gXHf*R0jEb+iP%v7L~N|RU4HFU>nqaP5s z4v7`A*%h)3Zs@e|vaRN+zrKfHaZvRbF`x#OsQcqoTXLnW^t0S^kB-0jw)q7dm*F=~ zx;_l_mAarik|Zple$kuWjYW+P8AQ1D$`v%Cn%Nkd=>hBq=zb(;6nmm|(~vzi0z1K& z=xgpfb&LUSFi$fTqm+`bw-lKbW?s0`yeuD>^kPPrPdiM#eBjnnmf(<1WW`RT{P#GK z6;m0(E+JZl5-4Hgp7940TH`$GOY?PHPhl1&FJS>*Zire znkE@7__uSZ4f3911dM#TG5>p?Q5j8%?Olf!OULgIJ*Qvg@yo>RG_3r%Y^qHShp}>C z1>|-E^QNWaJyJw^zo$D@*3u$Mv)~y67W_1pzm0iH*2Ea2IRk>c6FD;CJgmsn!qsRA z0d*C*)MkDM7mM_whU`PuxO#BalIIc@&rE2~@(ySIOt_|U>`)rF0x$9!teOw+hikVo zf4hKix0B1Uib1R??h)_Fzd#x{xks#{nAgqg-sH-UEp<;+k1c@_5IB;Zr_soRXH4Bd zPpzu0?FPPY2}#NNwp;&+kiNjLrT9;W{u?(S{K7qCUK-q&eSwN^L2?+r# zbb`&$d~hTha&eie*bnD6{`c$c$7)go_O^ifzoE=II#f|~9fw~rIStxfFHw#ArLlK3 zJ8jk1^pbCyd{?ALlIg*_xaAe5cl>cZ8Ws<83~SNjeFX%`vrz+Fi0o2L?Ytg_i#EfBh*KNvDl+51i@z|?x z@<7tY2zb-(X&Fe)!lx9EO>2F=@ia@_DCHS+$T-P{9zz!(-752in9}QN?#hQU zg%je3dvF3D3TAH-?M2~H)UQ+ollLrq;?_Th>|ToC>nlu*D!w-)#T6xziWw|#MztHq z!*ll<*L(*AQUVW~wQRsRTCwjTV=MJen2BNtD59FRPBj@b;<=|CmlK3I9MqV=ii<{i z*z(p|jig$rO|qdmeva2PkVo~!@3~i7oif`_Ts--$Z#0JBE-tf4TPzC-nsL=B=;Dg; z8_L&FpBk^lUmN4cPz7LU%VQV8N=F{|I!#_GiPqnbWv9%pQ|1;iMrpQ!qwEz_^TXiLOX_PBJkuZJg}Q&K@27FF8SJ-$(jXP{|H>fO8WvgMA%$uV3X#O5(T} zFvL=Ze9Slv_nS@ih|9Z5Dqh-tWyl{n@r1aX%Lf0F^?|%63!RMYu(_)3WXCBf3uaAz*V3MU;%r_ zsWd4sWxpdb#I#3hEVzr2>{D7f(i4W+jSIg|NASn)IwvV}Rgvsfe5C5~_^_()f(&E| zOSAVGrnMw_snx}lB#=UJJ;yB}#AB2GXgh0-hAclsnbB;+6hKi4xMo#Lq2ToA>L10^j`*2Ad@dtSR z^J#O^uR?eU7=+1(f>gcqm(+LwngvT98XrgC{2Wc>z|IMI{hB+x5p+ zm)w`QGHSheG1%RiV2_H|+>uY<`rt`M7BB_TavHwUI0qATqo>I>$`}y|+>uVT1-B!n zY^LCD6uWITy@gCr{}yhbhxqae0)d?KE?eb-yib12s|@VMDtE&2uN$R!jo>U-8XXu` z(9Kr|$2zeBS`;qC*ohN#uRQ!_DhsRfb>JB6a8MfwyPG?6v)B%8e$Y!Rw1R%jsF-P6 zGp&5p?tX$0usY+T&}DA@*SoKGh1_Ot>j+9IkO?|%w7B8NE4tKTAJH1%bw(-?Z&Ppj zd#!d>kGk`1d3?7OkUW76rNwZ+>Ce{Zo~*`yQx3`Ev<--Grf!#j0Hm>-yZh_$bU;M# zZ;%z?QSH)Etc!w;d!vv}UnHj%LkX-16E-f{s5j^pqnI{DVK$wDc0TO(BcPkzbrh8W zqu>%ook2br^7T3nZSE3YO#?NPcVNk0ny=5?<1TGDd`tCSn@gW4_z`Ph*dhI`sb~DL z^(wm5EVSJmZcMMY)MA$C+j&et6Ttzn2VuDWd=dMDTKXoRK zId*zWu?b&ys|5zoj0WEB76{~)85#;A|hTvje@{|6~U^R~ge0^&?vr^%5Na$v*Gi ze6H|}zA&(zY2M^JcBNuPEi41U6Wsdq5sif}!J*WqX|lqoTv0h{YZL~|#sMc+_RC%t zkfOoWt@CRp@a9LjE6VlhJ|01(Ae;|-2 zvDTngp5B~PC*0OpVk`w_d=X8cXwSJmoYKtsq)zbiE16cDT^ktQ9j(_8I)1@$88r%FuRHiEV@ZC^jW#g48%7Pk_ZQ3o-AczeoM*q6`6r>+>R`c# zQd&je^dwdOEUsIU0CsDu?rnPimI19XPdz775EqR6TjnD_kW5%$ei6 zBTMjH^LwL_ZKtjC;W;=ZFo?1?pZ$%+VtFkFs`!3P1M4?fa2xRu_@iV5pRk<&C4hfZ zZ+>D?R}t8qlyxi2%R#W_aaWxGL=s?V_~mo@oXz~%lga0$cQr?Jd@e10dG&j#Ov~0p zcV2c5ieXL7`F78hMASgZA?=mcFm=<~B{&7%wD5T(nQD3>V)^a86kyHG#sSNpc{$z& za8Ga9<3RUX3tkb?jKtQ-v!>D}qkFO4;#UV(s>JtaI zc3#q@EOb6>%;1mD;|^I1z8F0B3JAvu%Ulb!xo()9+RLmZF7=iT>Mlo8p4^lyLw;-ziw@^m&kc7Je(L_eC0QN9ganQ?xNwE91}qnkU*N1%K{xv_}~~J|IJQX zpv3#HwEs6w43~#`-{ZD?TIe=0E-ee-Ka^VBRKDII-SENT@OgPdA2tKA;4g&R|CROu znN}8L3Jthhv&WJwW^dJIjUG3fD$^m=6jqDqX0seiXr%+)kSzSp@8i4`YepyYT0sbm zHk?5*vjepA->vU+OvSri;T&-Xox!v3;(`iM3jttvr+U&AD30%Q!Y20W-s?gjv>%|L zDu8vq9p6x*JZ?_4#0m~bk4%NEo0{jSUy zu3YI;)W{NV=)swY^Tb?s9i{xwn>=DywhoTJvYY-dH$awjV12i#PTUDzfTlQPQ74x90ns##?Gi3oB4-c(bon3f0kolb{qWT1wRCb%iWP;)w zh;ZY^U@^GznNG?rwdD%Fnos)m+OH^RvsOTtoOBuwDl5B|6TlQslCjp&1fS!-K#=8( zI&9vOh*Atki~S6+XtgR;=Fw#03JB=m^#P!^$Js~daVhoT*@Gp5sN?3r%ix@>tW9jZ zd>G;8t1UMCkNE6h$idkI83pCTFdOO|HssoheN%$?^cy1I@yv)M@dPPeJw(0 zY$fZEWZ$#zl`L6Hg=`ZtgdsaKmh4IPWo%-`K{F3r8qA1{D{HJWk z<`t<2F)nYXRj!7Mn2bxQHsh=uOz*{c1m~i5-41Tqfx*ve5u1y%e)n6?HrrxRD{z_L zZm3`+=hZ~qk_W{SsqnlorVMxdl-zb$L&4C|Y|T<1q0qmh#b&Q7dQ9U;oJ7QGFz(d@jc+?`c%?djh%h2f6lYc?K(YLqRZERX3J7OXP%A}(h_p1q+TX>`^ zq6F#Sm5R~jajw{gq0#m+9HPA6N~Oz)HeIDo^KJccXD!AW07*5hNf6=YZi zh6pBA`W+&4iZ;>QP-b_dJ3A1Zm&P#89;6Qal!%k=CtTL94=Jyr=}-oYXQ+@DBf;p0 zc$K=Lc6wm(YOw$E=EF~n3Odu{Nc<4V!F5dGf8Y1GlXuj^X-M&K7^z6H%8gv-r_>S! z52tj^%#K%8+h3AqsYvsEUTFIaN9stqq$n%i~&lzmq3}Cq=6HTz--<5w|EUg6OV93D8yVn&cwC zZhlGe(q$eTP5fK=FE{dftwraxa}nWOixOj8!)G4hB#+ikD;bYzxs%ctE|IqxDy?qa zj+qW`G!1_R-dri1ukdRLZHDK&m3TK4IW$fN$R2{MYp_ zH%x@GSU2_?6Zmq-EU-G~inzG=*xEe)>(HBpClWA|k*Vi8$aU8q%;5%e=&7GS-}QPS zx<$(RQgI{B^eOa)pY7bvU8;WH=xv!0WUhHXSEX+uv@ht9?m@+~&<4J39}7L8e>R$X zH9SMF?|M_umRr(<`>UcP=iL`t^t$sJm%F(6Mt6RHD!{Iiw|`U{v#SpU;Z7y9p9{23 z!k)apLHOhs|H*^I8ya1}x82@)+Am^$&NC~wMY^Z_<$35*DuTxxze1)G%z!~M4qBPH zedeY-W9uHRnhx33wU@_0gyFxxO@x>IS(E3n5#U7N6&tW!uh~8FKeQwllCb^h?`##` z-z-*>-5Kh7{4o`NYg;4jc9?X&t5k;(F&0m(8nf|vdJZB#8ch|I*(Km2TSHsPkxK;o zOB4>;*#O2`DZHsM>P#PTLH))Lp`HQ=1pxps5!!)^MxW4QNxq7CmBxDd!#u7%Pg>C3 zyS+_ZB!NzaS20aceVt5Ubh5Rk*N=Uv>~VbCRJl7phizo7dve1}h^@OP1E#*v`Nf5+ z|25n-;p^>m@awi;s+U3QL=H{mv|gxtE=fs8MKGZa3Sl}U#tufnpOjU!bv)cxK0jT- z+}=l~iJ&Y(?G0K6X3w~4yITxS{01l1+P?u3=djXs4Wm3ffzi&f}E2#eV{K9Tv=K9GOA^D&nD!1h$Xw=0P054 zz3qmNZQ@0s`BjV#`b-jP2?;;Z-4iQOndjO%N=Bp+OYA<+2bC0aE2~6*0!Y11CU3{b ztMl@C(VhMYKOeZIALq|x{ET>Yx0}}0$|Rf2#Z64sIX>+u8OWgk!{bv;ClEsgh8SH3 zk)L(9MVsxL3u!U-o7ap2vX~ZCgHb+y@A-#lsI%8XTg{y(y}4U%RBcY3RZQ#Tk(Bw@ ztM6yG$dqb>p%kf<9ndAWngc_X;LuM(6p+lirS$cLNw(&v0 zVPr*t!HA!^!f!Xrc=$L-&yxi%ayFfi5Shupa4sE$64BgTJ+3j_h>(dmAy81d_!2me zKPJ9aApYXZ{2fnN-CiHY;BBh*_q_eKhltCv`_ubBbc}sn7aAgm%9Yi()?`_-%xlHZ z(FXl+Gk>71jMQOGYc41<{(;3du`#w;26@4ApMd@TZ=RYsj9Fdr%~%9A7RW$Qf9 zJ}Pr>#vx$UK>4fh!tcU%(L4TYbK2D(MOTU5pn!%jHApuC8zzs8+`rGoxy9ZjpmQPH zsx;XPlNBoJFakys`Q@+!GKl-&=GOheB1&TLkJ6w!qzF+*X`gLG6lxv|T1X^4rfEU< z11{|f#^7+c9@kbV{w+89=ILAsuhA#!Y@g*x1-RV0anI5Ye#UniK`irEu(JtC+;ea5 zz;4~rmWR|-Ll_Gs_vv;r#25K*b)$Zd$U0WGv~G1J0fv*;V+KieXXojv-SzgdLkjGs zn7X**-Mzo+onAUeu1O5Helf)GeoxKw7#I^5wFCsSOg;ex^{yz%H+p4OHsbi;a!Qn6MJRY0yH z&);BW=L0P-68~d*W$}X2Z9Q$#y?YNZ9YpJnQL@zB&lMVUOX`ziL&z?YOV|3e^zvpk z3^HJ3X<=c3+7f^$yZ^o!8^L7DFogv439c#O+a5?fi!1*#EtcC}lyAQ%)BmE=&e1?y zd!|E#iX=V17O#_M>@0(ts00JXUkxUINwh5I+DINLvx*0jY{YvI9Z22r@g^b$4K|u^ z5#Mj#*#~wTt5>Ja{XAf%x3slph0GhMDa@l zfWmLFnubhdR-f;5c`s?=Y14g-!a2CRGxD*}B!YK_5)b3xke4SUE++Qq#)s(X&4m%? z!&^!boZiE+rDbVfpK)$^8^vQkq+SMn=_FKor29@oyR`4tJBZg}Xv)8b{+HX*Nj-`= zwYq&$Z53m8rvl^b`R!wAmd*F9C+-%(e2Dx$Ej-t6eqe|Al)D+z>W-|8`$QJz8aSR| z4hlli*I-?l&+(@Ae2m~yzFz@%W}S8A;uhXvOz}3hdiMH}^Ebe%x?YMknOlpWZU5;Gk3I zF)MWuW}km@V{CL3LZb-BW@`Rj3sFOr6nzT>o%v>;_N_FkF1=At;rpTBnHL^p)VI3z zhPydHEmi*b0zQFGF}Q762(iuCr_UUAG+`|sZDlzZRKV9EJT7W99(!_)mo!#6y|a_pYTk`V2@bg#dI2moOzcYlh*M5}QaFo<=H^z;v;bp$ z&O)6z$%o~4DP;DrD?Do|v73>^$8#$mRJdPMq@W7nXHJZMzU+kqwp;qK365=R!WT!j zkDcf!Z8vzx1ohk~?*pnmzXTvp0mv6zBzC{u|DLt)U3U26$6OnbR}~J>YWQA!wU~t* zz2NBHwnjWVu>|VCT1O!;^n^Z^*R-`X@J_#Z4&q&IBp^N@GQh`W=f5u*wP6vswZ~ko zpx@ENhVt6kSjqr?Hoc#bQQ>yC&~7C)2b{jj%F468jg72;vvg3-)ik&M{~BPB+Zi0b zdPheEDY-D`8+Y6fWfxMVj~S7Z%l4kd^6;xu+}>GG_8v-M59F-;(FQ19t|g$Wq*J5{;^1OX|$^`X`>c$3y9-VG#aq4&6EA znEx1Z3L%>Yki^6igmB>ew&@bqg0NXz2X>c*fax^>cD&Q^?h|`I6UFMT867qh!4_-C zM7_%r!RfivIT1YLigfmJ`rJJNKp zM8S%%@7$vk-oLl|(5|7;-Vzxg0(GXjfUl=12Tzhpt_rKXqN(y``iy6ciM`-O-)=Gi z1P$77U3+XUUqlcD5)iGG7u1AjU4>?qg zg;W@=-0RJ{_kmo_$!igoy&7COr)l55lY_9#MVtM z{3z(#x-GxDAefY#q-7hbkSizu9%lZ|IcEE(li|uscACJ0^E)^yqV&_fiw2zOza@f;yAFHg^ znjUu)lTtB$z|#Cw6VAf;N>9nP>FH^1D;7S)ybOw50Flc2{96kqV#o3#D z)_Q5cwYa!iL0_Yf2xRc9>8{Sb zo&pnjCY@&&5ZCt@iZI!qzlWCCDHj&`6QY_+VoI#Q69CF{9~mCR{i>a1RW~H`z}r z{ZL#85QKq8HP(%oL-w|aXz_U_#b48v1IAVVN^49IF7wXW2lxSXmJV(yGRr z(o0@9s+h5{lsRg1ZGMf7Bn6UGN*)^{gKLXX>FHVJL_>W(Hje7uNT;@LA-l{4Ug{k; zHiBn~e>%n5ZRX$}D});mk~qKyDcR(m2tPa|k4;^Xy5zs(=mk7L-1V;kO%t`+hYR>j z1z0Oq$eQtJ0G?izjr!X&P5+K(l8u)Pp7Bh+$zd#eaWN6+bl%o&I(prWyqDB|1uqum8F}0^h|^$b|InlTEkhi>?4gl%pNJyatKNl%I7-lqqgz#QQo<`JXzu5iYF~ z+yuGQPDw3Zl~X%AJ6)XYjM%U{O>FB{C}N)!VpE%ex~-3mYxpQQzKP zr-zm%rx>DtsHXW4+9q~11U4o3r{NAY{Vpjkgx0c@>5UIyF3PQ~ZMv<)wanX#sPmDT z&OrH%Lt+f0Ld_$AQRDqJ<1fsd-gfb4x~sl%nVkW`yA2VE7o;#alhW|D;a8^axfu(TOP* zO}2Jz)6}M5h6_9Qxg6M|C<-zek0{6<;?q$L&8khq#=nMpL>VWu2syLkne<&_kM+Ol zg>?pTs~xEAaaeG&QNJ%NHjOw_gn>T=&KuYtSWB` zQWAKSlzyPQ_ndt=wXeio?fEQ6aMAeT9(8}TunFUGqLNI9=w7AK_Qj9OCaDo|hJS?H zs35ISu}BA3mW+Qo$MFfAa|p0h%1?!TR!4#ZBTIMWpB2Zz!yYOz`Bs*|4}=Kcy9$K+ z8lBkm<(2~a#R;)lo}{RZ=ozxYcs!`xzD2V@KQ z6I{diV`xHC%Q9VN|6~RJFu$)@$E80@Pc=KIo8sTq?_hhp-r;U_SEgy;Za_m6r^5x` z`?ed9i(PA7JSc)+9T%G#9UaBc82>4Q9x#zcbW089{|W8-2P-Z`&DG2smbB11q+O=o z+nJUHvQXY|Cxp;xFr<($-x`m|zikz`=x-U1U9`DVayysIVPhxi3v#7S5k#D!D3ybh zJzn!OwAo7|?!^Lvm|{?-J|ll>&d?k6Osd}BCGC*+_lVoi#9MAqAduiSf7zj-4+)DE z=7e`;i!tHmAnZ5$siziQKlB$%u1lJG`($MXpK84Q^Bm`s)3~hDoZr>pKlE7sc|y-? zx3;VF)97CBm_=#g;JTDGkHoE^q7;_hjhE1o81)6mazrTZ3{~%*g<<-4ibUEo+1bZu z=V2@*8U4SdZ=8b*SQ2n@UG2uTiTBN~Vd~1Txtn9boLi&nu7Ugvmn`WaYohB{Zt#{` zpC0qdQHb_18QkpR#*$YFGs=IRRzTBtz73Z) zkec&6Ez8DIPrVQFBZUwLo#$~l+RKvdffHcJCk1Zo#cJFFy& z-{xS}zP_d{pc-A9Iw$PHcf_~C@T8DDIX#4akg2hx=>&55p)twEL zb_I=DPBE)p$XixB+OSFB_Ujx4?j*ENtOCBKyjX?$faTwTu9iY17Zescr#0ar=Sus5 z_S$(U_Q`0gElIW#uB~Xm;~ z@9mL+=VWLi?aSOxuia_>$}qgr?)-EcTCgdg&JGwF@*hWcTlqhyY~_H}812)jsaup? z82(R(k}iVwMjs=yHuj&lVq~n3chQZ@)N6h+j?)}d8Fz=c*NgZOsR+u5>+_O}4w7p- z1a~5YH4nyBvG@)pBype6!`IMhXfvtsMvK*mD*@M~0A7SUBOl#T2zH;dfN64S1LwUE zyU`VWUXA{F8m3kyG=+Ywag~v@whR^yNrReOS$!vS{Z(Eio~Gh6?-=1RRSWdo7~6A z&LNQ03h4~>nmdc+v1io7r-Qf0*SWBMpHmK!-v=mJ{}4x^oOhpbfa=;ey zsHtGrNIwq`@kZ`xHc|m-Gs|n`BEY={&&MM7Mh4u{KyU@Nl9~b{KMNhPdn_{eoO$!Mf4v*%6iJ{!|#wJfOhe;?y;;K=ApzjC#2UKjwUH;RSEA0_2U*#M(&6I5qHl>L`K z^JUpc!1^m)8?b4^ZUsr{JqoCUUx!9=CpA>0_0bhc^)ix@Fk4^0K2gyGT1e>n%JN(~ z^(TCezgeOt$)mi6wZCS*m(w0yKbL-OTR)onm7wMwBpzx7gF@%Ad3hN$Boe+NRc%K? zx_C}8JIA@@1{UL06u=Vbp!H%b0Z-+S`u*+>1*XCTML%#WK`gRP2%Hdzy9NOmbKnxK`&# z+|?k7{X8~`JF&AsV2l(Hmi=%Kt|grjqP*+Czi`8njY|e4u;CndVGLv~Fcc+H8`su# zyQ|0p6ny?RjfZ}@g0#G~LC2Gk5qFvT?G&;@_aRf8|^2@s;+-2JOE%(z#bdS##O2Pa)t8S<}Ob>S@%8@YDOonv|>3Dv$iMBGzE z;vLpfr~mLufSLcXpu98vcLl|ds=4wH-CBz+LH4;XxbTI(fF2*3ik=7#n5o5>xqFQy z=<~-WQnvj>tPE+IYmn+umGv-nXu(ITc!7#@ z3PR6>sotaO^%Mtv9bUGN@3!m3Fo9|*D+?=mf**Nzdv@aG4E)=%ven>ico}-Z|I{b-jQf-YP7ndfo%AR5l;=sf$&C*#`pxD!YI$zYo?L$qYXFyiwu9(QIc?I3R#(hs##iCQk@yxJdBJIRN}gOv_O?8DciX ztcniBw`hoO3!Z$3JdoW}B2PG_Kt*DAGZU1xaZK*(eV`qOK1uUQ?&1$%_#pRWTIiI% z?^YBfbb;7sb8{M{htYw8N*Nh9PAns`&GXRk)q zs$`5Pe*~4gdVjkb?sVXm2Zn}Bq27%-ZgfUY6f8t*W(dzN@=N*FK9w>zp=}eVg!mt$ zJtiN`t!UFL9jWSxCHX(l2HmeXqTBF;BAH{H+eCG+KF?1o`VwQyO+N%v8E zGTK^z2)U5Ht}RU?%9*(}-eBq6*qYCSz}DqsZvTQ;GL+W?+>RLQ_kSX=x!zR-!>1(f zt&3)5QJ)?`QfCz}`b+iQP&|IRBE!N0Vqp!Bgv&g@79o+U5KBc^R-Ufa(zK&hvC+55 zZyUR!%}mdy}BRjaU-QSz92WB-|*etE>NIjY1ozH?&`SUIr;hJ zJm}jzZU~Yo{ zI#;GWM1B{!-}cgEOiW4!hmKPs!v`gm2M(5Jzlb2}T4JwnE(LQQgzaiS;l;ma(H%8N z%zXz&PH;ZBA_zj6VpN#z(IE&5Q2%Rl>DQrq%tD^wLpQ0#YFjo-rL^4 z78cLYJnE+3Lz_8Xa4e!u@e z4p4fVh09)AZW7(YGzCg)=_JV`C$cv;koy(Sp<0XxX;w0u5qr3&v4 z=qPOR#h1@rrgo|Tt<02%MDD!dQmzy7($*Fu0g+BgGwtpZ&VTi#i5XWUCRb*pE$m8o zgaL7PRu&kyV1a_uU&gpEYnn==^0@Vrz9g2seRB1FlI-4W)b9ApX=5o^l~sKyl2dG< z^7+Ei(8q--b_S_pmk{@hsAF}*!6FR#dvTYsQ}2*;T}g#GI#)vxo!27+?VB^TK0%1^ zBLBAc_7ki1#V_SSGy9Pp{=)9mHEUNR;;;T9UGv-cQY_sj&b*>A(4{_jSd$&XPQjt? zy=qoTITmF`{h!me_7|D{xkmFSkWK;U5oGh5dfBLBXXUSjzJPu?r;NyIN8Nc#16A$b9K6kUej!nC33zhK=}p`En|=3=veOqkoF-&$ zJmL5UL4cTZ)>)&%bA@VXu*!J%@$IPzsu@loYBphY+c#i=;cUJQoMDiO#ad;~2Ng-G z11=)I&M7`wECv(929mV%kbbOPQrl$Mt&w1CEZm35vfgc${fIQ<(vH4o+k>5Zr9tcd z4jex5J6!OIfOU7w-*FRSTid7q6FbI91dhAi8K&q!d!V)){~_cUNK21^dXB{ALWD%2 zFGcu$%gFut(`armG=fAydAY26rcd9f+OsZ7cE4YpOOj=)?Y-6=!cXVq>A1_a;!2Ri zrFkbBZFxFSC7#Xjr)4AENu_QfUkt!(u}A?$XV4+r7>skzN>s|)c~lh}rE|fD5z96 z3-3wDX?Ae7d{FC`?WYej_SgLTC%x3deqYxPC*6X-jn%%Y>UMPrM8=6wcgR`-Q)@vl z`^wGB>pQ%X2U%%@xvd6`T>zsyXy5#^9B)ZM^Q9n~sQe#VZo>x#YJ3#l zIPm+}g>1g!ET@r9eN`kL&H+qR>o=d4f3&hL>LLi?rkuZZwiNtq;`I9oc=mBs9N63a zH%eup=C3NFUCFr zWb$40?sov&!E*d+g4OJ6RP6;#^4YLm6yIJsjq%V@|Nh{(pN#`kP_|r3HGZRcB5)=T zl2jh`AW#lu78pfAHR0G1{@1j7qqt0)I^OIIU_U(nI)JS1?rv{<`K{wWVXap+HioJL-oi7T_8Zc>i>;`eN2lYt_2y3|b}OW|;QDXngr$LE0naGSdc zfPhsz>=+?lce5N4;iJ;dqUob^txWp0r4To=n@u+1U4$~K%uYsKdr7Jji}c)DwJHk{ zK;2hlT6Cvdm(>gTx+6=q63bdT;Z*GoBCx^z!N-cpGy7XoSR@d_Ee!?xWVBT#ws{-; zNCmol8++R%*|AgqcJFRtd%3qn?)c-6EX!Y0T$Xv+6zgC|C<#!~tf%Z-bP=f}&kx_x z)86@AM_)vd=wj`4F`%@1<;>5XrUm)&i-(qiu(|RF7Nwoey?MZEKYpHW`ZJ$uR@R*S zhES_+9>pq_3P_|^mW7fmIzi#=4gh5<<-PtZjZ;ZXhxdDI zuw_*^)jj)8EHXDqQ73k53S(DSew{krm@l~BPj-L*7h%A`a3E%yOd7F}5fps!=`Mno zcV)_PB_AUrK(|p7gxZ;ttrzG}-!rD|f5vGGziU49BLh!j$7lc1uPQN4QkQ?>&2V=9CQ_%7BvUQ2-VsF#fJ=EIL-kYE!741?x z{u2|vizz{Dy8(^c-t@bH!QYvteC2oBuiBCmNyp|dAT7TRi{zD6tVJWh4H*OYxJ&3_ zs2p<(L@i(mi;}OV{z>DdT-6)pmZd{4O@M={5~9l+e_W|`ia_>_<{o(R67^7ME9JNVWY;meGLcc53ol=iJnsvFC4J< z3`7wK+wTgRDr24;u1FXoDI}*waDBdl4ZBF#O#GCq{NmB+?G=}tmaS_15;)yplp~uk z&pCcU-(GlCcCNd6kmsS`-nY8#hiTQlnJF*WdbCm+vlm9XAAQ{85uQTVpr^gnGhZE= zNM310Ty=z~tI^S~tt=X$4NqSc#|Y4hme0gmbt+OGi)ksxB}%Rl>SrjV%r#Dr%_e=|-p2a03#{0ZWL&lGr z(kW;f&g56!jWGk?9q_;5)7~x;=VZ2K{sz~uXR`53)sfq<==2`?{*E8Y%Ocn;8Ym;( zAg+fta_KW`SRq8KZC_%!s+^4i!x4zMWK=lv{A}F375&87jgPmBzw+@-8J`JF{e&zj z2V^p5e=xwR%`M_{y4?Qlx(8#@U75;v){J9%J~!~(^3NW-h?w=t%ujEqaOj{Hwq7+y zw|FHhW%oW7Nz&?FJmzY1@Mw}+@Si=68Q@L!{=5Buy9K%GIm2|Wqz0SZEgh=-(hq9# zZ?NifcFild&Y+ynhDa7Y#n>{rEVm9T+ys&kXMP@zhjhrm2K(i)h+>eRLGD7i&nnjb zOW$ODws=41us|2u@=G8Xbh?Fv5QuoR{qb3AfvFn?_RBFZ&VMvwnkHT}rG+FvSoD$H z!&ZVr=B|6KdP^7Z;X35761{82eZsEMA5%kAaE4xHw6_^vqpvMje9TSg{iwm&zOv-& z&>Ohumsi|a!iQ+lSiADqWLhJ&>mlno>H%ejZW6iNZS4v@hcu88N#&QUKX;(K84fYc zI0$Xg&=)#n?q^-9I9pW|qIUG>qtjt@zpmhRGiU;yEz~?~cBx&m{O0I!57&$CwuU_{ z_*~@Qp{b(FhW~0Yb_6}sFL-_V{=p9$Vx-+`P)_G6kpzphig+I+^IvwuAxlb2ujjxY zK?E-)F?tXaa}}#UA6lMVdS&@)xYOoT0_|e&mrlN`ajmhhv0`l1zi-{vwwXgy9o@U4 zUr+X3mI4Wb50S{&86ilL`n!@}mBXKWZre=R-5>P@Z`Lt?BUud?Zx*coyxLw?R%Z0e z^UBBLgRIN%=v+*mKBdrUKE~6&(wbVoC2T7lwnisX)Zf!pPnZ6}gEeiM?LBW1iP@1a z#x0w&U_;MbRg}Gi5A{pq#8wJ=6EJI`2g-Y6zf^sfQ#+1K+lmsJ!LbQ@E1L|DRy7?? z(C=B!VCf1Fcmm8Jn3@Y!-(phv+w7|PxhShh3ZV+JY?T)3ANVy0PbYF-F4+weU?mX-_O zar*gKDaY*1H4rK#7B$_&-Cw?t!AAr8eaa0%>7&PINVOw@@u2b8 zuLl_Avvb*WQ}++sefe8;MM2(8G%Yzvg4oBjkj8BeD+UNjNPW!u3VAxH#z-{x?5;t? ze%|3#X~drKbX=6NjE~$THA$6Ts}v*3WysW7y}jpczH)}-|64{9CwV7>YIWU9S|8JQ z*7JYr`w)~QkqiTf`lW_Om9UoS_Y$2GVz5w1s{579hkGDNa&T$-IvJpT>FqSL`FkxE z5knVD)>VKCJQGXSWuG5QPz2h^q*IEgm}yi@FzLD0AfRgDOUt^Ng-#Lw{5duH`*kaA z-YiXz2(HM-K%vYy*qv%vx^!Rq_#u4^^Gd^x)|0gC^XCVvRnmmb7&~8GpbD@XA^Z5q zj>5V-C@0^Z4d`fUU(}1~oOJ<(4K}xV#pkA&i*$%fzV7R{_e*Umo*#>-1t&`EcZFY! z*2R_aUmbo+`4?&wF8YwAQ4}>R_{f?!K8%&Z&XbaBQ#w?>>S-Lj02qEau*J(_QVx-b z)!ctsRW^%$QFNL7&P26)5aqvgG>Sv!v4g*ZbJH`VuO+73b)Fe45zSAQyHWoHg~5%_ zFdp?xD|FMx&%}y#{Ha&^m7;0SdZ(RxPaput;bL1lWX=DHY{KShCK%@yuBYle4;TEY z&^FcykqRc^CK4ZD!;DMLk9U??~+jb)i1`0_x1~N}iq)UpNUj zrx4;qnl>40b@}^?tf$0o6@!zOvtVxkrG90<1S=5X$-j_sZ?I1aGUz{tGJnoX)QP_K+{Y-x?T_AL#eC@pI z4aJv}`G%p4lpGs!kvzAP!Ti3*H?S%XSyhfSOZU%P+ApT(ic>%PBk!z-@{#iR%MWq| zyc;KTs?ocZzPUz~-$DDFulwak%oDw!Vz;%iE9-#j4a=XJy=|v3?IEQ+wDPqA5F2b9 zilh6}1Js9AVg@rdHpSdeA#Hq34lAf%ZHaD*;>4xAS4nwC#i$(Ju~@VuMUtcOLv%ZO zxZI7gV71ZXLq3;9+|M-}_}i}dw~n5&3hz5A8@9QEPgiK-tpZxFiR81=S`ET-#$e0{ zGf4Id>RAgnNmA{gWU?=PH9nJ6WpbEEH%I&SNY^_vMkho3yT;etCnRyWU!(rcP;@dtL38h@S1+W*wJPPg;T zK;;~7kDSROtL@Gl4UY;hJQ~t>CdkDfK6eOh0#^(>cqysE8b%}Yx@ReCHei-7**-!6 zUwi%OlxY#**v;pZ{oC+xRTqby_yJX@WvqyhC(GgZQMR_hZ#>+#rE+CBVhh=yH)K*^ z*UsnZ|7rogv)GQc>a&!pH<}hL&$!||lA}o5u#JylgE8=|NQV&JZH83oD0J@Uxp*;z zWwywI!ZFz;fj+qVkjdD`H~XE=$!f(w?%Vjbj0r>4TYi%8Lb;DyI-{b^6&pc4$k5?F zez^Ahqy0G*TZaZ|& zNufCBTcPdgxAz}jL<=UIv?G%9btM+s&>@Qjn@mQm1--=asfe@i-9rncPMesP@=e9x z_Fo8ko9pR6VR|}qUqNBzbK`cU+_}o6qrvBoZ;bBJLm&Qw#aU*%4w4vOX@%n4Nd=Xa z3z3~KYEs`n28Aj>OH@EW08P}-|MdY3<2NMSPZ3rsSllxBnIUY9=1Dj>D&o<4bj-eg zv7Dpg8X6knV-BOani_ER({*MVpLQO^>7X>O1-CFYoP4qw#f(JPr(fH_R26XkV`=Z- zAs1=|E)*TiI#%K~FkQI$WAgI~x3__JJgmdwk1ZOq8y7=&&q7eUh6-{c>0s5g!(%PJ zk2!$_pIA>KMg4FJJfX*TbwUUIUFQaf`opeP;q#Ztr%`==D!mVSi~^GMSaDEIbZ>~q z!B1{7YopRH2T2!tRG_bN9d>gjxgFc@and_aEf4A`hzwygt6A+aJTPxy+w$0+ZS}b# zVpuKvL+!RCy_D)oES<;^5=m;chDM^A<)eQ`f7Ma?p5{%OMHOB!?c7Kz(ES1QoFmPB zrC=qXa9BD|E3(>XsC3(xf@J@_+W%H&?Tl|$sh18BdZz2I#D)kbLRjGuKG>Equb`<`Wl@gvz&uE@1@2V`kT| zR>!lbon7v{HOst>`Z8pO!<%-IR%SXIkSs@a0iwLqRDONr<-+T-NXtufy-tB2&e)n; z7ML>)Mcbu1|N6Y>R(z!;p;3eRV)v{I6TP#D#9eQW1-AqnoxB^yd~w&A)!WolG*ko2 z?KC0=89NWIy0Zz>UzXt)K#63^RelM{y%BhYsWl^_MaMtz0$6(NOJVWx)L30`Lc5N3 zgNwvuXPOcqaMmDu!dEQW6GynD9Nl^-;QvQa_18PmC3qo+YfiU!q!Mw2qVCy>w_>rd zc3nos&;E_f@k3NYhigZ9?jd(hQ2Mvu&tS!pgv`{+^{S72SL3lYZ1d|59n+AwJ&g4| z3xGO6^ZnB|oFc^u8?U9>MQNyD8ZEkpHo)?=@FXpmJX`0lx-Zu53=~wOkfrJIEC>oc z9wgs0(bTULWg<4NF0&OPyW1`6YqPz?T|4{LSLlqskBng2GKi?O|1uP0 z@q=r__>gUr)_(Wahs7|GLBlk1-CX^1=E^lFT-(Q|qt!S~9b@?me&MQx;5p1Jf9cmzmk#cZ%EtlgCA5`k|HAMaghO@1#4?fUbjtUP_q6Fn!H^P z!(gL1)M5)$4eJh~N9KeD(LC$HOrFqQHMK@?=uUOB07*8Z|KuY>vIH|(diw6tEO~pl z$~D28OuES)nY`)MEd0PRQKi3jg5&Y2zm6{JpG4|EQT8gY)vyWGZ;eWe^jF$ zH%IQCs-##My-p{1rMR9VI3+dd+oWDjeP0riI)jnfU&#p$p7K=FjA1p^PyrLp)G^Rh zov3>z5PH{u*KZVuHZ2UDvV7KKU!oIpF)Z+E|3mFSE8505gea)pxs^jEHttQYD4cUZ z_TEFEHV+f;P8}`F5_=e$R`BzYlzEY%Ru3K2EPC0U*N}0-T9qVu)Yeu|hi)qC`PWo5 zwQFj=X(o?wLr(vlclA!;ebgA~T7gf!)}8aNC+Z6G61sWC=j~lgX~P;Gzip+reT?kO zm)`Y5!GcDX%>u8AEXJ*~bnoY1%XZt@-$F2ra7tA;6kpxjR}Ls&N|eL8>dhS}F>UWH z9;1q972DvUlypTelWq1g!Ae{y4hv9ouIQ!Qi2$#a5qS5G@(JdL!yQB^IjGtZThJl(ml ze!PyM_`9pl&7&h%`pjIVT#9H&CTMKX#X+O4D?YqIBq5) zJl~l~6~%a)HIutfxT`DPD-0KlEMFVB1~5z|yH}zx$<<_Q&F#?d8bxNDnIN9djaX|q zwmTwE?9Dvdc6(V<8FTRo&C~i6SlKX z;M34T7l{n}>$Cip4&fop{z_NFxF<)YQB-B6^w#cP80z0f4&!IeES=t!90YsvkLf0TB&12VVunil2L{Af`eE;A==d7-EJvJOfG6>hJKfgZwCcW@v^CX%_g^Cf zL0=0?VSauLHu<90z(=^*`QuEPiStXv_FP|IdM%eE7d}TKx#78uDIxG>{-_|8%--+XaWL z+TN2?OtY9U>^pgq-sAUZ&D;-+A10DCSZp&~<}?u)_0L@C&(Rx?9UWF!bzNF2a;+iH zrj8FeinIl`K2vi{no)O`G%kWn@>X*IKm~jTuHm@6^2gZ56~i4$$=PSpNdB&1?0WmG zX>&nhs$?-%X!Zz4 zaY&CZ)tG`;jp{Hk4_3wci@FaRRuE%b743LEh0+R(^M`~rXM)*Wb2L;x>Vbh_L`gp8 z+UG24BKaXNSTJY;Zflyvph{;>8>UU^#5M;D#cKE*hBpXLDclnpD=C8fveom{5+ zd+ww}`u)T_#F3WvlAnw}} z{;XE>FS<)c=S&DKOSunBeBt$S!x7w#?zk^;i9^~~!{hws6gR?;+>piPF4JgkBPKm2 zNTo5QTW?PNik+7NV3HGN#g=(xXEX7M827n|5EdFKQ>(ctEi6jpYJ{nRakv@2yGc)~z&7Yg=M%*xrxg zkJX(XD4QPL&YcOimFG1js4JiFi~V+wP@D0PY^&TqXQ%m)$=G*oP4(FO_hzsPkAhQR z9N+LbXMmQ~u2`R2dHKhoKO6mwqO@Rnd43v39W+n~ z$&o<4pO@3QU!45j3;ntZ*6^x9b_oQUWTG3ds)iO^xEa()R_;DR+<#N@(;eg+H>Egk zNO3@l3KaR_D&GW%!7^n*Eo*u8`ueqW>}W?U=*DvH6)SRDKk!SoS*QZ-?Xpx8**EpF zA=7W9h!=Yk)Iy1*Hgk>nFeAlA*3g1SE;mvyKc#)7$(ksfMnkC8;&JhG3xyQ@RDW{l5W*;_pYEX-BjH9VD zE5?Ervahf2W}W)=XxL)Z4l>c~U&}t-o(tGc0wgF*h4 zdf97}O3u=+x9reUy1jj-kJb3hhWTsJz)i%Ir+n08Jk``Zb@CvQ{3sZ=~^s_Lk}uktTw<8uj%TPA;gCf22m*>HWx{D_L2dPrDR4>QDV; zC}t|JowNHiAhRJ!c6N^C-<@gBvblV!L1|+jn6z!KF^kfS!Ir@C-&`dWXvcZAeFbW- zu8nBje>`stu|uk1Gf+ZjUHBDv=4RDaGll|z!pg2*Q#0kEY*=l53`Yy)kZN%&=@kPk z4tB#ukTxw&)}fibtsl;8J$y6SHR%=G_?ox%2K5=<1}AMn19Mgz(e~Zk9CC5i6^arC zGQ1DMx>vNlrTgG8)^%RV)ZG^QU3y>pFjr=|9H&*!o3P5U;*;to;VFCsjfWV*rg2lV zN3s$tb{;aZ(Pw>k`!m)VY;^EX^3S)gtkE5@Pq|~m7h|8N%^$7x-5Y-i8;HhW`I1spyYU@>vCNa7 zSue26z9&NO*7#f#>HnDe4rr?X|NjytDJmq%N_Mh}xONnE%eq8H*`vtbo2-!Rk(tr8 z%HE2Qd5sX_D&yj2Ub6W=Z+$<%^FQZvKA&?wbv~cd+xz``J)e)+aQ^@HbQ z<=^$fM#}Tv%SmeFWr?2eGrA9l!FS3V;jqK;iIS7_i)4>mpAYO)ubx}@E!Sq5umq68 zWB!k==>-Z;Ref;V4x`WA>aV>i^B>9|p3==YoIKbyiQ?BtU$)viY`b%r2Yp!g#lz($ zh2mvijUrur595=~uOC!G>)A~pG9gbx83(1_ARWA!T>Z1+5$vJlP>60w+y!z8{foq> z_iM%j>y7g^`*+)3&y8Ut_d`nF-Lu<&SFuQ3w8U#Z++TN0>D*Ds_u1h3>Uefvh*Ac4 z>{a6?VuV**wQSykQe_ElI~g(>=`(qH+loqE&PO!#C%ojdKc+}P{xhdJ!Y~+D8b9YaMhY5b;M%M!PupH$H z7RR0g_j1s<(MKi1<9?oO9Yxu>Kvj!I|7cRltsTXnMBQlm@s1XikIn1(Q;N?wrHx0T z?am6iR(wf19^SGkVv(;v@4{}|^<O0_}b*B+dsF~)LEWZh|lB55i1QQ+h9Z#_&q z_D!wNV^rmEfMLj{g&Pv%{)C!rMqe({t!}zt;I*pbo%h)4V%n>VOc2YNo4;B9c~WS< zva&MmA|D?S<{Qo`=japyvtxFG**_^ss*Rp-Nj{g!YUf5j;0tcT4yzXUM`2-gZ^4Hf zXOd5;R30+1;+aOQ1D~$mb&G5=pzK5(m%5-AFBNR zMXFjTKO@dHHQMA}C|j<@0`d&(l6ixMez_aMfxks9E{~}VZzPffBbMs^xTM^=ky+C1 z3(>L-Mhojf7cI$OctIXDl|nkI2u-qeQ9JeKQt!ON3r|8bSqxgRAiJVb;D=?${Xza< z=J4V=R2JZxGWyM$>d?n}}5BsOPSQTE4Mi-(`VBX^A>mf`1Vu!dMq-TY+$#>>H&T7aara-R=8(LAHIAA?O5IdEXe5YmA>3UY4zdqPDPB}LXGxJX03-^C9-qqiOlFy zy5`8-!im#lB8`?Ge%{g&uv$52ZG#UMVJ`JtVC?t|?=O~Ft$iwi#F<)m?BVn_DR_N; z?EYi|pVUAn*18f%Ahp{>SlNrD@W#Fuv(>eM`TRQ{{^y|LpQxpx_EvDzBS82JxOeq9 zYQ!bBR!hLwBYLBB8;Fr6k0pwEpRf$=)8+Ty1US_$vT2(Z36GuO`;%zuc2AWC2zoR+ z$D#}UWFZtUOD*tyB4^ODzK;zM0R*OiLwC|#A-fB%~OguQPdUkbevT|=@ zvbeg!e)05-uZ}(qwxlA$3JQ=iUmR1pMtz)Bm451YaM4;{^K0wMdk$_#77~XObjF*e ze%V7CkalWyG1rPDGj@|4(Y^G?$2vD?xy@R7srtA3Zief*PP+#?!c@yPo(qR%ncJK< z#vj&t?6l|ZnI4LYSTt8IJf@T`3{Ew>1?-WM;K8>=Wrz}j6Ah=&h5r zU5Q(3V$-u!9DmNVAHgRn=O^%2+a3+uKg7SaYv7l zP;-#|BWQUy;OSlZKo`X<3YIpLcWFF7biOp zF4H7!czEs(yXx)SvF!21jIy8(ksV*T!_W4^JE#cHqF(142ZtA*{JFMJ8Or`3A&oDA zkArV;ZSdw6BShLxw{Uo4N$^kN0qX=^KXi)O>{*{6-lp+S>Q%finr{6YOjvs!Hu6a$ z$Vq@5ObxjU!nPUUco+3!1z$qai(R!Y?X}?>58^F6r&>>okM{&F4~G$tE}@@uTM2B} zby@W!xigE6^dRqu;Gt2}%Slnz*(IfZx3c%!X}|{%oq71t(_hySzcN|q&x8cYH<`RN z^KyHzUvudeIf);O%Qlq<1-b1Tj z?@PTyt-xML_u0z0@i9Krp`bkZnS<3eI4lh)dWlZ=XN%F`9W%ir$4ES&M&!7b(I7OnEmfV7-~tQ{Hy-v))UpmnuGs zkG4Xt99^gZJL8j$g9>`94|D*$VVCXqcQ!;FPWTdc*Uob zAAZg4-0|(}UI*))H5CRLpdEuzF1p=#L*l|bpe_J`iA7-N8{V3}diqgUfbsOj)K@)} zp1K#F12Hj-Kl_put&(?shN8FKjeg!O<5NF<^Rt^q4Uej<*K=6)`OG69%$>ROTlD3) zK>GgiA}wmtfSjuM7_Si+*k^;C?;BLx&17TCmXf5NSL>$o7#bkldGbdbPZsa=#byHJxKxH6 zX^<=|vV*0+QE8Kf!a*LTZmCHGivTOjFM1NtJb$JGg3)#K))GwL$^YEB&x@YC%p zmpQoc0`!aT6%St__bBu7I%pv4D1l)YqVh{FmeuyuMP~Ylg?=9&hkoDnZ+E2ozdt@M z;ZpCn89sfywwr&-U$C=Lr{6=RmhjuR`l-NfaiiSmx6@faAyc(11Syoi`Iwp%T;%#S z3O9%!H;yI3sG_0*YT5o>CjnK{LmMjdau<%cflQ8FNx%BL4%~%jrt}gpIKZWk%^=jePlxhRC8jN_4(|1&2StB6>4}AY7VrXIK5S6f60wEL>|lFX|FozWyra zC#(|VBUj7L5{hv@4zbKC>-I?xPtWGaGF$yF`mFD{zd7TU@Efusnt#3k_Z_omy+E&J z`McMDk!3d6uBQ@8_(VSjz^zQ2SUMkaDuHor!k$nxEYChXq}Pj&bgn*U51}IU?wh(F z-;|az4=c=fHbL}?)_pVe2Z~or3EMey-r~%X$j9$2{DKrCX?afUrZ7~ML!`skl4sGU z)7+CR-UzHC*3_#fY)oFno*;eVcHDmK$8OY9 z0kXkz)%Nj_6C+EbV13qTpHcZdDeIzUm{V=NPJ*j#!M*V+i8CdR`jYv>nYgIitYiLC zg-$1=gH>YXyk|aZyp?Fy6NBj@_%XPX60>PA_CMReV~a zC)cm4#SwE>K7aO=ka|Q`BL+9mxp}s~U-;j@d7X7&Y};!w*lV$us2mW<#xC1X%!7a0 z!GRd%10nXW+NQ!Lu;DF+wj2*yY5VnBUVzcYYPhIAOVV8m7LioK+^P|TV~f7+IKox= z1Wr!yV{8jfd_Q)2U3YtJ9`vBsP}&e01#dIdzqM?X@Cmk7@y`i(lm%^g#~65SvC7i)Ej{mBa5#xcwDIPsQK;@&Ax=pi z17{ER?o=;3hMg_%%-i(uZfbR#%dfrnMAE}ygZ&{Yuh90`Jsbh@rJq-vRbaI}mm#?B z_Sm83ao%X#?x;U?mpkt9E6Z{n-Fm0khf>=>k@fg%zo$$6PYV!41sxNISdu!7d^>mQRl8~9|ootp0wjAw|!AZD%+Lpne?&2}emHAD_gm~Le(??SedvvZ?6 z=k6c2A)PWcP#;tdU!l-bb&6gr`o@8;|4Nah@Bdsof$IathWlnKb=z54>dD=MoUkzh zqDkP#?ZlL&FJ6V7Fo}Qiob=_Pwaigb57gmu3GaqB-D;~RR#vC7Zz!OmW^Q>=Pi`MX zw)Q=;`q-*6O#5fPmW|J>r=@hvRZYg=PW_{>#{qfDM3b47b6a4!dA1<@F39(^VLEik ztpug69;=jI3wvR)ZJdcYCbz(HcHm-#xd8K!wcxK>&fVOYrcDosFq(Ie0G<00kZ};{ zm?KLQ^__FZ(-FeX3ifh&huUBr>3y=vx09+!TRa?LT?hb2X=NjB!bsU)ZEo;albdQ` z5#E^&Ppt6RO95crdZG@}K0+uj{6!$DrfbIe{XZYU5FnfHdsq1R#``-5`@0C26(0%b zB@l_&n^qaofYqmFKHv6+})TE@cD@`QgAGlw|o5;pp15qHP+B7_R)?=YJ46||Vc+MEC zhpfu=F4(mnGlRvYL*+wTsX@!!I)wpFx$-F$eWU&=vU|qfWka`BzksX{;?s=1ZEOe) z_)QqDzs4JQwi~-S>NAM6J=LxV3NFueB-Iva6jI zN9|8E5x2r$+Ti}6r-bh~(?#jv?Y~(oSJ&`%mtFNJ(Nsu>d%AHU&PRH^Q7>R-G1D9$tDjmZ?b8_<5#}_x6gi z@KPvF2}YhdlhB2`ZQE6DrDdR&;P~^J4(}ezrz0k)Lb@|v&s1^u=T3c^{Q+upRXPBJ zU0`ya3$FXBs`E4)-U{OGjgQKiU+|EUwyPr=IA6^_tC_dkL?C&QClSbVcb;ujuKH0s zPG)$ysJ-6wO!I2Q*c|R*s!KY8mz`=oRt`>->0D!i)gPDU?Zweyjyy~cIUJ+kp(A+t zA3QL!rtkWL$M7fgp~QfAW;#F_Tqg*HI|?&B?;BL6;R zz}!Tt3JBL5_uhygt8J%RtC?Ib{<;KSBVvIdj1Fc(eZELX_5GOkP#fR!IJWE1fChiC z1jO~!U4IQ2cAl%Pt7JveqIH?u25{puFU&@wt=Ao$Hw>$P7-w-R*&V#4{8VS7t66zs z0>`wI;Uvh48OksSQw!x%GIy+Tk^MU5?~l9_x4f%cU-PhbT*^M>p>(z2OLUQivv`?= zUXy@FkKE_dNcYj5Y!4v@Texvt5II~FkfPxl2dqr1NHTc_KQ^kG5fHlbBvr7ow03s9nqXM*zcIKw_3hYouqVBxSmD>}s2 zH?ntUsTwlfIpl~6b$GD0)fO+t`>2=@EExNE-@4G(CI$_TL1_jzhPe9AMa$zolV{pEI_VbonYk)g2&Jl@M*aqp5A=>=2|>hSb-|4 z)>Q%I$zww^UmC z5E#gTA6@)&>Uibf6TxC=6gl-jVa_j{tUqr|I8;PzeRaq<^)MfavK3m5fFx2ejc= z*XItzx!$(DpFeixfjR=)MlYXwAtmM2Uyrt^>z*y+YF$=^j}C24xzn-hY1qJnZ)TeQ zj|ZUGd#mxRzuO%1|h2_r( z`m2b_gtNz`R3}R%>3c05$w$x5F9t}YP5j((7Y+WEfG(2d2IzhmZ@YZp84(fDs5>6P+)qcvDVvH=$Q^M{zS-oENXxwE+xO@W14nQ%WDV^!R(Aoi(jJaUw;~5P2;mEr)6Z*n+w8lpwxd)U{ zv&JH=oBk-lAzJ_8KGynoVWQt&*SuOAaC};RYlyRD9+aV~jKz=#wU%NxcyipbJe4~W zVwQD<6AUg1q&N1v92Q6FG>q8im9>o`F6DTFZ)D~3_kN5KsIr0}zjzhJA$_ef~@eJMyM zy|U_o8PD#s>|1owTRM2J@One4-~`rGyMn~a@Fh$9ZSrBq$gEb6>h1VkyjrSlDTpFa%;hdRQ3 zth$^IyXgu|1S2COuJz%>$cIMiaqA1%&0A7Zas2<&>Uo*gv5+6k?1<);Cfod|`ds+9 zGPNCHo%GV*{}>a(<*1$KHIyN zg5yR-wH1PKE$x0ec=3=8U7LoYa^BeroooGN3Q6qj7QkMc7i!60)5{Ph*G&P(;y3;9 zd4}Ibfi&ha-862Qs=_lbUp9O`&W)uCeiQI+oa5CLl5=Q4_l^{7vs!IOpM{QvyB_%5 zuY7Xkk-T0k#-rYX0gbjBGiT_?eAH42ul$9W?9OY>dQWrPDr-C)R>h8I(>5#*d@B!g zT9qst(jXcnlWSR1rE&x)Lz-R#bko2fKk#kK%P057xMp(xTTeIHctcGAiA3-OfW(uS z-f}p;oN%AB_zy!xI!|B{&t0E0)Q`VSZ@g^Mu^M4|Cj6a=n$)*;O8#RAMbdo^paMG9 zMhJhyMZmpi2D>jB4Q+tIyniY+n5QzR-S)_s!&wy8OWJ@pqY^e5?!EM4JTaXjX-D3$x5YrUz?Foikq2 z11oP8c+dD_QSFb&`QB`cR*jrdnlw+WbJTTPxs)&b(K_68VS$}kecJTooD9Bu9VP5a z=lm9rU+CsbMb8oNTdrj-G#rF zS}-IHrhmgBKvJ`E%=wJV0^PhL&YKwW10hg=E=1$D(S#p{g}3&P@P#_^L3+WqN5l{V zmT>c|&{OK(MTfkObEo(&bmm(3RnQMWA#}pklZ8(1=Le%X1j~K#TE$fZ4I1C}lQP>a z?l-#+TSNRL=agVu^VD!H`PDfL0>PZ*t*d_6cEj>rU!qr`#A$FmfqM~z5r1fohv$k| zBoVJKfL#G`u?zbv`2Z*Hq$?9)+hcH!80tXI%3sPt4xR$O+LZ3z=E>32c$ci>Ri z*;E`{nQd+I5s^Uva4gh_Z|FFU|9&W?Yh5E~Dx7ztQ)rez_LSbbW}sQX5QxIh3lGRE zzh?9x4uv|w)uDkZ50O!Vb6u&a+=?hvH@TTCFnampcl~oOk5*2&M~-;3?w{B+*kvei zZ6vH5^yF^mWf0A9J8l=;#TeI`sidm{$x>4|!J8;)y?^+-UOV#2ous1egzX;5KVMPz zEbwX>H7Di8( zHP3#9{(TJ1`!4g5D=KH%-!9EQpfdepl_rgKU)I|#fD&sukn{mv_3s}`;*Z7SkqF40 zT94V?Ts}|g+voEQiD-oE)gBB6o4By#RNLL&esXhZ{8*7${;Ci(ls3kG^pwVbaDsha zGk>ysn9(i`fqs}ak+7t1b6r>)o=?w=xRO2!fwX;{w5Zez%9 zPwq7i^UH1P^O#J4lKq$m*2Y0Xj=nowEfnfO6yF;CeRd|@eSN9~_lX7Uz5hMV&e~4E zprHNdXD^M>C>HBA@|&_RI|g!PZI>q`;qC?^K}PS^TXtgBB;chzTzUc2>$}8T{r(5e zS0g$`G28$Qg@uJxN_M?X2-Ocq(*WAcMQN*B`NuzO)RX`H?ZDsUKaRy~j-BKIxBs$9JkDlLaXZX8|m^Gj_5` zrW%%T(kU-E+G{$!vX|sg6)n_5x`;*iPbE=o4u%F$JI?HMMDizX6g1eB>nPUyr}Ny? zZIcyOY>ehR=cg%SRoqh9=-oQ(z5lX(J#OcW220zUHE+JYAciPE7w)qyc!Qh_D}%=6 zT}OKnkTtF9QdLTsg=Ibg>ACRvXMbPRI$ng=UIN6rL=vqU?n)p2y~CXn5vTjECI9BT zLo3%i@6f9Qd4#~h!Lt7@21;u>N`5Tnc-;e04jk^KBV8gk4#wvV#3TGmGw!+$KdSD# z&`EaT!Ud2l!A~Kn!%iUjf?i(>-tC<~so8=Ihl);CY}5N=x}+KXHF*0EHUEyjDe*vi_p8?6 zA1weO!K7L|*0P~1{+3@sRgI2JLDd?0Bv1TDTu~6UA73YM)WGhAX6Dhd@92>2@Z1&c zR&pG8r;&wk8x}3Iu&a60mE88jy7EufZm+fIa=e-)K62`>91&izvqRme%frBl1^9r0 zhz`r&cTZtyI;9@L`QX>Er%}U&DDp4rz62~I`Y><++Bq;Pnmvb-qrQoptCi zJtA-(c)*``rxXuC+ z2=KzfPBBS&5Ywk1Y6Jc#zqbC6G>j>-^~$mJ!h5c>I5fu8&#S5fap*WR+_hTRz%MHK^8-ktMYrrqjvQ>?#R>&UAR;H*RPL^VRHvVsha}uVJ%Ih z^X3DOG?Z5mJSf4pJz~-lSCoF$jOvMY%R6gL*hmj)q$ax;c+R6Iq?3*pDZZal(Y&gY ztW3}^4pIwkF|00MD&Y%>zXuxWf%(a8Cf7JM%{N@3<_c#q4PHH!*Hc&5+XqDZH%9gw z5nt|RGIMo!^V=TehY@y%(~NmK-#~Epg~LB&%-(B)X@@)Z0awCpumob%46N^&TojPc zl>C^v@&7xR`RF<^fboKb404+;wVU%fhb^D(gF2s&0;qlfNls8Pi7dQy4gt=1*ucB{ ziGaY*XOdFfNSTpEN9cT7p6-e&$}honk~Q}QLtaYm*n1SKRd;Z-1SzTUc$bEpnd6i3 z!D(4pv^wnCE$l%waj5(5uh0D1S!ftlU1YOxU+|n~W%y*G!;)+w_dPWoA~p`#YJUG8%UDxslqMkP+k2kd9sc>CV()dqlQ!EDKGe zpgPojn>OOg$tG$&W~yvjwFC+e41rp%f8HtT`ele5n0Xq)WHD9Ps4#87UX%a+0c}mT zs<)Qxk)Fmn{nrg^jkT#^%iDL`>Tnb3V-Xm{eZ+Rcui&eu+q@9q7zvpz!ok~I}~BXw%krOQJKl#YCtXA#_153M2GO;eMP+PGZi`wBr;qo2G&J+fjZE)OMB>^{XJy{AJTp>3kpk=LK5I zBf4h@=p&vAC=>)#8;f6ka4sMQw9T1Zx5*(Va>Sv-9ASuH5KMgVHH_riZFN^`YrL)A zxNrAtMtIFk&QV$Q!BiY*ZT;AldUZsjk3FRa3DZT&oeg7!+cf11omE#+D79%a24wC) z#`qEps6|srtyxk2o4!H6#}Br7I7n<+spDsJ&WH@+XcwX>#@+Te8~KzW`vIxWlMUT{ zWrVaY&5TsrY`2KZmXs6+rTnLWMD4h< zV1LEI?*Ucoa@YMX^vKWMG_=iW=68oJ>!+7-+*3by?iZC|Xqcbn)^VOe#&nwCkbooWA#(dV ztc_08!mHvJSYb|+N%&MZXgNqbKS@p)bkx%wo*5}M8w$6E=M-mvP*axLUss2{J-@iY zZLImf2V8d?V5uh{yOZ9Zf4J2lEuu#bQR^FHT)*1bH_8@FT~0KMH3aF{_BvFBV4#6uy<(SXDKlaM<=-oUe2)$-`D)=@6TD*wd$F%xQcO4PkNeuOc^y?) z$-?&1SL{l!)c_lU+<-pw+fle21|5q5Y7OzbcdSvLhW+c$B^9Ii3($l3kJhKRJ65zX z7t8M{#AU;L&UojXwad?Df!pM=Z`i}#j+3I%D%roDEFXcWi!~B%@RS88qkcPYUX0*x zUwhS2tyD>vin?-=Kju(9WG^hhUiQGiZn~KFu1teRJ;m0DLu)kWLs-FQ(X=Aj=ojzU zDdhox0u`bV|CV!A5JVKhGqpJfd&$_?6{PwsVS9`z;{Oil?X$lNZaeG6W26sL!0veM zGBLdzem)4#9U31H$Kq=Mwi+@s))WulgiSyIrZ_V_S3Z_bq11zo`Nzz-&8H&crjuYv zwyr$ogRd6r*RZ>HEt&e3lz|!_g~rD*%)1*^MM2BkE~!B={Q+$WrrErauBtTQQ}d2x zqREf@VKmXfKaL?`eX-D*QJnRBq&~bRso_j&G&|H9sK>SXg4kP|FFxm2{m@{+8ADVI zjkZ_z-kv3cm!m-DnXfH7?S&j!5>B$k8~i%+il`|ut2P%DcZ|-7pHFE7>DR#%hUQax z6C-jjWa>MkH>(l{_qI?j*S(J4ahMS|E+AbVkQwrywfFT(XC)ClA3VLw+aC*ofwEw_ zBlmafzkTKG-FcB{5fG2eJGj;E60IY2otIfdGjl>Mq|yj`+k{F<_Wwp_UTQg@Y>5W~ zImy9Vd}AHKHFKuh-YEFM*?ZF&=9}k|Qjj(|n`}c2c1EE2$OH;Ig}52U-^)Nv2H>l|>O}h<*S>pB^l1hi z`vs-*Uf8n7Y81wLmw#8CQBy9{KhdC;^vQYVL1Vj7VX;?f)HSPYRg^;NMQlwK_igWP z`NpKXy&YA9Q|zW9jCQuRedflR`N{(UC4Bfg-75=5k7BQ)(MQIsdXiUz^^DGL5H5Az zj5Kh}hE)lofEbGFaJw)!E2_T_RZdjQ)UndV0JtYOw+YkV7p439)2$(CIP+|3hG4Sy zciT0TrFgAJS0WXk$k~k_QzfrETu|LN3aQCGd-W^sT!&V^rzQ^zG&=JFd^Qvv`nkU4Pkfu#hNkui&4ID!Z z#=2q!X|xqfbl>pD<6E^Q;%cQ9b{gIM6|@Bmy0({Umt9u($l~MWO-rF1<-!-GSGa2E z_Up4uyj-SrXd#0t@S@wbr4&l^q2HbPkAG*67qpD1ORfV#9(cr-H zE$$&!e5(*Zay*9u=PpI}WNx9qd1oZr|TPIdB7pRfB$H>aC{ z2)DMn%_?IvclQxlOTS3tx~J~&jlnr{-L}H~zN@J0Jf5sM0pA@bV#nM0GpAVf-+T7y zWTDUb%1~$rjaq+)^?m}&KjT!D?);kmgSg^!mGoMl+&=!`3>iMs zEtP%wkc3myEmnD+mSnGSuE6Dp++_5<<>aN8D9sR_biDfS0JoB=OkS!dHb{=O25bSm136oD`VbIj>7Tj)PG>?NiM5%{HFy#3Joo_b(@`4_>LJ|jGyr4x=63;qI`hd0Qd8Bq~ zwCQ_`FWRxl0ac8nt=@@%bhXe5bHSD45D#sN?mN2rR^~qYf^Z-gX%91F%5}zXyA&IE zij9>GlI8g?B8>X{@#Seu=pD2lC{`e17M|3^& ze~|nd;tucBPR>x|YhUJFO8Uu@7!4%$wX@~(h;BnE*hiB#ECPoVeIdK6-!{1EH3a!Z z^yO@h+A@OplHBhSCJJd2Hk5=wYTxJVYP+(=&WaHZ%@jyF&l+Bl%>^awoj)N%{5tHm zMp6c^XS4_MH0EPxTk?qEWu@EDHY-crySxdfTC?qC%?|s3Pa7WZ9As@I`b2sA@CwdV zy_K6m8~qZIs|#^B=wVNRJSr3_;HgaQfCWQHoJmOD9jKddm^I|GNGhFEY(8st9rLxM zpl>ZtrwPKX?Tx zxSFjS@`7H^eDU;-Avjn3@vI}P!Sb>~NG`go;)2#z6(a0ofbN6q*2^b`cO%5sNg_fX z6*QaAdp3YN{J>>~PXuJ*p$rTk@$ z%Q>Apo~Qke3_B`CzZ=R-pt{A)PFyJ`cTo0RW4oM5V}q6(g}KF270|DTX8yfAu=wY- z8d%ob*9ufwE$ROk60U{gSQ6HtH3Ak<<&Fa&JFQFQy=a!wy}n?fsnpa=n@<8N}RbM4~)8KmD7bsw7d_3BY|>j9#7Fz10pxZ3Tc#!lcE;h%F(JyS6a?qe0jD3_p|DZvPB74WGM3L7fqtn zr?)q$9E3?5lM)R^4&U0AnCDzyL8O5#^FAHK=Vzl&Z*(r8&x8+s+dX>|HELqggHem4 zc_1r}Z2$F&4Sel2WHiCI)1@@XufD#1{|Ud{(PPN%H03Y%;LyJ9Wd9n1b304i-n8b9 zE#7QXP!7RYL5P|vO*ba}^f}_oyvCd;Knca3lN0ss#NG+#oY&3&p7TunE9%U4g;G8v zF~(8qaXZP|%MRj1RSt9^02a%1J=8D$y209Xd-NqO2oVIxRDco)9RR4-5H{DDah*g`Y8PBss&#&@r(nZTiJk@!0MmWju1 z_$>vfQba$D?VF$^%cKsDI&yNsh>U6WW1>t#R(f|o5E^f*2jiL*6v{3U@HVy22 zBhO3^&q6dNU8lD>L>U1s1NR}oMbC@B5dST4U^zz4nuPrsn)!jXhV1*}5GFxR`SYgoZU~Jh{W+MfdR${+=agl^O->CtLOg=E)j3 zlR8Q){me0hkm#+B6JMao4sTLE1Y$M_^sp0~Ui8r0p7q(H z@91>{R7P6rMAqmL6+PO@44e? zxA7W-hbpAA3uIL0m$FY$Ob341KGY38ERd?b5(oO;@E@WO)#`@C>!xXyYe7yM5k5V?NU z_6HBcXyMH}ZFfK_n&+>@O3FrR7@h=$g9@<>cD~^`2 zW9&LKr?rL{o4;)^FQFN+j7Goi&)_=+`7|O-!c5_b*Xg?L@{hOz1gcpqVnjVGZ~f6W z_hh+f({t4O(eWkft)oRaUmuZssF?JzE)sS-oR@`6#R+^*(c$Q5=I2*e8&5`JL2 zaa@Fp?d+UR1mxZq)PV`o899A10fwfX^@i%W*{`b0nryef}dmB3k1rpq{)FQO+o}fG7vaB6GlNPH6 z#AnPKI8K~u%?rKh%0b2i>=!^$20^8!(jpuV`h0XAyWN#G4wRKhR4go3z-fZZC!5AZ zn=Md8^@GsTrg2odoqBm4s=izNwy1fNK*2G+N(<|Gu`@-u3=I>xr4n`wAsjt_LpgCa z4Mo&aTEwZ+xMnSY7z-A_s0-aC40@uJH-6fp5?4HLw6j`9ZvXk(?QDo*=&87`VD((i zUrL9JTo0fnV>O} z81Qwxqp{NRu!tykxC;7BaqGg0K637Kvg)tF`2j-jE9y2X1HY2GrT3j+5Tt!wdZs^~ zM2EriU7y}-`z)X85VVxH+jy$Q&O&0oj`6thHv+P zP2tFa|8K$Hd?N4A$zK#W2UGUmBKBah{L^~va>Ep4n8RqzT;?0Q`w_bgE=;Tli|4>; zvd4vVAbSKwoO&W9mk3~ky8Ny?!?`vNyYS%g(mJYP1JTjqKlooT4hOuAlA#nCeE05a zn0Ug(S^85)9ZS`+tOZ$Xro_VKJ!lhbG~ut%Vg{ooosp6P|EU&_&rl8c@sS#xi8@(B zb=@{a_#XxCHNN~~Mgu-}*&5p6o_Y$6S9a(Wv1%xku;64hf5a8-As*Uno_;aYx0VKu zDK@3(ch=~k7SrgV@TPrRq*(ex5ku7zGYnI5X%yt?Thev|9_!h4 zABlJET9?K_JpQ_|AFKZfmU_;;?KdNUnB!{u%rMEiElnXZnto@IjX?Tn-@C0u9ht5$`U7C|xRK zP2~;{`yg4!d(Aa2kMhTZcs;}R0XBn~ME#=vhsH*O6K~FOGoD{svicIm{^;equo#hU zr!UQh`3!o>O5kgG`Y33cgKKCsASIv2f|b++m5E>0vWyc`0+1JU9kZpbQ>*-)C1-jD zBihf^-$+#)@RNB@QAk7Xi+3gGzI3>4`l6mTGi;HbC|D2elB(uc&L53TRi$&iynuDk zy~%V|>)0+Hg)hRx>+ZU>a#Y6(RtO+16;z)U1Qo6pM+C*3!)_*p+F?aQ<6|kfDdl;x zRbnmv%+vCt^56ZA3y$|gbYGI}dCsPGK1u6Pg$;A{mzuRCr=71 zdQV=lzp70CvfRw8aPg!c5i0?mdEwH(Rdbny*>jz!cZXV{y-tkU?f<65?fJXh#Fa-y z+1AMk0^G_P+q5g>*ERE7AeD7{(x0m6+LpSULpHD+kW>spK|lzy?nDCnpg%p*RBqM2`WypD}_M_g=7== zK1Y2l;yIsluT3!a&#<#^e(W3xLpdbbDu(=G*mTm4o7Nthvv4|r88hJlt z4TzC;oUX2JU6j(%zgyb{cmEi($wnHn=4h%Kdl3U%AWe3R|j*GFVW9r@p_O zi(90wA6v8o5+3BW4$nWs^k@e^5$NPry`-jmLs%60*WednJJPZGB{qScsJ~V=1Vjcn z*Zm!g)qVNieWLQ{!SpB%toM*Q^KMpB`w?@RKB#^mXO%h0eh$UmQOB-iSc+jHzo6oW zZ0m%YcF!zoZElYk^xZcB>>&U^nJ`9wISH842)F_TIU|ff)5jNDIH_xM`|B`oYo-6t zHDt%E)X-=&YU`QqpZ==PBd`! z&+k+2Fdj06dX=H<<`F;AXM)m9c*;gYB;V3O0mVI)R?O-CO0g}2OW9tx^IU+%8xZt? zZiPK8K#1G+1-UMB8H=kr&W6m5nOvsfN1o#KfNEyT^<&{Xmjd@Ro7C#m7TL0my}g;u znhUQ7e6p8}Q3Dtrj+RT?jQ;=tT&pc3bTz_g1AQ{Y)-r4&R`f3r_VJMyy#K^w2@FF_ zkV5pIE$0XSF)Jy3e1IIQ;kIIeh$ain0@nugm@eg0#H z@(B4iRQA`>m`tba+J?$A29=dB%DFD1cBg8``DF+-+lI2L(;C^T120UTKQKt z?YLmI$zN;_NF(g16+ESWl*HYQA-NTkhv8k9nc5qvu6X6a(Ffa9V@&X=5c*SJJe-3Y zYIx*WKtDqIRE7D|w40BU&t z@F$cZry1SLy#XOWu7&K?!sdAzf%ux+vY(y^q@%lLJ`25>3!+F=Mh9|qo}2pdhc+Pn zSUQPnp&!oiN}m8_^2AI**p}^027S4W0&8goNr)nO{|B&}v^Cjru{YQ)7Q`8HFekQWQU8VH9{@k6r3+BR{fAX|YPzCi$Essqo1>MZO}MksG9(#_#w4l*{${@0FCGQXMHrzY!ZKNuq7|J> zDKNzioLbF42gS9p&yV-l%FXH_rIHVe(f#=6#jT@rRyT*sS530(-=onZ*DE!1*~?$% zOcNnNC&ElI$`7nKg$=}XYvmJgB2wLro@Oa zF9fs@aG2$o&rNHyRRFo9q`)YG<@;bcw1tyCOoReT{4wCe*_GzNRI%3139#|&9E+^e z+wWtST~p61oUPZ#koJ_1${YQ84pG*OXO@33-;7oBX(f=17Sc5=PksAY5=@pU@_8EK z7nJXD$(#U<5?981rr{j6F@gsG5a_3PtF?z#sa{w4!dr-OvY@_~91iF~FMcssCzO>)2YL{RV>JSATM872wbEAc_X{nksY#oue5FPakSC%o=k#q>j35MvvX%K(MCoFYL}ZlzByOCP|ob)6zc zQ!L^OivK~O{OYl^Ixepg%XuC)y57M&tj1TH>}v0sHdXU1Th&OBg^!8{D7n^fuk{k1 zkOd>2%Om$ch^Y-Bb?%uuMi15g5w;-mL7f!Cj@wX76r~2VmMy3EaM{0=X*-)Od%Ci5 z{~8<+oDWm$7JojPI9nmNPSoiG^U-HrnM_8Eh+rf_GR)%|>$_Z?Z`zIh)IvW$`Bdz^ zZ>2j78UgsxKGZ*4h>Qc>N`j@sQ$r*eGmWNF9t^B=+Td_s?pt&HP28l$5V!~=#cR|i zh2*x3Z`e67r_gG$Z0Xcvvd-syPK_?oH86{??x2NgxI%|lQi~f5uKp4w#a$Z9zaU&K z^vt+>tXoN;{&Y62LTYsD$CJsIFU*S#57oOu5eG55nbhaXRcP^kd%xGxNFqP{gHz_F zn;uYLg?TOJ2ve~-2d_rTbH zU~lJTIpub%Se$b}A@x2mbnub`eVRmu26fP*74T8jeWdm*f6FKA77P3& z&og|-+>G6JG};-BZn9;RI@mIT_c(xGjv_{l#>5sMj`TkBSIu2J{+Zwj@=1!5Z7gmi z7cc1rzi;TFwu(OeK~J!#91?ZUk;*P&>CB%;=rM945p{UINA8%G8g86sSHZ|#OfkYN z6&sbd?DWbi9P%VJrj+9&)PpvM+j3&ioMgHl*k)VCEIK9iev!ibF$IDf2AnE7@baHO z&T4`ZO1!VlH~UUo5vAFEpi4-xd3C6qGVvoBNtBYogt@IKuhJF;9}+%^XBS;?ccAQ+ zb9e0V2c9CNHB>GvhW0J8p5}M^#|jm5NunseaZ;!TkN-pvH zKVb+d2kAC{@>9vRk*^9kdNsA){X5u)R}hiVxK^pFufMiF54$Vle`mYZKifZ4EBmTAU#-;q1uXXa@{y(bTJ08pa{R2iwC|5>=tSDrbmFy78 z%w>;o%ieqM?8wf{mKj21M7Hd48KKA~*_-FMy6^Ard7gjoUS2on`8kizalDWB7+p@m zJnkd)xcBUa_Ei1;Y5ZPOp>lp9tLjE?;t;nvqW0D#e#E}?Jshm8f>GDmTPq088*#>F zo@){aY)rJNGTP)39Jvh3{}D`6Nob3AFnWHeQrIzarm&E+Cx)%(FQrJ=jU!h~&O|uR zeY@p4apb$gh>9l`@)WORSmc*Ee6Qg>q3CFMMTZAViLQU_iE|JIe||rbHNGc*b1OXPe``>A{T*l>A(^Ua*5v5@Ryq{002zJr{@$yogxj+nm#voI>>Y$x8HRG_(W7m7~hNH9JuLN4a$hSoAak3nQIP$+ox1z@tWjVRw+^`*Q%kryIx^hVKd6VwBnVLsmZgqfjrf2_GBCPE6!DKf1 zE#W3_-3Fid_vg-WkADPxDh*%zwCgSm1**#`y@Rq<;vGb!`n4Z*`>B%#_dE@q8CLbt zr{`cYq(^k^dlXdVbrJy9l4cEV>fhep##2yStgM`xBL8=^<$}Q)?#Opli*s{x zPsn}$`v5e&y#f36@o8GQZswC%S!^rRe=@yVF&qUR(l98O;LN;4hn0ZPHl??q5Fc1e zv$IRh0ha>}#(7LVZ=EbINV3IND;=@^I9H;-BJ8hVtOXe9qfnimvyX_ zKDL+^7%Hl>ON`#0q)=aqUaLDy2MGY!qUOZqXv$IFWlJQO<9Q$8Hg4uu=CFHfZ}d@z zI6rKxEfW19*CtI$k(jNH#O-UNoiOgZ}J&3Wifn5vm&H z`hm{CohA?P@_KcOz1$bfGco$SI}}Y08x;_V*3fe7$tL8XK)H4;vaC z_1bz*<=K-MD=Wnt>-Mg{eU-fz?$w`<`uza~SXc}*;h>g-^FBzh-xunNmyF{b)lC1M z+Wb;#Btep8qB+UK4bIR)!%jN$ShM5m;71@NkTc93sh0~0U14#=W&4fbXukFkkL3$y zX2e`B+tbMnKDm3qZ`b#F=S|1J-I00Rfq$gK@Cx;K%c4vZe z0Q^Anr)&DbXF5EP-l1_~aHO_oheC4*iVjpB@u^isAs?(|h58|KjEj(}!x4c^O-;?S z8lejWfHKrPP!gzytVk@?kW$IH5wEf{Z1SzIm+;09!P&&(eAh{EdO~yUnjs4`0Bk*= zB&c9RFhvtco>iA(>37&clNhPj>XbGat~WM%4*flU6FC*j@ykE#d_$Y+xO3`>HWF)A z{YPrJO*w}D2PLK#%HZK-lB^^*@cZUt|-s$67#zWpt@kj@dmc*|7Cj@Vyi{|_Y+hRwb}1?tv|NH z5DQ|YGq+~wVIKiT%9&?M_7X%?vjs!^asx~5;5 zVp_Y0zvwVr_QOi=>R$m-&zda+T%yOL^FP6&Fo(__Z}$K1;iCZ7+XBJ{lrGSu^96t4 z`Sim7IZ3i!8R@j6VbfDU;UGsGH;Lr?ffpJjZkmNS7-)jl(ki9?<)u(}L=sEW4Kf3x z)uzGyV9AiTIlA?!bT-%$4xx0zioYmdOXuSF1ASm}9;j&LB2BcO(v3tv)>Nx%%;oB3 z)m7&Ix@$|Ff8}EhFT48Xukjdew=tSxYVpOw_bf^qpIO!`@Do_qJ9m_81ke1CmHknR zT^hbr2bN;@U$bS}X9^%p1I|GQR_xy#}@(FW^X8V;&NI0~n)>2~=j}QfHPh|14kz zLl$)JTA zg^Skt0nFIe%XA*ZcU_`e4r{}+xJH-d-mYDrtlF70?Z49EOGo&}vuw*Z(O4?^rIT$v zepDM7Q`f7)pwXShH7Dmsn$Da}+Ehc9HP^JWnScHH5e;(W=M4=>4=AHHEsX7$HH;vgS~3jjx?hwcV=CKeizdqU6gHzcO;w@GISqqaE^p z%w7%Ecye_3US9Q+_$DuN&ML_et;lq&k-cd#k}2(d?|R#@6D*>B~61z$fFkq}dk1KX;_aZ5$~;_;Dg%il}x>z^s3jq+lIIQWR z<=c_e*1@f5^8J`P)2Gt+-^&WaRvgWX zPX2bSeQ;|7TP%|~Oq#?54HH3us-*%?9^fCK?SWvt(yr4F&wVe67ViOlL0fMZw(xMJ zAMQ`tY^oxilk;HUg-herS{+!GqnBaS9boi=2Q&DyJD&R!CUCMy@KA3H;z02L3j|mK ze10D}K$*)U^?qXQz?SHiB$dCh??9Fr4P^(nl%`VrsG!&rx*$d{VVUi)W0W%!vUwyq zD`|P^!_GbHdd?fLwJ~s17vQ;LkS%TpUeSPfqoqan@uS-e!J8I*GEm6xb#7^D__|TE z???GClqs$U{k-U(N!gW&$uV<}3R$-P{5hDj{2ytKcx|#G_q@+0W{4LKlu0-BUSa!* z{ON1@;-Pm$?mC}_O>`-S;tx0s$@mUqe@=Oh)U1_y`A;!TV^VENT__$=R^D%#lNjYU z>GX;%L%qEtBa)*dY~S^cc8@~lDae>XhREDgVYcYz?P(Gf61?e=d@+sXr&3&W5J2|= zyagaRb0(0R+@lw#3_K8qt5RL{?B#Dvascx8Pr z)t?lzJjL_6))$9wm0g!YH~f#rUzFZ#EtjNDSF0$ax@=Jb3}gXWCGi1;R-yGfJ3j+E zKw;)B2OfZY!b)oJj`YU;38T>eQ7FCUjdjh`jfXS!Zo`iTg_o2JD7%r#(6#B!U_vno|4;^ z#&gU)YdfmDUZ8P-Do~@zw{)Y9!W~?iGuL8~%T9rIWqsrK;D+P-?wIWP+t7Y!mL!ZE zb4S{yY~3^(kk8i1B~@X8Pyizyv{`Y7-IS6`t&Yf@@A~|>P8S~I)91_1wI?~zc=Rw~ zcsD`b)xuEjQ-C0HVm3T%HrDm;X$K-on@xv>obNxR57WukIA|p86w6ZTl=~=tT4(TQ zaF9Ou$rI6I$s}fMLk=#~w0qn7Q6EjT3)8lT>>ej;L8_51O@CAY=g{rAfx2W(`lIynR;7ufoP)gf>zn`S{D8(gGb zCa5c`o9T2_K13*^AM_tK?j(BG2*xN8VG5JE8BQ!;{l&1cu_K+Nz{AKb{j>Q-B~eWR z+f&`0Q7+5W$s6?8ZjBOD)6^t4$md1$rtSOQoPUg{>dK?NT09N@MF46ia_AbK4Dn4{ z6R|KtTNsO$Ku2T=SWO<;ejThzIc3wbh!`_1dA~+k%tVM)*FdA0|J58lnx&@5xP5xF zJe+J^O2#k2(_9_1>v6U}LTACws#NfD4mUL!vMDNften`_3Y{$2jkDRbf`3^MH4ul1 zvHZh&-PudcZy3t4tY&;_{VO9)8Ncc3kX+Z_h+CJ6u~#pLoTWwdnLvLFG*L@d|2R0r{?u567uh^Sl@|^yb7rHJYSO5jsxBxio!^vL=E<6fXYbVfqg5?f-t-1IFhv}Q{T=7 zf)oV3w!-_E-5t;;4zI!upbJ+KY#?;LDt_yo`KVykT3ueDT=({_Jq)aPo5-lmFGA$dVFva8p4dVPLeS-yls# z1ye>!XKb#o|C#aFOxwx41Wz3NZNB{c`LlmDTud_o(hBU>#@I37r$Fac@>E-)gr13t ziV7kss_Bmf2kMnhn(N-F_wZ+MiuKT!oV@e}JB(hwqWHRrA z9d#N1C5aHe$K?N@@_Pk`8QUm&dbLGAQl`^hy)-BJf}hQ~hk@uTOv2;1>hsVhIbTq&_A<_;9JoL_3*5qhnX%g!%`M&5#{Yg5CWrdNc=kcGj}aE(dsz`3DEq_L3qxe!0ykJWKT|b$YS6 zA0;U_$X9SH@|C5vH8=IO(5&SMe<`|L^Lqu^T!uW9!b6Ea*nmFGox-ip#-&9ft^Bz@ z+MiCfKu|2{xyz#gQ|omLi*~c%8w`3vlKOS?t>Cy?p>*X}!>|*D5lGj74N3io=-i$7 zF&$p=%VsT$mz8flBL6KQS@@UDvTG1beoKlONI5a+pHh4=eEY(x1a#|lJ%pSK!l{7WE0BBh{w>#C{`hVm`A8&Pz%tlq+Syc+J|MCrdPIW zOf7zm56`j_qpQ>)&yugvckLe?^sevxm)@%!XDo<3p`?OV5sL;W0>URvP8qX-lo|gq8$) z+dBCH0;L2T*%%-$X_d%;wdrms)zVNW1Onld{N3A?P4;#^0AapVJUfkw|F694;FZk4m&k-3y|!U$4IcNDzok{L~PpO5mg z;zdim;8ooT<03%#iN)p1C5o|B^YKIf568Hh*3Ix)>Zhflrjdg8{^W<_hz_hheoVf~ zBqG9N+K~{Jkk7>BwjC%?9|DHd+O>k65RD%$j@PxgcxSVI=UR=;>`Rf16Q5=D3)p#L zEF21CQx5Cr?*F?GQi1V^h7o;_zbA&z_-f@>px`9^dN5a& zDsq9f8&a}9rEuITdc+TQs1_^-(-7Y%lGYT8?%8Xi%gE-o6#b>tXg~4 z>SSllzKpWaYiw}Ck74kG;I?`DTRCGq{4v+7uK$SE|iIE%YGg?FrA|BoXj4s@@MRGo4dJktYb_W;w`5CL6Z%t|!``I)d zf&2E+UYU=4)2xw$MflpLt_du&k&uw8zXlrska1M6CfqfMXr_EzHVZl=;#Yl&q8Ys~ z%4acy#ft*HgLUf|1WCve#|Succ$Acz^br=2^D4!-e=24IYOTl>x@!8u~B!2bxrmTP}dfMxANaekkaT*4l{g9Q8F}^Ge zFO~fwmwvQIQUN-0F`lxFzEk>*G=rBxZ5>H8D2yI6wp=*`M8pn+UW0`3N#V;9r`PK> zQt$K=nBW6koOYQt762NIY&Oe7CmrvdJ$_#TF-2fpKHNEMm=-2am*x-x6+Z$s z@_B+c#H6u0>PZC7DiQvU&*kN)tJTj*PE#=4*fQ-m69LBoFLpQ~S49IqU>kgCZ^uP{ z3P@yCq_jS&HU971{ev|DJoqQiscm{@`~Q7aLZamG>_YE}?YX8)(&aiPzYdnzg-v4R zL1r0vmx3A3`MC%n-5ioO=IH<*a8V%c+EEdTerq^6m|R0|t1!O)j6Rt4p!IE-*5%M| zB>V#VMtl1qH5T>+0`l&R)Q`yawIuYWQ-K)ZBy*kX{R=aG4S9#`{Az-sy zr?i^5cKD^5WzQ zHC0M2oNl)Y+0X9KUBe!{pm=j}aBo$SwN=>fkSJ@f^wM{bUiu7}KvWhNKDP$;4JK@W zrGaSx!HO`S|Dmr#zcRghAP1bD)&-I4?W>*teO^MMUO92Vw#sAP&mW#2*cqNH7ff^t zIe)(Ge!>08>x2&``LwjOJFX&D$ceSRWyeR~@+z0KP?mi22l}TpzGaQ)-AAK--esWP zG;KglB~~9Tf7J)L3DM%#tf-)qcGBhO{+m~Wt)IV0>v9kVa3H=D+EkR6Hv0UmIAi&IVMYc(zUIHCFsBJ zb_v#(7RF>}-#-7ndHz~ot?3t3AR`Zx6uqVnfGR#Yob){(Ww#iMMV@&#U7bd4J}lu4 zUuco{R0W&FyO5fe@N&a$hs%17;T>wz!PPNDXonuC-+{00vna>6m@^lJdB#I*7NJBn zr|#T&fLG!1L&^wgr3++agC*jL{|_Ic!Hb-BXZCGikZUoh<)4V1({XF#o)JVIYl&~I z=ett>yr5ROkdi+uV;w=Q>V$}-^ujN7t-(49ZIdDp$~}hs@|6CQ`yQ(S#rBWpfNF!% zzu#h6cwH$N-|znWo}r53fEw}WRaW|4;$kYzUDW<(wg%rZ;)31kX3cfVlKq8fqeSVGR zBk+ufrIa6)Z{;9v(Gfm|AL*E%-)9SQ;<72pR zD|s{%$%k%Xfom0rSl6A&p4~Jmk*3$K>OpTY8;@6uGW2dE(HGjOrL9j#F4%_j2QU9u zHpvmWXfwmYLilrR+y&Azn45S`i|`e7o1KvGgE8G1_DKs49~bGySqpKf=Br~$A*gQe-)Rb%YEwf~>J)N5UDv&ix`w?m+c-#!|EU`UZ8c{G@NDiPxeIGVm z5*JOS8R~IoRQ3lu08TutAih@%<`c&`L9qL~662ebf=EVWUxoJU>Hvzq!s^oIU8Y6O zb+h_ofQiYVsZpSmo%{kBIl&+1<8dtT& zB{MvLxmA<@jbQ{Xn+l%$G)Ix=UMpA$YwzC0J-ZiKe^0sTc_*iC2zyiPc=?z0o6%n$ zv%0<^SpOzLUR)kB*B0Q&eVs$5>7Vx(c9A02LoUl_L(RpS{p?a!vaNs8lk9LMWIhQ@ z&s+ECHA+rJ1JSR+jUCMEVH@w#bdvV}_8xR9asY$0Q(PRRE`?&JDJ;oH{k$uczJvyE zR)&~bxFqpI%VG1}0YMaB2cxsUW}}?lJ0_yf{`~n9KgJXY%cu`f>P)#Ti;{EWu$3_! zK2Q^PPA_fa`BsU7w84m*-}RAXfGRsv_OZ-j+q zT*#L5N0&70@|?em7@9p?6ZhHP5ng>Nx@jtUwLdowj~)~h@GF?|m?Qbn&^9DD>s;fg zbTSL~5jyNx)^gZc>~$!-WqaZ_eR}`({QiCgTS{JH6yJVCEJgSNK(R$acjbp2Om3%6 zGvt5c2H!Mre(}Kdueu=@EuHm*Qu$_1ybKd}P$n}z4B@B^`}@Lf_0_We=R1^VZ>5W| zo13m84*G(R3>lP2_B!Xs4!Yu7Jzu5{pUym0%f6ty9!$??S~z!6NqHnHRk~8*l;1yF z?-pxa*7HKZHgY=oB2LB9(h?1m0bYdG1^jqq=>cQa(i7ve8Z~$&hlk@nE8BnZH@L;T z^9tbA{n~*N=D=@Wa&){_HUZ|xRay<1nGH7s5fnz_GczJ2dXsz~N$~(;=Zr9!Kqf6c z%fCw<74=Yr#=+6Eb?Y#xdkpV(CifdsV?XY^t3y>|z5nrAmm$PHxS9FiBxSyzJsW>{9!v2Obv*sgLwhWwWXAWloK5bpAWsz4Vs!L zX-m(LiI!9O^$&ZbYvlq*m;k{(036X}SX(K5U0k!&&Z-P_bu-uu<<@weC3!)9SZyS+g304B@)v!3&}lK)quVAlbCj|5Ab zc@<G!JhfZ)52oyd!&|yHQ0HBRkzeuj4mc8^IH2`a8S=Nn>;MSWUDai zJNnv7%kj+{CPP$J5i94@uslptO#!AzLLBkJ&a7)r8>x$Of@hE~kj;xkW)vz!&<$Yv z*&{dB!kpA2t@~ZS(b8sR6b|`BAkOR}pY+?DOk`L;voP)fH)~NT6 zEnJqDcK7x{lnMCBz0t4CIc!e>>;}cZz-tgwKxlJTL0YED1~47h!qta8TwNIqZtjfX$^p)79vPY$r^Hr53JtfSZ5_0X@lS6X*ZE0D;#K8$t;X zv%URxh}oBUOuRn9n*NGX4(}-t6@UXHfc7x`NAO9@KYs?e=n`uz=k_@yXA5d_*YeN< z;`WW{!;NfSV@<@X(m~T(Z7`om;8|LiS1~Q)YFv@%R%5cKOvG%`G7Rsh8>*#FuGs zB;>rc;Hn;*E7m=+o?Dohx|<86D6X`0rC(A-PRfc&j?pUDUtJfc;JfBA@teAqc)2uF zjd!$lMNi@jPwYLgsOY*6?ceXQWyPz3{|cL~NYV|c zXXl>6ovJLjy%)hNWYqLMnhtB#N6ScLB;;o2EQ=&Pd^%?*Csv{Xf3}UubBqwo6>Rf> z0Hf853-&8ik!bX6=?Og^)?bdDt8vobW(v9|ru##%S83D9igN;T| zt@Ux@-R!D%EdYT#xaEW&26CjdXVr-aTVUAw9U~-JqaW04gj9vywb>8Ispjpu@RZs! z2u;Fo@wvsY`82=I=ZYjf;;CP)^#?DMhANGa58XxUULQ`g58i-}a<(W}r%|YY9ddQ; zN;vqM$HEeFcKy;|p)MdT&~W~XvXn)rgh7SIHX?)}7fin!s(kp-^&B3q4iM_EH68WZ zfX)(@xQ$Nc7X3T)8LFX;Vfx^bb_bpDC7DQ(S~@OKC0?gqLmHlgc9C@oU|0 z5S{7b6~N6hTnNuI~27uBG?G z)aj(}GLEEDqx$+qhmdKXd)%zTRl3jO!Wd;I#>amE*a$ch|4)|?b4TI+0Pa_R9b>(E z1I{kT8B5im76OQ7O$4alRlO8UtHwN@Z&DRK3wKVaeU)=}c!flfsAfzMCn}~u%z(z7 z#)7^2!}xc;pS4nQvN4R<20vI)pScb%d-+=h)!)8y?&T|xQ0lhSla)3mH4`80dsLNo zo=E1rM)oxbzx9pSd4q(i(!~zGd;U~m)#Cof6r_NMuQ-Nr<62Ei;WeXYZ~)=as$RUW ze@5Hq{;s|$>9Mm1@#wMt9?99>|4N1EYwaFV$Roo7=av61A<==ryUgQ%rT1+3moh%t}Xi z8{RgIkI=94@$pT3|DJ+@WlQ=)r~ZOY|=OLZYY=Du2ke-zoW&vr~ZmeiBq+y*lzM6>*aU@&W}OX1Ci z#qGJ0Hjx$6gZO53aDrP?*Q9&SJZO}BZPfC{ex{_ zZv^ae2fyhla9}Y37Hwr^faHsm7h`66d=s?m4z9L`dBI0=_&)Sg@6lU=<7RWv8@PHI9KL4dk}s-J{u5 zuqhlt%}VJ$?_Cs>cRiQsI-bC|@C>2B#)KhF{;@uBN|Ba|vu%sZ>^eg~uE*mJIL`ttYyjTM7ce z&2x9~35abx&*#rSul%=GI+`!kmL2GCy z$e`1{*72m|Er#o1fG*ykTKm%#kyDEjZfT=($ULhiG-N@<`^pgODu&EqSE;hmvUSbH z)s^Z$rJytS6SzKZwZ=NcskzP+UVv@5XI~b~oaQpEcYmBF+VAvyxAGerxdJ!phIEHU zJQuAiek!nNhfZhb=(Oabcn1xqhQmKYI3Z96;a8g9Lbq+uL;pSF#5wPupTCyA{rh|E z{6*=G(Dl9k^9j+D({&jA{NW)t*dHD^h*^NMKVU{JT#i5gA(>;%We$(oY&`ibPqY(X z{=RM9bVTKPa`bpBho$t3$em|TSyKK?;Cxi3zApX7A(B8GSu35aMYUST(C=^~Txv?A zl1*+Y-+GL!!>+O~xM5{2Y`X)esQRoN8jAyn=baPCL#+*M62Tk^Ej8FDo3|fVVAiQ9 zB*KbNa}4u4qa1pvA)ZdYtTnvh2oXR6uYo-!MKaKM>d__tYsAT`-RJypL*w#~iY*kC zmDZCw5mA1 z0r$|n>|Vh(IkA4jnyamJFR|Wyp6AhDXjOieoR_+BK^OE0H{eTJ1jIuoOP6|&{iR*> z=lu=Ob!wltn|ktZ4-wVjumy)3?iTdQ1m+Xq@UPIjd1nb_IRHUs=^+{iYw$>PnQ;qN zsF|8cWV`~h7cP9=FJ>IJht(J-+8TOV_Y;hUzQzH}C`ngfz9dcF!i(q~A}yApt=Gbw8s5zVH&X)p=QeeBOn}9{nJ6opt0D19i|p z#=&mol9W=(#v{lTy}M*e6L)zZd-1k*9}T|8zV zATNk-Aw?%LZ%oysbj9nDBtK=trDs$x)02|x0>BXsW#0Pqw@=mqpKqAC!D}RqXyAXF z009`&Dz$n+#R!!&!2S-znhL`ouXs;av*v1{9FsPQim&hpn@06=9Z~P`AfIW?SmOOqXoF>oj_FTrP(L!l^P8 z7~p|GP|FIotR<_zjH`fcwF3)(_x>P+)t;v^sbbn&o^~ZtsVQH+*G4gn;y9Qf8>}l$ zk`%CHhyq3 z%ip)nQd$|xOE0T_15H&Z&Q#3+j+-JwSl)eMj59^^Z@lw*2eq!{ud;DlRp^@3lcK72 zN)&Mn=|400wjF?i&adFr|mr25Cok zs2e_wj~kK@gfe}=G)s-JlFFDM&HByu9kY>j$U*C*@sb<(&VfM`L68J1#=kMy+u~b z0z2!PR&jdNs&UTqm4#nGL!G;g^Zz7TPkaTw%52saS|_)*MT z;xB!b)c$D;2Dt|3_le80NfjEU%-uu0QDpCuo%)t`P%c7`vhme42TE6%vDV2hy=}Ym z;_?k;Jn{r6_=VMy8w1!>p!D&8(ZU+8UPK1XF)VWh zHE}-`KWBx8-a5~`mQG)H-Q02Kb+g`s4_CTmBSuQMKcm(RBg{tVOSjzw(_l#pb}x4b zFB!f?bcMJp89fbWx1u_(p4kQuR-F$7{zu<~lFgFS>{7$khO<<~5Oq)Urwn);X)U2o z=8>QJacW%Dhw87nHqft@VNsGc)nJ#=WIEinVBZA=2o~xJ34^qRwi)($iujxc zZ$D7u%ym5R=Chh!kD5v!Wz8?;l@N=@w#8W=V7P|kY&}@j-kLD(oYYTFYAj13ZE0gY z)TQ!qETSV;jbz8@wml|Jl0F4_9H-7`Z9RJ?Vq7=;D45cXPOtRmGJef#pLfbl1mBNS zqAKbNR~!Xl+^svCSl<;Z-2aAI1DO%5|2D>e3^DZFhk$ZW1A5Pm{@Y?KVL?Ou6{1pI zet(B>6cyxX3Qf$?-R|28V95ug-Y#om@F%CW8}O&Yd&ogh_~zYQ94%6R3(+yMb>d}D%u!H5=OnEGM$=&qc#XYZ(VJTPx+HHCJyMM&)JjYj73SE81%rS+( z@AP1RISka|SA;R@t=pHSCtv*oN`#DcjHLVcXz!G1r%PU>WQ(k;et7{>z zt3Kis`3$=mxH|aXyuv5=HH-$SC~FA@S>ZI&tBNJ$Ns41g1Aj`E8p6tGy%^+a;GWU8Dg6ElA^#Z1J#G?qZS00v9ZkQ?8(b5 z_0)UKoZQ(zOyQp8Q|^@7#j4%y_db(iN8Ix(z+QZQmAC+VTdX=#qbCb84Ca{cL`Y!d z)8YH89c5Knr*!=#P*pC*DvHqe-1ojXnT=hl6}9-UM}`9olj+QiUQu=9a^cJVwRs&T zcU@Ft*5VZ?W9{>3Q#sg$A#m}qZ#+%Tvl2V5Bcv-Q^UyujJ0>i4Ehk}p6y!H3T4nM zW~P(_i^!_QRCh+1OOj?R;bfyFg!lZ1rOU*{7>JMee2Y;AZZ7!AOv z@Znn??>&^Qka}r(!O_5r`vHPVQM%t=z9_qC`7#sB?iXdYNRhq%H=J#c(Bl*gkI@(2 z+1KxK$Yk^{jW|uGM^j-B#EW30~5!(zn!J00vPM)8E*s75MYJ&q`tBiOlyQ5 z_}@OlRqwj`VG;~ZUUydASeGO~k+Il>5DJ3U2uN%|?+G*rK@b-cjK%O62vFL4I(lY) z<>S8b!GC)`Y?R@yZtm`JgY@hW4?#Q-RzCDvjSZc+S zx(UM2_c|g2?w#vTr*^w%x)wLWnZ#`yC1!UCsnxJu>{olS-pawPGqn+8d~=JLzA=to z8Y{2G>2?)e0LF6^b1nq-q3s^$w^ER#U9^mbqOG3hAKtg=@E357IIP&TK0}<_(C_IZ zm-Q{a`RHCh=cM0GVC;85gXmx$HMIfFO+ksY;T5HlJQhOT_+#4hKbN5+w3yLCw_&Go zz+#FLJx`*;tN-2e-$*y_)+0ckrT+_mRTTGc*!+mOcn;36YBo{u;~B35-MqWQ1h=w` zFmV7hstPGjuE|*XVxGTdDdkq$R|=X^DCoIgP!d&_FEHR?&G~p6qj6m|oe_ z1Sgpo3VKE@6mSY01wkd==;&+xvDpxQ34zxDr(4z6I_q%W2yefsSCdHF%=AN{&BvOqnWh#=}G#(Cj>nI-Oi7(D#QC=DFXJj6P9DFx;akr(jE=y9g640^nsO6|Ak*I|mH__&pwZ?;J3CQXm!$EQ#Z=?oxuGZUZ` zad0g$x;0qn6iC{t{C)M|m-hl=GzU(V15Tr-QT?%B4+{&yXyW^)Ep`dK8MmcdKq-eA zox=&~Fy9_YZvM-y5EaT&6eBpA)GB6m#Zl&tp|nBgYu{F_z_BEue8R`uf^8%Iawvs) z1{{i|AoX_OGT#+x;iBVA7fw%<`i9f`Vust6)-~1pd#YXLU9mAXTHgY(ndoTIhf3r` zjH?GPX08sKm*$qk$**+xAHI_<$LHtKVqOK51>At<6^+0zT2rqU*QTI>l*N&VHfB-&sl;H&rU7Cvb9wivaitUNg|w&ih5;L@BDp>W8d`K zuZjnCGIkwsm*d~uW35*AieYBJ^)K`&3@A(ZozlMWYp7 zCHjxrZ#iIp>UqAH0VkFp8#aAhn^dhj0*dZTKUg@+PZfwSh`5h@5}#k(z8XY#n1X?y z6mj?TZ1zH!RY|AGJ1ue$ms#9*=lEXkCs-DNum$X)r$4*sXJd7utAr@>Us5Ek_hIw@ z=LPib5A4it3HM8!E$E*wEUoE7(}VUOUtV6mdTk|NQ5VI*MH`8bc)_KSssa%G1L3!N z>*mNyhO93zoK3kezk(38ggh(XTg;)+Sy!ubRhU`2!eQN}TREx_TtI$*lA@e@T#Ple z%342dxEfFV9qG;yH9a;E7mOkZy5n0Y9+#oAhgZOi%tKg~M16EdwKkyW5DbMk7WVkv zz0NVtPB#)@<6FHd^4bV&_xh;$6^RBiAKs=@8`(rL-p>_X8{Q=BEY6Kx%IU2ei`2mk z6Ughnzsi%Xr)jULa+&vj;)t6#Gnp)PcGZ-PlxDqiP-p=*hz~gUM;H2sJ`SiR`n->x zmHqZwio#DrC>UQRpuv(W!+hj|gbx3J!h(H%o*Qp@zm8FMZf5jGj%^3*rD42(KobR= zF++NN9o0T$7H1-? zCEHRcdxC)60sw8_#@)MQGJm0#(-o*>)bs{*g5Znikl)vHw& zU+S$Z1+BwqO}$9QXk`7X4-SEG-Y);G2E<7fXr|9P_N?J#Drd7KEA!kUf-M zTT&L`+(AW8VCF3?`MP8^(X~^+WCy0A5KNd=aAi>U(<91AppZkp3KD7K{;5nF zTkrv?W^-Ym?6YSSuS_>imx(7|{59uw6x8izfGB`%Pbrl)RVgVZIl%@RJ8Gi{x8etS za=?K-UglU!o%59VMSb6buPQUW8(E&4cYe3{hvLYO_Fk5pmqNOvXcNJ zQOUJrz_0CVUH>8evF>j5vfPV+oAKmI99CTTL69n2l_Fel|o$gSTGVrdO48D_~s?<+{6^ zNjL2;KwNOqzfrJS_O$hlxt&EPsWn&-a9`wj`F3{& z_77M#SsC8a|`x?5V@ zbZt8SvwhF+`_|&PJi6o@pM5`b&s=kbD>Xlu9zvn9dsK6D`n?dhVv5w0q2oCOPfOS9 zeJGdZizJI@w6@$@U}+&A(r34RmmMQdzsxi8cgas#kRQR_8%fiS&B_f36wT%3`t(Y?euwAQp`%5{xt6xh z)>8|vpSn%4@&m-Ix?OdWU^AaVaP%cMu$E1+gY$r`p_GE-7#6h zn>SaFX?&M+9^LSlW>E8~UKCt$HGt?5O-0BB?1KNO+qQkuMDsDb;@`FXrR--J7EjJ} z6mM1Tuqvd!@duR_a^VlPFjqJx_cf>So5L+h{nyY<#IfJT#_1~_6vb5!eb_uqVQ25( zBW=VlS3JZ~V#sY$8bp(7ftrvu|8yVrJOq1b6c4!q?=q?o#xbUl{m4tOmk?<@ zv_BNUjNr2}GpgD0!f?X=Kp%sav8U!&Um>77#tVQ7k4ofdaP~KDDF6<&M}$@Xu8Dm% zx;)Jo6}w4jt5!-|8wF^{ zls{5i^51x$L2@_U5~f@D+e0ynfhGvhawm`W6UH5HwdupOKXC@1+Y(< z{0NjLBO@h|DP71v`+g48%-jm#*U4W5FJHoTY8xwG% zEMbk+*jwH0M~uOKpL4=x06QTDdtLD2e9OO-k-7gGWFYKDz>=1ryweT zT+IV1kt>OvnxA4BK!%zO%^#(x|GDOw@py#9I#sm&jZtpQ#rm}cP9r7Xv#U^nIZ;!x|S-- zk4?Xf0ZQY3mB*T#m^p8MqT+5u&z5r>*?X^jqdv67^klg;L^ex)D^YwVw!ifD?ukm| zctYqvM|%Pm`aWg!N#DKhu<6{G5JFrY6{#dkNXcIK>lUe7{cr!}t8v)VRmt=j28GE2|)0+3Kq{;OFCm zm8E4}K8_U1&A4`_jgp<6{YnMV_!UjX1r}7YiEv-x+KC<6>6<`Ou8LR=?10}|kolA9 zCO_0NlTTeO(4cnuoez`VPFTrcELY*dRuUg9FRo3zRLn3(&S#aHe$liM<>851^c*<9 zt#giBd3+ZKq2{M*mSqh&eqauC-YO&XjrYm&R}1h`*)0e>2|pBC;+{$_j{NY;B?4_} zqI;ifLwz`P{<)+X1x3y+Os$;la)y1PR|<-AUMv_j_%z!)5W!bEy(}w!lhIg`(f}!m z%a>}-7K6{YTVF=KvP4ExTrnVE(UjHjX<&?UxUbH0rgk*7gr(4i(z>*N%S?J|BKm&r zX+2~>!H&&C*v%jeRZ3&Kk~zUy7?|Iuhg(MDenY4N3tvfFrvT2*yjr^tYomMFLVYb) zpD}ipbf2qlzfa9K5vG9zuBV2EcU1{mB(rRxeek0+dU2@eZM!ni&eyG0#12Op}x97B0krM6!OkP>`7 zAYu(({Nl0F>CL{D?LU$yy2SmN8-gG&hD!eXZ2jS0&FqJo$))nKVy80hxr=Sl9Oswo zzG^I;m6t@C*=ud2gFdwOSw*&;MUrM*dP7z$vP{0qAJAop+pY56-Q3V7p7o&8xVGz` z>-o{2z+-!fMs+6s#nybg#engXbwOsg+>Om*iSwM0`l5j?>r`6)0>3ArK9qt9=C{)h z`K`g~Nsj&geWLc*p3HWFK({N_sBx_k@ii0?%gZYbj7Z_le{ts4IA_}67{0u5X^{yLP+;Ac zzQfi)1q&_ryh!X6Ro$mgt?t-itUh&m#u|ixyb1eQo!4VGDIrXzWP0U_o>+Opm#NPe zkkFW#e{`{ORe`pTRKTc(f57MB2cmE_>`VIn=JMAUs|@!{6N5ISueVw=>^Q z-XuGnYJnrRl1pemD>S{wN*gF*P{I zkgkd~iN{Efk+BQ+BQ!=}|7&U4jtAjF?NyByJ1%}_?S9G`2-L3I!8hjLk?d7!M6UO3 z!J-SynFFwlO1!`~O&#VTkA@;PSkz5SPrJ(OkpalK@bQ&DnCYk=!G z>@-vwz7FW{=3B`Q@2geM(cngxc0F_t;oev4}_&5CE&SEKW(-LqDgEAiyrVG<34bj}Lzg7o$30=G`d z%?j3F-aa}yO$*_^bH#PYxJ;HUTD4fNkXKh%;|Yl@W!n6#gPlAr=>o^OYP8LJr^8-q zSbcSjj*f;?zu~-x#Z4S~^67qdxW+SfPK>`L!S&x;onNCDT(eM-LYI#@q;(+dF$>+L zqGt>b4?p0xjJ}T{L0}y5p@>a3C-&YCczN~J;TfT*3$3j(sHXBa&i^j+Wa&6Y{km5q z^cWy?br8)(D%X}8Hg-X@#y8jm0m=r}tbu6c{!P$vezN@pCmQ^t1t>Ii$hI}-aJ!iT zJV)rZl)!QZMDkfSoVH1t*}18R4>=tgBRvD0*FQ#bpri3nQQoEp6hiZMZGGPTwo)RSl*D-UFke zgk5My|D%1sJpJGF6<>ll#5J({;9ky08){3v;>^aKlE0aNZR~;+1?h^{AMOTLBa4D% zB3gGAf~q%#ji0B?@{Ip4P6kT6hu0kBV_sSqCDX9@D zA>TN6EV{O~Hf*mo(Ayg|_5LLsz}LckW+o>7KsNLc7F}EVce^YK7~NuJG9jP5hiq8E zeuik){CD!$m4I3fo=Rqq(lho`IdUh+W=>8XnUH7a+H|D_bKyc|9Pns)X&Pc~$YaXD z)rIMzaz{*?X9%;95m>|mVcR0lekWsgulWjU!Ys5N^W&))#JfELd3JRj zO(zmIJ;Hs6fTwDH98-7(NhFWgzH|Yp~?TNB!1e2p6r;o|6)T zjf6JJXK42?rDOlf%Ysj{1mTe%c?s})+ayakjbJ+{n9gXg|bDRp^`?n26%NZ1f=Oe?INJCzKB+K zdj;NTmb`+ZFd!?JdiujN?8VVFGD7qLZgm9CCLKU~=CEVT{IB1MgL|1%a{7nU;yKXE z#m z{nd7=@Fs?dbmc6@|Uli z#_!|du~h;eOux!GXl<+*nKpaYW*_+Ie;2ScP$e8|cK}X)4G%e7H^-&k35G-&jraSn zIC#GB>Lvlp0_c!sKc0WI8oW8Q=L7vp{%&vY?c#&ux1BeYM`j)E{GIy$+EYqV$*>=s zzD^1!9N&rQ&R2yRPMI@@lQsX_fKqmtJg zxOW{M_CGcgI-`|u`STpj=RjX3Hb+~fJmYZ;le_$9~fM4Tf$wPU1B z5{b5iCGFHX@IqcA37PFh)#^6H93?Lj)bc{>=21w8*!J8E$I{$0XY;To((d-=n`FF= zZ>Ae#YY1Ib%s6b7v4$OK+wgCr>_k9uD@(+Dy?*OMuFbs_Hza!$Difs7C9GMN0@eN@ z#s&uop(a9J1@xTFF9d|wnEq=Ejbb4P)N8A*9eN!&=5zY@TV8|0^bWT4%@M> z6F2QKFompM+S^BhDF?8^I4;Gwvqs)?Yo*bD}Dj8_6udl0X^Ey%8A>dI7h~tZX zmQZoW2Ss}evgVPzk^9YH&54|@D6W?6SGh%|$Yz6E=870F>r7kg#W$u7voHGC_DUoi zebswN_K$;@k&W0*JY56T60Ff>@o}on$iF|F|LO@+|}jv9)92ejn% z-TrjT{EKb;%WcRI_Hmf4-w0ba0vldedz=g)0SZLz2=}?sNm16^`d)*w)*vgoqfJML zMLak4+v;1@^rRJsL3JQ;obJQwM^A|P+i21jkEiu)DZUhj#j!-~cwY{`OPcU$yy=7e z=F03LZD!;}o_AspGCtZej;}e-l0Yi0s^?Efkj+$`-K73eDg+_L(eO`l#6f5w|teh>UXqO?(-Gw>RCioeqj4_-1Zc{w?-fV;UsoWBR&u_z}OI)t|B%a zc^EDPfJVjh0(?#ZaBuE2EDQ)i492vrW1 zLR%CWv5E_)qTsBNu9~9C(VusRqD4N-Xy6@FfSs8^QBigwa*vN+ zWty}F&CU&c3p$=FQpp_EM{Bm{sC2)b_4jmZ&|I}$mc1-mbe(LEAIDBM4_G1Zr`uwE zC+g>4ZA}5;>DvLGqP4qrn1|1WQ}Bt?J9gi*_Z6fCS6gG}ga#Q#v*2cZWhrGHS|Mfv zN3oFKQ$PCVHea74Qj{9U2+h8<>piBw+w7L^C{H;XhfXbpl*4-|?!#~^=(SmSA{Z`z zBE)z(cr#;bV&clUzoQaMLw|KV&9L4{O<^(3tovUJKLUvyxsy0|htJ{>>^p1)1dWOOo(P8r3f zhwwu;kq~<56bC${GnQV97!I+U38!%N;55pH?VaNA$V3$?f}a`>#jRFu)Jog;ln=H% zXIQ*@c)L#xPb(+Zi*U}Tga1ZTbf@|g{<$CYOU)q|`VK2$No3=;xp zPy+xs4SpSnWB$uGFu=Z-gH%}C;<{k&;Ejz996{`vfAy=~vlg6;;DP}9(&>Rc_?hc+ zc2v>*uaL>*+zM!Fbe;6ZTdmG;S9Y&4pxk(UKd&#WNyd;XMVVvxZtw~^4S64FkbQn7 zOe{&sN%HX+1Xj~ou2Mr*xcK1<6<65bx#rx_pg-K?I|1QJS(~m z%dp=uf4(?2Tzfcswnv%qOMI3n)CcW&am;Jd_CPqAB|@HvaxptW(pDvd4BI56GT0;( z0>A5{`BFQql(okav{fc}!0t5eZmvQE=e26~epjhj1QlM?axOJ6ZYO?JLhH@vY{8}~ zo#g%Lw%vfY+@y=2%8<93)EzsXK5?p=!ViU%prxL)67I8oIC%f92x5qb2^$?ouW&bb zK7v?p=;qShXF!Y#Y6E@Cxc??s3s27!n8pA(0m~cquHIJ)z1Kd}AJ%Qv`5kT=1pk~5 zVp}jIb~SiBR&mG6+S)o}QAB7^bF%giAZe-jRa{&CT+J4;l>X!s43EYOV!5!dzlq^d zn56%7;CkI^@tNH%YWlx^%z0%2+~=umpLZ1TP5#_TK}d#He3}-O)lCBPJqGl@9raD< z)h&NB-ErG~l0I|4ws8ISvXS>?UfF<{6Y&)8-Y?Ql%k*<|T@4-HdK5QWf&da%H03){ zV|#XF6Sm;iZ+v0=0iOP0Vo&bAZ9ZA#T$8vn;qw1+0j|2ytdF~BP@c|2HKeC3f4r6W z?W)|zW{XxY<0rhPEHPfY(sI?)e|{CN-Y~;;BCZ_ZC=!VVN-OBJ6|K#TI|oSy0m$zK zR`A)();SGS1K5G+*P?Cz@15->x_|%vz}h}|!N9KB^ZB<$;Yj{d`ljO(m;_8C=69F6 zYF9m9R)gcYy|I(iEilHQhT)7uS+v@Nj=-xTRNi&hC2i^%9P8adLcJ+Fhi5os*iI$3 zXHV5}U|i~YZ?{G8Hai(Ro8?i`CkMwb9M{u-@;n>&VOmT<6WT(W3$5h7)FH}jTd(Eh2PUi;f;iaW*j3-63twuuJ(9^ z#5p_fCdnf->6jE*a~-&}--4v=rQ~D&&!0cP*t!r2&IzG*M@Fp;k1u?qOyT+{st(~} z7CkYS__t5$g8#~A`F^o;Iv@W&IXhc*Y@T+=Hm|p)%<{3P>+aZ zybf@K%)r}UsUbg~(9SSBhJ@r>hiTGeSo+=mayv>^xg?@>$^51EgprC$5`u~bDw7}t z=>U8*KmQug!RhfvxAW@!V>O#UN$)M+2r<9a??1DaLKd@ai?7SKERTPGa1fR-?}3d; z*)^oFk)^RdLaxY~l$^W~5x5b~f2RqakNLNfl4kdMBsJuBf#MB(1Jd{7p!T84U-8q1 z*-ThFY;07iz67ui%)L>K+KbUOkCoeI0N^hznFE!_pSD}+yCh24*yp?}+#n!@`M5us zmxVyDJBK}j8=I9tvwv%UTe!GKrm|r*Kff@INM`T0zc@KCr|w!=2}jz{kPbx8`jTEX zb3xdzca(bUw7j=u$)JP{;}Cz=6#B_i;lVGLKRzGACSf5^Kov-wjg=a_rhEwp3Fwcw z`qIfXV{*SoV&5Vxge2!)e!e2%oIcKxne0!4Uv98Q_Snt*zD&zj&nxRE1lQ z?CX6|W-#Em41`8_H_^x`Z#cMo&I8&v+@Bn>JKb2OTsl12Xx}ft5$W5iXeYrN0deN8 z+K+Wm2DVBuSOr@UgpIkOp6uq zeud^UszNI>AY9Fa`%{j=#=_mp<1#+;q3q))Bns~dFhq;$(6a_8OmH(25@f&{FoKx~ za593|v>3*72h&39TeRv4M&m(WuH~B%1W{+LP~}J{+l`9cn2P-R?e@wu!t9FvneoH> zT@R&C_cItf&Ta%8OkKgLy9V1Ygp{nMjv)#$GHL*59oa_d_^qz42NZWhE3Kj9F8@1R z8PjXU4InI90-s~IsNXUL4T6X_dIko7Upn@K@)L++zNhv=&*MXuCR8gQ(mqHfJFdEv zBn<-azbBf~3S)PZENt0TrFcr}itCiWLs?4Rcz1XJM6q~}w~F?O;^UQn?KpU_Akc=a zC5oQq!GoJcn^*HjLR|EHVX+3whQ-<+=@hA3dL9I5+C51-$&vMIFV8Ig4Y+XAHgk#7^^bcyn&D!P&rUUPB`3U#l32(2 zGn13@$6UAUC-)*>Ms|u^sk}Ls!3}GEA`8D+t4If){0E_gxf*;$(&KMjhOAa6+mgx6 zE`9If-idOz5<}WH3Ln-*jg|IhsbCJtf zJoJEpw!d~CSrw@6B#IcC>zYntzvIHKD)W6iZ}sb7l=Rs%w%5 z%lF8o0lkMQ%D?@7!_`?YTU>v_*45Po3pALK;03X)WBgy?N8Dq~dk&Z;0B@=J^T<9i zF_`JeA_ygG{YJx&D!~7Xz3Zuw5%XIjVYMEdl9HYSnn+pX*9Dhiw1IJbtJrW)uqKw$ z)jrBlBM!cT)OUd?6d{uT+5u;Sr{XnDFui9+Pk3mXu=o3k_#V-lKevZfH<`KHi-!AN z6?@w2ztOdM*w6IK=eiWZ$VxP0o{wJ+7ekmSWF+EBCTKAWEqjg|`0jf4yj`smA6E$* zmTiP&54(`cQ56wRbig5YcOQUam52O=069VX^^gE5zDmA{sVOgSyHE^GuDAXK$>A5| z*(HL@*`x%ob@>S@GrO*pUG9 z)1m-#@#5Ou8`h~0Xrd=3CY&_%{u>f*_aRZwMCCCooP1Tu32)73^-Q?%Y@B<~%7KV2+O0M7ISu8wv)*Kto$4T^uqhh9Z9I;!&GyP~ZqB>W)C?2&Z{L^*W|IZd^b^dbECqib&2CsmhF zFDtx3gTi(lJ?*367)ecy7dD0hVSG!6u-->@r3fyR!V%`fcrj~=a*Xq$HhtcH-UAWQ zSp_LeMTZH=A63ukP%d$d zGdCv^Pz$pR1RUO7VX?&#(RANWO|^xwnZM*1#8!*)9Vkd&iR5Zxudk^Ml~MoD`(P<0 z8<~PXiTe|7#ObOEmftbvZp%MEPkHlsXz*7M8L$c&Yq5@qo-Xp!Wels`_jr|2{Wh}a zhU4VTKmG#cKkST@QpuFnglE{N&JuX1%#bfsvNyCKy4EAZQs_7mx~lT@ zQ$gUG&y9Xbi)b@j?W9@!*+k!ogizz(XJ@2f>SOBYcUefu>&!Ty!}B*))+bxlExfI z$~RY*Sh<3QyMUqr7Oxm@T779}4<~+4n%digQoPuCW!HR^(+EY>275u6E93FCuIAf{ zS6qE=z%t)X$Z2Bzf3LA#2oi_*GN9DH+MHp%f#>a6*Ew^x|3owK(T826wFHBm7 zpDpZ&k6y2|E6)#uXO)NMw6fPcUmwxI8x9#%-5I}G-Nsb|L4o`uw*9d{0g^d3jsQjCl{EVF*5!u`RM;yiJvtEX>F zzkS{R0XA13m)6Uqd%o+As$SaB-ZMv8$>lzEi}8JT@));$phl{;TfoD0UyT_ey0+W? zc`H0Kv$eUKK_7Z|1;VmXAlepeh>pn;h1>#Y2!&P#%h~;|Y47d5ndyDP>PwC?!J-d* zhkxh%c=mkyF~4=oFsWDC8lLH(+pLfp(;=h0)OoS(FcuBuN1uF=^eKS)|B7$2mE3H$ zeE|FQKg(f!vy8yT$21CYFMx9lsjA!CF~WTY^eC|STB}nx><%TdVKD|T_P;x*HWw_H zvBZwhKym{NECh$J-JFF^t^Ssgs)rTp0AI4P=)91r4mF#8ERh+!j}U&;I_?JB=q=;~5XZ zM#;dAC_x&B096vz@xm|*vV8rjSBYL=wNFhgvg7g13WgI|2c?z|&=tj_3$eeP&T5!? zjd5HhA|}IO+@U^Qz&$&Zb?wzNpnG$-!3+-6f++jyZoaeyfeb`dqPaqnx#j*1XpcBP z!^n2Ar*@eD1~`E=?pvUFgm?abP318K&|>!2#yq#@&`@;2Iw}OZv&^0gxZGzT;4s87 z(nl>EBXUcQf9WR0k_is2?BT+rzV%Lr*ZHwXMWanw8`9@dI)|QZGfOkh)y`_)r!V<} zi`WrYrJ7VVq5?u4s7gn5*sUdgm!;vkM%qyXYARP#v(2_sg}?M1Ab-Dj`0)DN?LbnG zJh|l{KnH-P+a+HnhaDZ4x};D`p*;aw z=P4Q>;fYJ;Wuw1q{4(*yE@ITgP80gX8hQ?T`G)K|f$6-x4e^M&y1Mf~(AL*80?T#) zH36kyCSw6Wb8m}>N6d~Z8Fw{bdR@fGuD3F=U|pMnq5USwzP~aZe%^FMtXux;DhoTq zS6^5w*@{X)89*M4VR9s|97~IVR7uRYW(jNlhvH=XY;Hz}UIE6q?VWbont9Ftda6P& zoqqPr49IPuDh1X?9|{Wl6SjK%-+4Rra z#~d>55(Sa}P~Ed+%18IqnTX6c56~S8wYLsmlS8j!9k_=%H1-brPZA@g1u|lf#ldAi zQPK>n`vyjaCh)VoXFpm~zyNKP`uEH?8W@LyavVnWs44>c&7K~W%3CY{$P380)Dh9# z1n|3XLGcTfoH^)pq{ZZ*&`>|9E|VsfVPTz;tWIZmPbLU|kb$$;JXU$w-hE@wWVi!f zX1AWN?3`wkHz$7#f!a?~3zFDMYU@=i$8zHHUk;X0XRpljrv}wspU-W6h{;N#sVJ*i za*srpm>!l<88b}h?Ct%5m`QZM&8sH zLX7t6LIwuy9wh}bUzQ5Hr9M!Wj-L_Aw>KTPG!-aK9347mO9<;dn80WrzG=3E|HEUtZ|98$IQ3qZDbKQ~}FSLcYbe9h3({4?> znJTeDu?EOk-1r-HXB#<8W5$8o;6(J)B5h+I>kEG(%v5*`-<}0dSDktzK8XV;Yaza zcq9D_xtlZN?e|1#{kAmDWZs@!3J-G%4}Yn+I!)4V6k33ht@6C+GFKLt$<#PxxYx{x z&A;HNU^uvOpI7mmP5%)tMgsA)18ugVae+oooS$3HTU+Y+7I6uBQ0h^SidzK@eqniFA2oOUrs5iOt+yb};6W%=O7I>f4*@gWV9o(a22(=QedE8vnT zs&`Q&Z?Vge1_ZO%`SncSgWEuQu{sY_tVAE;f3EZJrjf{>%>{#8W)`7qGv?9vKIwRP z?cF>#;w-srpw1E-{?=+{_UgSQ^Ii0Obe9QZ4(sJ{ypP9YVHG=^e@i49X0nV%hI3K} zdf)8?aBIp3mQjjiY?Xh^IsY-W0!k6Pb+wGXVh@jnsyRSk?%(-`7l08;Jj5T&1>pY{ z*Z9}ny-yy8X&f~$FYdepgDs?pW4~Y}w9W4e*Ivz7|3*bYcvav~2kZ(rbF~=1Q_Y8g zxYTfS#ha_X$CosuqUM0d)gUKF zV?=JnpNgg+xK$ypNv54!lMQBM7R3l|;56zk8Hewda=hq6uJ3HVT-kdR_=(>CdQ9tL z^~%(2=HUFrk8x5~u)!Hzo6P<=Yms$YAKetQBnTn5#MeAyA15&>P?eVb0Iy_ypCuAN z?K*ZNj4oDn&XyX^l`f_)k9F)E?9*wM=&xMEF!sJmZ8c+EaET0C@e?*FuIW0;Y&$DB z;=Y_d@#|~gx{MRkJta!2WfE=hNrNhs&607Xmu|`2hQ5WM8S&E|JTnQXWwI~pTDNU| z{ew9R^V}_IXD2EI6gzdrdR&|J_dlyJirh1hbQtboRhEq&7SnA*3kM3n38})nq;vYaeMcx zjG(gCec>+nHALyR6f}eWSzGnW#En`X+%K@Ih6JUkJKkcAkHgwtbMw{beYFkiBpogv z)dKB97*TD7EhTO>wH{ku3%QEMAM(kY7tqhX<2zx%wzE^5^c0}u!M4-F;nNJzxDnqwZK?Xq$B}Hg2~cQiG=^uivHzw?qSzy046D^{I~-8Q@8=QQ+Sg6>>G5}2^YM?ZQ#s(GXVsv>j257~hqZlIS2g8Y=wsvCAQWOImYXY}0I?3_% z?dq=`;qQTH^w4l6NBTa29vx4p%JI1BOJkZkhCn(6!Z(d_H?EK4df4Me^1VA)1P!2# z%8*qVH+J6kBO1fGoZM)w8?%S8nwmPi+6LtV9D_G)Wahj?olJ8cql+~jdJ8WB(du>$ zm;V6L*X8sQEZ^@%wN_JI{$Wi)WFX*?Xb=<1aGO|RwLdYJNitV1T@kJ}7tVmKvlx?`iaQ8DudH8Ko#lFH7 zs(i&%E!#oqkA2XYa<-`UFQK@T0t;^*6E1SPz;AtZ6>WpN4Y zsIu!y=4;!;fqdls7#6D`VrTS_iMlrW1?gq}9}5nd2V)c9A%MX`SKopc?{4_+UUsIL z$`D=P99VMOhmq`#hRQT1I;rOqOB))=3+H_(OABmC*Yu+eGh?P9B~Q{AjS-B&&NACX>wmhe@o zrAU5oya7TIJ2$4{MKN)`qnSsX0FaPs_%MJFlE9>!!JVQ!pf@y(*M{TtbA$iN;SHk$p0{g;$o;O96{>8UTbJFaKbTPcyjn0Xg-_a_TKf;Ok&n4ipCr9f8+LiyC_GJNZhTpsb{72R3M%VY2b8rDa z)z*fa^&bVESnhS>72i1&g^L`*4XRG>8k6Gn>|>T%WPPWujIM({M_CbDoPdR^d64&` zCVa^R1W;3^o{|RH;H+a?MbH;3-nCIoN#=PRiP_9@S5o8Ld0tZ-~iT&Jh z&XC2uw(An4`;C$=-%&lYDE_Lar4Fz1wOyiT&-s&iMrueFjiRjXQp_F#(Y`G0(T0x& z!ks)Ah|y?3X$M|Pn)h3%Nr*PMeI4tM??M(w&83)^`-MKj6>)s-(+h_4n`C5UINzO! z_%-6lCcv9zYIDVdO@w!7sPHUicvvfsZ79)?J#khuQ9&&)e`;m(<;V7CUa@vcQSxCt z`~)pgHN}0-s=fkbS2{5CX<5$s&0jPg{X zs?+Dh7#*t~AA1NUX_cZr;)r&0U0J>rkz$n*?1&~oIfCE|AKIzo^}FdSEI}&NZhzz# z5(HFkN47`Ax6ImMOWtTDJob)7S=_v1jA}Zbw#t9r?|H4^;p2t)nxSdt`b}mct4k-n zwSbd!(+_i>Oq~UHkAF8s9Wp8@#3lIpiC0eLiIE$Bxx*DKS>Jf}TR1!%2dk!Gh-Yc% z-(lt1!nD!0m3^e|>{#7+7)W_@{bFN$`G0Z1lzqr`ZjxKno=T7ZVZ@`JXMs5dDgdXB+g(-S>jOs4 zK=>lZWg)(i&}E*VpMOPcYmi*!!&74r3DfSuH*Bw+WY+pC^~`G^ds2-yn^{4Uidn0Z z1bimA+Co-XKD%I*vyUE&8`uVgQ|qqE>&p_Fw>U`>T0T$tDcCRZ`nsf%*Hr8y}fn$_bOjaT7+fWbEBSb z#k#+5W10W@`cyrO*0%c;)8*$;22ze=r+yRmflqrgmux)8;P7S_XS30sysW3%cXCPkmS<3#O%=ZcAV z@jyU*gFi_i+N71y$3Xl+oa5SJqEVHThcv3&8d5?-NEv;XUEK^gKzP|M=m^@w&~ zb%d4hU6qG#SmeIzOJD_SJYwu%`tvfXw(E4sw`~)7ez?(Kz2u&ba2D)b8q75kVMs>K zKTqho6-cjmFBte*^D*;Q(n%JK*3AMmVBWE$n6lK$^yJBtv#$b{D+krWul7P|FP1~R zFSi={qWzAEXxvBN{v`JrjjM}~J&Wd^sC=M*Ywv!fZ`O5R0)jIZ@h#sAx-m=0$BL{I z8Kn`)e#G0Fr<4qTRVcZS3$>u*%bBnvZ2!J)BZ>jX-BkWU`wa!Fmd=N?RA%b?^|a@6 zvqV9@SxzMKeffLIuk6lV20Z8gpwAZHhrqYMVaaTy-P`Ev?grXFK!sTRp@9SoJP+Gm zZ2lJfw=2FtW|qRH>;J1!<4ax1+-=)OJCG{d)Rma_mPkf&j|em=H-gajU#07FAVQw2 zmXvYfqS1=G*GwlPt~IGt_bbg=P!;VT8~i@~T#6ffb+_v5Ie{gQ^*0SGYJy<2$0KZs zHbGpSCSRD!Z(GMLU?$nUGmR%sGZ(P!c%byY4L1aY-%M{cq_;V1=+nu%Lo)Ha#%%uk| zr7rC6b?L}tl-1N8vk))ipZukYIm}EDe12-Dt238U7R(7 z?+?-wU}$*1pov}(@bxqlf{){xfZv7i!-o&c^zJ{=(SgCEy^ayC3rXyqH+5j6`P8<` z=d@y7lB^H)Ni^#zC7Hv97qF6f#-|5Y`FSPCfo=4~Z7r{8Oueu5~gPgqHB0Q2@qm_D(_mnSTwO7H0CN|Si@{rGYnNZ>O;8=CAi$hWQGk$86@K&ZY*TtDRPZ znwZ=L9OK>D3gi(!v#%1mK9sdt(PrBspFb@aO$BOD@ho$4I9JXz7{9Xu)(zQU7 zi_3qy#zJ~Si!Cugb>}>*WN2g8?c`W$jO16f0xREL_G*b!M}>G21j=p*N@W7$8WwbqPh|!=@0SWt2x@f zC#9J?nHQ_YM;(iqFHYC(DJ~xe3_O$i%@=qn$awZCbes0-8zanR`$)woe(~94^V^ZK z0f1J)EJitdggF=ei<6TR^bRQJCg@P#>Ac!4{Q8KTJ@o?rIxflIisQQIq4?Y2TI*0K z5;^(g$GxN(8lcyjL;U_04Bk22%2h*vbi zhSK}i`<&(perHBi5PHK1)9=3~N-go7OL}^G77gPB<{72MOy0Y+IC-n*e5dV4&jJ)> za)YnVa0|jHxRqWLugCdlitXZlE{|xt1E$s3=oa~F%40TKo#qkT#`lj|vNbv4`^Z@S zApbCvkOWD_ntqq2H)1Tt`IGGY$M)I{iC9goTz$63Y{{%7O5MYj9WsJ;0L8kZxpTFQ zkV~cJ!MBCi>fCo0Rk8tPZ06caU)g_zbaCk(UW4|J8UqnMHg>$y=i4^xyXSr;b%1}i z&{^}@P|tksqcBgsl4#0sS?zP(e3vNjY^s^gpRjYjIP-)L5R{ZG z3*fV}-tnyhf!O|dH~2=S)dy_pqx7ZI;r8m&X=X8<)*Iz{1Mb8tEO|b8GFuXvT-OV= z?$LVT(&lc>2HqpSA%GzFS+IyBkbJLSr62XsvX^SOz~0f3_Au_>vuy$I=%sh*>8*N7 zr4!E`9k+fYGpY()A5hEUQPEHYU6f_-`yJPtuQltD9fET2TR3}g0u_n>z=a{jdlu7z zy7LzWEQBfi?7n5s`Z&CnB-ZFgV3*(JN!91bQjfxBC$}9)Y0ZtI!!U4u_b4#su5&7Z zlvTu~w^_fqFwNp;rj&Kf=tY?Qz;io%fWnem(Y9G3`eb;R_~Ap>&OAbtZT|Hh)%fTG z2jtq(Sgq~s64{2)cD-+A&2KZuA95wh*_*80R|5=rmnkvp3N>;*QZ~MN|IY=mq^4Br z!_)UK>-*F{jVvF&dg)b{{P#qtLn~kX4&CD)tRZPG#w0db-uRCio5Xw(o{7i)IW}r$ z@evZ9;t^st(U@!lewt4NE0o-ZnJa|HNi^3VkIsP|@n4&srpWUYFitKZ>$m4~VR$JbR($@xeJFaRXW#g0b3+vNC5QCo zlhdryLiLp{jfvedc&GzbsKH3@OB-}|PoF+TF|H9*_?xq0KQ0V|ZMRz#Nls#e(Z_La zo{n^HaXH?TXP!P*JU7hiYA?+2i)eySY}kWnTp{%&M$~C)Avn?kV~CQ7mozZ+zw{5l{^V}`Y2(KJ!2*M_Q(md7>UNnI+V;NY(B=pATnAIZ&ue^4 z*qE`4+%-Bld@k4ga95sWLu(9yC-5e*_3ABG!PUvp_MXQ~Q%?^DS>?60V9+hNLyv(t zrGd2YMjW3`G!2B^<^zkWC@Y*>g9-r5Aie;cE&--65u&#m5cu*}a4p;MI~_TZh5H+C z?4cU;u#kHHWKvf;>51m(=3hhe4)4Sc@T@j#TF4!+qYo@Z^Y`$>uG!< ziP$mCBz)Xk{)IFbimCG@Pt1n0&q{b)J_B((h|5wL&xxM@jK%mt5;jL=#q>R>DYqML zTK^GQoIBgy!}4q{9z6dbsOJ2pzE*L6j<_{7yo5^Yp!ojk7crZc>Tas-wy-DUmBOa5 zadhUuctdh9nZFgV0D%1W@5!Lk36qitA5^OT&^ktG@yn`Gh-Gi^_SmyYEMmK~FO^=& z5f|)f6{i;#2^U9UMAqom6VbwQfoNQr=E!Qw)DgC*d?(+i(Yqx1q2q=R9V*nd6Mjq@ z#aM(F5okG}L>gC)fFM@sTA)H$aFHXAPbF!Glj znWYOVmWCz52C?C!H8c%Qsm8IKcTStrF}-47=Y>!bVTt{by{=Gb=l;%qWWX$r_5Ry4 z?<1SWK}wH+uxZpe(}aUmo&((b&2>ntw7&C0c|SHV`b88dIsvTT5pqQ!ALtJ^VQxL7 zH3}^Q!a2H3<7lV&dX>5DD2@iQoUk&Z`{|l5Ia8lBs@s^623yhf(?-vch;ZCt5n73( z-CdT0TB%}7*XI#>+0tdP%1lHm?|rz;GgX)}n517>1pE2<`QkNzF>B67!I?dwcrv;i zGdxo;ZUQR$J*YCu>gvwyk_T@6ebG6-U2fIxuMOJ6n#_g-Nr1Tcfg14U@C_g)F<%)i zzqnZh>ZHxX$+ns5PZ=-HEOi!JClkMi z;mpP;m@03#DzOE^hx`eDyKpCgc*>T7haw!23Sn(yYj%OtG%&yBTkQ39yLi^L?u&vu ztAAbacM_ywuV7B+z6A0V*AaTzmiZlak@IHU$(gy8$|nhko(kSwxDXKI3$Xdoo4ZDv ztX`_==ki(h>g?T?CE4S&-A7CNhFK*xW^`A=4Cfrfj6b7d59e0p@;SCLG$`Avd5wHlGVvzoqaqhE$yxY_ z=k-Ps4yLK8DN~%>BllxvmW#IZNW2R|Ff25nHpo^L+mux*gMIMQfje7TB8Ny3CZfK* z{0>U3_!WKCZBbutP1jLQZxe4jB|)eNoam3%37%%xDA!j`LxW_sm_HU>P4*8HJGThV z9#7x&JX^Jys{W#QW^udjgW)9?^?4GW$BVKVcN zzMl=?K1{i+5mwK;DOo&Xru}NvmNG|6?Hz;Y?IkK~6ge1j07%czXa0Ti2;>}{dwURc zL({f9q{Sm55}_IlvVe`|zkSdfzi*q4fXQLKyQT)bEgnG|q$Y|uP`&3x8*IIK6Pu4! z-aR0PbPd=8E#&Qg7Q-gADiDUv#J|NK;CbFn9!$dEXJrK-ICLqo*#MSiVeM~t$6>uf z5S#qQhgRZkt&ol})Vlq;t$x1A=aYt(h9M1~#k}gI>xq}XP@HP`fA_uSp+V(PpXx7` z9$>;rNcnC z>R~!g! z1Q3Ow;exZkFMAKi@7;QC+ht_GR-shB`rTA70{4~Q{B|c4P-T7?$WU~4eo-9LP`0hc zBK8=3G~qqW(W><%ngRY`*9+kW+la$ziOh*Co}HmL<;?^7R-^SJSwagrB6E!Sbcs}C zK39x%$Hg?O2}q|=hYKOc^0pKRDWg{50~JEM%N7)bmH2-QGU4P)0FPBJjdqU)r)e<@{LVuWmlcEe@2jrY`FqxM{_4XUV6o^Y7bBMs z)@6tY0xehJvsO|Gica37ezS`ueDOeuDv^j6h$gj>y;$MjZ<+`#WKM1_xKiZKS;ypT z*mB4wUk7IM?g0PdLxzOjbO^WWea+kU1Gam0*uk}g;STgfzDwHXs4Qxe^jIHg7s7Tv zL9k%-Wm4>xe%7R9z_iNxJ-^E#gLzy4z8a`@2EypdLDAPPp2&^Hg3}KyOQ?`?Lpg=H z2P77JH{e_^Z)otC?R7WY+9WFq+!eWM!9|T@Y3g;~V)X$Yk;+o1-B5qfU3q@olcaXv zkqw)Okmk%fm^)1>ja>M(2Hd~Br@A{|)?@^j=Ts72HAoguNmmlJt8U2NDJC?;i-aa9 zCB@X%HVTme_SjPvUz{SzwP66V4`9{+w954MA^h5ZF+N2))FvJwp?+B3hik!(MTG(r z8m6cV>&1(d4WR3v1#@BsWk5P7NE4G^aFRymY?L-cR(BaTS*UdH9zCQwonR4|t;eOF zd;a7w{?CsS7yX2EXQIJtmCJF#{=E}^) zApky@e_VxPRg(ps!vTnioa4TJ2n~o|1{Lb0byb87sllBxo7_fR*Ndsv_QC9HH;^y; z3m=Y%D1y}j*M_s&h}TD>h3>%1qrhKRq3E7?8P1GvX^%htzUgQ2ayFUvB=tp~4YsQW zmD@$1Y}J=9Qgw4Q!FOR3tqtU|@E7moe{*0Sr&sJOu!G0y-c-{P@ZECID{S*sSj|gd zf~Km}s0R3mHuUN8qFQEokwvg%nqn4zUV2#A5PV_v$(7^Rd}nEQNwo znloYFNyRT`!Tk2}O+YoTPEOc1&^~I?=25_<*Q$ZW%O=55}LLs*o{fkDjcz{0!i)L`pduXOTBm~7fdvx2G?NZ z1aibDf$TV8P*-9r;~$3StFr(W`(5)$j+p`{^Zwrn?uF--CTbWRqM7EGM0XzhRKAe|`?ppTM;s^sH> zk~b$SEr2OrlEA(76l>rpfAizTPolg5qfYAcTMmA(RW6mc@th)Ij{LSB%5eQKa7#KK=nx zsx+=U{B2P+Je8k+fVi)_wq=geC zxJ#Nl112_Fvt{kG+=CSo<0<7?UO(Liw)wc#F<1Ez^AY4Lo4}Loy{BCIB{wG7wVPhN z*|isU4_Hum^sG9%)st1ClJMugu=JxifRIq|hvdpZ{0rP;jl&5+La~nFpJCc@DiPrw zdg0qB8>!iN;=huvh1W87zttN})JI8NK&}p^J#+Q{=#1QiE?lZu*mVA#2f za)t_0Z>=*^Ipr=W%3kS;A4)UtB%|2Kta@8nJLaEXEA&=# z=4fw>a2({(J+*u8z}Yv6B*%LFmNFCJd43{i*06b3sQ^t|dQe7SdwaXD8VAg`|2JB) zZ3B7~^r0DZ*8A(jnM?1Hm=y29*c;+EVG!;o-t3%3g6ZAD95DU?qH*o;=kyYOmna$bP3hRu0GJY$Rya`!ZQi~GI4JwqrLz1C(+o@dI0Kv(zX3YF_Cd$bgvG1 z#dal;0~Pv49RK>_@bp#p!d_7iQ_9d|BhW+6%^@rYM46$>FdIxUadL{cs0_9be<&Nc zbi8tfn|A#Z&X}^2YgfdRPs(-Vs(yl-GMBnO^F!4y(VlYh@me?k=)oDgh@P-PwNScc z#^pQgJzo+~AVF?g-G*NqdGTsP%QD#SE{Fn*O3{z?UjyyEw}#CKEKaU68!;k(8dd-R zAApMR{}4*)1zy9jc}Z=p>ufK6Zs@!9V)Qi%5RU+{2JoKqv^%Z&?=%pyQn*R6NpDI^ ze<`|nn=zF{hW(4i6{T#GY$KJC?uv%t~~b1iru>5|OewMXKGYm(2D?8dFV7dMh%snQCl*LK!SVFJjB z4bI*$UNC-&Wj!9{A=s{0VZ0zKd-Zwh2P{SzJ-lIquzM{XrC9|lV< zc<~n_jXg`e-J#KsP2_rY&=KxWVSL5i-uRMc<;42h!y)IJdrUcQjSzvr+$QS3EDQ+zwC$8_(-)a&-&$7a%-XHY_LQztGZgc)c1;o zkBalS+m&lsLy=?Rv!wPCNKwYka@n;~ysdx0&Ne-XCv&hRmNFn}iL;ko?T zdc)lx_~I=Z*Mahegk1-AH~*?LBx4Z=pp7+8HJ=mcfy#Ke+xhp{a6ZC&kqCHyl+g0t z=;$ci#TA|e=N5$^Qw7Ao_)xg^XQ;a2LYH#ghxK9!pQGysv>wVwc7!_3>3vxV7tDEY z1=bUtLU8zORNNW`Bm_oM7fzQt9j0GFTL|N}lM|SeConBzK`ljqx}`l^j$6NSnM;0V z&jmFq{UJL1M1N+AsT(#wzJ4>zb9n)}ecejVZG${_Nri6Q;io%fDYq&8W*i;%DFvP< z7(NmW`zntZ3#x|g2N(p}@mr{=!Kle2gLY2q%3UX_nJ92>kpd7Kf9~)5BkJ5l zogTA65aZV>g;V!Ys>t@&!B!&pDr6esxqDT*NLZp zg;pJULr8vbstc8p=1UbrxBbnOUG4gZ1`Ckj0cY#Lk)&@H^~y2cO3Wp!#C)5|5-Y3>;eo+KkH4GFmfysz z^b9B_XWHV&y8l%kRUmlHsE|G!Jp7%4V&1`D2(S|zqu5~jXgdBcnP-PS^k>h4r&DHs zxxBw|;DJMW5<_6!Z8XTQ({1RvX=xs-cG=IOu9U8E-$HGPT}!=FL}YX~dwo?cg`nG; zaCYd2)4hv);VB3Id~%kLEEX`iW{@@v9R|0nO09MTpHo(#j=uLEu|hV#ut{Z0LmDv#Xoc)$Y{z)wg>P9pbHD-=bzeQMcqfaxeG5Ce&+@;f!4W?|~Qvis=V^aibwoK;od-+!?m6%0`t# zJdH)7%94_=(9PFCx?#Vm+T|tF--A#M0fcg;AQBrUFFcaq1(5|r(t%wh)Jk5LJr2=N zg+p$^2X$oD?ao|DGp1g3KSQogX;EnP`!kIG^!*_^O=<2I*m4P}`>q_pDCo4ZdoWlC zg}1Us_JirS9E8IyBC`PDk;0zvVu)(Ug0lZ6)%Dk=+y+kCAFFZBFD&CIs$BvatcD}P zn&x?g_jJ_q#YMhdss|qKmM7fX`6R-X!RKC6Gva=ElNReV%Cv&tG=Or)eF>+gkfL2I zN{2t7tS42bd4Uk7D2Sg1k|>B10&N{gAgFJNUxPHm6+8D$?S+h)?cdF4R9&0C|1Lv0 z%YJx)z?2YXVNL0y8x%*;ZOn8ur>xdqL!j6I)=)TAn%NOgT&jiwnq5QKZ__(Mx6u7n z$+9ZptLp?al*-JD@Pp$(pPnJKkWc$oG^fIqnJVvF^eU=NuxS0}<1G?eIqyU~*Y)U% z@I0V>Fh22I@3|rH{ooggcq-R#fd%n?OWhzG1f<3tx@XdMzH5@8%G1~*x>vNQq`0MD zAa}-j=6u6(Og#||)xJ0F%l#>5)v{t!&#F^jj>dtp$)hqf5nOYHO7o_9__^|x1;{VI zHznI&zC*$+ysxIFM*2b~`Z2?2EShVeS3>w8Ti&}39d!~q1*H%F# zb#NvGlS(XY>BCBF@c>VAMJsQd7)!@38|A5jaSgm}X0OrUZk+uHv<+)jG@b*hR&>$y zBp`h{{?l@AWpsu{jdM|e#TjnryR(5RBQgIK%? z$h^wfXkkO*k3a|MVL1;P2*ApCGsi5VOr}DLd#{oDvPvA91?^JUtY?yqzq|;a<+zo$ zt9Clf0hR51N~K&?ec zye7f=s;i7q>@+0DHO71A3(c7?;pdim8@=NRAvTt$>u0DMNN)74dV}t}4r<~DtiEpjM!pXr}kp=TNN=dik{?=bKmTHy{(|&$h?iP9e zHESMV96-MFlYO1)*GMn0VNnJGph>+Tlj+uX_-bE&KVo1zJ^dkB?%y1#eQeV)xc%<9 z7SPS~k4ZS*y<1p6U%xFy)2@n70nnIEI``?KCDkmM$mdbLFYAJ< z>!-u12}$2t4u}qu+s7!)!%d|xSX=m|!SZNt=|03Zeg!tSm$eu8uCpUYfq;?Bj}38# z#m^5u9Qqn5$$H})Z&vK4T80u%%`l%9ofwOp<~n3~O)qVU#OsZ&-w)F+t2PM`GAo_n ziM>&ICOF}Rdf@FSIo@raYH2vg-y$wkqkV|GO>ybfXe7m|fQJk`4}x0o%sn;WjAY&t zPqwpZ_(Kdh{Ak_{peRg>{Sa57o-Np-(WVXp!K?tIkeHrDzeqe?ckyUC$W%p;mf~;4 z(>XClnn@+tQyCL_K~W8YOydnKPs6epa`Xa&X*Aoj^n=_niTcoQqUorO`qLk6J*iEg zD`0e{Ug?EEyb*KW$;nw`aBP&s2YEO=`KUn>PN|qI2+(lfxJsPfB(5^%;!||OJgrIq3zxhL~uGAER)5-6w(m3NfE%4AnzDf4VPSr!sDg}>y;OOTtLr;i! z?o#F5U}rhq5e!t; z<<-nl=t3RfWVhAt{r5D>Y)q?7HdAku`j~UGeid>lI=~e2SEF6*N$hAqjS6B~4KY73 zZas_9-GEI6*9OJHXAlAs58Cxm)t+601pTyk4~gKyM;r$^X6W6suyp@{genonO)&Qb z6bXZ#^9!YVPIw4P_wPi2(K9yrSd3i4MZ(=|Lg386vBlVOPj4Hp{5s`y41Cd-T1RwW6r08>`TeTZ(u02~}GFbMtg4?ZMaN(Zthb!;f3btPBeJK}?cCdk|3eqvBI?&dxBZP5W7{l#mNqkO0NfU!4qR$9D>lA}0)j z!UJZ)P{wG-1|q4m^{ zHvzE>3>=l2h>1yH1>4Bg^#e8b%cQ zCZ4i_JupWgBy$s?FxbNi9wa=$b!t&5N27m@5NAjVwCW}AP5wsEgGJcQJycNEUJ< z_A|1#j{(=u!E+twjvoWseF3X+pXY`*$?bb1FE$-1?20qSL)Bhj4j66?YYxRpe+t@;pwgq$)Bj%+_I7V~czJkgf5CZaR)d z9^3@Lpn^^k8`Yt1ZcVQoZ_!*AHa)8rJd=P2fLt-es?2|KcH2G}g#pD!Cu?4*1w+&S zy)jCXmI|es#!gP-yW%Ude&WzmE2u#uA)8Dwhlh5P#rI$#Cz84EjH8iiZiVtNTGAxo z)|-NR3#A_~U9L+sNnAXg*>fk9%EY&{j6hn*udAqNgQ*ShiS(g&g=-x*kAypmG&v1~ zc^kEspT0s;5zXmpjEnYQl_<8*Z|64Up5BiP6Dua~^SE)*ZGFu8K9x4o8Ce9Iiw~QS zqMM4rVW7%ZNO}?rz;08MyC3eiO5x+F;?JLPqtE<-{BWF#$1kkh^VV6=^Y z5S^7ajag+(gNvNTr)M>pU*S_@XwgBiDh3aT8{2Uu=$mhx2p_%qnF(kQvwe;`anEu<};-bJg`PGUGGJyYm@_Ph%Ao&C%RRl9% zQ^U+---bm`Q~L(2jUX2Z4o@<_y}wRuD`{8@ntHoxlw7uW)r85z7x>>w0?R6jxT!FtYQmavy@yo>`hjo!F?kS!@d8I=u7Uz}D z)U~`i%qd3=l|X{FJA*Iif~W;C9hK5|n63qM7;wn7T)IbrP@ zEIPWRIOl-?74p_n2Zhf<(Qxl1AN+X3!B3UprgU%6euNhQFMOt2g?BT));?Flhmo+8 zvy<5bzt!CG11@X1!wj)n%qjjC&ABKS?>oNSJ4s#XO0jERVV!LCn2qj!2Nu_Jg3g@d zfY!{bW}sP&%g#0#QR(@JyJNt2Z)Bg58>dSq^7>YE_M2h|4%|JEFHVe1Pb;e1arh9w zNP_aki23rV*xr8fVx`ZpNcfwBI_XF5zalf3@}7N)UE+3{j`Mt7jpl*CBtQ*bgLl34 z$7?6&uKjwOF>~HG(3HJ7nsbJMG9m!U__@dhH_tjFw^cj#wK8mS2`C{3v># zruIlalnZDsz+>>gRS9dfNRZm@Il^WKudJDKO(hc9jTg;69mdsv5t;PU-UcN;pYd8@;9HC*~RJnbke35%NmXEgaHA zk2Ke=YeCf7m@^fVr08O=FqU~-Q^%7;@*5o*BgOu5C5Xmcp=ZBCuodQS|#U2wLh!V`1#Ji=?YKHcV-uK{%d1l{Z$&*my-pzIEvuo4ihO6J5~* zNl%U};V&=9Y9@lG)w^VdCWuZ`Z~XR(F`T$*YDBsl%6!VdbiuVWOqxxEaMNzq@Hw!^ zmIHM?&~ZSkAhOtCdxuxStcr7Lzg`0LajY6eC8ed!z?8y$^Zz{t;0vJ2z^X|{hyT^{ zVL>P1$4BADW@d;KSJ)HKVZY`7qk?KqwQwwum1|rJobJpX^fTWQ^C&6}Ax4;i-2V2; z4?BW+_||t)|2cZw(aKe=w=Vq|Hk%w)(g%&Q%;7KZaqvu7sN_GxctY>raA#GpWfwMk z3$?3C#<}&9OB`IHnrhDZ&NouenRn|ia5_kL<{Ns=d4G%jjIAve#aQjXZr@(*`TLb0 z!5`z{b!;k@Kbq+eVzGYp5=&jjPvpDVdPZBDYP0`lpNoO7Z6#5zlG{U8h+hU@>~)+v zFopmGK_?HsKTv0bGejSs+kf3Ref$_S%c~?!$0$_pzmR~H5!sOV{b+C>{#A@JEtjpE zGv$5{tAOXKD!Y>>cyof>_%ws|h?TUqz2*VoYc14S&x%VIX3V(X_f-&!IT3!rY^Peu zdnI=IQ?s^xyS}~NI`VBbeHzEj`LU((?tCxXAa!0LD z2zzV=%L7mbrR6e*D9RHwOC2aQtJqdX%%Mc0dssHxhMR-IHr$#Chsag!y zcHKJr1J>uG$bjm42hC264jc^o$Sl@uu#KihhldOEv6M9)es(gf=o&c;`)1K=BWhj8 zC;>y{=-xdCn+zO>huL`OUq5SEjr#Dr3GJ2>Xs~=EAx^Zc#9@_;9fwScK!ebe)$oJ( z>^FR72j=pPF+9`cc1PixYOD#p$xW|QYC0$^*T&)2+&Xg2dU+Z)XjW%VW2Yfi-$&0VyunI0%4GHZFb~yjx*JCy67Yr$*1)=f0h`1hI|P5pUH(Cj3@XAPJnjio zcFE`i@(@Wh1P}RFrwrm>*~QC-;-kI#r9Z1lHV98H&{?;E7OBtE|JT3cG2jn-N&w}j z=I2eJUwgFcf;b{&zIbz5&i?FO9RuV=w+;VGr{K( zSXRB_3`IVRD4s6e$YkiI!zh1@N57v*&RxDCN8Q0{AGFKU%n~fj-3ue|P9nu=i9DU9 z_~VDt6W5b)sfdPTNSI#1Kn9j{?koJ}`aH{50@8Ee4yX=mz^>&Al1#qt?A%#V4cgya zt9iY5ec|fz2(c9cvlGw-8FSMpj22VG=-ScB?HosJcsN9+H6yB_VbBAmpa8Xq5wDna9T z>CE%@4Rd23*K!^0o~1^IGL0)vAM!TCg~+WZVhV1%e_-{*$;4W|Kd6!o=s|8-5iId+M+R<0uRgDP%5 zR;l6Mzv)m6yLwLc)oep$K-s&N@8i1g%>;$X4UGI( zE7z}r+uauo!rF=B#YwPxB_6DOnH&%#bjIq*<`yG0K(c>L^%%W^0sT7AVSijNN&=La zSE`!b=COboazW6i3kz$IyDHz99^Cuyp}5^=&PHr~51WJQ?Hka7rHUV!w!k%o1-!a! zH1%C*GT;x>LK}UlP9hMOK>+@WIU5t>2KBGU|ETsVQ&$jr=}^0&d319;l)-)YIpSe> zpEASf3-+(|Y6i5_ss0tkdDPhX-!>~WG=k)^Z7! zqUruN*WqwWgImc6?@B_`IXz^~2?~51;G>{O`^vJJLc-xz_=Kg4l$2@9SxKdPq0q zJ(`h}Fmq@hwBM?Ei6Xma;gr=`NnV&u&+Xj_<}zps3NVDh7*u>PkAdg#|KXj?SR-KSnSvAL8DQve zRhPhb3xRkf!6U-akqDoEi};IZwraChFO)}l#s~EH-zfcF)f8Ej8!6w$lpT0h&FrVm z%OcSX*dD?mH>XjKixWG}A3a$cy!GzKgj2d#3^n@Dn76H?cY{p{?zWmzFeGiw)j5OK zW5J_FbNzHY`^e(my7vtJFHNy)s~OEYyj>}2hlCl53oocCQKUGF$+l{3kI%Qko5NwI4gSx;8KAK=X_UpUj7(w&h5wVN78>g8NheQA6h*RM5!(jyBWV9 zrS^*vjd~tnTUl|f-Hi1Pa)0@LIp0i-+jjJi_s6P0R05Z5pMz>GlcKSVVJl%ZZ=6Ur zC7FSU`~%DNhHL(Zti4iAvMPl7A9ybx_!KPA*ioS^lqY-)MIm^L7o56^r>JD)2&25Q-wF{qNon=`v!+$kPV;N1hD*otNO6IF) zXcdC@4zNK^b+A|j^~Iu+Jf^!%qv6dwA9!CF!{!(+)x-FdD zfzbrSVE0?^rX2Mk8k?3C7sZq{C~VNq5ys_&NKrxyK{~SgM>g8nNlbuR*U#8T_Y2`J zDamIWjOdSr-fA7}=LwB1_1e{GWw|=uCz$5!_qZl3@Z)+1&udz-grrE&*ygqAp6tbuNvYtExyQA*VV*`F8{)mDI>;T}l3k8WxcT zQ;|$&ZxA6z5b2O~q=s)GYj5>A%NAgKJi(ETYU$z*?l32uMh$l8TTFS-q1e#=+%_7Ll zSF-*mDPkTuI+ahj3Z3{()Hbf2#yc6FK3yt$R_ar`*=X~#^zK!O!PV~3hPvP^?yh~N zyKjHC!s@6Cc{jzlqQ3jx9XaGQz2frf>NlEuh*2W|(3$O&E{}uy(Vw{@7tH^RmEku( z4`TQq&RAVrs{xNxP|ty5scXZ$ELHRo<{nM0v(?|87Pwlt2muF+6=E$4yi+iQuD02L zv+hPYb$;3o>(-}c9cG=u@&Lk8*?5;BHY*_A59W?YNjn0=E^M@r{X{M6JDDtlqPQW5nO+u)O7@UDwu% zDVBq4sfUM`jb4%SSN{xV05Ip`;p20z4*j;T_Y_w2q1l1H)&*FdRIf|^)*nMhTK{_w zfIEgp@7mVx?wRDlygUN2K7+j`WF+`D)AAryr5szwG+e4*Zqe!l%}U`pHctUilzk~H`T zi*x4_uFHY3>RCmUd}NV!cyJ43zY%LYUg;msT0W`8bd8+xG180-+4CF=OYCCi-t z$i*&0`Y}_x2@BCg)I0!DFu>3%RLxfhTbK-{^Mk^p9$+JN>fhkMzy=!~SX~=JTmO#$ zn9$PHL{O0c?qC*qAsWr6hA0HODukMrU}a2$?ZbfrwFTTCE-qnS_WbfUTaf5f^p#8a zsSfQN388DJXg^9|G?ka5-&XY}Y&Tmi34EVvWuBAia#c%SO--$gnu>Rq;+>bHiEQDM zo>%yBo%ekVkK>w1@H6aAIAu~pJ10qMu9ac)<_rcLtem7gx=B{M@{u~R3Tr~lQ(CMg z-;?5-zqnVHN)_+wD_@s#?+=o5UL)J=L3JE43v{n3f4beTwQ-tyK4nOu7**7^c;YlGv+wX*# zoiZ@pvW>~E3tn8~=Vd#M$xVHI*)gMl0v*mAN-6iF%Y1EFWXC5jNbarHw-=G~>5A}w zywx=LiLkS+k~~gp`+eO|xogia_tfczn&O+oxX6ZYG`FL(H?Wdq60D~6n=GhbV@d1N zbF1gMVUimZRf`H7Q;UAC-d$lH2nLucBhbcBH%3a~0IvGfTK5H;XI< z-j4_9a9ZCL=ARj3zbjrjY|uED(^vu)SHC`ENfzRTi_6WC#(C_^5~yGjAzM%7RdN*3 z&edMJ)*0!hUHVw~4uoDerW+#3)3loLabmn>YU{I6Gr7_I*0Z(954t@bzzn9Fmdd2AFlp~Hk_R*vo9kobRo5 zFR_s+adOW%Oee*l4bOD6fVOQ+``hiC z&*Br{)VwoXcRlm{Dn#XBR(nK%hY#8nc;TS?N5s&ALRmIC`5^rtyXuk)L69sk4ucK> zl(83ab@P320Vm~yTJ_B%Da(FHlN^&H5-ZWnfSa^X3WlqDOPxHpA;$V?Kg1pObAVy8 zQ1duq^qknn$&Kmcp`eQs5}VUV>_y$LZGOOZy0liD&yOL1uIYB+$nxiu$3suAcl~^e zMqoJBY02!e7DR}!ojV>K+L^dkNSet0wlZwv?hGXgM~TzLXJty1AVi=4N}CSFao_3@ zUpC|V!poMc`;Q6Ik6-?9ofqtxD=vmj=I4yko{R@qjY@oTIaSlG^}0jPH@v^PJ0tmi z9IuyeeS`lg4zr*Dp@E8nfgJ>u*3C`L84e0E7?Rq77z;FWQlJ*uz1-P7r;GXzp%#KS zKj@}3Ej_4eo$mrF>DP%j0m>P^%%tQicmHO1#WQH+fPs!NZh6f)qtMGum{m|>NnB^1 zhW)d7A8mtC%ueh}Y(Wga85aq*#ae;xK<@K=9aDI7hOG!5Epe;FW;2n*IvKSXI%E|W zR|vyun#veEbi^j)3{5^X0@c$r7eO8MrX^U!V^8x+#rrmPWzc3ZqTW)wVU}B$+{41p z3s~6GGt|Yi5vjtyvVFYbL?mvwwoNI}OX;JdcBeh@rP*n7YuaP{PA<^8>C`#|SyUqC zOMp~8n|2HI>UpFs`$3m-4K`XqhjX%4`oG^DvGVz$p8*u)V4xM%ltyWqa#Zp68K@9K zXa7>bMXy-oIq#>(`2J9)Q9fhMqWL!Wg)0z{aAQ?7??{H!7VA81eLmx8s$;;2YBgmv z&&i%FKd30}TB&EYH_P7xY6K-O?o6gNy~0l9K;b`c}Y_8)YMtpm|Lj4%*!3f;zw0i5;k0kS(o ztW)~40xmv2X;S}DYF*JZ_29hmPsjoWb#-CPeOm$}(}D z*e(|^n+4H5cznOtYhH30Tm(5;{naH<8kBd0-MgSW2R#2@-3bPr0L+fT3U|X{a(-SI zxO_bo0CS3=mGNx7(CKHrl!G=;hrN!|Lm;Zi*Bhd-xkqcS%eIX@*<$UByDq0R z>~c=o7rgmA)#bHC&YxQ^-lF%_`uY3qZ4^4aEdI<1z23VYJYGell2FnQdjnm#j+7oN zi-~Ho)W|NZt;>+GMqcNdjF$Az-FJJvh0Tetu3tjJ=G1PqcJI_aEN|oNEB551(L6^< z2z#36Y6DV-LU!+Ktv%J!#3!isg`!S`WoL6$8iXheT$52IWqj#Z)zWr?Ccj>b=1w<{ zW6QD{+89RsekipzeZSjW0S^^4+Rz25<_}p{fh7VIBjTiiH?rkx9x<>=4U>wJ@!uP{ zsUW9VArb$t3N5e%-vtLoWjWB7O@bWp|DKb&3L(UO02pLW=nbGkqujVFPU>%-&HNv) zUtZuuhIty!aP{)-D{UE+O1A^QNT+7;m#$!=x~Xog5h-pkfGENCcr}9*T^K^15 z%fw$<@8pXVGZD$hOXsQM1V;y2(k0P*vY=2bWhzTY4+M z>gjHgVwrQoQ|nKA5GxpT-*+PLqy1awy_oAW70RWP@$D%|?AV3ZkaisRbr&pn3YD%~ z-3qS4R=tLgr=*nP(fJCILHw}Afvx?*XSfw#!hczEfQghR6fKtSF2_oiid3xBPF863 zQ7_QD+FPOnqaPyt%{*W3S&j4Z~`4+G&0Q9k3Q#0 zc0T$jMH8n?Rin48tV&6?V?^CLjHQ8C+V^jU0`xSb(bJWMw}mOAvf{Ca;oH|*slR!n z4-@;n98;^+=qVmutWiql>oA~8e6E!5Sjt4%_%5#fn$c9xFdFM;eA4GHPl)%6#Dwtp znmzj77uQ&HUETG?;}i27i@eAsJ8A0S(g-`dv$65?_6w3{RBQnk9cQB|c}bX4#K9u{ z%$`vatr^xLZXOYIMZqu6H!+rO(|-OEI!|6|ZyR9f__%xqnU=IvlWknl?YuS6sjeU1 zxaV40Eu=^DE+x&E-ydhM^#=zcvW#G)c)T2=1abwQE1R1C-qAx|@|%dj#o=uym*ZbQ z+6{qH_mLddgYHCtHUdC(l~t@S^_*^tTH!OKDwr`xzo$$pc&QwTc~~Zf>a#`3 zC8MNEYBr8-wEUPjUXH!X-%hQ{vWQXF@mtVDFtic<+4LV+Sz~)lmdS{NS1UuC+dV9f zR>OrJqrt2#Zq@`vGKDICT9V;9W*`4j%8Qc%N~>B68k(zeY;BaM=oV^JHj#SQyJ?P} zdS8Z}p?i|yo$CfV5IIeW-XQsW6+rgw-s;@-I%84fjot~p_jjctJ;d}U@?JH6ChrTD zBnYq9Z>Ec1R_Xc9cjF)zX^+$NYWj}0CFQBTP$>7imw}|tXT%|aZo5_wk`Vde|28VL zEaBYI>U4BFZe?OE9 zU@O#CkcqJ;1Z8yHbPtx7crtOOP1ydU=_5*a&c%9-a{UXPU(e9X?B5NQUt^oJC+?75 z*Z0K7meG%#ecHF|l}H;Adse=@>@y3i(*1*K`kJB}X360sk>dEypVkkK88_op*E#9X zeQ2Gto-p9m6}gWI&4uWhi7{Nqp!R7nphlij&s$z6l3VEb^7)LM($6(-Zj7eRXIec^ z!C6(d!^dGZ+ORTH*_rpSzL{OKFFN~JGF;aoB0J@cTZwP%+vhS}vG%ezi z&Q?v=D;~9|1RM!E)W0!-$D*Tx4}jl6=s{s|5k|_ezqUWf_aDL#9J9C&l@~Ay0+0zi z>^??3&ZjsnwvZrA0d}%Dj3fABAa2&9MZYfp|EPKksIJm4YFMR1KxvQ$L8ZGpl~TGv zQc$`PkVZgK38h;)r33^-K#}f7knV;b@f~L7|Gw`xYu3y-YZfze?|sg5&ffd%Z2}N7 ziK)fjuUdNlY<~leM5mHT{b{w5*uSLBU#(h3mBb_&1m#j4vYT zm_?stv#sFrv>#(z48L)m=fRkrR=AAV2tz?yYZ(nW7{CX)OMPJ<74nKNrYi3HbwxIq zRT!=cu^$?f4?YsC$JA?6DnJt_B&nM$4<8K5B4#!lOg)UCO92;~K*PM=xvZOi<;4nn;HqC-&OeXUS*%IJb7763=)UyvoSncnAVv0XUx ziw#=}p4>mYB0#Osx(fXt>b&Q=EWqdtUbFuw9{T@*+^$=`!m)Li8kHkKqNypc01%JfkYXup5|FbrNL!E z)?OrS2v`HQ2IjyE#PR=6nL+xmp(~OxL?HvI_4XQIcu1k%ko_WTbHc$fAYJ+Ms4W|~=&eOl~vRJQ=OTO&ND?R<*NZctu)s=^a=^~e5S08QQifnDn z3ZNcl7!~1|i`MdUJtA7_FJq|k%jk>?xkc4uQ<9jg)aGS8^mQrhm+swPoJslakC{u= zOv{kUc<8&@iO`1Ly;c0SH5ADCVoh*%uBfkvnd*Fg(KFs$RQ)(|5uiH&_F`r)k7|H` zyT@8{_%Gc3b^F>s#HO_I$3n+->}t}gt#B{G`??)04(Qpx-mXc6ANpb<#n?>%nZspZ=cN)Q)~>1{JK*R6i9x>t&EBkj zhO|#~OAGOwn7Om+))G&EN8TGjRVT~gNKe{!-CscI&;BZpVvZBSmpzRJ6Z-x4MV%yh z__ChzGu{0uOf4j?LZ#mW#0LgJr-puJ{+_~Zdj z&nrk8RX%(4T3sCdi|vCM#Fbsf|Fi&)(rsyyM3?gB9|qyy$A`w@m2Ma)99*P!aQzD1 zD&$HfD}KeFi}mz3s()SjIw&U%7&VBpKphK09bo&NEUvtd{(ay*qB#VB zqreWwsUP;XI*6~`uKlk5Q6FaYi?18kzZ|;o2E#vSlVIhdvf+D2?amalE=(~lDru+G z2KUp&Fxi1@DsE*Vqqx^-{l`PwrfWahOxS|+9w!+#$;M{6+W2$1FDu)dCRBO@Gl{~# zm{b_eR6gR|%8bQ2+Gj@muqLjw?Y!b=MD(h;-C8hxSD&T4ST0&jPdp?={BW>r%n5Z| zz0WstQW3c>OI7dI=}Rh`ar~j%?=H3R&jqPZ#3cQ%M4U@2DI8MPu3q^YRE>qBI@P@y zI0$U5)Rgu1;|QL&?_8M={j=cTGK*U~S^H~b{Zj;M)GD(Z`e3v>0TPiZ%a4yQyaYqV z31p!khk*tnlb2hAuwd>X3D&l`$oVjnQCBB$t>uNlqA`#MWJQVYxrqM<@2lb8xwf%u zG_>^fO@lqn(+AGm->)xud{{J7xC@58Vft=%1TyIUgc3GNB#?d@@xWp#M)dARa(fBM zhQG^2XO<;y!$#)1e0&!MT7D4LzO>T%{TbHiCPyARt~L29S{v+KCZ@1IWg`q+55}o; z#(Fq}1mapkyMUHDK9c`o8kPy)HoJ_&n2zY9#}AzG@D$tH*<7csQZQz4#jT@)iH>#W|xiTR14g%x$i5BgtIW`QgsazoE|eLsil1=Q|FSRC3ym zX9_frfsM7wVJ|Rdmg@f6!c4wV-=50XsoKZK-7<@oA1N3UM_?JWQGXWy#|yRLd5nGr zm35~_F7-4ov&FRW3~wi$iy%?m5|n+_W5R(H)`t|BLutwST)wJsywI0i0??x|mMZ)( z$HpYv8ZmKJt(b|iG@VFAF1VEldt7%sWSD)x z8Md&{CRtBUNdE>4Z3v^#O);K5OqjP}>;aoz_w$o$!QOLrlH>!E|HgGokZ@ibaXtJ1 zqZF6`pTXDb0QXoASY^TZp236(9A>fRuR}0ZBJ6@N6s2r(spi?Vu00{rhOTEfoQB1x zGi^oM7AtGZ6gdTWXawI(Xs+NQ?KSt5y;{gMS1BuKVU;TpxDfP z>wR^q_EacrPU|KJ*fx@bUP)}*WV=I-l}G6}eO}}%r_c!j@9BL`ydlf2z{k5j5|_lJ zYq_*%RJ8tA47cdmEjbE<|3o>(UitVNaE+M<)S0Qe9dH?8(0xv~v+icQy|7OAMOSa? zp>4mxW@Zn@?@gi!;iShk+TB%qf9HCU(Vf3Rvr5cnxcH85#u)S;vRM*O31A7gaV6xZ zP!5!W&W7!#U)Nn&sqcjie9jh5oRk0YIWI!dx0|m-X`YrNRlP-VIl9 z;L!(66B63cLVi3Nbg6>sha=hp+#;9O#8}U2si#ZGfehwlskk^8Y>y55RAsBH_1B(E zxq@s|;nfq>uQu$ys_9p=bKeCUHj{Hs0&aOr)hQg3jQx5F=A%~4(r{-__FYVm)1@!7SSl_NUfQo13Iy@p_|UiM0DPI*kH zg%xf?0s`OnYUgF&N_4vQP=BWLHk(S=-!wCpqbC36(ka@rIz6*&xGow+#5?xeRo?dg z_YaA4Sf%d*R-MCTau0PSNGMqY40Uz?Ky)xLjsH#wK34*dHyhP9A^hQ5PzqXOkodyW z{J-cWY1aEcn>Djw73>7;B4n{&4-VHgV^D%Ul^z4^=53H3559G#>HFw-4_}t1i#|ha zMQyPoIgykvMj0c~t#Q=)iSfDf69I-heYMuXeUdF*ntAuiO5#4sgbP@v4%K6;%#Gcm zzU8uQH9bF)*k%a%bnaEDfjn8oiid08_{ZRIvsxH)RKn=ys#3y- z)Iaznv9&qvYbCc>#ux$&D$>QLpXH-rf<9SnuydwL^kGud6}s(n13eHEe3?=Z*{^pv zWY-8E-U|G_ohBcxKGoIyN@lm#xJu+Xx&+@Fu~v3H#yGwu6Ab?98=XgQqvIYe^Zm5>UEeshRW4#K#sVXUGI*1Tf6++>3x4 z8nQDLj zo_O?_`H#PsiyGChz2CIG3VCX4as8o}TdZD_lLxM@>_4I-J8YkR=3p%%6i9aL&@Iw_ ziGH6On{8|GV*b96Z(oLkliyKuk*bF}qoxML$U~DW{NqfyhAyUwI*PC&uk$JZd$@n4 zV?yb(uNo(1Z6nga9lmLA**#qa6c;^{<&0X*=qrWDri^I?W}e1d7IT8bhc53fUBq_^ zZ(MwqjS$CPs-U@wOa6mEIr4As(d!!|qq!|Dek1c6i`7Z%s0y-+p4#h|Bo;`5Vk`Dq z)8=*_Q4Zd%TWAf^A42m9Oq|wTZ{M5gZi%S>q?~4ym^W;Ft)2!`W(firDDL?(;wgQTs8Gv&GLJbQ)kgx_j2*S9~ z?j7F+!~u~0rKKgNgkLKD2dlGMg&M#YAP|V_VGqR(iBHCQhIg#q^fe4HlrE`Laa&z^epqW0eCWH!k0K$i{_tjW-e=sTNcp>b-memvmr`yG za^_!c>*f9`#+n@#PbnB39*iwXr(`lSV!EX7I8T2=mfvt@WAh^0ep_IzMD|J+|6Giw zWi}`p%XR#lKf{IHv%O|zj%_k6DUC|wrqjlsDc_&1MDZxZlnt&7e0HlHt$mU=OVbyC;) z2dWxDVy62uw76We`zBx6pVv-Uj;(P$M#bJf?6fn_2b1TR;8oMCYODd7>t0YcX5E@C ztnDMoHYo`;%Ic#He?NiaKe67YXFdn$-8>6N_Yag?2q}BzV^_bQraEfn2ip4j7wekk zH|dsgds7K$dop_sMwO?#B3IAfKOJTXsxJkqQe%`f?MfrkplpmV+WLu;~90 zlk}v6RPFlKg`|7f?}tnrP@Z|bfp?Jb9kj%=+rFPo`TA6dW>GTMty#kSxs?C~PFyG% zV9Jdf)G(fre8_qrbX#OuPD8Pf`|Q?!{5fO0iP)KgMsMidjZ6ta%wd5fyo>e30vf#@ zkRZwv{h&V$TwDr0=X=n;nf#iME+yM+@WnnI3QcENUY4MgbT%wQS08zNAVXFT(qRkvoR*4!ZP^$OAX<5`Lj&y|^l3Z^Wo zgK?voyoPD><6WE=$>sa*Azj~CTv;PpNER>+-wQH(B~g+(=tJ^BU!n~ds{MrD=AR8{ z7PfZu_WA^c(`<2_a4@^2&P}p?kf&aW9cE61#;KKU|Hd<|M2d1a!N#C)1^tiK&htT9Wl2QcIFL3-&8KHdZ znO(*KYcVFvES~v&xB+dLc>D1gCxgj5(5QP^=HXsU=D!MZMuycN&jdcKY@rlh-ya4j zv6z6y`4(aL5aL}%-Dwd+Es?vd&{O<)akbH?V{bO@v3!i^spHe4zDXa?Iy6zOrR7#R zE*0~8B=oMr(@g0X*(6WG-eQEbMv@|?x$Yc=)7>)><3Hz(EK56|Ll-(<%-HBxl>Zph zK2Q6FY0Hdl*uZAADZLEot^StC@_w5Fee{ij2BLJ#e8FbSbbI_HzU{^&kC;=j*;DVU zBBjeiX7z*SHAxvSH;d3ZLISp>f)=X%lLV2?xL3K1+gymPdu}t$ZPkUN_H}I@A=UAY zb=ZAa10po~+d4xso|SK@xrxch$eurc?hle~r@ci594b**DJ?JO0Qtj>V%u5&&cVNn zU2(~RE@5sn9wA_PZ`mjiBTs+#tu$?nNOxx^I-_#(+_eB5c3XQrooHhyIi#b6welYV z6b?q@!`6TR>R_1$riwL|52WvNCl6uLrxW%m1pTRW@Ur8JRmhjL3lJ+h!Kd`HMce{z zK4htgE{s{slf4#yr8f4;HBxN-8&+486q20NAhLHa*<~bXyP)_5R*$*UGsi#X)-T=sHcik8$}nW8yy1 zeoRaAM(1p2m$ErCh0gP{5$>AVhTk1jzKTvcZRTDGj~{ zpW2fXezwMgyCFCfe@=E6A|fJGAufxY91zAIKR-|`b;i)a-z$UFXaE)d>_)Z&8lx)NSLSvPg4Iz3V8zuI8YXO~z5=ah7OyPt9>a%$+ z`yd13Pkttk%(G~jN^_}iO`kpxPz>WyZ-1dRm)l`sL#+-8%Ag_^*AEbTOI%g6{Wo zxSr=GQDXUtLZ}ns9KykzY+ibKRWZWd=p1ghV*{v$(<2{i+gO|r7NqK-W3r;jU4s z!Av;HtEZWDP;H;GWlL(x^x+re9sRo=3VUJIy5{!w(Yw12sHmv$v0>xjfDa7`2?-=C z0Q4Vs?^K@n&O8ig(9&JAhuYeqTsQxHz|yo)zpdG_q2_^K!lo-i$L<;Z0A27(%yKMT zB7lv91PvP-`{lC+Z5w!9rVcM+l9G}r>{J=2%bt8qM-W_nl-f!(-0w%@ME8`Js{G!= zihcFkYJe#`W8CUUg{!-GF4<>evpPK>496P1uT(VahRE#z5^R6p@dXtD5{+&YslENh zBp!ixuWvoL=;-*G*L~90i(h+*neKN z&G|VaC-EfOpd$PjP7#5NcF(%2Zen2vAoL@>rWc}woFy}EE!DUCnC&on+YhGgoN%Rn zSbwBAo%m-d$ax-Yz`+TCYnry?^JiUd%#20&YNn!hn9? z;_C7Oeu0XHcKyBTvqJ8q2m))+tg4f zA<#X7{s^4&U@xU|CR;vR4!fVOm#0S{I5?Pug2JFdb)+>R-K%^Gy424vqnNRvH{ypunXbp^!5esVKtg|JyIT|M#CYepfG>^ zIvGACr?sKahP7~H0iHJ>?^$n5rGtk924pP)9e@C2mU8}6Pvz?Ph?NOa>hfHlhZ$uN31>*8peN|7{Fw!C(5y2^|yjvA5xg}n_yvW-wIuc zg7mhq5h<6W60BPyeZ|j)IbrTJ9XD7#mP{oG;m>O}S` zUl(q+lN|PL!iw@WyNy;s+jr-{JSx6zzwgp}?_A8*;7X|2w*BPY7IS0)D$l^eS4yhj zEf1xSch88KK`zam81+iEMIZOW-T*3#jcVi9wVgbvVb4olWzqP-7naT?ZXg5)^%dk; z^d59`A8*a9qpZUPQ52WK^x|U)QTp-eP-BtI8m(~=gVM7BZU}w74kAkUb$y;8WiT;u z?wcPHR6~gHAt5Eb89I@G2LAxR`wsPWfG}j8FM(>wq2SfO_mceLTLIS%66juzXMNL@ z^YAUh|Er#(W;!EI*|_jinF-_vs)(~0-{t_SO}Pp*%KP$K!w&EtZQ_vub#&-UoEl6ZCYo-j}8&s`3ATUc7?TrZxy zNRrKJdF&LVStxUD!e$${EOAA9pPR~HKd-cLSJVFxjamW!=LbxwYO<`XtgiypD!@sPZyiczh-av#Yct1oP@=;9V?X!pCJv?WKadrCuxW?)W&S(LN9;dHpaOWT z<|IIZ26(}L-Px|AYrus&XIF>RW9tD?ctljxeh!=WTW~eFHK*aQwmU8DX<-rUM3ubI z2z0phUA=(Ch}wzQO%QwP$4zaNj(k*UHgOaBueK4f&=I&wbC_trPNO6}m3@ z+qRDr^@0yR1@%R9R#^5+w5Pb7RN_$J{x%-;O`$zD6i#ULYK!r0M0lP@VI1W(6h1WS zc)y_{xRU-yMW|x7OTJm>+Z1Ny(*e6&8&(9%mj=U9Eh-j>oq`-v-ysEBDn5%;9eeYyOzTx z3xI318Hm#1aR{#~g-P??dDKtGhFtLYpP)Nh+K9+VT3YnG5Azyy-vIUZS^qh#dUkwz zcdOH1LU7K=4T`tUSs-S=a?RUiwR~FdXHbQ_1C$>MZuQ?39q&pOzx;cz_@TwxYEbg! zn~ugU`{qCCG-J5TM+rxDZkEmHp;))=e!nZBJ0Eq-_j^Iw9pRBdX{2+IsX==uRX^N5y+;n=z#5`?#>GE%IZ4tXEXdRBU#Aj)Lx^tUt$sYE>A zL)*wDDhggyS*lFw1#HrTSzs9oN@9=0VJ-MV&QChTEId2}cnRM9udlhI5X;WXD;rA> z((N%j#)?M@sfVc2v?@s3B0yDt;R>~_3Xef!m}KSB7ima*5Vs3vj0K`p!rzcbdj zp;S&^mH0G4#J0r*GmZ1xA@|Bl{%vpcONOW|uFhmR{Yarrhdhc)d6KCEM*MEX{LOAl zC*9)vRVYp^)GY9S@NgItqAIPcClDU)?um{$5!CO0=A>4j`0Exm^L)nFeyLWcj1F9v!NL=2Y zL)WH!`S9h^D~=a&)1J-Xn@03P9x+=RFc1`!n4#7z#Sxl^IKY6ct~ z{%ZJrGl?Dp2?Nw&9_r{@?PKiXTgF0(}sOtY375lhVa>FbKj?zeg(x@pjdt zh6@L)gV*Kt2LB=dZMCx$r|W&{aAH=+!?oeOvZpP28&N`K(dRPt0#-AH?+M&m<9z9) zG?5W%;TJ8zyFwT(d5aZvtd10#Q!nH$y>v*bPJF^n$HcMd^{~chd(pPE9M7Ms>}_&$ z=ly;|yVx8Xcku#EWbwg;3gM!+#8PV9=y+Ci;HciE7wHxk&OL%F4UDAm#tz9}n1p@x zvEEq$kyciZG3R#=#mNYibXCosfD* zic|gl^{ireZjBM2N$PU=o)<^Ul+R5|niKn`7(%~baTzF`9aOvN5;j$n(fZLAqfTOj zDH4v;;`mIrP|{J3IxxB#h`7xAyfMw~ufD}xnFM0PYbXpC7^uo)KU3M zEJQkJ>*%Zoje=$CRFli6p!PYnw6rwFbu;P#tPz*N1Xmt}jo4fCAG)#htKN{Q_s@lV z)C8jp2_>Zkw2p7zV%%qB6nK5Y4i9w!CPk6sv%WsOwzf8Ug@HnCUtQ>r95==|BB{iB zU@gAZ>zH-Zb))Itf0vbqBXpT@adF_o0L(}xCwqm>Tfu}*thY|r`87q=;(fKSJQB-& zlZPo4>Pkc)YGA=nxc%LROdmPj-RgaKIw>KQ5uS#ZP24a%`J}>&8yi=g2nF#3OQSu- zv38V#xl~}rn!~f{0*t=hx_SY7Fa;&i&udNorTgsdo)r288B& z4VR6o?Cq91Bd8OMx|aj%?xMy`Wkz4b;at|rO&H`1731k{3-0yl-E2LL5|AJk5k!ym z)8~^XKM!o>h$@or;~yp@^JnugD{6R6)Lk@}M{%6w{}*rIS4!C|pjMuZIB>n+2nYy( z$HK|Z|7J6I0e+GHkkySpL5-Q2y;%*`zlrAGR?_nSP*yv>zq&- zz<*_DrV<=fq4nP0ehR5*)3(PNL8UmCUnVzSef~oVSc#Pt`W+Kb&w4&|ivJ$-TVY^C zf-*8_KtO-|ayz{UumUmzi+7Jk5-fk_kp~E~%LDrSLBqu$Ej6L5tTBS}OHYBX0 z5R9(lxQ;@cgsp^|6l&)$Lc}&>CQ%V|urgZX5klJ#iwtcmpcYnqx7oYATQ0xHp6mE+ z?32zsY`-cdv5@%s#*r)OHWF5s5XR|fMf!)c0G!ok7V6OkBINrkLi;Wu&;IGGr=t=jNPoiIUD#VkMBX! zRUD(rGu8w+$BT=f<3iEF9I}X8Ge2rXA$DivvGiFL+l`C(!|K0Vt@l|JKjuQG#3?9v z_HE(1^d1~I8?`GJ4zC%^*w%PGCe_$PcwAiRQ7&wWV&A?E=c(3yzBTd~<9`qSt9B^* zk3@rUVy3$~D$bd5hVHPi@$9qx(T0w4GJnhBB7N8&ja~Pz58*#z>Z?cG6Jj<8s7Wa) zvT6QQ$518S6FRYSH%*N>t1%vFht9~L5yDK_lq^NwtpR*+S95Yu*r5@9M*lKhfq^r% zdI};-G+!tenajMjT*qYjW4x>@?t?|6u2$or5MJRWy^Ekn!K2!jLZsM`X}~dCk&&^D z6%omF89{gT?%wgow#%v5OAnf_ly0XliK)5qD37f$>wDvT8RXCiR&it}w&_*Tmoc@; zU-sXL@*S7Dzf#-Lye8iiM>}}eg6*}?=An}I=I8Q>H&yx%=+Hq)3RgMQ>D6!6Qao_b zgCsNTxcGjo=^3!1SCp7}vp8F-v8S1n>ck&j80^i!rb1^0wgyA56MUwioC2%kjDqWJ zURZ91zITp>f`nua0!N@*AR;ENb67xqCrc;zknX?gJ^2GZWRHu(QIGA$V=xl6c*#sQ zUj6;?K_`|<>N2P}uJ^5|kqJyqO~<|;4Y9(B=;~6S4#XEKaP2}*T^d$BAq+|4EOR(| zjnr)r5XnSxq~Kxu1)t$l7Tc&g zb)%v5Scf(-wl;Sj8Mn^ey?wg)yd#)FG9xmW2Q@*Xc*t50oC&pr?41)eI zBxD|I`LW(CZK;)GxGavo32CPHIt>DD)H9FWT?xeHQj7Go;?JH=*>##}eW%)3f{*Id zn}zC}xgKVOQ|WykC@06w&1pc?ZQe$U)yWf3_X$Q*=DJJE9i!)FE>?foXpswg zRR~t6VR_T1$4V3~e&rsOp6(xd#JWmx;o?cMI+LIjH{*D9yp`b)34qmgc=~Gkbjv)* z1qunj>i)KaCX}6>{YGGO%G34#uz|ZC*OM`zFlA+Z zUUp<}H)NlOQoeOg`uK58V>IVQ{gQmg95?^KAor#cTfN)%OeC)+7cp}c%CU`r;8KS9 z*~6Y38hJhYj(Ubk(uP5kuP6g}8@Tvo8Gm?ug&0pi5rFa(V`^Dg7unRqIJCt4_WT$} zlvkUCM4KS%r{ydfo5g;n2R@1>t7^9nTtL%Jp?O{?aK>=^XGT1=6Wi9loJHWG7sgU9 z&DHZr-|6{a!mbu)=87`D$amcsU9-V8{Fj7smmVQv8yUG7t*>3g;u(@nN75{rYfW)P zmUcUYPfPg^5~Y?JIQhsb7tmU`;d zXl2txA<~M**HYA7a*k<>vBDP56Us~3Bp1T|1v-G(DEJB8 z$-f>r;W;@uO$BGJ4byqiI>qj@wO@T6+ompiYi#rgBv1N94*aiY5s~<;-b&I2yL50v zJf$ERAC^veLSKPniVY3pHC8j2r^3a-ar2E@lv)mM_61$a_l zc?Q>6NbY=%K|a43rOAEbcRaw1xK%qCdG5w#h1G@2awLbLJ2Z#ZgF?B(H`KUhZ}j_V z;TRP|Mp*5%3x7xD1XhUHe3vg5-6`&arTEoVKG6@iP6ASonqSiVYKcm@Y;cyVaZ!nW zlN+Y|@O0aJ-o>>i_WY1im>0u}CYfL=!D;FdYx1KT2(IvphT`5r?LO%i*U_h1Q~iB5 zEmTfm&r{T7RleLHdbocdc~#FiLZbU4$}|Z+>w56CRGZY0+!|EgLt8LGCHWi$ac^+d zMO96bPp=nt)j3}!-PTPUw)YzT)I@eh3{iQrO|W+8XhdC7;O*z0x(r?7fuw`Rrogxs zRGjrs?bWrlodW{{bemfLLuyXvzrV!?kTKcm+90s}u1H1UTN+RLikmhpQc_aayaR}8 zD?tdR6nOw^M%Vv_b}ZsL5Yb0!W}AMa+FkL9!lV~_%!~3%S3@3S_=DF5VR3bOv4c@( zOOSYh9TirzFHHzdP%d>1@^qdRi#pCHJyfS@YA&xVN!|)BE2aJm%DSdH-*0&{uBu%= zd~Mz=A=r=Q_R=Ty8%Nn0^W@L}nG_#?2{4}W2SUg75<`RI!hZik*? z8~^&ckJDZ%4bxj#BYMS}vySjrg_^w;MWqw@(5VPaR5DKvysa~ossu@0yvRnr&VP^D zjL+fh;6-pq$ct*-*9ZM_LZ6CZGGa^GFOW}pO^Jfc%A87&qRe7j4!r-4}78`m`n08>;6*Rmp0PZ-@sa`!Cd1D-YA&B zI%zyE|MTGA(!EFuG6INI7fCUuulRKRdGFnT#41m!uf3@vzkoyg5s0y;EOj`$i{C-| zIclc`K?QwI5Jhot+zW{xf#-aVFr!0+=8(3O)lHj`D1jnc*PX(l);y)BgG}#*YJ&UB8OSeWVK(b?F>TUxL>dIn3pLXzmbC!n;NNalPqe>@6wA z)4ufIrJq%nzjB!$v^%CXY1zJRMK9sdxM5x4oT!v#LVV zhrrzSsER0=z8KqYx+uj=oR4bR7EiJ$9a}D}BkNcajRN=G_i8Yf78u1M3*X7d(HD(s z59$#GKL0$npOV-0aiIwonMFl=peH_zxkHqY01v@yqhlTkjA!Q`0!x|;;t<$ERfiU-%ig~kZd%B zn6J<3f52z0Te0`$)xi!Xwqq5gXkGxWY zT`~3w^~5PW(v=*giL&)h67dG2-1xU-QFn|e|r<-JekHIC{#5O?7tySHhk z@+j^LA+bg94SDh@o5+nc*Jv;Qi*L_G%X+u88Rj}f1n&$zPHEQte*Q^rzv9PuH$i>?}j3`7=TVv8f)TuqIUVM7P z**DQ=Iak(J=hSItvG$M8QC z*2564aiCMK*Mv4UUT!$xkK+T&boZ1%{R05sNH%KqaJp7ZIsBD$}neVpGz(Q{=9^@~t_~48>COWbeix8YCQhEFu-KVOcwsi3XBT6v|kGI`#ofxN%ko(DGMTtiXR;VpnslgiL>1n5zr(1Rgyu;?X0U$MGs{`n>jaLSy?E z$SJB*PeZ==Rs4zaoLY7)6EB?HmTcoyxZihs#@vu{ax~3SAbflzEUy2IN$oiI+RHdG zDQWehM6>Yl-uexsVLv6Bx=m~22oCVt2cS0>p&Xl?_g*0uneGC~s8D0SaJ_QGmh`J# zeUV;yHkpqpHM}Cp!&K>x`;K;q+4L4c@2eRULd}S+4Qf|FNM@J;*mF{ z;k0=57>iaV>d{2l=iQ6NTKY*j@JQR<^4{qv=Q)PT-uAPN5F+0n{ilOCt7(K~Vmgx@ zl#={OB^f?X^`o)p*~%LkZ_&2Og^7 zu-J<%Y>LCqOk>dsnCCc;69Z5sNtn3{#n4hB#8&O|L@uk^(hiKpw~A9n+F@e?gb#Z-f@Sm2$qX2%Y!%{ctjccFbYj}B=NQO2|89<^KIpgZqEqE(m z&-Z@aRjk^sh)MS1k{nX5>jkvW{O#S z_%rx@dw+!{Ds3p;x=XS;zwQChOEzI%zhjzHOj*fespw6__y~?|G+O+bF}F7FiDh(h zj#1HPJm%ih&*W)uOrhgb%#WB^TC=3Uh`j7cb7t3S+wZ+(Ql6W@q zXahHPr&c(}DJGuq_)D8USK|8oc?M6Azdx2W!96Pp6IGL^)SJO;A;K1qTg_1qqUD}Y zD@A`=Pc_0g37`xM!+Ef!L3~t7C!gij<1s*rmFwk0HB{}52jq-zrq`aH8}U*uMycPH ztEjcg8^^lti~uwM+F(`Q0TPCZ65?I6V+B~U>3MJZJ4yubv8H)t2$s)`T*CT9;9{=+}MgaewPQnmA&{HIA}dzxKSj6StGV@n@6G=RzpE;sKa_3$u|Vs*7%ccGbwRzagQLW4&Pt965%sumVX9n2sRshZ(Uu#D)_-VNYX?}1Q=_k zgb_*SPh*CisktxMs_tU=TQmf|Lg%7prOI)V!WgeH(1s+W_8fD#* zWqSW)z2s)j<2o3TkywTY+vRfm=zy^MHwt zjt-V&nfRX;1tFo~9EgS*fxj30aIlDbwYNO;(*Z%@$atIepyYUzYPZv1oQI}9UMhbx zQV7n9E!hSNxo``v_(#bzU*gWoIGj^GoEPXv#6)#9)gk;=^vt@?&L2d1P1BHeDw0LE z(Q&VYZ#>6LXSl7rMzJA5=Oj6Q#ngAUO|i8vu!MvqcGGG0`|^OSuH>Gwf3t08bL`+L zF-uiR_80P{62UIF8_lx|qG@rLpIUQwPUE5lT6%O&j04F2N}i~o5%>*_bdBNy~#4lQZj&;gMcfP+YF`f;rAZkL~{?&-ky?u;< zne;9`@txnrnQEh;YR==a+5YnW8J>Ewlgq=G6ZO|lHi*_E;EI(9*Jr#SCJGqtYpf?n z$2a8=u?)AT$bjbPW58e`*k{|UJWkkrz0;Jr2RTp?MY3BB|#FZ`xPjo$y(f3zNG;K}LV(DPI z`uNRri72tPaD4zU6&hf+erTeC?DWc7`b=Jk^l@U{ugGU+fSY9Zw{@CiHL!3F!KEvi_eia!d z<;(#76}>S3`OIsv!iokZJM4+}r}ZD+9+b+MDTyy6uVXdvu}Yy|r8tRDoojlg z!@Fx@Z|b*tY3*KE00iTaMtyH@Z^zH0e<<%Gc3`!xd0=3zu6aZjv`M;{Y55}QDCyK2 z8s=cj3LxrSV~6gqCT~Q(`Xg-~>c=!nq@<+tKuO#HCctTu+($v`o4?qGgB^djL5qGx z=Wk1+pe>c)AMTe7xGXLDT%B;$BCH-`!)PH8ekl_sw$^X-TVY0l{g`s@#*snunLzjy z?u$1N#ae!D;?H^paYTy3)T}_b%F& zMwHlsRr3Vx=~MqxonwbdWk*Su6IZQzLNlmVBR&)C6p_&NCnEG#Xyees89s}0^wB3z#9K5xQAl{dI62Rf+H3)Ls!nuzuE6}x zXOll%3-<~sP0h>$(`FF@`@}WPZXLE}-qlV`!_K)O>HSs*FN`sRB#m-BW9i>N&Y7vG zj(=7+gq87*L%rZb(~V}`&$f==7+(OMY;tU)q>y#p~|q)%9N8`e^BKJR>7x8=BD}KL-T7 zLS{h7FN4y|SB1HTD$mpC2@Ju=msL5kI zTE1E;TtULY={>g*6I+a>u<2)y2rv@EiPZZXq7bsmslm5wd;IEZ-f^L0ioe_XnI<|A z&7SDteGwFW&Y{3FKY9`8ymnx$mcpzYrV=38~?Nb9%yZ3nGh zyxzm6gpVw$O;7lVcAnUuemY8ur)JOGPk+fJn#CS{;N^?^1gIP77V7!C^rl#%&iCVj z#om5k!Q_2gjEc|{yIS}5ry>y(n}F&jYD!6dF>Ue<7DnC-UiEdXSzrV7uBVdB)#arrLD14~3#VT?z7R$1opB0C@9e=YSRF{ZZePUHAY^%Fe@y->8#^_F zp#zAK)6>(<;b~b~p?_cJb7+uYzw|hlHI3il7F{lRHdet;zW_86GRo)9FW)y`wakKs z<;&)!xl9?AuIi2@#VH@>fY_s#4T5tfJ9L!3BMZH#DT;f=*)^{w@BA2RezGGcSatP@ zsOm92Zq~?7^lQczo)+((c@?k4WNNjBHexCdZjf#Ytt&Jq`8*%|zWIHMJJBvU`jPLW zJn!zOXH-8sC12xs--Y$8MuTtXt+BpzbO@lMk)8lpwlr~cPl)2_xkAWAPSEr~f;`ME z$FDTq`1T>_dz69%q>~#40T(a)FJ2tqUkDRg?`)0_a&max_~U7tc`ll422lC21`-lJkujWS_F!1fT9P|)P+11?T0SjBOEOnym~jdDfE`ihmG7tB z87{F|qf;>|E z0X_4cM}Xl)Wd7Mdt&fM{weB(}!SD|Zhz^?CW-515p!wkit0V#E6+BR{&cpQx9|~Sk z7XRTQE3{7Fl-B_s;k6DIKfd^!4BTv|+B>16bYkSrj2lnEJ*_G@X`>X`c#2PUl%(Uw zfT2A13R}=cT#DfgSc+w*Si2m0-0hr4_xN zqB^kB2xwZp!}C;yoMLp2z2@NQUn|>6?nx*vI=Qf-^yUcb&93EGfXM$gY=&SCB zP(G*s2+%;O>i)F70E;`$55!Tek?8jvK6HAKom@7x&bLWg*mu=fq|=F zMfN4mFGOr^mklvDZE&YMg4(VA<}wc8>;kntaglQ!gueeDPhS~T<@1HBbV+vz0@B^x z-JpbYgLDW;mvnbaO9@CfNJyu2cbD{`@9_KId*5|f@CjIF&dlun>?eM2u6%i?aF=K# znwB#DH3=O_71sf?>ne{t?HkfKPivzmEghQ)3&=EgDF24EmQ9tzd%}n(=9OS56fJrO zeJ0BN9vL?cc@W(fkfeC~e0ziZl#Ef3Ap?T6FvL&}^2FJjqGi?P)=(3vj<=qI| zq;CAWPtILrSM|l2_ak&=a*Ix^Y>X1JPj+6yTbSBcPmSVbxdZGlH*IN270?~`Zd4lO z!s=Wa_JXqABgR!SCBy+2P9?3f%r$a_YVQ~e@L567hGMRFJQZL{f?L#eNTgkh;d<#D zlt2yN;rGqB^2#JnN|zIJniV-`HO-_>DOLWqfPBdkgJ=9C-+#hd93~5|8Y`jf7StZ z?`Eb6Al(9NN~@-iJkCP$0R5Rsbz3p zVo#FNPp)r?XWY~ZD3nJg+co1pzq{3t`)+R9kr9{eGDk{9>HGQ`&-KIhWf5D>9=lVn zFc<2PGA4L^(H-!i?gq@RvEa_%wQ0Y<q|I*gEV5l;N z5Q!3_LUSE*P5xKYjF~(G$`e7G$V9>Z!QADODwhwFZ>&DmFh0s__wj+Bf6k;}ChU@0 zf{$Ze=y4OTHg48DKs5JRSeW9?EsF);sUXPl1P-i4lSZztt{>)pH8#!_!P@{$4-=D} zc8YVwX*~ccl6*@S==Zdqo&Uq!7yav!!8)#GE}q+K|6jn*G(;_z278tt{F|AEFGockP#N#D-B=m|G-z)#E+_3< zeFUe`!^<`7PI+x^w6K3?eQESf4Ov_AU*atAO%w7!uoXcz%7UC|B4vACI3H!FntpZ< z%jWVKTs|j7jAu4UG>P$HDC~wfNk|#OLOuw2Y1e+T= ztD;I13ua=34xZ^HTDqf&g_c8c5$8kn!E zykM59StTSa+#yQ}5F`Kuc6*Kid1W$T`hTbL+Y~^MPGh$KI}s4h{!K`e3ce7?--hAm zNrN&8(8?_>LjecxMT|#9MFl2PU)2TPu3i<6jg2@z-nqO8Lx5hUzWh$wI=mhG3q2ql zcMH_Jipht&7Tw%q1Xa5dEq@wLvcQYCR0RBH2Q&U(9krCcH~7&rvN5Z(Z^Gbk!j~WK znu< z7xHTE9K~3}6f`3<^UbndelncczmC?{CFBcrmql|ODR91;o&tA&$d$pf3m7ZD#5(}v zq%n^K@;GVo16}esk{`=BxF+`iu(yO{yB9G_uIp9=7TLB@h;vQr$xh)ROL&X!$xVHt_zhzh8oN%9lb9K z-LDk?3O=J^W^UgE=4~6%x5^h{7Aa?&`xyD_aN9ebjtag)LHqiBW_i6a@Yp8vnGSrXr!-0CIFGge6ZNhr` z`YT&jV;7k(K*G3>kx?$Qmw~r(>k}7|xVJip|GrebiFvd4vcC4!+PYdGn(@=8u-6`@ z%9t+&Qqgc27B!>`ul+X!@)Z*Me(g&+dE2~=(^=Pl`A1-XHcVsf=sQ~Kfr-T^LBSR6 z8xGjoVh9i)^yYH@0i%oEx0SEgCV#hW^n>Aewj=g)pPHrJU21k67(G55u0!jcKdv#u zb=_^GUF;i+eds>AVF!(l0M6-C{+fZKsc-7KKA5P-#XlX2+5CdwLq0?w#jt^CiJ=`~ z{Bx1WoyBLBIvcMMM8g0mNxpLhi*A88OJGcMYSE}k>|`M0lN$Tf5yYuC1U>3Z-UWD1 zzUR`u!*1<2dMm!qkH^auHK@2nof8Lgp%s|v`JeH;`%3l016A}LFm@Y>mp~Q@1dOi@{!nM!l z(wMdX)2(YUv{=Q9x@x6YUGbxBF&XC~6y&YOpi zZM!j{8aTdPpkRe`M_;ZM&5;VO6cCY&=WxDy0QP7IpQ9faVVnG~wUw>v0`l}EsqdCu>yY~%r`;Zg?^FhN^S;+IeX9A6E z{6+hPh51R9eUti3d{W&PO&2#86Kf8cP)b}mN=dZ>7^{NCVY6uGw3{zk+zm}58HcUh zvlE`JapbgN8#09GFg!3c=$2og_bTeFD+hlrv9oEo)!3u%5TwOne9}uIXi~pLD;|yf zg68ZTu2V=)1(4$zjeDf*`pHmIfRLzU%rb1clV5KVc6duMG z%h-ocpwtUs@fYm7X+kdH+0W;AAQRlO_KFS(yKNb7O*n+f2eY2W(67~ynQtpV{Ko^Y zjA{;9BdaJA-&DMqAV{t!^j^*3Tfq{7WRPXmD)8c3mLql<%ExM~(3x9Ev~Z=9A>6Gr z=vksEh!i&CAXX;ksa2qap3U1NtGUx-3ZaP8B@KS>xm-W}im~pq%Rl98V4vLV5)~|6 z6Br}0`c_rQX4^j$<*4DprA_}d;+s8J2JoXrNdzwL3z|<03k!a46y?A(*clhTM_UP1 zk|i%U_zw88eg(IuL0)lKSlIVEJqZmVMJ&tI%9lsD7yr4wrE6r`)ZIO-7_E{z;3?OauaxUVkpGSsSLkh_FCzjmp z58GC3Ahd5VD4##$A1&mHv6oRCEVj%Evl;@KH3s_h2hqseDFL@UxA67mH4#0k9h6);1yu>$eF<5j>G;RtIp#C@o! z06ZvaG}x(`nOi`%37wEdOG_Q}Q9@ak7ixoN2NbStmU&)6%3K+LQW;||ff_da4|!b` zp(-(}Ft>1gC_&xNi5oA8=8tWbqSRsJ!|uLD_dX~{mx|&$tHIeiJC5Szo@mY&Sb>i? z^13*eAC3jxZty#Q3QrbWAYBDR!`jWb8`1oZ;H&fxbxSNRB6L}@?WORT_6TTA<^^Yq+P%S#eP$f?-IYP178 z>izd1VndM#vCoYT$52IdMV1xyUxDZJgruIUsPNQ3hZ|WIw}Evgoz;3O8G@sRR;@xp zB+kllxAnk(D<>e=!;=Zjqpw<*tfv?Jo;|oS3bhxj zQxF6Ew9C2hMJqXbZCq;QO4?@^S1S__Y)Lak7QOfTS*+8H*qW4c=-NC4DwD>xowv@L zNPNAYJcEI^D@YJ&n*{*gZ+$5VaAfXdEzZu&+(~!>^uD0g+0IgII_v(}tBu4&;q)SW zlcz3ER#ukR(dI5UCME_1VeyQk{V2%9R^v}eOr+?+?*>)gOIi&WgMeT(dwBW)oCq9X zF##MBg>JX7>{gov0|GsCUfoy3^iF`hSoWwkD@RQdw*7H5&bwsMF%sd$NIa?gFn>sc z@sV)2V}jWAbH8!Lsd(7*<&U?=p2-j*3_6WeQkYaAlI`-W4(lKgmqmCwhfz2%{oQW8 z|B%524B{afv1^r+yoZ9hqUT}{_ZVlV(sPws0m8_L&)#s}@+PZwsTqCT(%nX6w>@m{ z;jc@tl4(r>CW3ukjtwxpiO(i{A*s~L*_V<=Z~38OMee%!>l>O*wU1^^LOY+dBfb0l z{n~R`x!>HW8b>*DyL<0`ts}*1l2zmg+sx$nM2Q`f2~i z-rnB+ooaj&d=MrYnnQ}yy*b;km({roX`$C2R$k$qrB;gQS5fuc_2D;|J-iZfv~1XN z2O0(Mjr+U1yNbB9|0da?p+IPrxiAj4OC}GKUULr^JONEJ>BAa4bVB0)-!sP5^9(=? zU_D#mc(x%4^g^Cu&E4yn`O}|)UcU>dF&drkQ4bFfy;WJ571vTG7MZn|%p$f#R%iAK zdzcK>b2YBt)_G?->=K_0B|{cjcfpIrEv zWK@5VYJJ3;!V+AI@Yan>H|($hYm=+NvF?k|M)Ft4ZgG~tZRJ*G8`&pMnep>fsaWr~ zHP1kw{mS=nrV6p?Dwzxpc00s)K37m`~>)3vjZxIHO;*YU zC>7^PxPfXRDcx4B-vtz3LckEu)Mb5OElw$-8m#sTp+b3frgdU`HEA9VVOWD3Q_3OM z1bZ4vq48(K4!}#K{)=}WB&3rJY6J;ylVKHAVU+H6OUTHL`)5s8mz4brJyNHPvL3G= zH`=Bt9Ho~@7~fut;$I$rDA8~`^1hrpyz&m)b0n^*ujj(V@CJ_oxktK`4``y#P=hDNbt@w#)>)&rgLS?&7U7OdMy?suBY$pnhL{C}#|_F5m0 zur7e|36jA&(Q$lR+t)r$_x3%x|29tJ|Z?-?eB`_X-{C(;?{mvp@ ziL7^b^lP4@y^e6MSNB(BmcS0BjK@FMvaAiq2B32KKL5E%jRv>aE__TbZp1tdKO29p zLAwlG&mNUS+iXd4+vrxU`^%#uSsuQN=JcBe9jSE+gX^FIYp(3qvSvg^M!v^|m;46$ zEN?{zu#|k?84kHne8BFw{zSqk2y##d2o!UfCfew)nQV| z|A)`N@KE0Y-i6AZxf=#6S*!c%t5lg~5jE0^Knx2k^akKwxA6l(?HdurHA z??bdd?r}z)+%-qY!~e@CdoquFw2IW$?0M#q;>7OsMM7*Rf(%s6#{Pzx>b3IvH;vYB zD)w~exeBa$?)sb2O}o~qV4C)RoobP`k={;Ace-_JO39>TioCl;RJq1Ds37l$4avYQ zAdkhHNMO2k`AB!d;LOYBHl6zXLCn!!R9Uwqv{=&hN*tE6kDt?cw+j)w zV?k6Dh@qDR6l~$AvzVA>xtGPLa|U<4l$JH95tcf9Nq32dhK4}5rpACfAr)w;679v* zH&sIW8!Zv|uU&KhLbr#`X(6OV&^qNkR6=y>%@t-XzC$Dpw*S6a)a$w1Ze3+ijgD}) zgAgB3k8>B+A*JL`hkTtbIl?nlD(C(8#xD_u0Bb6MPjywe#3Qc40(JsUH3NC*!)tHs z;%Q1b2-c?L=mjb__%+avVWPtBk1!)POhb4p_fUn#aTdtPkKST1R!Sy2B0HQv@9t&I zNlvOM?EcUo+caGA<>ob8-FsFj^9=^1JN2_i32l2|eW$#k^J_DAOv!BEmuDFHsB?R| zK;bL+(P_DMrr$#?_T#B5Hf%c>LZ2^!oXfIZL_P8%E|TPgS+$JSF(x$NgMxY7W6h^62s`8?c|sW4oq zONuBfnga5E-jFv~RnG2TWJ#|!xA4tg!`l7L?J~9OaIA(|&zGQr;XY&mOT07CWFC*# zzoE%X*{n_IEu{UCKMmWnc)~ZcQ?IJ0!>-DpRt9maJ|`L5<5Rb_A#ysRI1nb*?2fTN z+k6LxLPyP&z{x7Y2V!xEd-Fa**P;EBePH^>*ly1NHyo>5NZqa4mFmW#DypSzS=pN4 zD&zQ>t#FK=EnC=Q_@B0vxpv(zGJkRziaA3(iW{g*(%TuP&-%ud6J+6{l)rk;Zz$bE zmx%ylH@}uOuWZ841;>l9-^x!-aVZs6X4Tr;D?4vEw+$zxuu|7!zG_=XvU*p#A#G$g zl&h7ad`+-mOZ$E`=sLK4E>b;Ch5({Hpb=#aH0zZs>``&_x#;fPvp0+Xp`K9?N6?B$ z@z-Bm^X2dV!nQJ<<|m+->r|e_cit=GQ+kn)nAbGz-tg~&B6~gs^5$vY7_@E%0X_|j zX5a@(4c-<-m6x!3uM5TIWjkQW9bD(SIt%k~wQSFOua_2oZk4dm1S$%X+8NWDPb(m@ z?d1#5nEZTVzF0HHycOC23SwY|Yw_ic4+6euHTtvuH~#l~yr=Jl=&Ek}RYc(OR>K@L z8Lh-Ip4>wTx1Aog@Od0k7$#2dMg<^MoewNo9bOnmnhe+Utn1n49vC^)0g4@4Q^?Q1 zLwzZvM)|sgM<6hraHhJUPm(E+Y)Kh)geL)Uh{bxCoJ@gymd=@>Vloxb$hZA0)t-f4FC>6*9Q zWrnlASI6BDj*Ja&;E8x96Eoo6BO-KOzV!O*Igqb-u1q~UVTW~&#q2_ha1B;JDfBWd zDs`A|iJ+tAr6fnWTPb_?R^-(J_s6!J`(8cpS!t@RW6U1=Kvec-nHzjBdt>)O?#<2f z+w%q^v0J-S<#~|AeOrhrzT?CTN_5m;QndF*Q&{Nmj?YJzr>oAqmHt8FG_BLpSFJv} z2bhu=K=UU)L`X!m`FQhRW*qRxKjwS=;xv44aL|7E*MgA-RO={(@h-RbVK}mP!3lNp&1k@~~^4^q=+BvZfvuhpGm`GrwM&KHSKZ(|)YIYEke| z)hnl6f`vyN7KR|I))jc^T*;tiJ0LXJd`I`_YR7Kl=J%tIxUpAe$h~5Rr5{ATXCKuG zwtZ{z?5|BL9m*Q4*2MAA5LID3MN6L+0!fa)RjozKIqB2g=6T32>GD1%WTsBslB%_p#dnH7>zFwac_Zx__~VNq-~?bUdWB&Gs!~dqm!2Ud zOO?3qXJutkS()syu9{l3V1|4hV2z_eMlHR(me5orMR?_c$nR?LX4vOZl(Pi@LCT#2 z=hr3qCMC6llEW^86YfW3((QSnwB_d=HE&u!U57b0lAgirNdyXJb-i4nE3_syrbceY z>(XPycO|hxFewNh-1H}`6QYH$r2xJzzfgGmnmMjvT=fe5O3S1Jmx8m?XIe~koRr`+ zrybVy|S%t79*Dn`(Q#t zO{KTBzb%Xdw&7Mw+t3=5NlhofRX&HpN3DiVM!hwq>8v9`bNr*ved5{=5+|ux_J9_{ zcmLdpiV>|wsqxg`fZV1>m)e|@&-N3T?nGHxO{`O0^|KZvPNSk+yl8zI{Ob=}uLzgE z1!C&M7ejN3*6$ZuE#EiZ{G3<2mY_mBrCJ930YpV(;Nmk5z9TlcXu!#?dTsACK#?ik;-Ss+PwDIan zoVqsOR|ny98sT4K)}JJKoj^kO{;0(%G`eBvSu0Xy%xiAB;eUg6e|;UU7H-4UVnJW9 zTW8IZm%INO!RG#~nN&im^rGxh?tz?wmz{H~K`^PNuYtb2f4gDzrai|vR|L=n!Z){k z7C>O+b<3kVK_^GXh`0M~jGBb+3e3LtL%e` zLaz%@mUDxGrF)dfPvMv#b#=sJRKx8`8oy5_6{*eE*4XoeyMm2q+4$|JEgKx7=VF|2 z8%22G%!&_)&oJN@kTl9s|H4myE~d{J}Z6*qve`|J+_rkV?%NL{u3> z3{;q{mt2e8(Xa8B*HI-5H~_uFixg~Lnl!5Z;V^jE1^Ssw{9%mTmvJ=)@yS^RLMndQ z_jFfQ&-bMTk2TSNkw3B<6SsO)4)#Fb|u2(Nj(t~ZS zTF}at0b?OhnTy{5-Xb1RfV3@4PsT|$&*@ecddg2lMR4P)TZB$g}0NGAZ@i8G(VC_4d(2Eh6qu42f7K0 z0P6^z^;$1NTOG!iHk*3vW7D2tqpu^Aq}4$Hc7y9<>!7_*t(7BW{81Ri1*9 z!g(jW0qok!^|zlj}AGntR8KCkc+gO^CZ!s=Bn- zUt6vRGSY49*Pfst!|-(|S#M$>{8wfrHHojn@XT%F=gutW{*oT+#}YBY3$teV(aJd) z4dMO1W?{l7n7EKpGez2Nr8ky~K<&RX5FJ26~ zlYm~TMH_fyMhRIbXtYSS>613wmrWbzx3m7cnd@!2E^#DAL*N;0(kqAk-oUthB|=+w z`mLNl;r66Ks5ezGqBq|vMy~L0d(YQG>^dvkv4q!)B{QY>)kla4Jx8Cv!;KZ29fCW& zx3Bl>!xrMz9pCc1GEdZa)h&vD22uIhIV!{oLf^WjB!aK|n7fPbcH5|O1#gw(XlW}k zMtMO?F}5H{`{(kqmQ;Wy>h(u_Oqdm-GvL>^2`)AP4~S*KkmPiF0B6vk-x8Y&`Z&68 zH@DbbmDH+`C|Xp!M5wQ^$Zwxc>RQUfg#M^ZOJ{-(F&)wHfct_0N z{i%i>hN_A|>B8-+?@ByWRmSQHIh2A$(fCtKZQJcpu}~I zDShl(u#Jp~V)gbQEaz}LT?X;*Cn7Psw))rtibpL@ixP|6nFi_!hIUp{lhEyM>>Gc! z+R*R&Pla5yvXAb{5xfmVUu}sB5eX<0;8E^lnW@DpkdIs2BU4PGdak?!y0+KTaCOBK z9V|ZT@hc2{q9V$#;8m8luFRj;M8@b(k5^y?D<|S|7RZMF@^h=-SQPx}(6pslq7Ct0 z%wzITpY5*|um4PLC7Zi@!&FUQ4oH6Z%c~*gY-za~XhFtC#itEw;bK)RWMV<0GF;q^ z3<99g2-WvTbY);)t!G5Iwk0?#1-PNB-prC+!@g@hd25TRn`ZW`U4wj)U~8sbL(3s6 zXbcRn-LWNW`Mde&iiwUFFSy=sU!cc%&y%*6zCd4}rf9GuZvVt7Fo7P`JIN&SUG~_i zaQd<(QczdF#HcQlG*?Z_)xeNpWUk7R?{e++F60)AH9#$#1qBrDH072YL=ujX#7 zSS&HQbw9LdSol5t!@?Zj3VHPB_rm`QauWIb{i^-uZ$RXo1t^AbK2_08u|gM1gT@uZ}f5YY|UAfbtS& zEW^Q571eghNd|xOzE!ncfDT8VB4h1M02ta=+gGu&bRuWx&!mIt8n~vl^ggYFOl)Xx zEp!+Py+VxO_5LHv02cg`Z590B`)m>Xb>~4DiAxM!tGef@R+_lDk2_{^GB0(k5>1Bu z-HYPw{SuJXQ|mGqONXzCFZ^o-H_}~32z|qHb~UBR9TWszSXtzvtD|I`5_TIbR1C_h~) z!+Cu}%PKgIN0h!~rpP<}@(y`D+Z5r6!>e6z;H{%QA0w4zE z4)%22x+^XJ{PDXdceI&U=ICgdGGf}_geqYEd ztfr=>FDtkIFOACJhLgCIt7Bs+Y1ahz6V@gc1y(!Yd{;Cn z=_do-_TX)LM|f*wX7)?7N{wHLou&}%ygLe-RUDwC5v-jVV6Vgbn}x7kEN_zEIg-KM zIIO2+Q9Q+@AUZzf}la*u=}t} z0lb&bwS}irJCG5cI$ptDJhnZsj`Ht))u~d!Tl^--5)2}Xx5w(l7L5ej8@<)v_ zn~w)ys&z2J|3r~bPt#3LFXZY@=97n$gSeLQd)Dwgq34siUT~7<%GPbn*)Ptc0g%ob z1|0d`8xq8QE!rvqm6?hEJ*u$-rjWHVQuN?=z%XR9cZ3MqTOS=x+;-_YU}iz5FVb>j zo$P>%PHy|J%pg5(#8!28`H6lq2=GaPznD5oQY+zzUEN{%I$=LHpjHPyJ$L9Bpe2fbumdI^mI&Jc)OdjXCQJ~wG{VGYZQ8j9y;8U)*Q z9FhK;Vt3h--MbD*pG-9%T>50sjH!d58&7=lij#g?t(YH)kj$dhx1!}JmKDsupCFZV zu-P2S%%mL%_9b7D@usg<#^I~G$ggC4nbZ_9n^q=@|Fo^bTZ!k|5e8Hn>L9rdNJC0* zY?%3OcwUGC>6sGfZ-w2v0PiX$#t(HR;l4r{LN|$e-+rY*PSDwARz)OIph9moHmk)J z&}PiaJrak!N5#@2L>A<#e(nU`BsE_ zQ)FVcW+;9Gmhl6Yn91-%W7|$JX5wwS(%4_VWJtwoxzc!Hel*OlR!R)})vG!-HBjfY z#Z~<)4`JigHa63)<+jc@I!Xj+Fw$VE`;42xb4*j2qLr?lM#{`R=O9sbt*yDq(Qy|V+FBIx(XFh{lJTLkx7mXE)LZLEuZ0Uaw1b+j=T zA(8lf1x>W2jg4eD|L&Zn4GPXgc^wBAVc+435}44-%DN+ZozKyMQS;BA6)4A(8#GkW zQrso{gAew7X=1s*Dl=i)oX&&d!tRamqixh*Lj-v9OEXx_DFa$re{d%&Q-C>)KC2L9 z4f-Y7aB3>?W>xKy{IBd%BlwJDdtVbY*sU1*_&ohi*lGME{osjVD)KxGa;n$zx8hAL zfng0&)^pPvv+-<8Fa`U1wi650R6yC&L3(TU?s$8>^v+&jNuST+OHL3J4Rz5wVCNJ{$Qz)G5wn zg{j;R0rm~dnvrX2BvgAI;n9F0oA7~E8~U|(#ACWWOCi~wXYg9fqA||~CHWm}`>7fh zIP6)4->{JSKFNJsZskf+vn;a_NBRR91Yb{2CFP6o!-dVM^oSmjBptcacGn$p~6LSJlwVF(51m zvDPxvl}2@H$2yWZ=EG-*b!k?wR$zUgZACaXW`sR;3yPPUglVxzTXi+t+U6o~6V>}f zGUo=udo?`2#&#|oEU2stzJGbPU8Jo+2*gIi^ML)?d|QhbWIaS$uP|{o)rL#n*5Zsa0=@yOI{`>YDR+X4Vu0t&=S7br#I4|H!N<0GGM96I|SH(klGZA zkq%g|*6!g1X^;1G5E=PcjdMpg6_vkEyA;~K2HEeq?;yUYtow!6T;%xKwaiaf_}Hli z=~xzV7w$bB7!+7y5WMv&jM(?o0FJQwl#6$@u5cI0a(`F$jepZYlX#~aL;4-js?eX+ z=rCXQF7E;A`ZrH>Jzif07K(;anAy`Hv@7l28CM>UJz8us`W_RbXAKlf?%6!fSb{}} zPjp_nVX^=nrpNU*$R`!-c%vbw3b0>AnUcC68f6%8I*X;#2mfSnVC%GP$;hRw+sbZ! z%rqg9VLb^2l4RIa{1^IQP3+ph_We-+1Gd$(zGz zm-Iq7autK0CiJWawa<1RHLVmFqCV)nJ*|xNYcJXt*#Fhu8r*JcDE;qK%k`xYHSp&ux@Ib0NplFHwTfDW-oiXABtT2&op@6tc!1Fp1m=kDd!c$aVE5caG z8p*`pn1KPILA?yz@K{WU3MV$QmA*+ksR;bhEJH1JXAIhBsNe3V2Cs~xZa?`wIz@U9 zy=J|$fScx9$Jqb$%OF}6^|Gk1Tdq6HRUd+-Lch|rJ+7fBvk}AeIiUWSrYvV6FfWS^1Dw=X8oda1i8~I*x@AE`JNq^e%E z%BkCJJl`-(N&KM1gZJo?X60R5U0XvW{HVZiyhX|YNOAlT>>b7O=W__S_RSyai_s^( zFlsXzDDlry4MKwJrtM6eS=D5z9v7pNt*TVCFSnx**{IsRBe5q;74D6ZT}0oRiCR5* zd+1|T{`o?vcd6^!QoiG2z=T{^tU^TH`mFHZ8O|%Ub>Xh0s8}^&nOS^hHCPrF8hPZ| zxW5wnQm0jtjhH9&#gN{-y^CT6ZyPpJc8khpk81fxptjD;7987@jsZ4%jgJM4-` z?9^27i2te=2jd|qk>|mdAl-czO57?Rdw+?`ck%{)!Sms;@6Iwl^9RO$NO*fuC!FEC zC#lFt{-YG*k0etR%Xos`T3}c;I+j_aQO^2o^Q6M43zGC;x=;I95a1=YM6)CUx&LsO!^%*T9o%a==H2O5c*jbGqkU0EUIeXz; zx>y43sL9Wz&e_k=h*Y@=@u5NLDd9-3h~O*jkr@#moLyo-iGo%IM4t>PlV8M9QZ+co zr|4XCZ)PmKB$^Zu+3Kd}j2#nqd$7eG70mL}ygFK5lNWeB_}_`#PiC zYMX$a;A~sAQc!CJwQRe(jr-Wd!WSvf^yP(@DmN%=G5N#J@pG8ceJX_fM?qxl3(e78 zGAu8Y-|gh`tzo5J%g$r6YU)-I*6x)7Ec>p7N5BB6y3wYn^~&i3p7&BFS{fK8I?i*A zcS2rwqD9-+6r6r`de(`)e*W95U$Zxca+h*9PSF|IaWyN``)$v_EiOIB-nvVeL~rM` zTcQrYcq_gEiK=Ap!APjl8rQpz_!IdoN7bG)&u{sBQmac+3xsDL@rOg!>sb@fNMk%n zhBiAw^dJ9-`Ma(7WF$@Fd>3$cD(+*#Mg}7B+(oPD1rexR78HVPd{Xq;|0p76H_*#h z!WA9&v>gxm2LIMJpnHYhZl3q0@Z323u%G3LbVx{+)5=YxMWa2sdLRA5c8ZnE6^VnA z9CgC=v$(Z*SX;WOTG;qOasd5js|O}6gy51I?qV(njGWaaftj|AfTg3;T(L{g?bbGx z#_?kNqpQ6~ryi4S-TteCuxl)HM79&^-q%wm%km!9c4_TP$anryf=eFRK0j0&vL|nf z6ukQVrlL@IjKxj+DEubuZzbzS` z57GSq2iT-yDnqh8NALDL)v%T_01uKC@UgT%04gNRDq1~5GHUGphaw)&YvRpK6ED{r zCZI3j$k5ptGs5?9^pH_!GYWQcmp4TX@N+5@nCj+7fC9mt+E@065oDz2-?NOHG}2kH zP^I!RmWSq*@}~^*b&K>%YIvF?sAs8uy`J7C#5>W?(Pf?-t!uivR#Xxe9GQA38DqR? z1Qb$u8|8ZYh-RIHS)!;Yz2gsrL~j8oURWEVQC_7TwHrbSAGk;SEw5pvHOzLgn}u5CeXSIm85 z#Y6VE4IOR|c~;;RCwDg2>EGqVqIxpJHk=b_{zM8To_g6yiS1 zav*a4M;;1AL0CrIWRq;@m1)Bj!5Z9DM3*J^%NjGQ8OVqT4aNDSsA$boOB9SE_-24!K zDvk(08&KR8>ablHvCzrw-*x-ywCe;T>i0L?IJZA&{u97{-Pvxwm6VkDTb__1&|rt? zqynCy1qji|)nY(JSjuiVW}&si2Cp=&RLa@G8V#MoPd3$j?P3)Pg)3UrgAyEaiW_T& z=Bj|BN9WX_bNpH-o+ldq+tEtBC8QpVF|7?2Y&h-(h;+(vmrwplpo{_c54zh`D%=R2 z`o@becz683GhUvp$eijyQ#l47hheI%38 zHGzfzFrh#En*WD#a7K3SI-u#;Y8 z*(34`hPZ*^G^7;4O5Gi87PXJdJ)M91*QquzttNh=9Ix|?{(oEm7?IeoIoWQZ7?<%v z`dHlI-y3QBt?9qZTp5n)SqpOTwKSCHuXp(CI5Z0Xn)4;;E)^pPdg@2#fKsqw88p1i z(b6X>iyJ^$V4y7op=aOLlcQAY)ZS+dVd8g#T!x||WkC3!|Lo}F3J@QDmC-U8bogO` zRHL0vl*1$!yAGF#s{_8FX*0fNaq7MCL5|P3>H0%9FzEg@j{~$Yo!TvjJ(Is|0ddT7 zYU<#?${>+Pq-E0F*4EZ?9$c4Kb(^H#h4uuOjL)9`mV2mvQuRD@oF8v2zL1AI4d8_= z2AaubdMxHOezl5F|FreU{QC8AU~KtIqF)_GAxu*703K}kk5HX@*Y zP#Ifbd=GxDf^R7?u%z4=yEG+Ki}AMK*}E@C+wV$NVVM`cu>3R$8TJQ^n`};k0&%vp z7Kqn1rPmUHV$M5U1eU9Cp`xo?EBS3nnJL}AaPP)*nVE-v;}^)={}p#ZWe$=5?+!SW z#t+6XpSNsqWIA?G(^veD&pwM{f&v)A;LvxzJvST879InseQTU_oz!H`=Mm~fVMqNtQV^7WoUfp4*|UU3fT3+ z$2j4b7ooYp(oM@phAV;2_vlUuyy5oPpC0}~$tOhgShFVhx`l%lvUeJyvT9#`Re`b6 zo7&!QX#3D^gnu4%vywk~!on@wcRmPh zgkzBQhtF3e&oQ;t;+rVQJ@YUwzpaMmO~nTj6!^$JjEg*9>#k_<9V%jho|quLMiuRUSD zvg$q*z`pTFKnGJN#!`K~W&gy)i`+8v zny`IIe=yDnweⅇZ{cCQG#0jF=p&aR`#cqoa7RBTj<+|a=c@wCSuT(+Z&W~{xQa| zg_U4)FVh|5spfYk~;P{mUIj8DJbWFgxC!nT?i@qA>27 z0cIkYDgyzrmX3~zk>k2ZfkhMrIu+|dgA^;{3AXiEG0fcdJQWhJ(RlW-Q;z^`RhhS@f3FTC$yTbjOQ4{cF#5to z{_u}ZRKHK%eY~2RcRRp|+G_1b%{jHS7cBJ4B!lZmaGKeDGR!EhNJ(h_TGM`rbT!~;8$qo9)y%6nMgL!r>xiUcF(#-5EFutHE zO#S{Hh#hlOWaD{5#Mp(nMgivs$YFnIl;bI5>lP%mbY z0N;AIzF2hm%V)mvR`iv|#3Lzx&uTcvo6Z<0(l@RWgi%(s!^}~5XiPi>TfU{V4_BT) zW4t~!Ou^ukrC^CmIWD!5?ZTAsq6g_KU{Jpk zRJI|>m37wx>~2+d?gVo3?-Aai8gs3b)?ClfA>YD=yM-st(&M)@gf0Qds6;DIh2|v} z*aOg)pgaH?os89YCc;r4I)3aLB83))u&jhf{kR(C+R|q2J8o5H$$1a!ijk{diB^Z; zJo-{7!ngv#Q#I-Zg?QO~p8F5crLd|FTyeN5*g&a!ocGGu2m7q4mfkqAl)0x|t9BQ0 zqI4^8^3ymct=;eQ%0J|wQ=%jEARojv$i3UILGzwgg}?ko4CkCrtFMG;=Oyi#_F7%D zf0Vb`F$5bcq9R>f2~o{qPt15<4WocgA96xf28H=i-l!s@oHgb(?ftZcH}*d<4=~16 zq%6B1R-&au!<*d=vSDeD2|x5!(Kvtr4x*g0M|+!Zo9OtSZ+-R?~CN)NAM8 zjMrxvFYpN(q?bpBQ&3X+d+a)CnnznH@G=-ZPp^3yyAW}!$gO8?b_F5R6pm~EADYfO zsH*Sn;!={*h)8$0ba!{RG=g+VBT7k!gmiaHmvonOcgK}(csJkQynpD7jLsd;Id`AE z*R$4Vna0moyLU+W8TxKIDSc>mhZv5TK4wm2ywg_eZx648^fl;2v=y;tP{r6u(I6ap zMBLeAsF$9%*TsC=rGDjW*P?WUQGU%T#If?48u=x7z>dmMf%t5&ms1|4Dy>Cw5X~I< zI{9t3(B55cOosJ^CAHjVHQiQ+*oj>o|Ic=lz0u5Xd7Rgw=e^T^-g+ct2;|f-dVbO7 z0kfXd(9^6%kQf4kAsD|3&5~xSuF`31p8*!Arg_x!f?W(spo8@KxmFJ6tW7P^7MI|R z3i1vWKzuqk&!a-VCDjXhq=@GDyS=B(V194w8zf6x{F4sEw`qQ8>+2H8JJ5zQKRFNL z0efX{Iob!{g^jqATwN`#WvF04!&$NY493WU{~q3TMYDDoR0}MkU#f#ZMbJMbwz-NP zaX;*dr;G(yAryos2C+cro% zi;8Dxkjda49^qYTemkw6Mn{k2)Zd>?WlvWvteyu7UpT`$45Y{0gxZ=@j0AEx6hGv}h3s z@PLhH)`_z44k?dpd*R)!C=ny@pe?(l6dndHIW_V}&#Brdpu>tuTqxK>(qKg@Z9aTK zhlNquictNQV!yg}v{@6*tcWhz*SF|5S<$TXxss)}Kkhur!_6~&sD5Q_1m9j&5AS}7 z4e(Jxk_GhDFbx}$9Jn?5p1%fv2AQfhgcFdjTDx!c(K9t|=t-z`)0$Y+2);aT84B!AzbQ zR60Lg**|g$J>T{%-5%9I;kN@hKJ+DsL<#2)8ewuKK7!7B&62;DuJ5*FWC!0 zrT?PK;K-ts&To9O{}RrCr!RN$CS!VqGpX0ffEDoAgd2L{>inTCjkS;?@YV}P2gq~s z4^bw>F>T%`nAuHcJXh4h)v$V_JV$u&F``DZ!FAn+gTN#us+N^O_}9|>0X94y?pLV4 zpxeY?8>n**rplCKQ{f)2@N!;MY(KGU8|t;hANKJ{KQZf;Z0NXP&Yzfl zGa>rnokrVjn_?mf%9raj8~z5r3?NVoKJ|=2LD*N0Khvr$+qusM$L`vCneSB}7L#iz zm68ii7HWj?9Us%14X)?I((0Kl+`2i4UtCr`5-EnLm|Jb^F;3>SY#bY}<+> zt>g#Cer(6P57{;|(JG^v$`(9(AcI$&%7E24{@1tQ&FC7a>)s$?-=2M-_m+>Xf)pEK zbb^VT6r1_B_F8TXnJp%K2z=MU#TR(wF zzq`sUeagbK)AvC1$u9g+Vu?n!P&gds2W z4M%t3Iepmr*-uKVf+lMs{kv=B2JN5d`oB?R=F$lAmdj3L`_IATEgz+`yJJ3`Qob2j zA9m>WFj_Ng`6>ys9N|0L%rwJ5jThz9$PiI479AK_xZ$zApxzVdt_x?5e81VI5`mP9vS`87jz z`K;}74^QGjx1o^{b)@I=;*1U_Cuim9Ngvq$6_*F4vorXb#!Sy^^wMvBS91PsUk`e~ z1s0)+L)kfa297Q~i1@$!0p~=Ivx`p$O?dEPs~mgH{!m`aWV3{Jl9l9!BvbULwC|b! zmS>0vUh{?MYQg$Vc)j@zOtQovz1H21nWKr5|JnO|)FUE2@z^2_qaR)Q%Hz2zgoK7dR+dB{ZB#J5?1S9+?tb5AA>IJL1U2g?d!6E*&}%n3kHN@%$U}I$d;Yh~6bvZAmgj7(0|s1K zMR!Z*wQ{{|KY}bjYZ6#G(SPvkQ<1KU1KB4P_rliaA5!cq1XvkC&QtrI?q`-xUrMSQchYs@ ztva?D_ECR=HYi$QC`dNZ+YLWVQn(HSKw7zk{4^YIYa&7K6havj?6g%z{CDEWNR#5d z`U!n9BJh;w@I(Nfv=ApymX3W(lx^aovDe#IRK?}jiew?huE@eRR zk8ag6&7cChJ^~z$m<$_2W`5nHoz%3nc+WJ)$2ex2k$Fl=_O=0~G(CM~P^R5sJ;0s- zdQm}2Vo$sc|9WSKYKS>eM_c=&u`#K}5iepcLjyf(ZI%Os=V+{N59s(}&YX>_Q2in3 zejL39*E}cdkYGK>58nc?yAv0p5U!ACxCp$m5!>t)hXt5T1&L=Lx-$(4o_Gekwx>cc z^RTKw$!~2EKrHB=65XM89WV<^cnth~ccDj-jTmE&b=86VMpHA^02C zkKk@EfqadLcS$2y->tzJX!#J)M_=K8v()Y*L)@@%&jw6TEMyH~qg?X@SW9rh`u`?a zJQYoSk1D$E*yAKF2+;8soWXUhHJ8#107HrMFQq|vQe2ot)eskadLwnMx>nkc(PCn$9J z5Dg72LuT~a(McJqm7eALSSK_7xgO?F-$<&?sLo4oMpx6YEmx%i1A>vCrhq%AcdWUZ z->op6%ewUEaV}ek1BMG~8W(N~;1Z%^H)6+j@dydG&+_ED9fvzRq2-v3EKo1BV!W4I zQ16l@g(jneZ){kvY^v;CZex08upXPDEq#+KQBItFNojinF}!9?#>=`2;_nv@E*$Q9maVCVu3gXyeUg5PX|oBNon# zgbfBD_Ph%_+9lBD456RqFI0rS%V4cxaGx(7 zJD^rAv>a68k3XFSPZI{Wk72C*Ey8;|go zyqI9VD}j0el|RLz?kR^eu|K}W-arNjt3Ie=tV+)m5s^drTTl3@RwrY+Q~IvfJluqb z13M4srUh#W`gbTmFiG}LKUIw8nP6vQLzQpT-vP$*7egp$QV3_&6D^R_-wzczmsxKSGA%QI1WjJ;tGs4KV4LH|;CE?S^fo_g=%uX>gp#M_rUdDYUglz=ghCA4BXSm zJk=|Zbyr`X)jCe1x(}@jR!WmPD)^;$cMc=4Z9kYv*YDqn9Y?iy?#8;uYzgdR6~qQT z_GkY>TJA&iwG#DX8lbleHJ_5|Zb3?RZIJU7xK6)RFfbj@z!$nI`F1<}nPYJo$3E`C z&R$2oPfOp$(KMiW-!t;(nESQqNbAs2MDDLln7g{KREs>PuP$+MF&}f@ez3Nu zEa;MYJi=Ka+&}e3o$?JXy??TQT(RT>5O$d0nO}Nb_N-n{{4=^w2hFQllLHpz>?^)( z7y{(vn}7bR^8l4PqiKA7pe?1r_mMYHloYQ9nKRVAYV@yNtw-ZS?Cw~``Nh5(Cl{yE zI0 zs9>bFk6++OU&`>3(Ad-lHqARcynV+so3i`f46CyG)Xg!w;VPcGfihxmVZ-ff+m+-5 zWM6daE)Ly5s;+6{PDMMp2V(V7g=R zTN9`tj1C-Brh=0`=fCKGB0*NaWK{TG(mxc~`-Fkvq|fGOwmQdI0=v$vR9-iXG=lzy zXYYAE)O(H9HOv(LVBvoSP@c0aK5-oXsuw| z$_!5!N7x)v9y@zhJOcM6_>n%EKyQL27I(EkN|>V~4a-dRp$an^QH06PuYIV}9vXb= z5S2TB2F7ahPL||!U6jVPCrwr+@o`ZD1Nao_EFlhGd2c3+o48$-W5Ur(<5P_96cK7( z@_9(pxl((Yhs9bB@E2H{X@@?_L)Kb9lNb1VuQ|YzBEJ7)FDEDGL&_V$R-gMR6Mc5J z(O8C2%9n>o+Xl2QgI-CXJd|l7=V9YA=}U|22CBRdgt4VT^{8sqzEIq)Y|u-S-ra$T`PZRpE$Nrg9gnF3MvZJC?nDLFUtg1xkOvtB=_f zZW4}az)df+Qhep?|1KFjMh+#7Vb;4IeuHuxaC2Rir>qdDEBjQt8f`N|g8uaf_C>@e znGJR5h-#9Q0NojBLzYXzD%zU?)O(zY!D7xr%44{l>M=VlIWMQ#u+PX>eP3^qQofxY zTwdvkG2Yx{l@%}{9ytWa3G&#V2GoV0+?+56q&O8OzMp=L=riLvJ5a7Hh~JiiA+-IG zG1QDzW;GL454y!S>v5N+s7b{Ji7Zf_s8XFA{v;K0oAaKo6~lHy$@?;|v{FVqA{-g^ z!mQPvaq@{^A5g|k1`A5(>Sht!dWS#A-k)RA2F5dgHv8`zSZ@rQR zPZ^+Mu=I}G)q|^PY-ME?9CGMzLlXr^uTxV~Gu1RdtT?>_JK{t+a1M$B3WV{O#`H3N zwq+@Q9qXQ=Z=EmVBb@S@$1|^qV?mi*o<{0SBt4s(XdKVFThwr1dDt|zFz3AF0U)Do zrwVNYyrSHlDEd6GT=BG}LJ+7j6ruk;Z15xR;#$SOFXd-6)nfe5-G)Y?9)`(#i@L2F zs(S1I?Y(OI#l8znyY13Y7I+qowL7zpFe!--sLgtjG(O?#c@zA zT0uKE_ZAzCsnp^^tc-5T+S44B0)uvz;N;h(2Apf)$<0m`+lj#>uOg;w5N2NkbQz9a zUy?$PFc-wfe^YoWXkj+Fm00yu^kxPkAyUrkN3_X)xXf`F6^GUBZ%41LKuU+PWJGsS zEE&{|JWP-DQ{7^3`Xo2xbXI?;98nCXXgLn|R$QFxM&@U{EVO%%NQV3!W2{^`3gyZD zd22~S*ptVFn*C063yGMp%J|rC`-LXcb_z&_n$S!k&YLpAq3i+%p8xj(I5l5ONg&nl zJ@EV{uHqfvim)z%xi(QItbNWcRiOG(z2qMbC1#`07QG9A55VDFT~+01eSL|CXQ}XZ zH#R2bRM*9nUs6)?X6+l=%P%)`Q$0s+?{2wznf=!0>jqGrJHM5WSEtW+S|J6{-Nj`H zenR5M7*;>T7IjvcCo68c-Q15=I@?^D#UxG?$Fqz(JW z>Dl`eyI&;F#o_01e?Ijsbkn&DwsjqBA#KucF5MjYLBRhl%u=P;_pcuL_SAB797r^+?!id2`pSaH5ZNY3qm5d49JXJRxUKbs;Q~4}!9nATO@_&!5maI+zkCr?Qe+kMq2LZuth^>x8AD^kdtceka>dTwe^VL&yk;%ixY2d z`iye*1&D&LWF`h&!9UJ5uu{PWfB?bf69&URW$p&{cZztzaq#AAfK7Osaa{+j-yGL4?r^6a=lN+EW3-ZB{)tyftGkZJLA^0lygecY^L16 zGe2u5ZOv1WxcF8>fC2~At0KZK+$uWo0u&xCU8%f5PX}Iy{&%;vbG%VSUvH(Pi9XEftKFA`Lm!-bz#*{(MvY%K8Iy1DE zm=XtJ*H8Kajirm!Wmg>!4T4g3xwM7a6{%-M{0eD4oT1pGs?EQX@msP%?}pkO!gA>h zu}n1He;|`%52I0uxAwU@PYMCBzsW>kh9EfBgiqxL&r;N%`SZ;)H-GvowVbSdNxs zyB;sl#!TYCaSAR(3=}|guPE8A-ucou7)?SBEz8|d>*_a^ zEy;M7aY?vIEo+fB7R0$GdTL@j(09`>5fY5)Sd~{N&iE*rV`u?FJlO|G2_j`Ty>ZI~ z5GK_#2;pnyOi95R37x?1%!SbCq*YGkTtOvxZM8kuN4HBshtHt}NN~)k*Z<0u8Fe4r zu0s0R7^L0z46x!gD#?S)=ofvoTl&-ZB{^OdIB=Cl{TqPE*{E6K6E1x?KgNSzVAkGB z?eb>+x7$mK{YHq?xtldl#-#1R0i8?6{%4 z4Qcu{Dhp}m0Ug$@lK+NsOc*Xxx@SdAc(@1&pbWCDIQ^dSfvf&)4j8G52agHc=N`Zf z^Ge&mfD!>3tZKdQumyd^Lo?&ox@Qv=6&1mBrC$H=<#-B=lSCUo+lV&LH-`^Bh+40s zmD(@Z2d9mh_*=-;dQVNR;1;Z%%8>UW_XmXHDNrq$AG^1G4}r?q zrZWsMK%TbstwXv)3wOHKQ!+37m$LJ{IH`t=8flX6?qV0FHA6f{cDfrjtn0)(+8&L+ z?w0T%RJSHE-c|kG!zd{wCF;PCBI%l4!I(pAGrasNQ8kN2x-kDBG-W~;D~ME!$q1mg ztEw6Y01kVUs`G$RIDhMB-c>>9ZF0xMuy7LjofHP!Vddo0ds+_>A(p+KZk^i`oQ71C zw^O94#ZtyL*;|u@SSC<&Kz5&8x6|cqUxeCRu3ZlIJ)iAx`zik2Uipp_vC{rkaXHI1 z$_0nm-E|+BNizmNs;2tl>Z|PqzbC5tX;4na{5mY*xUXRg!V2lOY+3Zi^=}ULDwRjP zDt;zPltZ)X@{A#*rGTTDC@@OR{4jW%`E8lq73 zVxj$=rCCWqj-n&RfAs1`dW{@yjPt<2|j%he9$zc_uqsCHdVy$L>nqc6`L zN_2%%cRwq{+W$>cS5OEFqYt?P{z=hZ7VO8Vi`A2o(k)CZUQZT;o_sRid}qnX$~s0x zL)=y2>>u8DxgVrgs~v*>OI_|7W>{h6D8eCI{6GT!h> z(?HnFf{_KD_%PUDccflF3R{lQMj^T{ujdnVpaqEa2)1z2eNxr_AFTUy6x6ay=&YxwPq!i6h-A48bV*4Cx|=P=(7&3u4z+#)5{bm6!eY zGUiwIp+~ELBgaSZ44psSL(XfB9w?t4pYI_aoI*n5n-}5Xn^gGg=4PpEx8A-+!Lu{%|69PE za7}*n{X3x_f2!Mu;P)W`J;@T{h{hZrZ+!Fmz5>gZ+qV5T_mElq%PEn-+62j*D$38i zo7ztuY{z1)PDm}+n)-uPKvSB@ByOtI=dpS{GP9NZg z=!XOZpxID^!;!52TsZ&XgIvYOl_Wru15UW${n)ggSUkbvWO{JymWN(+xZx}1H-WN0 zn#{VDuwmwy`+x{|o~E`k=KhM-6N7_sbo-BZs9v2?al+vJfNv3145en4=ELe#(Ag=u z|2yV`9`@6^wH;wbI%X7$%{W_=x{AP}AdP9EOj=mZW>$erVoI_*^WgAX$u6LUkNrV7 zBZpC_CG^3R-tbn;Ruqjkjt&5fU3WxkvS#^^3O1SVaxarzuilcG_P%9ntky3m^LKW9 zo!gm5&fR|zg#}hIymEwntx0B|1L$x>g03GXZsa}QH(m z*@M9u2sUJATqw#tMM>F{&6ulus1IM=_ zyCdJBZp1X2W!|mS^W=4zP%{E?{3(f<6pcyW%G!g~Mb9$DlIew7LK{Z> zlvc%mCxW(ic2^;*ZYw73pJP4+Pe56W+@#cVy{gS;S-m!*Js}T!{4rM24c8w|{zTCW z#*LfsDVY%|o3F2TDd)l58m;%p14T# zY$FDr#8kBqb>s&B&|Gl97!*zBSTKO*`s|HnudkO?6O{US)pS_(vi-XEB#)mO$Qj7`v6d!tmW%FH$F@lDmGp1`; z)&bbLFR>GXhu+Kys%HcmfeX?JZzy9--rB=r{GrNv0%>p_1 zs4cYeV&h?3+X&@yn7A__8L+H{Zv`B^rB!v3+z7cy;>xu|Z0Os|zLEKw6j)-K_LcYZ zh>RZJ_&lKNJdJ2A>Fsa%(v75!L)B0xsL3|d6aUEZa1miA9+`Ysj+LTlAFg~|Gd>*7CpPhdoOU?Tf3lmgnHk0ONLjpz zlT&rU?e_RMI;e#8skaO_c5-6Vuo5ahbVgsw?hBR7!t%=MxqXgYO9exIALlkMPEM;S zcRizQ8WVF@N{ug3ycmGI-rOxE65_`}_B8VD9v}6*k?N)ffaR~+zZ1>C+4)*1hR;9 zvxztESgB6p%kO(kcKi?^E>27#jyST0^KLBz zZ{60?4)N?ctR;*!-|PhYqR?Xnw8n^!d^UqTXI9p9)ZCsD_51_FoaQx$M6BKW`7s z?eVLG`pne-X0$iYD+DUyRS@qqUa+^eXZi_GAukJEKl>*&zphR78B3*{mliV31U`Os zx_u6{TW>+vdCz$%^6CRRDkamN`U?ht z_B!L0_w$SsrdChdeN?4PQ%7Il%+WE%x^{tFu}?+*^JE!~F`SOdkL_kvv!+}11Ut;%HV^NZG83`a+eeJsi8jmmHvHb*?s9*uzxygITxK0$ zAM_Mty0G5%F{Z`+&HnuY@`lmx?sg)q$HcU<*}{Ym9Y(KPVF0gPOc0C5^<#=7iQ&%} z-`}`qPy>siQj?HK*z6Szy(#v5nSFCSI;EAaLg`1 zf0#Jg{2SL|61;gOJLa5w8Dh6rSqb z{A+Ab+fS-pSLRdx;_~S4kHKg&`x<4}6_W8X9g*74@2^AE7FOo2HqGdYG7DkSHrvMw z&Haddt*%nMwYigTG-~rzm=!-ZkL2F1<6tq(BM5Cu1G7mRv{RNc$=qb7T|2|^N%e#c;}xUE`wWy~x67A?fd8B-8~e( z#?;rK_ts~XYkQLUH}ml@)SK$miCM}47g&g>(4j@PS7%;E32rBg-BYbP?;wyfm&rI<#f_@JPqq|_GzwRLOn*-&C>d0E=9 zV2j-Mw(mM+#b4ds2cy^QxO4k8r?h%m|Ed?#6=a0^Dxar)7n z;U6wRT^#+AQFUCH(?x=F>c|hTi$|Qn&7>EH3hy~QYSd@0)n!~?dc_6(mizCaYRZAx z(oGqKC?3;%jaem+Op4kdtXOLS|<|E%*?oPbd_k9_?RMca&Z+AcR2E}v2}u~ zbEztAio_v+A*`eN$bd?Xn%83L1MbF1gaYRbmsR~@x1+a3+8-a8LXn`r8)EVP+?yTR zl7Vj3!^`v0VI`Den6nbrt3(rJC<`U>3@*6ZOvD6^t02m!>37#M;fCX|e%P2#h9N(k z=kVWNw{<;=%3m0{BeW5Id@@B?;KRJg7A+-(eI{XlQe{Jq^98fR(dT&jxg2Z z(w`1NjBayNy|?ev%%M8ggr}+NPfyIt>eWk#G`En0Xq|)KFr@IAAA(mG;x8 z{hRc214$S-5$0B?N7A4_PpOnQcK&UN1|^YccD_gc>92uRMr!o>R=a=Y+5L@%R-sfY zD;gdIp;xQ;&A}z@=EuSVyKmySkN;lHy1>Prw_>i$oRcIDIc}ffWGe=5Pj_A4?+$2`ecvtJ-#2e9ho1}Zp!yekVk|%G9nlvoQLe(TWquJ05vZ0u zvg0;08#~YQGJiaeKs>p_pdwaK)u>L?cgk2~zG9BfX{}?~HyvLd#^8)$U5g*uhCyEX zDVtX@*$mvMysgH5rvkP*vkIxbiwWnCO`to(z(8T_Fw)!b+VJ$I5c=A8<9@}wLid_R zy+p%qwQc03tHp8iHJ9DeM>n^(uX0@2USo(8fPD=ZDpM6uc|6>(0uq-xSBaG8%BJWv zPRBDY)kq$}1jO^Y~6@a3ZS>?UpyFa)4c=lAc+obu=2W0u6 zc2y}$n?jy0I)H^Dqg%YJqI7&8i`o@iT@K^HF=WBmrQLfUGm+USUz@?{{;Hrf!%_2o z@q0Ybxy6K{zv50z{~~*EU&qJdJI^OoLvBs6~qqx z8f+_(CM}YrAJAK@A9&YwbMr23lq3PBmFO;1(&ZWd^JAm0dAB^SdzVT3p4S)0UfY<9 z07*kodp>U1$9-nbfW761$p`5!qZ3viJQD~xthY-YU!-jC<@;ZC0$Jzqu)Hc_7Au)HoblS&HTVQD zWCKn(P>lr82csvKl;!F#HXazsX)?79!S9#BRpx4ub1}qiyPn4UhMYf-~MIP5yg=B34%+Big*+d1C8JINaKG<*^ zOw(PCjF2nc%roo8!}%lH6Ff6%E{Q`IO#V5x)J7ij&>x6MFRXdG5X zvg9&ifGsjPGwRSvSlKqvv;3p8@TMdfjK6llTz2?=_8cc3P9iyeepiO0%x?HqwipAI zoCL&EP2UmY?{;(rw|L*4mAdbK*>~{9`e+O1@j8c$6xvmLQ^Zrc1Bxf@lemt0a|$%> zqx&~I`l%lWi!IafKA$JEGVHb8dOnzwc_PUcO-aV~CK0JLt~T8>4(*=%1cGXYN*kSb zLBNBS+f;jP({#(Uk(vYQ9&s`z6C_loxOiW>9~r_nlR)@nYBwaC##IMY%i$-3GC_BV z{Fags1aKPo&vNhCs+gy0{N>A>5?yE~Ey6edOm!f(ssJSL+c1EN0N&<8aG+Sep^jLP zKWj_BVWUZQ>(3RF#8!uWlqYU&X@g^uP-j5z=VfvJm<}E z1tZSiX{yo-ni{%C>6yhKcKCjL^v}#!X57wk+2Od8&=mF44q)MONZzYMpX8s-d~kt9 zCC!H9rX-^piraI%-I#gE!7*z8`Fnf>~{a7tN zZKEQ4VkEOpBm1b&$~?3Lg^5Vh?kT2s!ffd_H4N|dDp?mW*K zA&{sJ+zRr6I0FejmYAhrRmU-2f1!&%e{%od+4hinfpPQl4yYp+SkyBzD$rGkg4NN} z<5L}V@0|ciG7ArnWa6iP!7a~E_b<$=r4|pYvJdakDF$S(Jr2mp$-QqTf&sMO5tR7| zK0lnZf8uQl6#kd^R85B^deKa{p%>5w@F&9dWzO;332RECQ*sK2exEz-p|a2)KHcGQUkuO*1z&51j6i&_qkoVahN=p8bC> zz!7goylQwv#OVNa#=m2GzZ9=)2;tb1MN3S7E(un^?UWhQ7M3U@{qIQ_FEu*K4j-$S zF%;|5((9dLaoK?TKV%udI>LtEz3kf`rpzJ&mA;Wj<|)M=*$Qdo9+CgvsuN*+GuolW zJk?RtzDfe_0Jo5HdV#Yu3}xoGjF!KrB`G55?+=k&jVyouwP&?24Owx`I-x*-2KEBa z>iXcIpt~L4MA^LbhkxbYyes~t?})=g-a>Z8$2OGtAN3d3dLWmVm+9uUx@8q|&AMe* z;p>~&HycToYT)cN9Ow;PUMsfTEOFK^W=WRo5gSQT zkfks)L*b<+%f=K6rhNO%-nCg;)eAQ1=s&i=d}WVLA~InB%zgF+vdJE zqT4aG3FI>`agtL;ER?7|b7kikp~x;&Thz>R?KV$XT^J;sx{X_Xc(GxF5&k^j<9U{_ zmfQ2v={@5h!+~7`#&;0A1F;!!x;R|Syi^Yn9=o@R`2dUO+@KeE!$p3iWjeh3`mvEm zy@p>yEh*#OmcIXEHRY2h3S;1HvLs_`aydM$2RyaH`1Kq93qN-*#?uOkIirw?4E$k( z2;C`?%(s_y>$`1|Wi(5}SC?W;+(%=2OTnlB$+q*r>#1YOG(l)(I_~pcFas`Igs0a2 zZBqz3bzI&CfeM(wO6WaeZzu*^NnvYE+1Z!Dpi5y~`6q9m1bo9d&6rGl3TN+SVP)+A zG={1O4~JbS`jQfHM>mr+1P>7l!ZT&G^mA-)K?ozVSb(pIvfHccQw1qX#pl7ydBu9i zL;|)$mS>*+vuLH*cT+(DP&Ry|IWjH%uTB;he^{ewngwn7|M-)_gFV*&g>qXpv}!`- zMCglfO^n2ZMav?rSC3uUB@=bMsnpFJ9o;z>%YKX9?yqqluzqe_>S7KZ99(a`)q{_%x5Fnkd zhJ`-ch2N&bh|04+avT6^RL$|~F}P81QWr{mdrGb6MnZr4t21XFIH!W%x2UeEN!mm# zoVU^=P2mwHE?E#25Hex>k$~MzeIAu9R!yz_{YxRW_Gwr0n`X|}2-8%AW690_5wYuy za^9_9VnQq*eQNa@)i?h3guQwJ&q+lQXV`w9(u>>@9z{e^?C7?0iA`)TWc6d`#!|J% zS(XfdJB7Y{<-4@xg_`X4y*&{>)#)r;EeC%$_ZOYl^QwkP3ygr*vl80jc^`cKdl49k zm9^C1C%{YtY@=Py+qj?+F?9>jl5RkYma->`~_mXhQQ$M(i zUiw|I6$gpP~k6#{@)`lz1%fuccFSat?oIw*~`RUM?|1s zuZ4P zhrUG)yxUEAP zW>0K?9u)lL?<|V1a7}24k2roUf{xZlBc6?REU<$=V%FJMwa$Wk3b5Y+R$mo>u7fv8sZ1O6LbnLJej32>J(w$n)l+++SEjQfIDOQaLPB6qTE%|Gyu z0m=#N1(xJAJa-#ZUHM@$%;VMsGsoThs~#>O?F-w|5pT!fP`1W_KxvyzHOiKn+1f_h zS=$fIGP)$8!!#a4Cc~BxR;VZKb;pt@Gic=C=%6S--S{=v^&o!nQXMYnfu% zH18m2ZLDRD$-FLVnmppECF;Bera0%Lm~k6^rVti_@al9wPe-f$r{{XqM>1M?JGx;% zPG8~`(sn0xp@w8FRRM`Sx)wQ;jD4U|@+?NhstExZcwh7JY_p_wLYJ!h2@nHPW zptH-@!VHW4!s$t5GBg9Hg0U0d(X%tB8LrLmAhw+53~H(}M@MWNjH(x*WqSvV@wC6H zGSY{zZ;mws0IYZI@NvybTsV8zdWF(_%iaF^yVBFI(4s4Y(itQO%CeWo0*NuFWU-JzQe_VHra5=C5{;1W-(Fp?Dw>6U348MjPW9bwKb9&=7xbGRY4x*G$P_nHqFA1=wfxc%!?V^mNlBhms+@NWpx`3!#3}MzZ;mfy2r!C zRO)J3c3vGl1}+WAtS8xP7KC?A?u$j1cRyK~i?e`!@FyDGZv^vMH{7#mf>EGyq|B^8 zQK0!#a54Rq+%{Z@@9$HS+a^(_A7kmQd(os{>&`~IeOxpi)w|T5Yi_@G_?T4*S+>$- zXbHyoERpRJc#c{Q+4r=f6n;E!qRC?s@fVbYT5ddk_tu7yGqN7mewTphmgm5wj>?H| zgbFZ=`s-qTj2l{+EV5c`qu3aquSpWHF&0uvus|Z_Yx*0&JR8>=$06oXbil5=a0z74&PJjlhIej zD6!w=5+S~4Nv^z5jDzppDhogB|5C3atAbaaS!-cxN-jt61&)m&I!~qj5@k5g@QSue z@!qTba`H*DOmlv2PI~zYWa+@mqWQ_9%-q}@%qHq*szC#6V&*CHvl4g>C5x$S7FFu;0&4pwv7{?-0RpA#}FRnb2LFoacGDy zb*F*T_h&(hn@4o#*&BT4zP6KuwJ5Qv;{3hS+ZfWjG_cM6rW$@{u}8QS3Bz&mxBkuDRh{XS?*!&^WZt9D@A3LK9U1U~rjO;4 zW%R_8=;xY^Ve;rK>P*DtMOIvF=DTBhaT!F$C_alWjm(YO+#1vaijoC_^F6Itp&Z@ML3wWvd)aRP)+{8H7aXp?$=~H4e*yMEnBCw?;-vIDeWkQ2&ppw+_m( z`@V;fmImoArCYi?ly0P?5v3b$x}-x&x>33tq(NzJa+%=HKEb{1VPj3Bl_0%cB+>^|NZ@3$jpy=>gxooGn&Ab zol2wX*^2%FbFh^<9>e{!?ujh$Q9t1+3)T6t1^?)0@Dp9AhZzPfa~6t6n6I$J+nt*Y zZnD??W8x=eSc9nFdbT^a#e}EeeI2eV-ae?jdd%_w7m7WF9yGEW0wlA-|2&4Wh(M0= z($8XoFF@P&atQ28nynBnFCn3p z7@bF3+xm6Z;z-(C>c;xZ{!_^|mLQV!uH_XmEf~?k%veB>Uvf$u|REmnr3$ zA+BfE=QjomnaQ3;w0m!_0c>&s{joGvK~G~EJFbjjJLW}(;f=HiobR`Mr}r-mcoRXG zkDa#ykecdRlogCy<%drLh)4N*_#y2fKhXB=Uz85f(yWt-OVv}SraM7_|M2Ffd0}B8 zh$}Y(_YvjSGLevTc2~<)^(joA5*{W>ujoLhsXGe|KH77O8l+#Ps{g+>3|E9 z;y(`{))ptcwMteBRccYJ(aO`Uz--TE6>0vAMRF-m*?5&+p+`(9eq2_t+5h&O?elN< z1y!+^v{%2mm6MT+<9Y?!{_tgwe858>O7U}SdS7N(v@{@f9$1a1O^m*Deey+?dx|M4 zv|qe3{+pMp!$?7MDL`AS>L!Y`XMi5=m@r7YWU5^e0OP!F+;c+%0|R^*dS&>)K?ThE z9Q^!)U~3H6_k!hhlwerkpamn}^)BNVSQZCbnMjaj-c&URpw{R8s}dKBDD}UEUEXxo zrPu8=kHB^@kx&5Q?3gx{;^z*#w%MHdG3T4NqDW%H#cHIIv`OB?b(bl|a?GudQR@`Z|X^QDJVSL}~&gGBRC0xF_Igl4{ zt`a&N-<|bCQ9&$-e!KhEA3qpGI^2>8P*LY*H@~Uc{7&x1$ZpZ@LwJdBHkUU3{xAHC z?!3GY9UpAw^mRWzBk^_3iK$2NK8Qp}QgC?UZDTtH@1;boHQwcHjo1oJVh%>w(Wjgq z;lRE|bXnr1S(i)srNWp9s+y&#^8Kk;wpjR@7Y-WM&q74%Ew=RypkXG&@A6HQ zTok3jeh8p62UdS6%F2D6Uml(O9;>pR}nUZPE-2Cnh?N{U@*XNo5=&?A+yO z_GNVThEcuN(@H|GXF*w211N&KODIE^e9on>Ea&n(yYDch5R0WtkA=K zgkU!<|M-3ctEc9y(5Bh%LJ@oW3uALk{)ELzv9dyDptf6)U+)R>s>Y<%?};{I;co=( z*s0C}&JcItga1V*N4LlZvloM;p79aUfm?1gy0ni+<@n<4a;VUTH?2EK9=WpL@ILVM zS7r5m4y@ElT z`J~a`KesTSJN0?OmgmgwYC`faqpco?VsMjT%$qSLvnk5plgJ&E5zCbg+x6eE3HeQ8 zqx1nH+r}S^n`Qz%JY{5MiAcyy-Q1F0OA?J*%--$5ymZdkS^umJ>o2yVYiwtCOv&f$ z<&_o}hYbX$z|ot~R3Nbd5xby6zYwZz0oXmTX9$$0;Ke^UI5-~(XMEu_`Aad7NVB>$ z;od+~-zen3zsXt@E0@ZpbE#^80>svmxQWo*d`jC` zNj4DIi;ZSH^6&TPMqL&9NYZ%VA~b#sX9wVb(3Xu}OWxJ7@OTKLq$xWSY{u2>P%8Ac zNVNV-;I&e8H|{qV4Ttp+qh#R|sToz@vhOV+zYT-GuD<*^sR`!a#*WHg)6-fr{kSJP zzq;?_Y?%$hS4PZ?JvN}hwp4vscqm~WtyB4RN$vjrfgQ=AA@oTKNH6k1N1+88efCu` zBse`6m64gc6XsmFaIJriG&@)~N{nim?zY(O@6*{>2S4Bkzx6i6Y_l^#KaWpe%*_mW zbQA?z`nn63d5VMxLgaLf&!qhwll$V}-2PIHr+o>WzQOetIy|f>71Y@&F4YstOdNrI z#%_gO;G3QGRs9v{?r?gshh+e&8{P8tFM`veNe2bhT|lN&Bi9IO>jzkluzh$}izW40 zD6f^K^%L(GBbGYW6c#7vRaxwvMx%rIw0fJw<6~Lk09|&eV>|Y z<^9LS>Q}5{T&$I+!Yty*eJlGhGG}&1_Gt`Da*8o=T(z`LM3hQitOxaidMs)?=X4a; zTA`hXmD(8QJY6yg-Gbp;7ujopf<^{W2ab}P6X}`wc!QyAc#Bc*>=Y_{sf|+~V?psE zq7>;@UGOc^MCY|8TJM#oi7C4L`Y4&&j!T8mz=#6in2ZcEtr;!rZHHHFPNLbfgW7t+ zT^ENmxq0DyFGmAyCy@jS4bmv!v4yda)9Jy@4eWNIjShi}iw3228Up?{0q*`VM)$~u zZ%Ii>X~U_jng2vpzG+!2N&gU_#9y6E3W_?j3u7ULw~=HlHydM7M^ZLk>|MYdPbk}t zYwNDP@zJ&^6_pL5*Rb)CPIZ>TpikFL=)o7S;(oTffHvEz<*(koEpTOwgLZGsM3W`{ zdMGQ@d&&$OE+}eqKs3W# zvbyinaCaS+Tlw%8k2g~1f09|%%e1bSt~!)!=7zS@`NDSmk(_m2zx3>j zgD~bj*v$_>0wI4)maE53_mb>-tP~w;qR&fSZY`%uehHnb&NW40v2%)z_=zQugt`#W zlRd+7G)XkKiN;$#+fdek%^&$yN&P+-V+>t<8hxw1Lgg>V@pvYLLpnlCJPyw{I(m_I zzjAx*>++7c*O`ch>(5A*7)~8xGbfLP#3{|ot1B!xX+*k^ficrREQOa=BT)sD~xRt6wuAH)njCjN?Ex_GBUTfd#zz}VRVf)Gc_{8@< zAs3R(E$#ZxlI66N8eLoq-gBk&Dy}Dc66M2&4>p7+%iH2#g6E}W+l_f%t)>+=7Hfji}enJ?7ZUP7pgvw=&W?C7e;qU^Vn%K_nx45v-klo zwo0{e_IN(L_qj24pZlRmLZMB;QZJZz!LZl>u>q z%qG!dQoepwNsl=>fgRd1GP6sw*;O6NCF9vspX2KnXb&OKML_EWUAYvz?3x9>aj6i~1{(NxO2I8d(b-m5-DNL(?3LUBEO1tn%}gFRy^L zMPSW-enQ_mYxXGVe|?3TpY?9A{agHfLeS2r>A}J@s#*j3IIqbBb?svjez31Lt>?uq z1)RVStI}DwFQW@PKBT}Z5z-$Z_D^}xE^_VluL8>Ugkd3K}4_L$&ax6WB|FFh9+Bt<)f2%a8x2*{S2n{ z>7s}0pw`IJ8B3==*T*XFc)fASy`Bv}7+Rd_d!vllf^ZRA44hVo%u z^96*FgCqI&r{~I9eRVb9e*RnNR8#~JFx?v)v@4L0WqMM$c)ejc6%{cc;_U_d-yb6% zbaZwU_tRj1JbhWNO2O+Wc2ZaPH;N-id8_42SzOfdE%s3&Kr8Xu=2X3{mf7q0x)t~Z zP?%b#UoK!*C&xiV@@{BB^Qs})qb<@T}s_S@19tZg5apv3t_V@cUbU?5z2yHIar+Q;=r#0J~tH}dh`x5Akk z_^&~$yI0d@E@Bu8Ub}nMcU+TVE zP9<}G5=%yYK6%K_R&QIm|NQ&M+0xST+0L$}zFwwIuRyPCVtF}+o<86eQXl7Ap`M`w zwC=>!z~H~2!S(X;5*Eam!!?`KzWl@?Ne8ScY4|t2>6b#V9t@;zdm|5eheAyr+oWBy zK5r$zyGxS&#Y}koV|H7Z#YJq8)v}T;<-^w3@wfJtq}8uyOBO%4V<=%d?%gwt^wb;}Em&?|D%f@fz>%e6!oQKd z!YgB}?SvxdIEY3!>d>;{?~)Kwvf>X;e0wWTpZEvNm-A)#*5BiWyZRE7{x-;nE{YuI zdmv?um*+MBBI+eZm!k;okUoQPVf+cGbM0FIvW)o1*ARb13=mbJQmuD zJqk@7!0ORqwn_Vl@sHSIX}=Pndd}il`dY<>th~XA_syg%kvP}pIL+$W$&QCm@SDG4Rv@g!w;Lgcaxdt!fc=csTw7kR!7R#)M#AirDw#+3gytVd}1vMLPT(yk1L z{Em3{QP&gHzG{;W5|64TR*^`qIDHms3X&IOTKVt#DXGDaw_!<_D#9zh>-v?V^;E!S z-)50WYz1Um-WRGW;Y-2T4pE_tmJ3l+V={F)1#pCPDr~MC1BB{xSy@#>n_`V&k#0po zAp`3ldy1<_QW&=p@dYCSk4{Cw+R_x8X}34<(WGRm&dio9lmVDxBIK-}M-dU7=f&f* zysBtPk8frjdS48ax^yxc3JLd3je&%CG)#0SwueUXRsmy z?s7gIg2R+N(d)~*UHi{%ZIzVf+~VSEd7NDOT&)t1PFOZQ9S#vJ)%*J&prr-H(!#<5 zSakwVLvRr($B17dcn#w`XhxP2IRn2_erFAAIyr-Z_7rNxPN+ariTK<}r^?zd1ADWq z;W6v&ZqbFsR4jQ(cHUOI7D&GdKAPuroHsYsLoaSP3PdbIKR7lVxsUi<^&R|F=-O`+ zH%6~_1vsNdjla$#CTk~nDjo)H4vr4j^bNI){Nbp_I4=ALWdEZ7YfNcVvQ$uFOK#LL zGqws_jl+%{jA=XvVoulxNlCP+Pk;OR8Ilx=8Ovh4WRf5Rer;bkNZ#-sciau4QCBWE zJkDV;=EabLC*E=UKB1Kzc`jMatlL=Y?5@eHFzgqE@$6EMf9~&J5hE<@a(~uWFXBv& z=DcxXbhG`8WH-!?{xyPq4g1rZZI81uUO@j1J(14&MKev{n$b}l-*nCkC@*%?!IUu` zsS{n2EhM64sC)%A7BgZ(8edgrl?FZ3_MM@baW@hj(G?bs%VGDI~b?DU? z6D#A)&CG%Tv#X`84Z^i^ruM`~Ef?;32fvHG8Vc}jG|O_d8mCgqMw|OXL@ar~eOgtX z@2+NM6pP@GzmvO`>DEXjds)MK}(`L}haO>XQyT*iQrX5QnD>w&aNr2yT0Qm(;TS-kW+xUWlg0i>Y{pn=OfVjTU zdc~(g77p1=yY(=!DN{L4N-CB#VjHtk_1r(#fFnfWM~_O~Z(z@_8y{;s23LG#O-(lloJ;{WDPZ6Q5EddLA|WARwhl8a z<(@sP11<;8f3~IxEeXJDFYhOapB(>uS^l)ZOsKQNES2|dh+ZIPEa(8#*c-H(Hz_5T zaIPrxMaE~E58kx33l8ejJ z;YT!l(b;=wleznAXQ;@h^E=h=3QdJM5%i>JF_D!uRpJx22?Y!eIbtPq`BTf3WJ*pA zdU1*`b9IyBGNOZZm3}_f6WqCN zvHo!9L0%frj{Pt5NNC`Q7ZXkhjzhgY=!_v;w3jWgp*Zk;3lw z-OF9=`B<_0JA@(qD*}6qC1alonCo=m4Ch*3rksZ<9{Sl4ojh%7U)!_DfF_%0p>MA4 z?kVq#ntOsl;uzD@_HtDv7X10Iyu1X3e`$cuW->m4$9|wE+S>?+iBwjusjKh%WbS{P zD107@KQ|O-h0k}oQ@l2^1>K_@!-GbiNfX#*rr$V#J2>4efbRJ&7NQ#A2SdPMHQF|* zZW4As$FvL~Hd@G)Wn1Fi@Av87SI+-hgNUX>*B0JO)?>-NfTk~1%Tes_5W`nQGFD~q zI05|8xb0n;rhAmh>%J8G1rA+2%PGHO?v2-+*V^~Hddsr>c;v12&PPh>Tcse#XznY8 z+cSpU3Oe?UlAXbSQ{veP(dWrHL#@(D(Qo{UROnSormpY*WaY8HI-B15F!Z$TvA1y1 zUy_39Oo94MF!QDjUn$MKV=5gL`)$6IYLKw`D)sxrOjEHCY;17< zo?mkv82%pf>A)u3!O+tT8;m-x#c)AEwbdP}AB-vJsTsKwjy=N>SzJDqI<6{P`kJ>< zfl%|w)3&UDCR}hm`|qxXz#42^-byclQ4e8v%W>PgnmHkIr_GhGCMj}hHQT^X<8mTrIR`ciT6}u?%P8bj(WY0hx~~p2Q6Yxk3P-&PE$}pdqFZ6lUb%A1cCM^YvOz9i zf5xqHhxiMUxE0%R+v^sS4sq#e)&6XMmooz^AoilR@bPSM!Fxx!hcK{iR142cgMQ2s ziSW}jA#rhzX|%)-spVfVQ4f#_+SAn67XqyN@d3Ip+D-$}8=p)$$KY=9WN?>Wcz!^| z-r>IMeD#o@_gXqM+JEOB8y5uuXg8?49v{g;lh;PBMj7iR@%q05_c}@@5EN{D0s{F- zuuK~)@j|mVjHbtV5 z^m1ZzPa=nN)_2$@-74H|+Ad4N%WyHvQs!`KqZp-A1*HfRZH$-wWJn`75Hqz`!XZz} zpBl2s373cxu*?^Ril7%IGb80prUJFRzpy?M`jCe2A=|$w9;!fYUlX3`;PdJs$aUu; zh*T?g|J!X7M5&op3C-iD6vaR4=34lgkI|)K8}x*vq#MCZY(R0QW2pPl(z0kq($o2$ z&Q~7+D5j@)vD7nGY&rx|l%B=?#>RfzS-zRif5yjEVM+<5#CswIX{mT|&V4^u%Kyz}`# zjF;+qd`a)JtH^0eLas&eTVucQ^Tq74741~eB0cVc(e7ayJ6-maI$7ZGw$6L?-ov8f z?Vo+N))DB;*6hN<{@y;wb^@2YNeE=7%g3&N&G28n*6A@pw7Jb?O&Bm?Yg01y&FXs; z8EHDw%vtBvf+nIl85uX(u#vz(gK}xYAH+p?*vt%KNf2M&c+rt(TqcF4XAfon3XMxL zE+@(NY28BIZ07{>j*Sc6WnX8*-Xgntt08c?($%i~ak`Yo%mTs6?%DPIl7|S0QWKL!Or1H%#NO zk|lULmqzarf`C`pe3j__*7k?_0O-{Xq5l!}0<6cUH^1*M{6cJUN_55;kW5w#E0EU5 z32EPR!R`g0uYZeCDboT9yS%y2)pbpH;Yt|(_M$uJYW;3i(=BJ7;{TmA8cIcV&}&)0 zB?gFq$`1`JY~b+$Br1<-J(PSsGQj#51i*H782x17;Cnj&iVzsx4h|2;Kl8NsQhs4S zZnxt#puAHHC(+)~cGhXLJV~j*Sw~4h7f*`1idsyxoMzJ?4tU7%wS(3Mj#^S?7m<$K zPPH?C_jcc|?`*Z?IQG9}vhB+e#9(0nc~Es+&N>|H0htb!OeuJQrNTF}Q;;CPr6!B8 z3zguB$44I}#rJ?Y=~b%lZVTp5+Aonx!>6j%AScM*m2C2CMvm%Ki4 za)bjspng)0SW;o_2Nu_A^m-XB`J}X+TrdK+kyXOJY^ymC=p3-!ZjYs-5*~x}gz{A< zWTA??_AV2^8c6=(Kci$@ospD@6ViAgL=E=pv&!NER|~$-XdBnssHPH#}G6UL2wv|5|pUZ+Z;;eN*DG5 z>w>U;*qz3z-_WF|a>Ph`pTG9?>+`BtY6~yWdU%)X9UWXz4{4&pjvMthq7vE8udV=;THsH!FnI9J-*t^RMfbdu-QO zaR6jSObK=fwoOtN*G;5bpL?l`3JV!Nnh0#kM@C1U4BNF4-;crh_f!5i4m>}W2k>8A zUCk{m6&hANr|1BN9_aaiAfQRV5P*Zc(Fo0@RQO~kXjB=VDC^822{Jt;J?}ug0Xm$UQZ{IGW7^f-Ntv+ z=ie#{oh>=5lRMjO;(F7`>|iZcA*P&uenSGaxsRmL^t&1gmkC5$!s{()N1~4oa<69N zFt6)G89>AhxWj-DUM@Zeq*MSsg4~wcdw$Dfhn4XiqzsM5rEU%#`}J^D<16hUNd;O;_t+dqzr^a^j= zZ<8Huemf_4bzmlCc7LVX6wPkqXh|{UeLkhtO zAoKlrWEucDiAi^_RfeQppAk*e52)FJm8`KV%}7gKnWRDx+{I07X04E9{<)%Ja(2PX zk?qW7GQkf{m$PYhU?RRl zRQ}(A#S=VvoRqiQCPxzmNS6ok=vC98s!Rw*jDfxyN9tUR5^IMFP;d7qp`xJwe%5cY z8Es7zyj$WTqrzE;n-JYeHT;!!rG-ZL6)RNd8y&Ah`rNeFHPphZbE?d z5rwv-#65aTT-v4e_~O#+Bc^hJzbVqb?&JZ6eC>y1u29SmY+VMn4$qGOli6v z)y-6ok!)Iv1-BBxz7eCEy#DFC~yhswWA|~VStNMnyx!G*h3a^g_5BQY=S3}Gr z=2OOM9&fmWqv1Ri#<4>md_)9T%@((LBv%(Pg?m_2bw8)V@4k+!>LCy`6X+n zOdzIhGuoleUOh~)D+Gw>zDKzoQR5=Pga;rjJ~;B6 z>E&)kT~&qjKsn`p0EFdsU>FOKt=Ib(92eX+Eb8j&NcgO7N6?QpUTMypfz=_|4W`kb zQ5_e~ODATS3G>k{y2Xx3tI5;oqZz&_$ZmaIvgNUE(8GLMsIrn5)MB=7IqYzqtv6{A zQI;U)Z+x;8`^{C?=~c?UVKKE=NQyk0cB!*S2OIic-eH@}Vo=Cs$8+U0uG#n~O%nBo zFQdL?h7(#QW?*0-Fk@6_P1e;jv~X}ZO`SWyfNz#oDx?9}36}dxs?XCS1Pp4kOG_3u zHWAN?fY8vk;Rs|5X?wm_EPg)rft6n{N{O`cpfc8e_<|UU2nwr(nGLePG?>xMwSUd^1S07O?H zly;yxa;lD7OH12fgzCdms7S2_g^{xy6#yZrhshxrdz3bP5d{?fVa8>>dJ#V-eALq7 zCHwT=;fl5)MLR_^%MVPP|Edsrr>=KQFfQo(NXvHCEuj}sD$g3Ez``UzDpcted;k|r z+IjxmoK`udS!ip(}^=D0(2wPNY5`o zf*KfNIPoGA_Y?813#uK|k-J#ndhly`%pT=jGi<&x=^Um)4&EL&bW%JM-=OBCv&veXLD3BfaM5j!HlpLfa z5Y`=Rzc#+E4k6_;fv@a0O_(AKgmpV!GKZMv&2)Qsa>kOf*eqI0>xF0W!Dnjz-=lsb zk7K*kItVfoz!m==8zmsHC!8YI+ogkWrn{SsLpYjl55tm}_5@)rkD7Y}9PlY9KQ5gm+-V6|^<#v4K zXh5rW1I|sybf=no7M;dM5n;X!VwY;+!29IY%X5a^(E=-J&?${SYJXYAUoMjJC6hFW z{n82LOj)2f;BjC5jS80VsyjMH%N82u=I15)?=Osvq9mkOxcrm^tzPQy5APQlDL`J| zV+xSyQus$v19;&f5KfB6px^?W4#_cLv4%2-6;o3>LlG_VSXk8e>!!_`HD%w=u8s8P4s_oqV2P z6MuZ%Be@$g$gl)IsOy4VK1lxl@Y{b3-~Cf9W`5{vh@R6xrgyI9w=nmo(?&7G9*dUoar6lv>Gp!HuviTzK*Cbw$K->i?e&!$YC?zs0S|1$d{A^^V zv2Ku`|MLAp;4peNtA62TPmK{4!w%_!BaPUgGe9tz3Kg-&C-SJ@KTq60WW$i&3xB*i zcRd{c0?w&BbJb7yMr=!YB}h%BR`e-x2OMGWOzXk*xv)UPe?XdGduF^CxBNZ$7ncIo z|ByJ~Z;+amg=7rEkfx?I!Ilz$;(+!P6nKW@KT8z^_IviZ+2PzF<5j9M{W4&J9a>Dw z0}U<^O@dD@N`}S=_O~o0NdSafz$$h!JpR!e7P9h&%(n0Dn;Hz-PO)Ttj|u?xB~!08iE}wd^(O7s9BvVv7)gNvGlD{RDbbL{c6twN6*UnS z)7(2EfKiw(mi`mf65NH4rV3cIjhc`@sw?qpNI9kRm_MDJ+U(HIl&p$fd@q@?H$zfAS~7w3-aqGNdfztT%=4 zjh)_sApTu*ua97tBI8jh&0W*C>8A-PWd`EAaMw9p+QF+HnM(wxVSwBH+kZLOVJnVp zHus@})NLr7>bCs#qcQ@amh*s@N`r4pu$gfOiR!g4s+2GBSyvrXD?MAa?&8Y)h~`nu zV$nky%ly+961O=I(R0EMcWa>l7~%nLy`Inum!|m{MS%(5r0b|sw_Ig?_y}wi2Y(Zz zuh;$X9^uHnYP-fxPFC(=pXz>(ov?4Vi=gzvPG9>?(6wEOV2z^|;7sdH(0(-aNR8Sw zcje)k)iJd2f@C}#eu;NYdn-TSX*K?j&q}d#>~7EQ1xkC1OntX-;Xdv!1LvK}2Kj+* zCzXCY`7W-a{cqy34?98ZH+p5$au>bqGN*VZy|5I+;_w@%Nqi z+>V&RPUPQx7x2tuI$~`FuGR~$1AdTZOSf{HH_|yLi+C4~|J+qj)%-tXaNrJZwVK(~ z$tj^>*(VJU8(=sAS-Tb>nU_AC9hn+2@S0FfRSF(BJ?ljg7`podq0RH|Dp&<`aNxMg zaraw(WhHtYLHPwhR{@nFPw^%G^KDdtckC zmWG%p>i5I(ZLw77%U!#LWCH7Q7G!A7_%lq1b0^!}xAoFmT~e1iD`NUrqA}G}Qock~ zS5X}zqAxF8b%oX*PCF5|x})A>9JLiVQbWTsR>lHuFpwp?gE%8))DRlO}&4mCGBj6J^nEV($T(k zhfAc(Cd;F0ck7pJWht-4wa^c4!zoC8a?MVB_At{;QT7C}7!`;a@?jx+qZfr0MBCQ3 zcclG%E@rve7`;d%AZh%$y#aJaU94Qx^YB``1&ESFAr8wVxK7Aqh>%X+H78^u3{{JN ziHV{6=YhI))P0mBW*5ud$-H5<&i8sI34Qb}#K6S4Js#E3qJ zq1he6{e2RUeQ@r{2c!>l|KpRA~_R9mFaI=Q?&3XI#Urm5)}`$A)X zRwyB*2nhH7P%pxme*o$+K>mO(zV&Wy_yfMvWQ6m0R)1pz(VXS|r^bhh4=R2;Yy!Er z3;1_>BIF5|$1Ilyff!=9m^e^WB7rS-Ui7WPVa4F31mG#JRdzaIX#|89Kn*Zjw?8xI zZWFj>BaQNuBX;R1+v3&;ux|#17o$lU9NeAO#F}w{v*!=6Y z<@<)_VH2K(Y2qY6=w5-mU!%QCXd3yC4 zt7Qs8U}?}zm%NNDuJG}go42dv65!|^o`n#HEz9QC)<6Cm--T~fo9L`1jyYW)3T-&5!+diDRs9aF06Xl8w8tw~KBL{(>jW0qm7jdR8&XI^GJbnh&Wk9tq1%gkEl z`#kN1ticgfbby;S^(zD zpaXn(cmOLJ>h$;+jO3c%24o^*q9`z?ANR%djl-p7D#Z9)o?^@BO5XR!9j>)2tv553;4Ui7?etI(f0APMW?OHi7FS=O26 zrquPXexF_prs|b40<(_wwA=RFk52uhL7l=_uj@8On=(%`Z}ec?r~);{!l`RUp6>4u zS#D#+2f_>^qI}%zwJwj+# z^>%m!N_Pf0AntCd;NXIHMh7Ty#y^A7G0GZeM1gg-F1ZKSpZUMS{W1?ARA4{p*9Qde zW3T0PU^&xz(uMk7QSoCh8#44Relh*u*q*s(IFPFBMG4GQ7;FRiDH801gY0F`LSw7x z>ZnPr5v2DFH5$~yvZpfnbEK-P4Sk*-U#zR4OG%!fYfRI4qjz$?HNaTr3(k|c|25_s zT-KG4I#Ibja3~uQz9Ow?{f7dK1rClN-Z8CBHtbj4y_JjAvker}TNZ$W@0cq*UFNQ| z)64CMWa#ltsbfND_*Iw**|?66ul9B7rjb9=Z-a|0DD z0*ZpVThuv}8dx6tD*+rQdR)|EPyaR^PO#epWXfP%wEhkRKP3Ak{jBTM_OM?c3Jd@G zFSOPD9e;75^~r9*J17>(^WCCbk+4FN3_zml$E)KFM!ap+>3@1`4L&gn0+1gzbR-Z( zO0!_m)(OCUfRO{4xnQS)6DUzZM?&p0{wd$od@OES69_U-p*P!vS%j9Rrh#{7SI?rV zalWlYjNjtL`3I<%&ArUT2m49am?m#w$((kqW%rls*&{N3A17h85xdM}LB-F%_YNh8 z`Hrpv5p>qb7&YL9n$SdbN{dXh$_9_{lwSupon6Af)b8#?l zf6B4I1cs+w;2j()X||@GNpyThp_f{Y^lp$?S@&3BYWdtu_g;GG_ z4d0@B5DBlYZjXx@9yoV>;e;7z?u1e&*BgO`4!r!Q88e2acDzCZ(cjXcNwBiY|C=*| z*8fv{fc*r(NC0vhkS&40?**)3fb;?Sa20H+&aV~n1p9Eu|63qJJI4gPD%dtR2IDqp z`_cus_B6I2-_73{leNNN*7l9HLJ@t+*|6lRKnE9M>vVQ~1 zoN}RAaysUiw@5d%I)$VUb&TKG$|_9#71*K~!s+FB#-mzY&VJQAN#f!OZ?A08#VjwB z=nQ$Su%aBjFAB^pu+khXH?yJ``0oBfsuRk-bhMdZg|c-S+93;=qu)2btzQs}buQfP z_~mjV1iw{ypcXvRnW#nh4l={$*gN0Aw)!o`AK6|@g?q7{O&#;!d?tNOErBa7HQsIQ zYh*;R5_~3+vtE{IUc2y89&D#h(JD>^9?MUDWB#*R4#m#FlMcnTeic;hM~D5?I+~;6 zN=;9%=VJBOt4sk2k8H3A$u%3PwzV#%@m?Q`TB1&^K!XwFvCYjdQOjpmr6r%9of>E1 zWFu5twIbLM{7*v+j{!heDA*JRogEiYumz(MG}^Di!ok7yI7HR~Qv${ndp-n}-PIsZrBGs!b+C%d8+Z!{?P7{PNXhz-a=AIFYm^PGQ>Fl2C5|ClUl0^gX6tHyhO zN*jm(d4LFz;t7+>zyF++dxm)nGR-_!1lSs7uree*EocCj;ituAXLK?FowS^wsD8RW`Sy$CDaW9Q7A6q%8Cq zWi4ipVawTsmkU3NYHPZO{H)ERH)&M68Jlr)a|NpheB0!=KiyQNW^}xo6&#Al1hPfm zU#IYDliA>Q3?^;KrlY{u&d+tySLvwg_it^A zQ(6Ng%-%khiA{fXY0>NXqXI@#CPzeT%Pd#~xZK&M3b&{)=ah@`JMtSRF`U}e z@q8AI?Ph68Y~R}HhBvSTKefnR7T{j#%LrtH+5U<-y-bDv9=w4FCD=;j=@Iib?BXKvq9?j+8Os(kG*tk=v98&cfb8p#O+ zrrFGU6>s+}%NXY@)#HuaR1o)kBJ&^JhtVUNYy-@HVXux@p7MTOMyc=RF+O$}sIf&iqAD`Z48A`GtgTHZN^Pc}{FH)&P;( zm6pQ<+RWBhX-dKMZI}2OKV4Ha%aNh##>O5%St)7I>9TP+A=V_(sEXRt{n!~GqJlcSxRz%2?{SdIywh<`s%=Sx~{2r z?H>*a2?>BPW6C3|VjrY#$1s3Yjo=MSY?3H%Va}4mW;Ez9o!^f$yuMQiFS*?xXTHAL zmN(LV^u1g<;E!h&KE7+)Hv3Y{cmQ7LHb|Sdk*{!?%vwr1_G>+yy4h-4^<3Qcv0yUS zAiR&Ve9r419*8iE=(`B&@#+t<8N$(2sku?*hr5UzL-Oo)Ax2fWe)CTJ6>LgcIb(}P z6)-4P=|=FdV!0}*i7uQ>XZ)jgtz`ZmTU#hFrNp{FlA{W|K;9`mgKgaldNc2qum+e-_rC(OfP2`RMEUlW3SDwG>02k9^_ z8w~Y$&~W=2vdp_>xe@$7w}yp_`cn8gLNZjKNF%MZwuv0NlGw1c8O9h^$QGS>OAhiDsL-=>aY>rz z0@Huzvu!{Yo!@a3qyT{2q#yEG9WR4*}=5^Wnt-c zU--n(y0q&m^$_%2k#*6!GsAI57s--LYHy~dxnY>prjGbsf3l9DVd3(z(^DseT*&+S zpKtYwh$F}=lJzEt8x|Vb#GlR5fy$=Z^$5gmr%fk*9?Y2xZ(@_{t}x0RC^?%nl0n(} z;a`-8`fxoKPJ!9HJH`+kUtu;T6^DGzH_)2fPdb4kYQa-4O=|r@k-v51Vj#KCMiogN z!|Pon#T^oTi*tH0qi)j8V83CEZNs)*^BH2^dh<<^qIkcl#1-utT_ddji`QeXkqR8_ z2C!e_Kh3#ez0qK7x0D!=qQIeW%3sxa+=Wp$W?^YQT%ds9>x=yavp46ys?l_LpyE7E! zeT4fS<)zLKknaHu*vB1qvGc!>W>gH$rrf8(st)RschAoq;rV_|?k@EUl?2Kf^Sth+Xh< zxN+@0bCPL?!32reuDVdJh=Wl`{0gMpCi==6$}NEkAgaW!d2XLhAvqQ97hn&u=0)Hc z=v1}Gu5gJ=0!rMzrdVympmy-#hiLSP2NPYHar3MC>m6Lr^wToC>mV$B*gch1qYdi~ zoqP@~a=a-=3#f^=?x!TGu+P2GbKvsVZwDRTe);7V$8{P2Bp_k8y6-<+9!V6;wgW^(eO zf1y>I2HjOUv+v?%Ai(>~AKD)vgB#HtYp#h)(A&&8`FObCe6c7V1&+S)bNPic>$4(M z1*li+C_wEm?hx%`JAVyb-T)l|H}ii$51|JOM&ma4G`ln#gG;C{hQ{K5qWI^;q;joD zduZKQb(U=3UITFL!Std#$mAqb4zutx&*=3E@@rR5v??htZ`WL)l&ks5zD|B;EC}B=^1B2ts`4+ezEL}m94yuW zrU7xe`De~&KI7u(so@IW?@TNM4DnSd2F_;^j~O-hNOu_nn^ugqK4SDzC;UukV_Fh> z;qXoUu6MUuihTGMb&X=)qKf0Bm9@z@o{4#+*y->7%Ohl>QFpVOhS(UhKZtwZN$eiq zwHqOQQIXZPjvOhQ8_H^tb;g3d0;ry)`hOi#0h&MMNaXcC z^7i(%3Z=Q{8xBn#t#)~X(l+kTo98qDn{%SJC)RU z45po(9bq5u4t1+N)TCYE@%0&M;Z%09Z#|DL=SI=J@D+k+PWMHX!^N3Zds_TAzCB1- zRtc~k=IE>55dmwjq1rs2sD_uE-;Zr=c46s#9U0CHpWqs`@xJV5 z)56(t@Yy(R9s;-Q&QsBq7|~=i)6~xZualLcRKy>(8=O31e#Wx9(Byl4OE%tV+Ac9z z%-t82Nb3IATvAxbf}z6w|E`c`wfgz>o#|qbVweEb52GLl@aE=*rxzV9h*EJIN$6~a zpyPPJD$Tj@Ii2xU*frwdWVsXdKUUIWEOk*;P3@pxMOVjbkqZo4{!qVdx8_r?R`DV2 zdfh!9i^@YodAhUDga0H>h3Ag$x5DmRk+*R-BABlb4tH_(<@&?EvPY&QO6@8CB>ENo zIGk z?!0;Lb-acRj`-Icp1uD zWm{1n4av|=)_=yrq7RV7x5XgL+~fF^ZU20Cy5*zlKwF%78Rf9Av*U?1ajd1~`~g)C zjMJ=4&jn0Oe$*`YIx1HPv}=pVTcGO?^E1YncSa5h%mySQg7{I#mPFqAUq)%Xh!2LhlTaPBN{{&S_57g`a_AS z-LsIGHGnr3Ol8m6Y5vp(83{li1AZlyf4nHg$JBK-NThXs&e;C8t^Mb0&;K$x?Ry^h zP3^l85rMm>WKlFJxfaNF!#5LIoMa>qh!NL*D_L~JEZF+A;t5vsrtlSmqzrl}I<0qK zMIx#AkA@J`R0VfxT|I3k49*p08gCPAL4;{Wz$aRYZeAD8-73b^w>3x`WtYDeIswWX zLt|(Lh*5B-XOxuy$A!s#@V8FiG=`5T%`h#uvDid2z*9=rHxN+I>E1>KU%w6!-B@Oq zQs!a&RV_xV#UcHD^HrG`#OJ-d6AMif!&0f=WVS%hh-kl$W%Mvx(^l4gz46~bysK{e z@XUq}?LE6My1INF!asN3wY8D!f74Hld&cIpFvd4V?A1zJYVAC$yfXecfQ!|Da*8Q9 zbHKN+#DY7mnDu$1t;Exu;w$)53}iWi`(z(j+{T6T98|>M^ige)7ZH}2I*B|8=8ChX zOr=V75lMG)(4;?HdMpw0z%^7jfR^a0rlvu4$dwid`UIj08xTAR5^zBm4-t_Z8W5jb zZ>h|P?N|}sz7XddIUVK)!b^~+7*twXY92J@B3H6hT=-1`u;Ib)kYCB&aSUy_-JG8u z@9(%Z%Q}InVabi^2TQ*IU2tbTBde4fTbFNI9Kg09%;>At!TT(UTY|Vtss;3FEsO}t zpdzssBzKbKw$?C3rTbT}Z(!%)ZRFNUoJU{2=H|+lCif&P2 z3gVlDTz-txUB}D$0XD1=AS;UQjX4?g4pS>U$;0xej+}EBU zFG~r?YV(Y4l%00qR^mL{%VZqO14&R@>iZXbv5yGjeS7;NM~hcikc|2Q+PMV(9D>Um zP{X~g!U_cFugW2)aDo3@0QD%aU=OF$Lvgg4+6!^}dTp!1CRJkwBhy$mSjS<07DNGo3?O{1?1@sXo;>n33>&?)9NUcbz zC4`yzj>T8;%T_Z{JT81=K)R85A>8v_Y<^be+H2_vK{b?defcDsgA&;>q4@T+l~J2J zfyKIHS4kye-{$3>b8ac9@B(&^UzNM9oSSf0x~p9K$?+%Qey|oBls+4=PVg(2EU{CX zI(3wjL|urggK4`I`8<5_ z6)tev@ErXs(#C0lZ3T95Ze|+8C#W~fJ2^#MUiJNjSo=3x;CG*W{AslE>k`-Jcz{LB z=hSf_)p-q!bdr1(xEhWDLI1;r>3PT|`I%Lv1yqb~FB?U*`*(l@rPW&EgsFQN=5Ui}wP{;Q*T z+GZW}k>d=&UT19$!AA+5L19cdioSt07VqvtAe^MUEMtUFS?1eF zD?%80b>rW7LHm4`&$hy#>5+YqsQ1`~G2Q&=V8`Wg0vXpd(q5}HSU|+mI43N!|8m6o zq!f=cz?}*8dsVf&rWx#zr~tpUQF2D(|6Z*Cv)J^uy1HJl+=CNvvpbv^iG!QFx}iac zqz^aP(+yJd|Fr-pKQys*dX#9-z%HGn%nY2t%Ty-kUgBVeMk;j!`jUMrNKyRy!P)K8 zh^GLMOKZnRa(!JslM92#tG$vI+F z)I}riQRo8imaP0sH2pEYvSx{cE~8pGgDjW2{ykWll~Rn>?HpRB(e0PBzK^Fbm&W(G zO{5YFFr2T&iN{U-UC^#`vA`eq-pfLo4&N=u%@=zLQpc~xn{&t|D5uVrIHdW<~p z9OeYIsv`06K#N*tek#EX%Ppv zy+`OSyQydR@PBw?xSz&u4!i@9)MO>DsvCShdkp{jnMm@y+|S4i9vefC7-6SMhY!_t zXVJ*G$SzCq2#WTB(aoc&N~U>=7O{bba;-ks_vY{MT?yC!R#Tx^uv-G_3i3l_O>%nr z`U(g~k+uEG&e2Nq^Q@ge`(aBSN08lvh+#xgBQX>r0~pnn)@dYXw4d z>!T^Mjo7rFCxr}IZ*GKLJ7xS>lAgxhr;3htH_7z01E-f!_KUWE@2={JT?XQO_?Uqg z@|OcyCB%+bm*YHQOgeKe?O#`>vE{#Ql;V?OAA?I|g7&j<+#)J?J7Jq)@-^f2y&#TX z`@Id@01OIb*j>6nMsK(WC4gCd2P53&hcb@YUpxs5zRQku)>|dsL=Bt~EnM_gQa>SIWY}F0x4tDVp*ox)IRkoqb&A9XiE9u?B)f&K55jNIPMaP&4QcHP~o*t-p{S`pgFgn zk>yf^X9+(T=zOV^4nZ!51=$3YU8Hn2GfGn8DUaXU&rYUhQDG{q7EYk0e304f&XhyF zwNL^WJO4F{;y%P;#F;Js!l1jYs;hhH@(u=2et< zIf0Yf_fiSM+jElzZ%Diots9mOPhZ^<|k2c_oiH$L&&j9cvGO&j+l#`sk3zLuE)AYIt=aLLeab!jsg4H%69-fNa+LG%v_CfLBN7&#o(giS@sK29cTO>!0We zXGMV!eAXGGu|tF85tTVjO4S+|{yqW-5^w{D2p07W5KW~-A`b?ON&EVg)Kn0w`z|Wm zh|5AQGBaGYm}5llx~ z`R9cw-;ki7UwCxnBm1}ZPNmM#!2I2h8g%=UTpIV@9T_L~?#I{D@_dj-ce!9DSt-%( zWqINv?G!oMmuOUpnIkPk?Q!;x!z-8HxfbTs2*q7zk-7tQ-WBg!t zdTgvK!`0#@OT@wly89K0<2Y{niGQOPot6ibHF;Z?c-KFr?e!t@sh9Ut`tp$xsXBQX zohn@4O$ANRgg2oUo~()o2ZDmWmcx$CRbtNuH|}@+J744;Mtn@{6d1|UcwaDOo;yKd za*y}a5M_-10`a+B)tAWc*GBS~0EAKSqHz9ZF0(ysVj~BY;WpA}SAi7ZDD|GXWZ(AQ zg?PpavfxvHQn{nlnxM%f54e?oi&sMsVoy&H1)t}MagBWVm4mwiM8PMM^o1{bH-3SJ zGfD%9!CMVD=1j^7R*5l2s=Zp5-n^mnAz--&OYKWb{a4M4)}KB_Gbs@g0qHDI*Ph3? zSb)Tp>^H3Ro@ji2VD;G!d59yOBNo?uq_uM!HJb`3O*nq~PmfYML4r^Mdb1~#T_7C@{kB)!_X zwuddaZRayL-?<>e>_{AON1IQ_uAY@1$SQyld*M_j$?o!1UJpb=E(7O9ve}j=i-_a^ zW5&kkP2O0LNJJAZBuIdEwL+DPQuP!RrndhnfZea?M+WRtXD!-KEZ9zNyC_b%>=A#) z%&2l``1lfyc7ICbQA0JpzM!1o-h5^%wPfq|j1ce2ORmy(of_TnX|VgX9MnnuNjn1dKTE`S`-|r1 zK?Im@L52Vw=fUP<8o_Sgc7z z^s=L8;+0mXm_Twyj$xxBjEogZtxF{lsedfTLP}SSI-a^+DNrlzS=n6;@(@~Rrp3@LBelm9>vlu1YF|Y_7+JCC}V8ty0T0AU2m{m>b~7hK8vw-iuBSlXn(}k9MXzT6rBJ zd-}vcVe$AiuzBHr1ju=Z`w zegy6;60^sh*B}Yc%8$kR+Iq-HBmLxf>03GhAEJES!g0-Ej{AqD>EO6$kMHsg-L=`q zw5Wk$-~yk7X&a;8u$#|PWewh>hqdW?PSGg4{Q$w_p7yJIz07l!NG8?e)fwov-c@%` za>I(ea|&5^i{*WRo%-{hFF0U{iqR(6!$c85*7R#WDJjfq<13VeieHmSuovy}!4&+? z6Pg@qDd8-m5Q!+xEA~te(Gn+pI4LmL{~KSSU?=Xzwd%woq|nrH!He&fvkK%ZP@l2~ zMyw}@lF4MAtiDqzxogD;hp>z<&RrT0c5+mCP|W+ENZWA^gwP>@JsgNdkwEmBVw(-Z| zJSfjNun4^tV!Ry!jx=v{nF3OGKf_~wDBcG6ieZenl}B-PW|FnDW1PVd!;TT*$@bJ( z;A%T9FM@Vo3=`g(1Z)vNN7plMSFyg!Toq&Y+!ufGv>g8)@B8(i#Au6_FB|hEH}MwE z2H$F5ChE0K;ugZxPWYQZXW4b7VUzy5&$jVb!z6(EbTMo-M~^DXamLxay>H~UX&^Qg zlVwT`yd0J+_q2;ORJg$?A=oGiAm@L!#7Es0Z@#-f!!{PN6|x`RNp6)+AeSVa7I}hl zMQ_g$o8aHb+q?5)7NLoyDv!F%cXgH~OVfq@r(>cw-AN+%_T<*sp;FHh5OcL>K$PgT z+~aanyU=W;fQCsdb|jbsL{q&pYNM3gm=w%PLV~f4=XgKLFKoP$0K{57O1DMtPN-ZQv~Fq69MdeIrIB% zcQ0AzbKc-skI+M&B^zQ~TPPnv5S#X-@HaCFp3XDq@&!J<^@eU{Eklb7d_0=ZKhb(2 z4!w!AstlvT9P-TGMmvn_zp23z`Psm2lLrxG0HFE=f^iFbBfum3Qk?nPAViHl7{>J! zihk9mRCv2^rE(GD31#FAR9mOq-{h+*_dPm`Je5A6gqt`FUe9eg^5i3? z^qwuN2@ewo%sVuyPvdUyoO({&%*`Cz(OyYO%{ZRi%A9+Pi3JH^H=ZGPKoa|ngGxdz z1Y-H}L&m`^0oEjm+Z#SGAR-{BC}VsZV@0`9HRvaei}lzD1cK|iqZviCxhHuJ>(hvv z*wVGYX?jCn`Wyl|_DqJoRkBwQd^8lepc0oH!MiMzp6bmIa0da%0mN_q)CT9Ttdsb2 zxv-51d=z}TOHB?EHnIrT*US#D4cL;xSCfU5Zaja&PvQjY>t+{b^X9j+q!!>)+b&_N z9;U{dsQCr?!hSw+zzGCk=m$|ldpqvp)MNOl&?~YhKYui+Nd8%)j6^c`fTBHmt#j;rvk!i9eS4u32<_yy)r{BI2;% zF=b{?nfc*ff@qU+JD01I#M0Oeiw+f0KU$QD^ulD=O&R~m9dFa}xDWN9d_UeeVb!bG z3(>7Xm-(I&wmF#!q@Cg22iW?&# zbfI~Pul{T=jfC6(UQWwdsgwT}&~a?%GPL~3t&wLFkD-s5P-t1mR9voKmLMt)(5_(J z0SP!j(iv5XhZe(e>C1Bc+m98Td9u-Apc*dIFoS7;2e%Qd3fnFrWrLmM7ZkxZ)qY@x z|Mvq1PhcAO7`ZhDsQKs+-ElCHyiv>qlb}KAyC`WnpDs&_me`D9#-RQr>7^@w`+Cu+ z99scH{`xx5o^ieNl1?6=e_;9$^8B0#Qc{=1eezL~GKh`D+o(HAnZe+GYFZ24u4=CLM482DSW%EEwC0^F7Sa_W_bd9k4 z93CT=$n&Uot0x;(m(#-M`YU-cI*ki%ozzx>*L}?&1M{{R>DoYZsTL1~s}RebbLYP? z)m*in37p3xG+QZVE-G%lK~cyNQSS9v5<&AJ2~P;l;mUzob@6RlIiP4_L@1n5W6!ltIJ@NorAy&AYBY@ zX?)*kWc@(2x5mVMvg*dM+!+%vVL5UK^5JkG1406%lrUh^ccWcjKB4M%QfY^6p6}0h zsjRnx%H@Y$3P?`DJnwOOL6m9Q2vVi~CY`m%hFqJ8 zN^~1l%fUn!l0v%lvJBzYHZP&RKfuCvFMh=tj5Cf2o@BM(UeCQMo%rhbQxd;=BysNH zRH{pg`JN)I?MP@!<0lhebUL;<^ia{&{i&=- zG+v!H2b&v>HG^=?6u}RL6Z`o&W4+Bnbi_|>d9E^ag7zMZtg=M!ZIbo6{>*@sDe9V$ zN7SIeI}*8PHd)_(N5|*bh>bQ=H00}Vt)z5(bzdRz`vpdaGNdH_#^^& zNBeo#MaaOwz`s!S=0#vp*PiaQ z#`KcpY>xxi$31$|(efHOtj8L>#H0XA>Yt3_SAHN==WHiGxclUL6{r?0X3y;I?|cLm zYH4}~E9|D1&q3zgH34l!RTBtp7Sr2ojuVRdWLdyaiN%lZ`7W#Flj;=PYO2EMPbgeb ziao23MlMTd{PU~xGZ%_!bJ}aY1Pu-2Crc@|w5eTiJ@>}0meiyiNpvR(2@9!nD~0nU z%_>tR9?8fMUix#J@_%L$Nbdoko9Kz`E%?+ne&Jg>j2apv@d>BOp2wY9WV7%4Taphr zA_WZz5pVf`u*ggBlR6I+T|4$!zeSMeyCtJSHxtVZS2f&M6>2;mUqs1!ZEMl#7P1`_ zQ#S4SnA|AGlJyg>B3$nU>hE30eM%0Js>=zEr=0X6G4G3xo{#94&#E)YQbf`ixp>sQ}CJwCMJI{B8Sj(9SvG%xwoMqc#1rNTu zE(+P7+V4PnhS#DE$tw-e*z&G2jPoLMfbX}4yq#R@+X9nf0(1l@cLL%VLqo%^@{P9% z;6VdjoRZ387N+ofuPKV>7Isqil+-h58iWDV3NQLaOMC{#9~mp}2@uCo)==;6*C`S)1AYG37$LF2X8 zaGdW*_RBL~MpbE>baG$1RNW14=r?Rf)1e9o;pGinT<&FeU*iJxz%}>g>Ia^Dj)rxg zy>1i%X_nv6Y)l{}I8C%0d)`b|uzEw0_-!V#E}jqH{jWmL)+xR7TF-mZOg_ot z_d2GnBjM1dxIgS)b~KkfX1A)fti3}{(L7Jdh@Wsn-a1I=O6$Z;%yLoQ+#=B_BdcQ< zUKAyw`X1n-#ZVY%6wt1 zx(5ttGrQ5u*9g_*@87-b_3P)YT&LYz4iMKh^Pfc0M*|?70a9iTO7UL+sSPNpfhxP% zj*C^OWIm8ZG zE1T*Dfp(E9$pNrdTt*EY$CKET{Oj|uOMKAZ?cxoG@IBQh-)ri*+va<>!Z*_}*MsLi zmrdstY()O`)aW$;7K}$bus4W1bt{wk|8PyVEz3^a8FenI3=R6;*?F65iuy%bR%x zUwxvm5!1QgDUJy_&z5|(juZ{~Md82eK~kIeDah*9A^Xm2ZXKxKU8Vy^Y@e?Y^mVfjl08ouNMZDb--sds9n zwdaxp6`2mmZUDh;OX@2^w7ueBtOkYjTW-zWPGWX%_tIAXlp2CH6b$HAR>45>^T4xz z|NhR_79?mBQ4mdV&QtDy8Es4l1dD(<3(&X9EQu}b;xQmjiogE*Qti@$TWR~lKaHkI zi~y~an8$^`H{xIle3QQBluk!1PiwB!raIkG(N3TOjs|fllFw4`vX*-c42pi zW=5}?pf4U8YOjfo50TcDH!V~|0>Lb8clXq6T3sx~7U>~b|YbtrNwyn4@ znO{!gsasRl0OcG0w3-`(f{F0~YvV6hA9^dYNHOSPki>`GUv7X)8{_>52ETVvo!(KZ@=qHNn2{}+!^@S+rfprC7qh8c$A@dc z^5L{61B_In+TZw9-8nzA4ZTyOD{>%rG9U&bEeQ6Atc(YQ1C zh2^3hOvT3R587n9A=@XjA?_)*V78uxn$8bCgy8|Il%^PN*e;U_eCWMH%SJ+O zQRT@D5){PW19&yfO#9YAfVXqCGeBpGr*jr5b?etb#1invFLQdlH1q|M8;+rncZTgS zI%{%*g<^1G!NXTCf>+LWdEPU9x0cQ6`cBB`qY;)kW(tWYk)G79&%jZZD*CdVn z=1bH{-=Nt-lqW5Ou%Nr3+^@uN*z^RwezCnHFjaTq63_UFCofqI8VP9>Tor_%@*hJO zF}xSAUVR~hMD;vm_>_Ly6cuN<5~s7^@2_I9HjJ9#o`tfB_NF$F(?C5T!AV@$)Owm( zl6MxY{^h448@+r=q7ehBi4MWnO;T!^z8}7b13Mu=cL?ajEuB9)!*wY<_%NbjrW0Sq z5B(k zX(tX`AGEDt8V9OKz|xXCn3?Iu=9}H+b{YwoV9^mG%gZyyGLd6SI)byq;WaQ% zMsULov_NH9YaO4m!2wnK&5j30{JA>Nu>QChQ_j2p5Wyuh$w#?us$MBs2V~&OjOORz zd+}Yy{b7Cujtx&*+R#q=`_ba){=XJLy#nvJ6Zam64iYZ~&;<7hUE%I~W03>L#DI+e8Q7G{bWRcQ9e|ykX(eAJ8HK^2Du71MYojY zsFHeyL*(b((Hb;eYtr=Gwt-gHIvr1ZqH# z5-^U4NIbS893$yF;wiG?&Pkr+_Z?+}ZM!&*KBC$B_S%Xye{5s~xovxk{xODwh`cj$ zFW$OKav_KiNe1)YlwJMS+Ij}ah5@ukqW93Lx3AajjnDM422W|-y|Bu~{$u>SdwI2^ zeG0rO&CGot8#z0{EWXhsZ1R8*_oCerS@L7|zd}_OF{kA}meNzPHsZ`^qq{o_p?wr# zmCdi!V>8G<=1NAi%(s=yek4oRssgZ^Grs5ho7FnB>xB1+^c9RM$;=!p@H7;UX%}1a zOgd<+cs}o`x17)o^z}sLkj8Rt@%C`C8I1J%vB^i9+S9II?jRm*Ord(wBwniAk*}*u zQqkrXM~IOQvzYMEab=!cIQ3Z+_$C+)df0fe-OCQ>hP@eK;iScBDwFWqbfT?Y^Lbex z6=iI!y?`xWlsoFdeEX5jO_`U52ivTU(T;?B@U=Q2x=yFCG;xrN!ZphpT&Kb1OH+;w zwGq{n$H?)C2M-M<2J4}nmEQ9Ego;hI(;kaR@W#-JdkqinfV?Aur}&T&y3t1pfe(){ zSehTqB|hA8r{EL~oTnFT1Tu%(TKV!B++Uvbjz~&VF06?JPtfWOIRBG10sXbttMhMo z;{RgvSI9`7b#St71RUWn<=_8}rc!rT;bjkO{CrW)X+jQ4mHX+;c-{hCu@=7gx=)NV zn!VbsM`2*3k5!PN_Hd1i_}DtEpJqZ;a?VLFZFiECyP^G+gFxx?4Vypk)SdH2750em zXos&}V^Wx=M4Gw~qnNe4-7hlC&dLXYE;e5q^EJkRx1Ek#E$TQ1sN`*RgJ`~ue;@di3fh_5pkuZhx+ zWFkE2g0nKBXtt4hcrz&?B>sl_vNnkVqz60z&`ezVcDK}m9l%Hjgc2Bl{jj8e`tvz> zKLM@|#DM@GlIABs!^awnXbpm;JG+R`{HG5O0#{IJaH6xBrIWjBtum9So*m=(EC@@= zg;%d$9yx}^0z|+1aBkF>u@o)c|CfV(F}(rJ9(!oU0&OxFlhRK`drYd^niyd^$J!O{ zt4m{UoIX=mqB^eKVJV9di`?7RI%ughod&9+e z$Eo3!KLs3t(sYwdf3Eq+EXv%|Gv!@n_s-vwkW{JVe!dWwmIqOLxpeu=N%YnCk?bik zRjqg?%2aOwaC2JnbP5P@H7_1ih{)-LR&s{Ub^c3R1-KJ<87Up!mrw^j@L6geb z_EZ6QVS$oHLq`scPg}kdNA$(Cg7Y*o=xcb`=~Pvn0C5`sTTsF8^pFT}V?vv=e~+V; z3A*IEHDspW#3$a^khX5! zbpOVE8iJw_J4{EAf8>{ri;9^5GQNH$6aZ~TiJ0*}u)Hx1FzjW~V(l>;G*EpHJ&$~N zXr@x%^G~mD&8Kw}vrOs$l$|P#5GbD#bg3NDp9U z18-)5LFo$t0rU<~R|j|&)(Ft+3PO%7S@RqscjGtDpIB5dD>rI~#2qF9k5s{;w9c*H ze$58~L!frcE$Xr!T(lQd;fTTAG+yV=RD~{uza`Z_B4S0=Ae7pm`Ac}(CY^zEidM=h z0!J55A+j`ZG93wF-miMzUo<98Co%S_jbqF_sZ{LwMhN-dLQddOPRr=?xg=^4;_Lfu zlu9!RL5ZSOtMc5vdeypPipUP~gqRkBv8?I{&P_@6oi}oQmz6oy5nnre*@7nfy_b+D zZ(42X%5KX^dyGGicl9+y#kX!aX-|paVCH3*Kl{QeAV-#0PPl1*ng~%VEq2!?Cow+U zGz*u~j4kR4&j~*mK7;qaSxX#AUp3mD-_P%YqdIlFipgO9-+;96jCg0UaVumpb9fvUY$ zZ%KT{|D0*1Nut{e*rB4EH+lV8!Yef^qoNCqK)>3!eUhhisQL!E(T2yJ8mAW?Ubk28H$BP%r(AVb-ScBBrK4hb*{zuM_IIyXemO zkfK=s1lAJDOZ1|5=w(Kh5l3(pWwxY!ZqS#faa74h5rL1(gzV~XQNi`d&6HzVE=6cT zcIZXaHFAVx87v`B7$%7h8fTW@y6SoY2Eoqkz~x$H|xC5sS=s;3nB zt5DC0;b|5^`fSCY%I|X7h?nH4GUGkp-;T3nFXZ;JsC*km2RN0et$sFV^6tiZoKOH` z(5tp~Oof8mSIbs;cV4#Tqw;`O1FJf)!2wX7S3Of=F_jd3DgE7D3X#O~7`zv}yhI1@ zQN2gOO=vTkmJI+f);(FwnEEX6D)-a}q<%gm{gNrQ>`4D&<+nEhbYA+|6=*F7YLbW8 z{f8aI?xiV()@u4@U>F`G{W7;1_?zu`1(}5?t(g`hq1}5c)O~rS3$bppY=6 z>mTkHcd*j2TAYukuceowz*_9sGDkvQgrW}Lga*-y^Jj%>C{tiJy+2!+Xl2w{EGl8H z9~|zF>ghs6N2Yu7OfGISiHkkms$9QB*7&Bz7~PwGvp4I0S4_IwQ<}jl1X=I6`pEu7 zbvP|^ebwO-!nJ&dNxt(FlfvJtFiYYD2|4+GI?xfV``<5KNprbQD=G9qL@4bV6?UWh zl5?mT1x|jpnIdPNvZQ+9R|C1w4iyhZphJIcV!yOgBNwv^5^TI+>&f_Cw>8fJ2gi=IhYSov zX3zT|38J5+pirW%J|nKRv9(>S;NI-R?o2&SPR4HVTceOY+E3~Ku4uwgr^W9Zt*;st4RqnHo6mA-*$a&& zZAR)-8)=jNDT0*{>n8l<^5z@iL^#&eHc3z?5(q`wNDu=i0FAGL8vYi^siUf`_MqSm zD8L*yM`K9YWF8`g`6pp|PcnwiPp(NQm=BT|E73@rJi3 z6up~}u+IM|8rfB$^Ac9@M*T+4o@RgO(@pO<-MA>)30!4=ek5-!V%6cM*Z)R?CHu#B zhut`q4&*I->BVPnMuJZO_t-!m^O%0AUzt<_X^Sc)$R%g(cA1Z11JdF1*UtCAM?`VH z&>!h1()u=*T{aSL98VjuKN>3w14OT(jHBa%ZbR&^>SNZhD1pt4ty8(qYm0x7-`7J4 z{yuOhee#vYN}Fr+4FwsUTGPfVp%zh94nuiF(DTQebD_$1^I>cs@mgv6SuLumZT_!P11DlC`)qqZ zeYeLRTdP&A4;qQ*QU@G7);9dol3E*$j)Y6dxnIli%s)->&8tY8rS=mk(!e(&zfx$E z|Gxc2R&ke#?Ul9CZjLRbJDdw!rPyJL9^Q_HGaYh?MIWOzDZKgAp39`*&(!fa>v?DK zM`S6x50Usqwx)Ob-EVZ?!{CvJx`IgjSVHrh{3su|OBx%VRcOA?HB0Hi?!1ZN-aui& zMJ3BRc>X5D|Ecx)b0mMf56HgfKNPZ_N#P@B_!oK@48yk<(6pI32{BT~i3zpdXBV>5 zi+v(Wpg^{l-PBCpM?u~zwfCd`$`Xbj(CveUwy5>basY{yf{55Go>tSrw)}F=#|mW~ zDI04rfl!l03!eeG=yA6wwr3VxV@a3x3nx8%8y~}g$r|((=px08yWty4&iJEL>?yb7 zCs0UUn$av2h!x2ElWR}v)JEdW-Y=rC?jngqr^pYd^SeMsJ(q#TpPjh!3^R8;6>-jG z$Qg%uhyht)=g|=_ONRx;#%l`-3?RRexW920^SvTjJ)&s8J1ci`ap8}AuATr+fIT=I z6{+psB-EP}2i@nWhrEIV7w~8oJ=}iCQY`e}+K$T2DF|hx9(U@{;xwXsIhA~Ii*+WS zGF8O^97+5>&@-zrtiHZJA$uAN9*W_7XfNX@V&{d7@ZCr^!y$zC#t!{6l$BtApGvO= z&V9lb?v|7pPygcrPe{)49XEdW*yCOV1~vPJ5Y>2K9%ldMEA6bu$(Q0o^^e1IA34)3a=|W#yxT}6rEwEKw3aC$d2&ibIvX|)6EJA-Jhh3I(s_O5`Pyj|d2RRd zB}Ka-(LZivIPM}ta9~}2vVQ3ek+g5N)DKVPHD%c5!bG2TlSef3TN~FK4!x^*`jUx!_KH%yIbC? zjdh%X?ABxo)w@*52Tmr&SuP-CVw;dNs83R=zH)rK7f*OI)Y8kJYxkqxRw>GnD zYo00U{vAv9sJ_ob%(LbeWPTX+O1AlQ!fR#%mVM(0rq>Dg?s2_BD#Jz>^iU=Me~=A> zkHrUZJtMH92x%-5^EgBr%Mh29$n2Xjg+znHBWGqeIHy{0#PUTaf#eMm0~*KBFSs8< z6zQ+>Em%~l-Tv4LG?Yaqm78RnWEwV_mHoKBr#EHS!|BSS|H)?Ewht=S22)`L;y>Vv zWxIij^S{srR6fmzYEBJ)=>OYB__ zUQ>b8qfeO9P}28G9GZ{5U)QT6bFe%bCj4!IZi$`4O>feJ>yg85)}qhwtI6Mkd6jXI zMyf5Iy_DJh@v+peEAGU$9X_OEw84*bpTIRtdkJYj&U)g9*#}-M4kS#T`%w{RlyR%V zY+}prkdHs!p)-9+#@>>-kZB5(xPRX{$*dcG95*V zHrq1CHngVD9?3;lAy6wL>u%=#G5@8BRNcl*pb!ZmH*=J3NZm-ITz7`QQ-kB9d&{l< zTX`n4b>8ZW%40Nm3W{CFq3B%;IuVTpauM-X9SXJ7;t@d}+HXeKum1Y}l*{%$kKaS? z24cFI-m&FO6^@dQ_bj?Bm15{j$Y~9jP&MC$JI*&|+3Q zoT#JvEWibiOPWCuVm=yZr4NELz{TDPKyss*9+2H|xG_SNUU(9y@!Fh%FUp1gN%piY z@;K36@UNSXFjs1oUV}vrvPjTF+tw~3CDVZvK&C@6nKP`ShtgT`qF;{^O{;dCBymZ6 z473pSczEN@IAtrE^FJ{cqaAyC)|czlT{YyCKIiiPntBVUD!1oOb7??_KLCSCP%7~l2wwB=zw!PuM5%fdl zB?^%MMHWhGXt+{iRD_`iuXuS@*QXW+BO6sH%OBfVFZGwjDPJ6xW5pcdm~_)NYtIim z!dY0}TA8ePX?5ICb%tZ2rl*Tz_8e1chJIf2;8%Vz+SWg`>Fhu&uJ8*Yk)VO3?Bv z3c66Guv>YSUt%H@Q7~VgtjTw>uVEeBc4zna};4E;};F8}0QV)GcZNHx#22^|ae zI{k%4t)qf$Ou>YNZBhpBzrnNxz{990kZwW-0{w_y8V}yaphF7k@RGEY`+c|mGvLnM z_5yVC{$=M5oj4U^JK!)EXGpmY%t74dMyx(C**sVYl^p21Na=?By~`xV-@yuFe{JDOmw z8V}c~k4(&Hd#5&{l#ML4v?o_5UkLLaC(J}8XaOS*-#POo7 z?ftjEHfnHMfO^Vrmw`Z~$L`&wy=_Du$X1g|UFK&$&0p_IhZ2D@d7Ji2>G8llY5$}^ zl@dP5E6fnCG+(QfT=&BV#S-JI?~Z$^TS|nU;Eiw``Ax^qdpys1`q^c153@#qo`BJ@ zK^V3282#zLEbIOqN3DOitc<75zGg)3kj`Jqvp6N;qm;hJ(V+9oB(+QoJlB@;{p*q? zc3&oY(`kbsrt(S0FG|*^DzCgs4FBD<)Ec(pqh=F>!c&k4rJ;^ywW{pkS!LagBmW#{_^?L>AHm`GOF}WUOX2S=SC|3!}o^9FJ9n6AaS@{aroHY z9{b72(GKGvaQTS)%D#S@JX%gzSQsUjVceyWs%nZenDC1kKN$Aln|J7xL#a_uu1H<_ zZDH4HFk#y^;iYF@$Q4>!Ye#-r+k7jvQ93h>vjE5PyccyCR-K(GIF_>601v;qq&2f! zY{0*9f%@;_GMSRC!#4F9+cT90v&qT?h3*?s4$;Z+6MG*ps`_?xlF$bk1Y}NLHlVU%(qUznV9Eqx z+UX4zjJ&$?$(}&__Y7NF5;t=P76zvmFTyD)WIuBMwt_~?RA7-gFS|wh$+OX<9VhTo6tz51%Q3N_ z%pnKy(Q_m%qC4+gW4w`!ew>CQ?$+J#03H#Wmv?YV&(4%iH+cTVA96_C@A-6xdTPn% zcTT6e(%i`R3`4vgF-3uD3M>&E@g6mtTAN!0+jG5FXVU?VB)GjVUVoh&vz;L6(j(-| z7kGZBh(vGlmRIIVRQS-;6=l+`wn2hC*!RcXX+@H6DWX2FR_}C`g+vl38ruu< z8ENWzAjR0{r-f>I!Zq0h=~-E%-N?uFH10%}hB+Wg<#Y=7Fa;K3v2x#$YW3}k=TKtU z5F+DgaRm4Ko;SB;$;AX#j+%_8cTR*81~%QaCXB+S{Tx`BcW_1Y|9JtJ5HmN#JFF5#?y^$5p(5;fA@f!~3vJ4sMuq!vT!EU{PU#;KG+ zNkqlg`QRIc$$y^z4%pf*j&#KWE~(DW&QfMt9`)4O)#!X6_M_!U#sQ@hlac_nJs6Wpc{fuDofBQX+cN0%>}!1Z65F(NPY(#iK$C zew;!jgWRImlw)qssX3a%QQ=(VxaDJJoC}N8i8Ok%3dF(&xtq9bslt;SjwgDBb`*p{ zM(5M(LSf}7&#-4{Y%P*vz2Bj{qCH04CybkY8Kx2lM=2a-=7vJVJ|-W|8c*YGn(e)4 zm5y{Aq8EM-B4X9$(@KH@C1#1Gd=GY(X)b(Dky4kmbj4^I44yeYx$nN3Sl)PI$m$s@ zzBOr&vhJd)+j(xZwv6_O;byh9w;4KWj6<`_bbE>SSUmCS=N|9QWj4a$sq^OL*MD~t z913S=$8D>z{qQ1iN6LBf-MJ&f{7{`}^CXS~%OvAbfGh1&x){)IOO}di?%DjMDZ-yK z$V4}Ai_`c#LZ$gJZYdAk2xB3Klce2kDuVANp3|E4m9Mm+%^2|A$(8%L!d&4uYk4S{ zy-FG;tG;>2V)!VR!0OGfZl|T!Z?HTbnQN_& z^yQ9yUSa4GH-GO{I))B;c<(P?Eu>{RN%_Wb@SZ_M3FhmuFyal8 zX`S9O5yAGLpN@fKiTK_7=|6kb35}Ium4W95pCdmL@qQ=V?aL3lt?1x{=Syou z`c*klL&oE47Oj7UZ0NkWnvUS3PC4)J9VLuITsM>Ew{LU%Ej1F}Z1k_WsdE=gFuC%p zV{(-)E9^vuOh3T_OsYKN&Ht*PLsBw`ETTKpS;SY{`}+X zCOg+sL`Wt^q@s3xpDI;z;Md=x6m2CJzr{Pz0b*0L5e;4{4AD=1<00u5&AYfDt3*BR z9R2urk}QnsAbKI z@8`CCTTLa$4NGx$9}(tiR&|f3u=u-uA?hD%n#zG6xi%O==$Y1wjjQxlyW5L43Z(-` z5m%Arylu!|eF~GV(emu9T)~(W&?lFdZ7Nn?zENXV-D=$>9s4cX5>dj+YzdMxbnJs9&k*>tJH57H7T&`zKyJEYwl4d-Gr0SL5i6DT)pGuXcPx z*Y5vvR-c%1r6-B(89fDy4d%$L0FB0MAW`)R0+B1c zeeNZirR;S;=2H7aOWam;mWjQ)QS8rC#$-+MQA8=(;k^{hrDj}zm9)Tr;V2s~Tb@;+ zTnJfc`Lk?}WZ~TSdiPQlg@4QvH`&T9*agjm_TWoIbsSTv?$`zEPm$-JM4p7NbT;M; z&~|IAB6FF8B5*Vixm>r2J|-X3{GFZ{h=>XNi&8ru&rLPQ+;f|dL5fPQN6U#d5G}}^ zWCA^pp>m}EODwe{lSb~3c&Uklt+xqpI8Zf2dz>_6reEG(Ju~!;lQNL+e6Ndvxc_5# z)K1L<+tt$A?~McvlEq>U;c7X@o_F>{hH6;8fRp~%tyiJ&q0(9%J=s25ogmFU6%Rky zLheZ_QJii!si>rU%eRVT_BF9fnI>~&NkxBrY7prjJ0PTy*d9vwm2<=RY}HBm>tDCH zn}4(d!XG-V#E6X%v*>*18+;ac4P3Cwv|rNwDc|UHqVmkX+3UocraZdk&PRpsg+<)O zdmpEZ7lvwFchiD)`@${~dXuv4bE?1EWw0P0HshyAEe^M-#bI0K zRBF}v&{@T)z-FvX$~mwn>xMc|71w8Gal{*V3R0Ixc5l|{2vL6a%?7h%Rd>?W}Z^di5x`_U*LJJp%u#XcOY8DQQ%Fa5JDZ9v1c z#Fl^(k-KxEfE4YJL)(kSnAt5TT!?HPuzNcqYti)hi8&gVoU5vv_(#8;!v^BvEme?7ZF9XPM2FR@J=Q22-njj(vTgT(IbH2NBT<}!Z!x|p#$RiiDwYJIkeNVdt` zjQozleW%$`X06diI<(K1UM=kD?NZ?dj7uZx9*&BwBO^AC>E}+5WGuDom`o~+rC1^j z#D+Bv<+VuM$|I+I8Jw7XvMI6y>@)KTUb&NKBti$sFHJqjLAj93j9j~OcE3N@F~RfXh|zQJox3JM0eKpL1L~Ws*Uzxv$c&(@3ms z1_uRr|GiRXhAwwpFujx^XQYc45B|l}$A@xxPwxk*H{I2oECc&7c2cM(1RRQFhqTpVZzs`U z+xt@1RX?~b<8jAxq~&7=m5W4QEYa_x)C)?Q0ym1Q9K_7zCjGfTp_;(P@ppN~YY zo!LDa$d7&?kpD#3Zrv{QfhgS0#nvW*cRtnGHIxs?5W!)71Jw@3Kx09tJK#rYBz!wQ zefq?S&E!%WuTG!XH|YBfeIUhF2zPwK2@71Pq%aCvLk6)fUE?G5RzpN>G$wv)ws%iRU3L-J=z60L3R1O3|xrm^Mwczn7A z@Va;hKYyXUW9)}tnn`urx7-_d|BKHUS)fY{HA$kYsOmctdQDxs)6x(%^nEv4ue*vH zG=B=K52ToOU7WSdkpZv=;s|?9&OPRD^C8t=I-)^rv#m-rG%GUOf^T zvA5$`zBs5#SetWXnQZ{tBU6g=jP@I*2yJ`|u@k(g0P%o1)Or&FBvNauI5e5mp1rwZ z@q|6u;yVujI`v^gxq;=q&BmK3pg&C6x*ttfm5n-#3!2Iv>2cqGl%77a`fx+5Cx2*g z^Y{+GUsYJ!u-?L*=dETc%!#9iM$o90l=O?*l3RWBlVGkQIr2X3T$y5zL8- z$azC$Bl~Hg_E_FOi#e}M-g-nJ2@k(ySKxK|dXEYfSr{Wv$#)I~c~RYTQKu3u#d(g? zk9X(4qbK#to|hksZmJ$n>ZnkC$kC;}rSU3oFyelj$dK=HPY}<+=OK?s^{udUHJnL~ zfAm82(uLxWF{{qUh)ay>qW$Ij6<2Z0S;stbA~2d-M~~jtwMN_?OI&w&a&8rMkMN-s zm4cm5t#8!GlcE#W$@M3?lmu}!H8Yw-6BBl-RcJW16%ORY>3JJ~R%DKLrc~VGOS;HF^yPi+%~cFbNT_ zkHr@mXLx>WO^f6*WM$TPZE=O|UqLk8wV!o!(hWL6TIM&Z<7BDajJZqN$C8NMByP7X zK#nI9zf;J{*hGvFbFj88H@qJ|%fHN4_ttoYP@3}+Gx3!qo3^qgdFW{{_TGkALjaAa zXgx0#{_ek_jkuxtXPrLlsL2ENviu-sZyD%YqQ4`Yuv~Yxt^FRzD3#-7Ny8M!ta$bX zV-1HQzB+7}7d|K(5Ixxvei1zF=g?dL`)ZHp>LtjTfX!mu%}umPTNW`KrEr%&9hi@` zj9CTePXXqO=y5br9~T6Yk*-LYWPLdomZW{ zLFClDccMpkh7!kAw%A0rRLt~S{Ru!oMUrq#2;|U$KoE!gN3c8h5+{%djS;E!1U{d! z1h(>c_o964?&)|5?_=Vtt(`0U#od#2onICx{N*3btbW^AdMAn8xp)_`hEg*$(zANY zkkakB^;s52=QD{J_zmPM{V?tnp3&*-$PVn#;LkY!+eP4cbtxX&Wz34r(8ZabByuc2 zZpM!-`)1X-F)jozFwK)1Daobt88Q%)N@3!aq9ka88*g=JD-tP#>KIy`f)9VI#pQ)mT~3EZ;D(v}EDW5wBfnzz@S3 z?-OL4jr}aL`l!Q|KUzx|fe7uQ6I=e|_DhS#bLGy0eAXj+^0q+gbFTbz>xct#{2~$( z+&{2FIaF!NHx~OazzOi(dt1qvr@ex&B;27vF1>0#L!=Lr7IA0nLGFw#Cb3YRFUqK}zg`_A`G;5Tb=r z5r3p>ih92K+h9&p6uW!S`=3e%Te-kHfsYYQUi9$0^+@kw%pGqXq+~FH*v?r#0c>VwtcfP78H5F zuvdZ>5XOhs)y)tLvtc??4E@6mFZWV_8$Ia_IG3lQrVh=2Lb390Q5aw6gQnHb%S-RR z52Tgyii27K=s z1GBqb3xtb(=i(0h*|4^3h#&$H6m(;R-|l8{(bdg;?33AZb?1DwP~e+XU@ll|^YLG& z07;^b4&K4T4!wgOGodas{_qpy;-E!g%8MTq(Q=gGrI{)vl!#UI&x^Zq!DWA3@7&4H z5(0-7LzeLPpCkrT3T903hh7J4C~t;C`^Pon)hl%0^Aji2f(r7LCMhI>GI2ZsAVjB^ zL=FLyGUkf^mb#MGo7;-HcR1^2x`DKcC=c zGv*TqMx~)Di_3FU9+#`|UFong$(a5KT=n{^N6M~Fr6`s zEw+??timaa>Pp@#Z{?DwFpUC5#KuoJjNlhJ-p#z+7)U+*9WL9DNJsJeRlgg$n~)eI z`zyN0e~o@jA1u#<^Y>K}%}56rT@%K%HAE03r@Dh<*Z1!I1jzE88(%`}2hH~(20S7% zQO2q734mURE>M3v82YM2u^PO(@>GaF3oVqTlBJ?{z$wUW2BQVcKE_Ub^~s2VhYLO} zIB8f$zUXn_bxFY`o&%a${+QML;l||2<=M{IAJ_RNZrn9Im!7rbv%GjZIH@+@e(Mf% zsu*70T4OzuRds>u4QR?vZzQBlx&xDq=XzOn+9?3b=*(D?v zI#&L@O5MeQk34v5ad=A=q83!IL^i~(sHQ3+L-j0EACl1u~6gS)#s z{DoJ(60vZD$I?h%$Cm405Z}%FJSoiMH>`5t2J41AA8nYstCs zOY=jaj9XrSRbIz2z#pWuM#l$TdyjbKbrqGV$N6E7ng z8<+C9*i*)@isYdP3hzN)vJmU^@UEXDP|Y}{&^np6;MfpPR{ogf-(9>LZ@m|Z5YQs< zGt!j~Bbe~o01giF5S!YF1;;Q*l_8sj6#7?_+s4GoE~; zH5<17YcprQi~$}19=wP`<4*QeEFM(ang{R2XH(KtO7ct>MY#W6_#^viqUG`|S0Oz> zwi9C=P2kVu-0fAYdE-JQ?=eg$EsQ@e9Jm_NGCUddkukqI85j0WG`J8YwLO99NFt8l zAG{||f)nzB7zM_?sZ~rqt+=1q2eS=dn9@V*6tJK^Zk^TRehsbSCpPrWo}MjLeXnjA zj?~*Rw`J(!-9Y>zK+Aajnt(=zErbAyZ^56i8Y6ZrMj$UQPf46DUoaN(6Z_D+m1Aq! z^Y%qzg-Hg=T)-JleY7I;$0%)*FAzT%QMua(kc zSvg;f-#Oynb+N^#@7&#WD($MD{$nB-Gr|H5$@tQgr6T4ZGp8P$IeunPK)G@L<-kfp z+s@@xqt!NwBdRBgSQpCaS=@*Z+!z@TE48|-d2*z&f(i;4TD&jTt1`NI2Ol(O(l;5C zQ-=HAmg%S}iw@7su&GaSHjVEHtP{|pa&BScPs4lnZ9ODn5FB8d@9kW#xZpB?tB%`D zAFnGjrXv(c=plOX-bKED7ZR{0?1&{KMz50)a|~+{w;=zo{T7Z4h5EVJf1HLw!nl-wiwzK`^qgRzrxp2ZHoZLGyO?sD2@4stHJBWm#6@KOAt_KH8~=pD zOe!{<+-W5ktZqY^C2=RlsCm0goEt@#O<9jDn@(D$!%YwB7~-0QaxAYS3Qk@6 z>R=T~8{sD6j?6DGTa<-$4?M+GWkzxyhbfq%*SH}A0o*2)rFp-*>;b(n@I=k1i zuek<53F@*EjA#kaeRB`DCd|h$%I79TzWDi&9`BdS5j`fzc@{cadNeOQdK->v&H|nt zdNexIkU8V3G+V1%;r=`2k;X!iP7*g4ya-1x_g-T4s3U3|sUH_V^~_FZ@^eFtGyl}T zniq`Hy}r2SMg6&8H+%*yW~-G5A)s+d~rJ* z%uD|;WIANwqqrKYT@2_Y)n62Uhkm(22^*ilznU==jWrXvt?>g{{@PZkc~_4BPS+Dw zBVgx%V8~uw=%oqh_8c5@hqjuK;lh{(xpjM?49e(}xrvL7vP156GR~`Q_vZNS59J%7 z$k2{s@egD6Xik?~*ds?peR&M^Mm&Hb4A!L%b6&8prnI_jL>`KI;BvLl z_4?#bNe*{28(vo-hI~FyOM3Lh*7n^vEPqdDHEwnl|Fk2&Q8l&s`R4^p{1Nj$z=BF5 z7|tM6P%y2>cQNpTdoX?oPB>ey+vq%!>>|5Q>m-C8BmhFEM4#deUm zY2!;|m3BVM0#j~!KZg64yW*77_uS51|GXuc02nm_O~B zi+|fXYG8@Dp#P8xpE!ic^~S-GosHmU_LsxCk@Hn`@y5fCm=hb5eA%rle|&pEeq%3$ zK3LEwm6S@duNAMEv<=#6|;I z`e3GUIi(EN=H_Nc6~C}e?Wj$y&{6AklGI5r0z{3ADWElAwP3dEwfqR|ltG)XXzO+v z3d)^%MWnPwI85EDb{k-VQNQ;o>`d;zc?T|9wr&lr_r?14E@i?lK423qB$HQ>@wBS48^FK+5eQ&zT75O1OxL-0|IDZbm(gx zL!t~Ng^Xb9^b`|xgs+r7MuswNCbCGqaTI|!fX#NlHU{GQw)eYlHtdJIlR4(nk8x0c z#o?3coa_|U2B}zTxUf%Mk(jJgG!dg@a*w@R_5Q0NB14795~bJlTK~26$Gs`_rzH*c znh1B(jJ-|gp%HI~r}L4=!{tAWEmU@cU?~vuKEY}~U*_4}A946QJ$H$p_{Xf^fg0>G zVPPUj-9j7H{^v3g^V-9>F1=eI1lNGDm>3e8H%oRt>fUd`jsEh$nq1OF2yV@gpN^2R zL{Fm>)yDWrF}bx*dhR=BWAQ7Ur59?o9<6Bw4{+Sljm%pG~BXrhsL zLNvx@n>M!3tjZm2F40k+tYCLd@66Lil`qRzXJ@83&yKNqhC60@%f$_-F_%Ll#DAaX zNP*2VA6gIge9(o#W|lb%*S^i&-g<}4gg>s{+p9B< z!g>RV0e7i-rRyifpJNU^gFx_=0KpQ+O95r06ZgJeG2qr2ZH%c;qrL4khOPv z$yA#~wU@UOcc^!3wob6G&I2NFm_fex!{zEmLD;;WhiF{z_|tgkcr2ha()22bHbhUq zD?%ouai>w)W&nHWX`w~ssWbZIZ?BMVf+16a>q=cOE(K4~e}m_`_ru~u8zxL^2`xB@ z3DT(z?Tw{gcwf=hId^d}XL@BMS#_brMpYm4-~msU-cx`FaAeAvq-%O%YVXJ9=194M zp!*K9x!-J{^$9riA;LMz&_L3t8m!EmsD$AK6!nnI7v3lhv5TUl7n5)!u_r5Swqf*mA0V!2i`l>^(7@1N!yRPt}D70gOik4e4N`y4BI z5%!5TJuoEG5l{vHZ1b@WrpXKPK||6W}-)>-qX83`(}1o3y-68$eO zl;4E|1r(I$-+5FhM#1aq7#l;tHjM1*dZv!OVxDXld;zi9EJ9+{92XZKEkqj0>Yf^kGezb^2QtL!rk4 zwZF(@u>1@L_OmQsL{?*q7e#0P#LJD;H@ZGGim(@tTeFYME}yMye=KolS9}SD5R2KS-Kc+tF{#!3YX9#zl48*r zkze!e*PhrBi8DL^w4X;LucCI^&hRBK4#v&z$6tpb)H0$sx4OcTu<3|ef4s7sWvHFXY5Xa>b2+*m+<{GjigI#_PUQVi<=M>- z)ZBC^VYeUPkZ@7n==m1!Zy(g4GCW?jZs5OQ=TtBfQ$4y}GjdO7#EHuFXO>HSkDI=0 zQ=lzA|R~ zY26E_Q?^2yC_F&inTIQB5}eF|^ib=L;22nT4%Y;JT;lsb*hI3y^}x0&6*>Pt z;&ri|RyjY>=XRlD*)0$+AB3f8p7{~$I$a06n?*a+x71HZf0%=nYSurBZ_WErm!)%w zj#62GW6uu1{9XpNlkxNv=u=UqGAy}Y2t$H)Kv zZbWcsLPS2{=Nlz)>s11+%oe#B7Mr^FE$5TAK04NzDmuOY&iLD8OXBxZQifOeR?7=? z-e%`<`P<>Hl5p)r)w=utyNf&i=Rg^;MFlViAix7~J?};uo}rEL*9*=i_|E^hT3nGsYU;cmEKnba}u-eLsu!x9KRF#;pFnFNS zF2IT%?*9>5$V?!N?w_8H0Gupne0S{7#S2D#hR$Ok4u0=#_#eC#-P4$zU*k=K1Qrj8oY;#%-2OK}GE|PuNl%#^z#ple|ImB(Iau5LVdZAuEh|2@;ob?S z%;ecwC&cW9za;%OY*O-D*%}0pCY4|zWVgq_`=G7_nj%%L&gz~_dpPi--N#Ymz|}oEExz{&TwJjGO*a(1(^AysBuq40Pi`6v4EFt}O)dTyQw4GBo6S(L)5yM~ zuP;@lf;OivX?wDIIK%sd{@=kA)LA_c*H2;QK!DK8H^yI~jGJ+V_`xlwqlcEVSn)dg zf&M9v-?xF7pz{HO!v;o{qX|e&6o=x|BNZa46c3ljU?UF;7ggeE!R*IX}lG6*|J1lZ?_SJ+P3=DiHczT8cTEJNXjiUml4oDya0hdGlsY)DTveo~+o& zBPM4Wsr=ozPkH0Z_R&eYrOM1##yx5vq?wX!`H^3X!ZS_|$ z0o#uqf?PLi2FN3yj0n@^z{9r(KE`V~Bn zhQJD}1i0C-cnn)R7Zw)G?}rf`5U1ILIS!FhbwZvsMTRt^pe1Y4HA{$u76*n&StiO|380=X^3^N zlgR))5aUZQ;DX{jd=JdK;5eZTmJ-T2vGz!Sjvo8Xd?s~8|3_r8roSaL3(pIPSJ7*-Zbv}^lPF6kPA!>13 zT+!z={SIw}SXNvh+~Lc*9DBDS&yox($Pn$QT!AcJWuKD~V>;t-Rg#B3pag#f-1eVV za{};t>vl8d&O=4tQLGUEZy{Hdp~Z(%(MwT}?Q3uhCla(pfrXYCds8v$eO#a@`j(xm z!}87dPJJ0|bd|yZnT2DizGF!l=#h)PIi@^dUTpn2Vw)wI&)9Z4=5`6HopzPh3LtX% zoJHYEv=dj6$1N3HDN}WKHwgUIDIi~k&4mk<6sw*Uy(12xr^x@s*az2f001C-WKxquay3Uq%0zOhAVvM?P6L18ix(VY4w=~1{WwdU-{}U-0pQ=gD~quYx}1CS zU2U*)Ffnh7h=@cmelz=T)f6L*FcvO+j{iD9DL$xGdhUt;zvo&S&Jy*6iR0N~UN1q4 z27KJ&xr+vFD@gbS#sfMv*ps`1lLoTqla-kG_C(9GX^rjForh&ViJfE#^7!~yyuS8k zvACyJt$J04bIBK|yIqoZRWTssSnsjT*V&w=PlWOcTzo_dmI zt{qNaZ?28-A(qPFaJtS<@(&dya^#s4!?Qe|Q4m}3r!mSI_9n9xf$fU{u>euvE6jO@ zC{TICCN1uC#HM)H`q~Q71HlnqNF6NPul4|%xqvHiFw*RYcm0Qm(4}+@Am@i$5L~nc zn(tu<#&39KkR3wJMi&&bkJ{Ip`bDNy(*=h`*9qY<{BFHvWL^VdG(Kzt=wpE2&D%10 zgzN)Q$^n6Of5rI$OuHnmf2|l(ir-IK&=Std_u$!+k*X7May+7ae3&Ao07L^sKE$pM zFF7*5`@iQiCVvcEE7Y6O<@7Er(6!&^8)Si6g6lVm0&ng2b!a-;qyUi?vxwyA`1ty8 z-na&`hu%+=oR+-$;cNmpM+`!Of~+Bx0kM4q|c*f)IU%hv~{4^Y(;Qr1zjVFl}D-3OlrQdqGX<3e=Zpnz!W?9nk5DeRe#Vzfb%(rn7H`ev-q&J zL?fcCur&-UIzkLoxQUn(u^|+8b)j!>Z^sq031tkazMyon(pmzeOB`mtWD{dZ zTk21`nI{;KPG6$P;L8s>J~gzobRXJ=O1As=K&Qw`n(#0QZ051>Fn`lJI|i(m_5Q0Uyg4J41{IZB zoF8>Qe4MhKZz`|B(H$2Qju}@%HkWfemcgZ)7gk}ZtME_Zdt7~c-0g0i-J{o9)FQ8c zzI!M0#{6sl&bxPoAG{;-pVV>o?d$zKZf1=bzMC;rTwQN{XUVI)?8(S}=0omqcrR;f zM;|B_g(ZZ^UWcg=B(5Qm?cfa)N&YH>rS*pCuENyLG1O+fr0oFGxu*vcVs$=i=i(y6 z_l6e z=yq?;s%ll#e)ILmB@H$|G->Q$x_&Vib-{!m?I?}OJL~Mu54Way1Q;U1E@|MWH~#S2 zoZEJ~+-AN5q{Zs`mDVAcpDZPMZ4;X;ou@7e=g=j2C(&CRu8 zBD8fGE6(8R{;)SyZx$)rj;U9+$M=AmsM*j8g(4L7!Jo8PAI`~JTDW9Q!8xo75_ z^URqu&&&;%mlZ>R!+`?>14EDy|E>rI_PGdjod^R3`i}NV`3ovOI|)fB!+<{CFvekE zU_@XN-vyQ3(@$32(sf)i9^U8oorWu>y@sUWKEsIooFLA2{(>HW0I#m$;^(VoGFu;M z(^^(`wlr5mtt$UT5L|>ZgpMc(=+}_(Q$>-tuU|U1n<*1>i4w|{?^ToW-Y?)| zI`jQn%5}#%@Hy}2P`)4xqt)8mUE}rYxvyJgD{;_oBWktEonTDejUUhizmF?ni0^uz z*Y5c`o@T3Ly;=#M7X}};FgrO;PvMAzkfE7*=kbxZ?59>%M&~ND_FHg;!U6@nytvcY z?J|#TKOUwmO7DTEZ(}$;b#-=@_DU0iA@0i&2vGVc@lwLmw21poeur;3nwgQ`uQ&ng z8mWVjh44%G`xe+GNG2xZgJv5fKh7KChAD6#hoSqO%4 z#FXk7R9u@Tf zhhgL{nH4|@m0Q$QxrvhY-fsk7l7Z(|?)_=bUf$To|6@-(Z zI8YtDRFLNX=|s@yqJJ`j7V=WyXr$&o>_hyoAwyLOMrYzab$on$r&Y)goyR5YCBrnn z*4}=&AhZ%x-_6z45y*Ql{ohu;|MM&yg0^vVZKz{xx zX%YYc;?LiEKdk)U9)n6(t3uNwh=Ze})OgnqqX~!q(=SY8YHp5gUI)~(&=mL6;W$1} z!-l^;FbsMKk(>$Cd}!g}c>2-F$*+Ii4o&p9-b;KxJvhK>)c!DDz}}u|gY7EU{3^&t zj37()<%pRcp@JSCz=dU!xqDs6o;F^V75Q)Pex_+(8rB*1M>L=HL|Ir_<$+wX1O%xf z43{gHlh-@3*i7J$PK_}+Td>z8CUmkG`RF5$M{tMs9jDcoETo_e==XMQx}=4^C1T3u zyU4=MUTd@5U~v$QZ0NQVD+~hKjEz7EA(;N?Y}X6tX*5XJl%gJnUmO1%2!b-vKQD5u z{Qbj6+-I=8#=p)D(m%ABceb+m9_W|ZzXk%5sFoEq7`^o(Q^jef%U;S=YSt9gIF}PX zn2rvePTHMcfWzY|ecz_wnj8{>S%$~nuj7-WrzMS(2;|TrkUeC*hr(aZ8rH{L)Pj(m z%y&(aue*eiBv&bk5sCetGw-i%-`}b%Y-){kp>=e0UJl6lGv{3OXt?%*1-|$bzCPqY zz&2+o3XVdw+9m|irK!>^y(*Ic-B;iHEmK?;wwj+8a0sk5uK~7kQg$Wq0cNR`FWF!on(_Wt(laUueNO z5P5kHAihhwM&Hl&Cj8UhdA;9)WU^^-Wtai$sI&iu^V!wkEhg3sF>`*|`S2Jg<6E;kr5?S_XeUbNITtdRFJ8X3wtsu=SLt&jq=puN`Q? z?mmLpxiKT1c6i_I%m^tk8i`6CgTF*k0Q2H+VD*~_h5`egq5xKj`1j?rRr%Gt%yOzd zw-L)iG>=Mc>c!vU^Sd}+TS8Wr4s4aDtW)kuILHqC_C4?Q(0Q4wbSBf$@n3h59gGHH zS%7TQE!$GPoJ6v-L3=#t0<`R0zgcmo2qEHFrESqcdThs#!lnqJ(e#TS8yf)GF&F56 z(FXK|_uZ3NCUpTLnW|Ji4PCW1xOK7{(Z&*v^_z4+ej-tZtk{q2CK+^l+mz)hZGN}IDx8g6|Aa4MpiQICBXp$754I?Uk?16VwmHwiG)KYg0LV|C6)5S z8fcUceRV8EkUtl=ClbSax-tMa0+1N|S=;v-x--2z_SUr0R7mTRTu^Tip^`?49jwNO zCg1%9;S3k{g#;$hG0xK7J}&10`E}7(i29paikX)dd%a3M&o+ltrbCs$+6TutS2(9| zI3HIFO?kIp991-QGK#!JOc4m4K0z#n5!H=_3K6PI=1C7UR(d5YIepj6Z0hF}n4Xj)i3JMB>GBPrCI>Y)} z3L){}1I_~ZEJ|oyaL}vrw z!BPN!A{dxj;(o&~)E0SgsX~l$bZMlc0`)rmxjkP_X1Fgu#ZGf(@ZZ0t81qTo&S}EQ z{%CpfY*=1ioT|PB^LrA)!vp0b{~ao!C3)9k4yQ3l(`neI(YG{@6Wyh%95G}CTP%Y| z?riG9NLrLZkB+9lv@jt?;^rsqYjf`?L_%{%OBnjT5dnm~`G-;99KlnpLvrt6JcX&K za&x=_H;Jg^i=9i9NG=Qb{<`d9Q6Qp3mCSy(2wV9(Z!!?|>o-oV1)9F1W*&URTyVuh zvwwM_$+FTi%nFzhpk??Iz_y#VvBbYA+=u~<7YT4cCNmltAkFRS%*?|gt<)AS%@%p= zq1;D>B?nyB6oew<&&8VYk-M(7KghsRAQUU^sF%)LA#5GHT4gh(1oNz!P&SvG@m&{M}rWS z!%2LxPkdB3T>Bmb1O93>C_&)a_KA_lElo+$c{VFSBlZl^Jn=;KpPbV~>jk1K2kvM9 zP*z=Ew@vMPu{0@bjE4qlf|@CgDQQd?q6vN3pH|N#_o*x7lL|T1zp0`_CObH=xib{IZ0G-D67G1QYe3NzePXpeLz^yC?L6TMMLlT%=@V5C+|>{dMcAMrS|ou3 zbxd{MlS&ROY#>GCNP|r|5!gt?kqsnxiE%_~Do#Z3ryP?BS_jVn18+b7h5@n|DLVbt z!u@c}n2jH6VjLtMT)I~BV1y`k?aX}-c@K19|3Ds?r8KMG^#SX*Bdg}3y)U1P>}lZV8!Q-R zzp;Gw(GtJ))c=CcTlI%gBM`kd*I!BmuYwi5TGG%q%J^&PwlP{=5N%K)3v)K3HQ|Zr z*i+GvNhsF1sr@R}*pR7fp{D}`W`=y97HXd~UR3wJk8`$#W2*bOU(5u;rK>xj_(!-P z6|09j6C_~k#I$0%g4DrES z{Y=$}-!aL{a(!EXdlUKU0|r4XWX}yVCwItLd!ld0W)gFx5*iXXIJns5c)5J4ayfD2 z$-r6{^RT55Qw-(0S|?#b;Jo$5%BIs{%y~BVT6>ioBrzgfsEPgXs_UKaDWI8I%Kz%w6k4|9Tg7>}ed28dD z&l4ROfehckGuNB#KTF#$NXK@yAEfS?DZ4pg0*9S^vHGkfR z3GHk-zUT!Tas5LZ>0v-3;uZFAt!1vgJ}4_!UF%DpA`K;Fm5RxZ8rff5TpSiMYynA8 zr}%kS9@!k&Q=bPY(0w|XN;{Oa?y2Pk0jGC4x4U#X}ZOYAIk0L0gktb*F!+JWD;hl8#FM z_?oUKbO=WZs(SskLZ-P_K*Cd!lhufw*-bM^pY)=Ued(E7BT$qdktzYwX9gch;Z`8M zw3Gr_MF(Oua<19-=C>rWfbFO;T#De|7o1YKI1M*4;bg7nSzyEh4x6k{XSnCerS<@+QRJRoLv1>YM7nh0LNl>LP!=huN<8yn^s6b0f% zO8JTwzZAbENH9P(PMPRhLBGYtw*T!x`osf_G!*j?$&v56&&5$uUHY0lviUG+?cdyu zS5fDW&@M~Qhz>c?lNzs|M2RjAjhd818P>mr=KRB*Ml?q~UsP>6@yL)Pp}Qi?U>SpP zgbX9nzycrPP|4xf97+9bI5`Rhk(Eiwr6ra;gfe>R-}u23m}*|!Km&LE-&?7lmdtC& zLScm?(EeCQRs?FPyPpVImX^U%BVdz{OdiMVJl@e!Wk^y5NX7?JEG`uH zqjc?fLu$e)T;vkr86%$y4iylMS%SLq{5FyfdRLh9UI^ve3bjG zAb#;ScVkw3PpMiyyQ&fCm(VdqFI9@PV*E&Meel^l%gp@t1ET6uKpnBlQANNN;~-N3 zOG)XPCDm&L1@4h}nz3GtwM@XJh4MCYwP**MfK!_|Xx2)R-fE#sGT9t3R4;f^fRj%m zV1KdC|JBMELZuX4J4^O%O~A9Dx**D^N5qImQjE+0y!p5L)iz5;IL(~9Ir_&Ik;h;j zS5~%fF@X}MOKUTivkCN*0_9*gZ+h2m{ zzt)UImxhePmO5Fpq3<{aShbQ&<S?SCwDQLrh*@$*(_PAIZpJQ)Gc?PI zjPQm_9H|zxDJ*PBHD=PNjIF!eQ3XR;Mm-=FQO9Ru;gKdwqqS3_>trd!^XNwVW5mWQ zh{U@o%hcOjuJa5C_Exs$0SKe$ewumEl-t#x`djX``^BZ8yo}+Sd_+eF-_z6cgk&;= zApW5T3sf|kbIuATjFzJllq>v@bIDrOcuH=@|ZKGfk z3E3Rl`V3g#ltU`I*_=mv5LOvqV=7ewK7+&^U(%H(DJxN+E&ReKYTyl7w>GC>Ihl3> ztr3Gi7m*q8VsE{D%Pv?(ruJ!K)zG(;>wR?HZP^aJKgG!|eRAsRs_6DLQTPwHLfogU zSwlNhXjM{Ko=c_%Y*-Vd3eowQ7+36C5=om~44-he+>q}xytSQ>_|=Y)wl92|pF=>& z1(k($a(O=T9C~+2rqpL^JY+IePC=(=k|r-6`%3vx4-iE5-6C2dWM_+$t)_aVvngC` ztSEc_xZh>5@O5 z`587S(YGy+dfQpb)#71o9ro#a67QSqGL~?pC0Wq`5XSrnVRIY25Rc~Zp?TEnXa&xA9u5L(g!<3xIPx2wtwBEE0eI!atM?U3(WXj7_)6EE5e-jC!Mo zlTW!qZZ)RjEQ}Y|-5sf}%1^^{;?rNwyVr0{6KP=qOjJe(NOfEdAFq;F!utE0r^JXr zZag1m*^e@rMeHhROR5z7v9ej=3vJUPQjm^g)%Z1~-Y^i|tgNb%SUWf&f5Yq8&RMKf z*U*6C9Li#nwt#(}!>1)DS7R0-3*%tVwXyLF&QLuC5yqy+9m&93Y{q`Qdb@%73{23H z`EKJY%+}|UF@3ZpIWfI+a;qk0OE+_HK~ECV*p7I87T0%1um@JT)9Q*HAjIA(s(h=v zvxW?-va0L~TRawm?kW6w=;mhl2rjOHm&F|L$kN=ML4P_LTzG!bUFxQTQ2gIGmW~XP zv~O|287Vj6!Q%P5`o{Y_JMO(Yq|-eLY-pp$IDl+h=?MEIVtZk0yg@|h+9XfEVfbta zhxX9y1`)W|ukyfIF_mtS(Oo@PU4EtJ@Xj)hWnuTnf{La3axr?e%xt{Hy*IvuA%Di*ulspM;9{ZciDtdjHiLhej3gN;S#jVMv!!QZ8dypg zSY6Ca6`RfHSPta#J(bXuf54Rm&@4I%*ybzFikqe|$xlE|Ei2mRf3+7b4}xzee!YfL z|D_>-1R{JwlOQ5IDflI}=?ROrCgpy5?q#s7{=qQYS7b;X(Bl`sYGzL&w7tg$n|V1L z>}$vfR4FE%biqzU^1Jkx%|5%+Qpk}RBlL?HZ-~*eK$AU}GH-f(<84TI@esHQ@!u8Zr+ecc!0!}8)US}KyYTBbHM6V$G*GoTzpr&RzGx0=8yVD&&BTdUj8 zp6L)Xf`d?CyqP>Hs$R^fE0lMqFS<&VO-{_VW^ z#^XAF*8wjR76?zV)mPmf&+~KAKT{D-%IcRQn#&g(jhz||?RDa_z7qPmX@!IA#0H4t zC}gJ%{{W@47^R`HcSxUo?fx#xc_#O%!D7!1DT+Ks)y(c)LVA8jcwf~udj4~amx%qr z`U0Wkoh7&27miDrDuMk}3G1eSohSAm)z#23WRIiV_N{XC=SE1hU!|@4)$tnDWJfpV`B9pGE^syAzvTl4vbwO4;Rp%xy&RzdV+Vj?5Nn4+K)Pk>L!D^aO^ydtAHer*Z#^> z!#`6I#?g%8#A=EMEX~6{nT;RW_uN(6FkcU4{L4f)ZP}Rd(IdEY#ELTctp?FTlW~;B zC`%HsWf9_?mHLjh&{V3?M#2L`f^{OCV_ALq+Ft>~C#m)M6!S?qCCse8?NkWIxEd^E z6e`06ijoTPvgg7&d^J8+&8l>hGlSze3znDlxE2D8Jn+t~b?EnC?+*HQE zenG=bsR*=L!P%SiOypW~O}O0owMQqzH2T~LSLnx>GzDK2G>&%ijoEUt`aRx0HXWh& z2shalzkZ`EFnorllj#D|kdxfwA=(#MP;HAx10=0+Em(o8Lo0jFBn9*K1owGrES^V_ zUDuE#-z39c2z?gxSRco#CqAZhdQOSCnaUJt62xy-aE0UP0SCXe2EQ$`unDojuK^*T z_-O0@v*S`I)oQ!_>G@NVhE$1?%fo{;Y~z)4Q&RenY)z;jb-!WzZ#Ayun(u^xd3bE0 zX^$CxxJZyl3Cwv)%q|q_xU05cd_MbKoo}`FpU0CPiKW@@dOv&1P7F>L=gBFvhtk^@`H^?tzcVP}w9u5G zq#I}SLEb$&A0V=%MsJFqUA%V*cMBVn^LAeD9Y1QHwWS)}piEJT3>d59^7UrC5qi+L zN5zE`W}YEoCX>!FYFq1#e)0Tr%O#jLJY~mrQRl+WyT`~xRy*h#GbeT_xvv;AB^FP0 z>*mvx$^YbbX@9}M$5&NHzw2^l_1OLnZF}R}{Rf*C%B$oWPIW2Sh%)kipHDpNkh)5$ z1T8C4PfV>ToF22ov1{Mj$f?;0dw;=9smv0a0fGmQXOyH{uW+SEfz>g_hpkAXXevLA z0jnW&^+-ZN^Bt(~=o$d%4bD#f6prm~0yZZEFXS`)4j%+gbd zh{s3~3~ntL+Tyf?bCty~|17GdT^KK2@xj}r+Y`Tsnc|8z^KN+3@~C-0dlg*I_Zeek zoG6gT>TeQI<76-an0|XuE=}jVieifztHt3zkv}Ysj>5?-ur4`dXN#4#3ZBD3FD@2; zZpzl8%vQ^klvnrz2S7mhVigl#F0*xdQ#`81ppRSHT6So6l4Z|BjHo(|l77T{U+@35 zes7g!#hZ{@*Mn=h(wef0zHUWgB({Oc{^^5;naW<<|2I-FDm}M*R~vRrh-kM#ra`?@4uA{ zv}HdWsmYY3W2sR!v7C7KC%EVf>j zQql2R;I8(w_FMA>{ma}lzQ@(*^!0<#i_^zc&Vbzzq9swrVs==oZcwqobF9s$@PNkM zgO3G3M1&I&5cu(l&-bxuP*bXDu06@=1Rd~O&{G;oB5{Z3nTO7WZZj>|?z(p# zRB~;jEyk_&yiieP%E%McvuUmb_*3{t&&$rH?pB9J@T}UCT2RBaqiWZSmJQXtC)rAF zj+L)WbPe=dei7@tMQcDr4uRb*#|9s^`F?(xT1&&wMZxhKrK-Kj619u!1!{>hJBL6w zBhCk=l*rS_2jv&kx?@+i;Ist;PjiK_wozYfdNl@u0IaiOf#WOLeheq;7xfQR z=O^wIFDUf2f5sULzf6vUWnLIATr1rdzZcg$F|{3gNs{Jx^FU*FxN0>vK!_cMVO6~G z7AjOWe(~qeEwdAazK(`BP3%yUj9)U+w`?dah{YR>dUmY3SA`qo*!laVG~3&ESLn(p zjRx|`(10b_+ipQjrY0n#S+`9x_UP!yTvU)4@e4Fsx?`&xbRH$!D>j31%o~{s(i<*V zi@NZEXuPwL*~sLo4rIyLO@sY2_K`z*A4DP2k zquKKDwR`g`M$qbWr#ugsQg8Heut8`v-&1AKYt_xE#TWzu}uBv^@d#bq*D-HbeO*k`B z%!PfYWIy(Ig$Jhg!eq7Os=bs8Y&ti(ZNvSqZ#aD2$?$rc?-B2zq7LQtL9MS|4@Etl zag5kkI}Q%+WlpTgoK;(DYck%zXTIg$Q+4%p>#R{f@{aLP!}%+#chi<0I%{jt6!Iv4 zA`D0s}6O%K!g^Ptdpb$;o$`}x?NFXf%3^VUyn zZAYTy8+AFlHtsW+ozwd8_2xA+Pnvdg>88!uY+adaht3OI=Z&98JC%K~(PW{V!4FS* zH7>i2k_}1%06}V9v`0&ZpTrBZ*nx=m*LOB_DWTD6p1J zd$6{s`+AvNm-IBaV&_2{2B7Eh)I^A+xK(_sy zEy8{sdr5B}T>BFw+`Ht0aAos7)2W=I*YX?3tnzAD;{1ZTaXSrcM*dWZVG-uofvSay zqKQg1^Fp}YOEDJbglVHf&h(4xgWCE@-u|l@bm_lb6&_m5J5=%bMVw%Wt4iJ~1?5G$RbM+ql zjM5fHM>vf{T}>aDb}(d2Hk3CmS_?ma-WXpjfvE-}+BbBd)%!g_a_J!ntm1bTPIw~? zOHJNPBP>9Ofy+N06j89PVM3O;e#vK3ux^W83CL1%0=l_*wY4nU37TmUIg3|3zW=FF zs2;vS^@~lk=pC+$*LFjfVXs^?S{DnsKGpn;@2Usm<0gD{*PmHakr|ELrKyfDAOn#Zi#58sebRX3}ar~j-U&KH74>3jbELo9I6olRS; z@o=wd6IEO70grI#9m4P8yib3@z;(jxi4hBGj7Y}-lY2~7NJ!I#x}qgfkhxE;Evsg@ zGuEufOaql~4A_qA&f}g=wmM2VHze?j)diFVSR`(dz0a?lyoStnTV?_>cRbGrU)G*^ zZCWx&ZsWJdZOZ4lsy5w^IczU&ceVQMu9Yv)j(cx;zVHmuzv_XaJc(2VD(5=iyT2cX z1G-tbu29wCF5){94|=(&a8nGvDQj6E?!$hM*duUDZKV76P}{f%e&lWZ%TQ-q^aQuDth;zc@c|%|{?KaEI%HesT;;-- z67hSmVlmS&`^n6i3G?RJweJlAt)~jm?nSF<@fiUa0<59a2DZPozZ5?hU732%O>d|`RL%c+LA+WKzxpxjKAQoxl)xN3}!~G0L zTO^XQ%Srx~kUvZ{=30zaFNV~pXK+)-OKFdW?>vE(BqFPh+c1z}v9XQy0( z3z3?ZQvgY0^^%uE3@0RWCr*~vHI+#)v~vbpVI#{)zZRE5&EvnDTLmsmL%EIJM4f+} z01M*4%gBx`l3;bzv*%Ci9s3;R`+$jTpXP@P*YCY5k$@vpeShge=bbqiFgU_~0oALt zX$cC*RLYPUr4aCuw$ss}gU1>34!`QLf^(JJYKT|52JA`rsn@!W^lyVYPLG1^;R*lh zj6{rbuI#S!R#tH)7zsChfn+HoBPxw{E_5ODDa?X?g&u^2eUjnNqW1p590J@SUz01s z`{@?%1kT3R_|$1K0Z2;51*{sd-$NtCDN@GN#Sn>FpVK{|d3(3Wu+z2#kEE+ja_o6x zV()Ek09Vdd1!E6WYND@Cl5-|s23mu=8HL|-Q>B-ift^{PG)92Fi zV*i_A=~N;hwD$(%NuHwgWZ02A(bWVk{faHxD+XOAzP`U`kXP*!>ICjhPPKTk1fNP) zU!_YP1;Plf2BYh%c!&z;h^2J~l@Wsh2c3YE{ZePov1BxcD!pP~H#WjfVt`xTqRC`^ z^;E$LEIi&I@nnVowTMABhYmSOUpdDHPqyK7)?vri0_;fOj;g0__4DFRjhJuNN&I?j zhXV0(6$eyQFmGL$_u$w=;&E~FzSoJn$_><+S_Nt2#UPs2Ti?aydra;2H!vvKXTJh6 zZ4_X8CPPDlP1SiHf%f-PLSI;{o(EZ9mtJynpVy3hJHVfEim%K7go;%il3LX$7sDA+4Ln_N zvW4j28PMh`urgX_Zj;Wz0)B%x{H9$YfIsx>rDzDjtWFZOTz7&)5_`k zn8~;a&9qcA>562{@4h*P4q)} zx3m$__j2k*LTPWz>oPfI-?Oit z;(?&ns^(O14JF$sC!EtX^n|W8iqWC{z_d>H25h2990COlKHPTzC{^t0*`n{xTftu$ z^T+PX`%8L9if2VjX;(G*P35P5+?Fp?^b{42&4vC2@~Y|JuVvmZFNs}v>OO< zOTofIfTcJ=iE?sqNR;YEyBzD2YeXpIkuugSfQ4+yj+46O|XxvjG;=V;FYuy_*+J4L+alN^;$X7P`;`eq*N<6iK$zCGr!_zx>X+ zs{B#nFd}xh?pGod5n{+I{D$1SXaHw3oo2BErO;gz&$S21dwV=-jPOk?!0(qFhdlTs zPiVF?8Vn6)G<(Pd7M^y1w10H;6b|IhDPDML`-mm#mcBt&H}*D0diUXOmCpFy7rdDL zrB}W#sx#cq4V80xpB#f^BM2-*Yp;h9|L&4CfoePA@Hw&KO#s{4ofcPR8^8n;rp9HV z^Mw`P&KtcL%&_ZtU0l6f;C;t*ul-QbyDH<9d;Htn9kN(OOS}+Ycep8~*4#@J&QBVf zjD_`MBjKD#6di^Df>*Z@$(hP7yv#dQpBq@@5%d$}gOLe)|pdMvG9@9IW>Xzjg%CP0ZFI zkBuwI;*S=izll{1n7(U7Bws1wX&)7nun>>2T+-djHvD-;`ioH=rfDgWu!U2ZljV!I z?H{lV*La=H@A2j83%PyIn)Veh{04OM`!@NJS-J&qzh(i2>$X4Lt~27voqT=NFA~I{ z&=|nNq67uem~rAeBd3C)rRU2EF*}%o^2V6Yuv7UQ!Aghl&lDjd7|W5IVi~fc4W;)OSEKdl~FZUNzXOT5NXf#Sv4lY9u>>EU9Fv95%`GErGn1 z*LRfZZjo{0)hWFI#gLFMdp5G$Ks z2o}qB6KJ&>ys^RjJa*{4c;;$MMjl4=2JDJFp*)KK!TfDwd+`-)eznf$Q!z!oW5?QO zt0xz7^kdona%&m6jObS#yPV@s2CVN_ds-vQz8CLwdoA;;13GfFdr^5U>Wvji*4>-) zv3O&lbRKb4Z@!dj74GSIT6v5|@Aj{xZBM^g%b!Nez||W75v8fo)g!|;bE=^%WNg(F z?V*xnqG@GiNHoV5(sKeSFLUwdYeDICRu1 zSTa4`>-?WgpF3~@rOEt(4d#z-zomPM+U&LjNwOJoA|PBbqRU8W!daTBI!BW~ksPRIVCbBKWk#?`vBuV*h<1(ww}tQ@Yaz0EX`RsKfY`CH)< z&)l>1gw1OrRe$a20x4;w22dvN;I;~~R{!3XiWgSXrgh}_mQE*9puMJaTX61|DnmAy zFsF~mUksQXt1o>;m($n4Xcqe6%_uh-9v?M$>62wmEQcIpT2^6*-r&f=?t{pPzCFI# z`ZuU|VR&<=&vA=uK+j3e{?p(#b}Z-&1jP+{iA{M*sX9Z_-# z1fIZaz`a6Jov@V3qFx*Buz} zgR4E<%ZpTd_fUTW`MQ$!aGmdyrQZ^uk3s@K>wr4bRPO-d694 zX>VaX*(SY88epmIG{)+EthJ8QX#IG#3x@hh;k;!}$NO1pouJWr@yf&t{r4yL{noW1 zw~p5ghmjN0X{KGoO3pMavulg%$9AqRXK{6E36u3+q*2HPh{%$|b^@Sh82#`2sUtIw z*YV>E%XdlZkw@i0*$qoK(r94SUZY$&k<&^t!*Eg0J66`KFm%o{UKZgKxW=^(72(@g z^tF-4%fO5WOH}lduRw5*_MqEK_UWI`(lg-bW-fP{wgdy|}J;mC%S zAofglpT*bK_TS4?{v&}S59!S@QHi@cM>v@G&PLa8!Ds zJ@^SXd&?E?F9~jSL6l44GWR%FjGw}L-{Bt18lHAP;Uj8QgPurz=@y8=KA@d-f69OS zoW-7H_M_9E+&#TWV?>G*(+F_Bar#1{w}HEd>)q#Fx02<@{65^;9OB3F-p4-5K60Cj zhezi~wS;;6T_r!4?#U$UcRgp1vw2{)#XroG3!Gm=x1uh2V2i2~ck z+kSv*65jFmnVkad8-3WTXxn_X<1g7(2SUrOnwPZu=X>6_684n9(lOG9F?)d3vQ(_7(5om9_l6X%*~FwH@KO?Rpo57qrmMl_VV)-icP_ZjN~_B3^<1FT+=E)ehWS4>w2P}+lNxf?IE-rexhc#>p%F)ta${donZWTyyk9JC&| z*-*wJnigmZ6EUE$w?wZa%{dGxFSc=#r$LL3HHgHrkk$IvIB^j`Sk0_>O;DJ zfC~Xi(?1uG?Qv4F?q0}bYh&@yKo(ikB>g7M7f-aEA%~Y`Oyy-QJe(sbwHRfOGoW5} zT*fLT2uT2E`@TF2hWTl4U+LZq4pPV1tHmpS+USYjx7FARC1V23GveE^;vW~|v;(ea z+7bd%O0>2`WaQEqra2G7m;PH@)Sh$Wu22 z>F&PlnJ^s)r9W=iN+hnJd+_l&c2vh}zaJn@M~0n8*!sBnrtJ!_VnaOWb*|ze*d_l{BeR3?`n#{C5qa4aad~Y)=BZ!q}xAq+;3^e|9Cv#_K=roRQOsBxEqmlvBO!8%o{)x6LgCfCn51knuv=A2}j ziOUf9((_CT4qoM`J7h9mW-)D3cg&`{+xAn9gPxoL+^W}%49%7BGH*)`L}_n)v*LV5 zer5oj_z<1_%flNhb&`C2UybxrIh^v??lh80Whm5$a0|6M_LAw@r0z)dNCg$WG+5S$ zZSctC<~IRo@3<&k=R#~Pb^))W>+#N`ZODfNL<&L83WT0*2t9vN<)Z#z*BhVRe%*Vp zX%B|{iA<{WyUZNa-=0kqwX2E#Zc+h;r z0r5Frf&5B2Q`%c?cok^AG}#eUG&YPUW>^q%l~N_rz8o`IxZLxhE=oefjbBKKo#(n9 z-jBy?$?d)?4MQ$!n`)Is@1s@&w1ixY!*@8oLzv*^EteK=?{{ZB9OKU&=MT^KJU~9L z4JdKAjgpaSQtBj94O7(chJ=M0RKn&HyqLUkXB@d>*OjJ(ls=oK!VIn?&B5j+hl~N& z6OI^W*OR8|o%~DU6h*_~QX8fk*@&+KG_YGxcfOT+@9r3pfkYy4U`a%LRoF0nhWCw~ zI-j!d0?+TCTemCxqOqUR2JPOAI9%R1VWRW17WN#PZW6@igo%-;%LZCortaUAk}g!z z8k1Y~?v}<{Ys*GcjH8xUm%&tI!^6U~VGB>t{3ad_0tJtoUuI{nX1bk6hVU>B4Pe|Fev}Reiwd+j!}vPJ@8c7T4AlzVq4c=4`XD zM}`NDcl0&-`LXq)Y-M+?|G0hrI=<(9=eu`+?R3Ab84@8ZUynUgkIk7)8_9JoUUckL z_=cQ2jc*hZt8eK2!+QYIK7Zfgw+wF99l+Eda6*K)u+Tia%=<^|TBDcaC9g;OGvT)7 zcl5QB*U$9d$U#R1Ru0y>4tH3x0DS!BD8z|RFhjwP+6b(nQyI2z#n{%h|Jg6Z&4zT-UsWuy@y8D`Ji$j0ARwjEc;41A{HC+)F=@Py|p)`30z3(n-Ya0`` z5$FY+s7`fa6Vz^7cihRf6R6lJTqP51DKm@dsz_|lU*e@$Qlo0vYa3UWk>g1_@cq*6 z=iU(bQ#^3_cixb>#}GdWb)fl%lS~@T6gSFFMTS$5iFBa*L;{1e_Dgmsefh4P+IoB- zNwv1Bdgw17FX$gtz4K=k@1hTIrDw<#^{^lM9tB&SKOy6SO%(@P~h)g$cfYPK{ z5APg-#=XCuUXufD))bzyfD_A+1MT&;eKX}`FC_0(9mz&O_UD^K#z54#*vzF??JkLG9y>YR6(aMA66C9cwnqmdT=;Ru6-oKt_S;lg* z^^#X5qPKrK`_l}P{(olyvbHf_^)^)ZRY7MVlw2dk0>vI3AHddQ2>m7#py)-1k{-4< zws~*~_hnMNn%0^#ec^(XIWu2q36VMm_IrCPTnB<*Rjo}HErRqA2{(+HM(K@xGYOsT z3_=&X%QJS3x(D5fyyFJ9-`!+e7aF$*A6pN~P8?jXD;{7-TOZ!v(6u(DHs3d)SGBOD z#vQ+UY=Y4HDRS4R-fv{`fr9_&73Q@tE283}XtKzI;RO!5og4JlB&ceG?X~e0TBpW) zEDs9*@NwHblW~Z+_=Dz+O9zfmG`$#7o$QI0H^77s(>JrVy_M*XyWrClJsEK|Eb8Vr zl3S&wm=S3Xsa`fs1NpHz4)n}i%d&kQJB$%+CZIS+k2B9$zqyLc;;ssR1-8PRVYG&? z@@mbqv4{#f_0uXwqD%^1>lcG*O>IqvdgsifSUJ||a%FQqza;eDi3(D>BAc9M4l%3{ zWiBe^464WPMYlt9hHZ-{9-U4v)$wwO18a7CxcX_LPK-tlfb}!n`WNkXNMXQ{J($V5IVvxpDk5U2lm} zm16B|oEFXCNu_<=x06~64inv5m+>|`qv;Z{Ox<+O0{f#WKnk&~o89)0gKo^unlSD9 zwd7ZokC=J7780f%)ILst*aH1Hashwba@L-rx3~F_1|aVR-OTR!8#T|%1%lr7q3aEg zA!yaUXItxUN4>vlU(0J_c><5vVGioTvX5377+}(TX0F~kQPu< zYH5&`mhSEb38i}h5s>Z<3CX3ASh_nUR#@V_%lG%rfBV^cX3lfYGiT16xjSnr1dX6a znHWS_mk-K6yDdAPGbpYjf8S?3dv$X*$|E8YqZnWN`11e=YVn%PCZ1Ke1t&Q~ZTS7o zbV1>46Qu7h1MaA}nm&D~g;mI|d|J1fq(%~_#-`W9CNzXI%45Gh5Wji)cb&BF+wfNZ z_L+QFNv-i-`Ud&s`EjRzn$oc;hcE-W0G~s&ny@sPqO_onKt0M=`TFLe;|fvSw#C+l zn@$ABiDj@DF~M7eU%U58HY;MNbDP@Wf;eWVhp~45bW|Y-I$o}IS|E1A;lT=FP<3`w zb%Rfmhz`JomwLVLj)HGaPQx4TxA2KmOvL^&!6ju<9V;v{G5OOB(DnZ1LY7zE8SVmS zHmURb*w|Y*#85@7Gbc3a%|>Q1s8_v3L%a4;+}-%Pi%zG)6M%IRXsjO9e+h5fd}rxi zF)+x+YjW1IHfWPNxR5bBh6b_KqMve@$(H>1jIJKF{g(~dQ5SQO*6&}TQThUHYZIX18Ne(m(IQCYu zyF6UeNo;cIR`1 zdh_vkkriP%7Lb)85Z>x_#ls*a2{h9T;dyUjHST|rN>l2mr$wxo3-zBWH~LlV@2Z#Q zFoqyjLWZ%MUhHTM9h7HfP$6OAGzi3QB*|)Vw~2)`*ioS-z1WkZEXAb26=4RqWg}Aa zi&M5TW1E&1ydUr(al|0cM@M-z-G#{$g`&@sSUqi=@PkN!Y`wC^7iRzEc&wR;M%0$X@GXn`3DtP|1xiT6~uL zGO9`^RMcvrKNdO`^Xp3cf_<7wCgDk#Hyyhb|+r^q`_E>qtXC^vo73uzV zn%Hb1dYf{gv21#5b?OWwKSpB|BO)qguRRD_Zf=7zhgJD4b5dLDg~)k9qR3h-2c?Z5t_OO+w8E_Qo^YS%ugU=WY$eU1JB9stREobVH{zGJBX^ zQ-Ul?ku}o9AsT}fN00bNP31>T!8#iO?~-&T?QYp1me|L&W0vf^vpV#{Eg@D#`Fm%s zj~|zYqQ^{MB#*$X>ZJKBLebv8OQwXldWs4Tgzyh&dtbhV(>QH5Gcy-XgBoAo=DM0E zaVc+O1SdC-?Rr@+LFr5Da243zV&ef#+b~Zyt}PZkn^*#^TI@>|;2Nnp8?7{1#{SIP zpMUISbL?r~lKj0`$n~wgCzd2bjmtkL@?zH7l6*_3c-x;ZH7JM1QW`qEzvHJxIp*xRT6k$y5_K}h{TzG*t2+gq|Jsab1w5&b11>Ji|TT|u*oRr24o=Zx#*5PkDk zJ~{%o6|ij!+mfQny1VN7w$RbE(CK%<>jDD3E2-ygSxP&VRNFSrX8m;sF-cROQvTKt z4s!(Sx)mvRG9)*Bvh&1kILVytVUR&pPhjR%V>}U;%jcd-Q6G>JBzKO1&PRWsuxW8% zZWQ$G*UjZUGG=b#o1;|{YdvTK68ZFT)7nK{T)a5jgYy`RRAwdT+a-$rMCUhPnW0fO zY__jZ>xz0o!U>t*4$-QB|R{Cj3miv9bjkV zS8{JG%>OB-ZMO8V6B@nxN;frOx?pczCX_;DsIcKP7EB`kg(UyCxlA_+eOIe(f`MObL$r zQu#~!X?HOY(5fB54BeERPf5)i7j@%ocYstyp1UwDGkc}uX#ewX?8zD)g+8J#o3y2+ zb~6nH5@+LOPhOs+O#Mt@v*aJ|%KGyKg$K%SLiER%W>~Yi!E><|r9I@6nes_tn%WsX zpCa-|XU=rs^>64ff*viyb*cHc_C3&WX3m}!vY1|zuv9K|^o+6^xED!((_}EaWo0S( z`CY)ucc%$zXqPf*W}XE*SN}~vYHQ9aAwbM&R``4nWi*2T^Bhhf!xf8BC!NI<`%|-6 zpd1=Nma{jr(?6B=mbYhNK-*xqjWS?c=qu0uP+7Bm91Bc?2iKP^D1-8*Q1gEHT^%|q zNuw=kS9S8PVm%Ra`+q@cP<1eo^cd2SeGYTIWp8F0+fn3{6|Y|!sG%Jlo0^ik?|8>E z%Qd?-c4F~WRDxlBwVB=Sz}SmQuTL8@Jisb{qParQJ+||JCaH1AffKWrQNzF$xl-Elr(SrA@0a6EE05gi4;q084g%$v?uvfl}YA6js=kN&~BZKOI{+e%NH zI@#bfB3(-o$rKIuYKwKm#G3qwc^N%9C(9Dc&1yXl71>pLG590~y~Zv1AX-VwodorY z3JQtQlfmxe@-PUyqd+)1?Lsaag#|ArxYp>5XpRi$Ny7SxjJ?Cu_$mH9F3|+*zh-}f zkn0}%Z@nsub){bC?XFlo-<{O+_Jy<$_2}l$i>I8r zqqGZ`&n*d7UKJDWoO$ajrF18`1QGy(G+F^$IyiyvT{^@Bv6`Xy?J`l9F0{KJq(e6lCL*|2NYB)L%W z+yH7sqacaceuA@e*~$p(TQOG6uSq3DdNVyb@<*j#=MPs$y#K6`+Z~K=UyLWXB+%7g zcwiD!PW(#Q59gGy?1BCM{RDA&um)R7I4C__(Y-U-|62#DhSi%1pnap`6vGjAWBs*o zu_Dd}l`nq7F=ut?ZS*Yv%9+EEQ`q}Rw72h7Z0>2bEkCou0~6UNZNL9pV=;1U0vp&0r) z9Ej4;P0uRzhTQc#lke$PGdu5|DF}z(jjY+6e?U*+!X@c7j}#}_kFRSRe*;hI1(#oY z^I^PO2?Ksi)Wy_QaTPr?s#>P`+QnrBAqv@!AKpqFPP}xOMm4vG=%BGD!B0KS8S$n z>ME{h_I&C~M-YT8a$#)xjx}#&u-_hLznAE4nHNdHcvVu)ak{l`UobOFVD3A3NBW+S z6Ov_?a##q(#zBYQs|zZRZrN95a1-oZ%AU5K7*?k2D#>cyGuP{kQ`k8=5VMb2I$V`Iu+N4WHOqX)vBF;f(2W^RXuxFD?vTOzOsCAHmc z(=~R=P{MP@?Aq3wO=tx_52}PjNd=x1g_ygQ`PKrow{H?Y<<68kR~$BkYjKd~W-kGd zmc8pU_n?6VPM&PlqAs4c`=&LsPt!39x02U_ju-FLqARm(3{z~Xi-p6QXydwhF(de! zIvbBC>CVA-zh-IkuI}`ZE1sI6xeyz^sAB{vCQL8chdm3XUPbTY1F$QK>M}7*K%X2$ zlOr9|?u*yr|B1ilukdM&rI~7zIw)fpU;5RQRZ=Bke2pi>@94F$Sgw%9tJBFemFWQO z9m&%SlG<5krHPtd4ZWF8O}32=2FntNzLPHoG%Sh3(4=a3gaNqcf=eYUXPjV67$#A8 znA1>_(jUpxLSJowKI2$PxABn_VmH8BO$Q611Ankl`19-;3kr-*KEEa|%)K1i(ecQ0 zBKL3k{>0}upZ`!~l9Acm+#ZEv5^OnDD<|Kj}6XG(2?hUM|G9DUi3;`T-QR&6$4-SITZ+(hKINKcU2 zFI4H*U!D!~vzwivuV+51ggtZGaxl+=R?GNCit=B9S95PNAw6%Drb@sXlLW`yyOw_M zMQEHrT{JY$97fQ`Aye)0OeEn*}^#e1cKyGG(uoh7I@lRL)5sgm{x6-Ec$I45Ml zk)1OB%c-A{o30*N@;ow|6`HAo6F!M(wQe3k5>u4{p z+8@`ae>-#jy%{1`7d^8-9zo$z4jmeLv#Ag!o%h~7H`uF88vCiPopO56acYI~qM^xl zTGm^K$>9A{vsV**^URq#uUlcc*KR41qkS$etoFw($`|ToZk|bMCBr#7UcXp0m@S13 zg^LUPjQ--@+it);w}qD*cHwLwCtks%=<1mRv&3;Xdnw7eodD+?AgR;da@Nl_={pCv za%F>Y%)JIvOGi!l%t6sGGC0qQzC_0$L570!C--QsFkm&?_5?QGbOZ55OUdNC(SbRH z_#v-iR0GtUm@@l$elvRoymG&{H&AqgXypqQ_F@=86r z^>saDn&=Y1hJQg2D|}>xeT@keiC-<7tiUI6&_~*_D{E+f6*xMfts|I0|AKanu6HX( z`2%CAyE|ODL=%>@*z^1Ri6@6ld{yG>byKVhFRW4MqcCaOjyF$Rz01S5%_cez1SQ(W zJI*Eqb*Fhfa>KRUiuzo)^2l%fIAT=OV&xzvr!{XAyki%qvNoPJ!#v%d${Y(w!&oXN zwL(64+w42MAf87sgdJ8p?1@jQk)#v3a*XrLBdm97?84!M9=+X%w?;!(e?O*lntEL`{)A-sP&PQ*l=TEtgju1wdkU4ob zZ0^NR-Km&pz1@!FG3aSuWWG-JVG?|_E>irnb1v+t-@r>}qJl&J`k6x)W zn<=nUaUM0XL$Y&C+!+m0WEyF6Tb2|V5;}FF5}bFQ3H>A?pGAT4&S2GFwg^-%up>Nn zY0iEZ6wb4?v9^J|TGDkHsW*41_H>=*^Ml81Su&i4_Oe)d9V5EF+3?91&`Qiif_;`5 zskcwMFzrTqpkDv{&N5^BZ5+M2yyw1_pXE{c_#nt@dgciQ!SEoE${Vl zi*2v`YO$3~?|@oxYk9eSIa$>bY{g*uV_SQ$UHo;E5R+vNnR400l6&r6QB0~ZFORdG zz*IT#`wzI(O$ox-?v;qAD|!C{$=UBkY&G|iI%Q;XuwlhDF49SIg@4|8sI(wmzdGsP znjPz#buQ!^4Pob*pYO=vO1%n6H)P~l$8+x!5b)?lGnok7W}td@B#GS{^c<_+$TAUC zoCEX)1QHLDd#C=wa`qfe`IGo#icgdhKrW>;N}cJlG#Pi~|_3>X`QXaD#S0$Abg zKX4colqN840%)k$JYQBtz79caEe+=i3u5~gX;NDE&o5c04I6!H(Q{BXZ7ha!{Uik8 z>tv$6CMWKiBfhP`_-QBN#rcN!ZYtXfWME8+V^pdzVl9NpZX}CYQn@;+Q}uC^9`UH- z&fd^!82d~mMqxK_gl$Ln`J0)9mgZzTs}HAv0g2`ja|nL!vi;TRSjj>}MX(6g4=uM*KYzQ6|Fp{gL~WSg8SV)#$3f1DY@t;a|(sAimU=A9qrx`HGR|WRwHs&msrJhlk1fLNF%@1Dcaf77 z5pl{aacY+JBNP!4WlPN(cC4Rk0=_M?dqo~SLqYjOYBA`URPM4i#PZ%cSDM!dpV)gu zOt=m;&i(I9Lmj!Q(#S-MBp$|iNr8<*>~)}NL8iqBqQa=KIlGKe?n7*q2A}^b z-9W87uhA6scceF%lO9=>(S`0#N?jgkF9+^CqNSxJ|H2N85YqKJPLb2iExNO_6Pa_* z{rt#UZ7~Y@FaHKgs(JOI5Be)6j%3aC^%un5eOXmiRloS_E)Iw;ab>G?y*~Jl ztnXht*y_5|fq~}-^WYI`cOA5aHI{d*7`3c43W!p zL3$P{A(x#@XnF5(VARAeo0GPFpSWq zzJ?ITMO95_6P4VG{nj*n5gNo?D9JawvO?3a=tg09HK;Y$MucaXC*pnSaI*5g{Uns5 z)|&<76vwxRxJ>ceO(7*CQ~6Z&1(i-3*q#Rwo12F4M33h*r#+4O)WG(l;NCY1c;Ni(W^anE~k6;I3goTH@8fOFe zya9ZC<6~pWEe$jv+k(IyknZHp&Q2H_v>1X91PCy4sE61@4Cu6hZ>uhUwAvl6AqZGu z9)cwNcR&W15Hr$4nL0UxKv;nt5hB-l8xWQx39OmVib*JEujov`fyNSm2WZChA1=$h z)zwuu`}e>EC<6o@9><%V?HmM3p0SjIU7f*CXM7jC!*QH<#&TT^wE)o)fa%q;Z*c#s z`%7-<{m(h;2gjPJ8PH1i|79kS zFo&`ptBW9^BzFOt$0iK zcxNL5tV~TModK$t&i|cjLy0@w7)s+=aGSS9x~Db`{d-hI=5l|;YJ8U!y^0Q_wU3An@XtmX#Weai`;#%Vr}Qn&S#`=v{K{Z@P@MhpV-PG zeKPUR1xW>aqpd&E>S9($KyNlO57_2%KC;?<(ES!+6Z-(YxDHUfo)%zX#sQ!eaIHW+ zP|cq(x7sIw&GA_s5#}IS3Um8!yhwm7aY@qB(tqX{0lUOL*oANQXEF^Qj1ptHo5FRk zpcn~MSVe$-0v#FozSUpa{=v`%zNa`9@c}>}U!>`;|L!1Xnh+BcQ|FBV5TqI#aBB6d z!zLhH76S~3vz0=^m;_*GE3*>wy33hjun+cm{xmRA$^et?9K3$`&MgNyg8;H~+e%t517!bip0bSJ ZKdn3fd%EWSi~>e}Br64$EEoS2^ndG3zW@LL literal 0 HcmV?d00001 diff --git a/planning/obstacle_cruise_planner/image/obstacle_to_stop.png b/planning/obstacle_cruise_planner/image/obstacle_to_stop.png new file mode 100644 index 0000000000000000000000000000000000000000..aee61797a6d6cd34235185066e2a02e68eb20eae GIT binary patch literal 25818 zcmX`S1z1~M(=|+ScXumZio3fz#frN_ad#qYItUyZ+T>W*W7x(nQ41c%3bRoqv=>nR-{62zgLm4gU79%A>EhX&)Vv*J* z<>fz3<9Ne296IdfHjEWc*22(D2(26)b5CjDDJ&AEGPxHvHwBia(8VIVC_fc}#~eOg zs?=$+S<>JZho=ZdHyM|OpbtgwP(5v5Uti}N`U0K=Iy*bNv9VFXjXe~7K|xCk&*gA3 z{nSF{Uqh_VIx-Z4W(mxH#3D}=AY~{*(*l<&wUphkz<}W?tZZyD=I`YHYe~MP9fqDH z*stKz@Hu*J?93E=2M)2jbBLaq0M%@}y-$8=X?9I^A* zD!mptoNr)gN_>2L)KFm9Vv*v%p%cX5>mtmEi_lFBW%0gI47z^)Pa+iQ)8g=~1V!MP zOq69Yz}V7C{(S*Yiz@jaV$xqH0-@+hqV08v6eUy$O41dqvW$Olcxn%ANj7~0Dl*xu|GTI5L0{?4{4%bn3g+&khGiAcPqy%3ART~#(fZS1LTWS*dKW$Od;mljx z+ZPuWnpR{|f#vlp)Gs&r4D-%!(s_C1;_plQo}Z#5*Noypg_cC9RCxF7>~?sTP4XNktFRT8TbaEE$Sv`aWm)JS#k90m zlC$-M>crq#Wx>X#-DHEaV&HS3!7T|EoB<&b&orD(pw&$??I}KqRdr=+{Hsv-)jpIp z0_6|~W$r&4rDjWs0BgnZp}9+ZN1Kg6I0H{>^XXG&;G@YmwP2aLQn?guG*>P)q4Ixo z$o;bt6Xg_!I(K(>B{y|cS=p7(2krZ?aX@(zss)P14rUBMDL1hYge9&CK!%qNJcGo) z6%%>#d9QuaO+OAg&g7_X-^@~9uGsAmN*dEOJ3DD6DVbhmP*jO6;h#d#_wvjMVWpeC zThHw^Tvml6XLt;1t-t>mF|looZ_i0rU6Xord9ne4T< zx2LgNPJg=UXZUAFX%h3Xn(%epMVM#Pe*0Zydzn{27E3Z00dC*d=0<+dL*>|CeI`C< zxt~W{1*x`F>{Z>rvFr@)`LR=dvKaI98h#nl8+ZGRMUSfc!y4=tX;giD_$$9vWt>`o z)fiLTSe&AjKtvDg1ty+j@XxxNjK%!h(nw_#pNWcq5K&RI+n74b48}}EUz61GUxjTq^>Q*vYibrL9BYV%(-vwGR)?4Tg~-&ykA1wL+snm z0NH;2QO@pK97^X==Zf<}S7o1DxmHvI=;*_9pU6OR-kE22abe9BV6zVIPhR7B@N(be zC;}8>6n=nl==mFK*3oitXUhPSY#mJgqm$})d!x`!yB!;{fH)sYR7k`>2gW+~&oPQA z#ATR8?b=x^)?b9YQ=8s6x8$k=dLKT3UfaGyv|h&YwDNko>3V?P0AFAwvN=0-0qbw> znf=1tH)X=0BxRm-)664QpMCE*L6F4d#~9l9$f@_C?B&M^C&Z+_H-3}+Z$&u>9TO=vsZoZQ?C^Yi_;2NR|3^l&MXoDam@HL>vlZ~G8w<9Th)T&eHC9+$U% zb0$7tn5BrX#S}St%@r9D-p$uJE8k^)-1vIe6P%hN{3_S*`uJUKa9Y5ck&$5qN%>n+ zTwG8d_iM>fTWPwWEiOc&OlZdG>23U-43C1MB8r1LR-Jat>0Y}AL(@u)eP?^ReAL8( z2rN8aYWfK21QFmar%Na`&8y_LLr>rPq}aP2P4{)K(Wnm+mr0vtEdpS>a1dXV2Kw7T z0}h6E`%;TD{;+{U`^Y?ZljZjDJS^Yw9%dJg3sc3JAUA+2dhK)4U&X67LgOU!yl~C# z%4k;#l)obgzL&-7&5n@5dUbTZ4OiCCYf|M-HBm@HOfwecW?(lpDB4W0IdDqCzHTK_6e2qfX}K14f;jB>mD@q!$Y{lNA^ za4T(>?tMmh!es@NMz#GSq!NX5<%y;Y+F=kI!}bg44(sci7VR1_uG8qIEZP!qm)gL85>`~QC&-C#?{;I*SFV@52@y! z_=Kx{AJR9IHnv- zwvf*7|L{1H;%8fPX{kC5$Wt{6sGrek?`nH<{M*z6q_#vMKi1N=p1 zZ2b-x4c8puKGwOr<0!~}fGI|an*n2Kwl_mhJE**)D;u*f0(`ktfR&M(o(>X}d%&G?drtt)m}izN z9}0B(z_0mzfrPTk!kQXKu}@}Wc2W$D%h-tby8BvrIC~8p>NX?1zFY-9`($$diqoJL6nLw8XaHSr1bHqGra((%<|mvOrA;tlEej0oYO zz_Js%7+H<+Tm9pfqv>;ikjzE>fVR_I@y-i1O7xJ6u2n@9*o(*742%!SYinrD+(f53 zZSH;UENcs+PRQ!D{Q{HUAc(f`KvNrm4vhbgIg+`$y3X<`2ZKrap#9}}k(a}r2Dj;Y z>t!{+=Tl4fV5nM{L+V2(!OMFcs(|xVhKKJ9=8(@+z9c7bHg0P3|UuH!5NM1eJ+ek z`nsJOyvkcUVZvAnf1)?I!uXG0n5g+4?s+(`F&a!cF+4)hP|~bB zjRugbX-?hsbmSaWfAEHz-?ZypLKb^okb!~|Wz-%(9}+&K-g&vB1zfMA_0M}V#+oap z!|IdogDuDJ16t*ZLQ|V)ekg@DTyl)K8k&XdCqG)&Kp+0XE!|JKnY%0} zUoyR(&$QUC`|psUa=Yv~$vn3vMvv+t79p-Yui(61Dh+4eTDsy~oq2ng&m3qRHyXR% z#e4_(R(30_h(Eb(N(&8-dvvA3d=0?K(T6C0KI`epwz#M}M*5g*57uKqh)f5YJ-NA~P4HzzT2 zMobMqC^NMHI{t!42HwnHLCc(PyGxcyKSG#HlN0Se_sSbM3jsa`YF^MHczR_N8pGQLkrwP;gM12yM2jmcqf1Ikp!^N~ zWu@Q{6KU-zdnds4VE0v6*!pGH_dM3IumWA7pbp>j`tR8oZMX>I_mRG__`grSE9Oq` zdI-`-zbL9bDICtPrz`|=#aK*Q;;0k0&?udDn& z1>cZ+dTt!1eI<$Sf{4*RhTu3DtHUzmTYvfcq;Y?>HM{5}1=TH^9-zRyCCnhjdpD9; zVgd*)7fhW=FFQWfsO0U#=7uGbW-U`sMY9E{Mi2 zJOtz8zrTNRcw0>Me4!O`&D(Z&hW~|J^uJWjJx;GaE57FhQwUTd|2z#8>i3!U`(oG$ zIy!hb@r|o`@3OnPpxD?LP;o?i6O;hi^MAaY`7rBEZ_Al9^>y}9jXga$4bLbY_AOkE z5S^NCjk^)w>1R&jO0MwtNbYyBa<$kS0ZWg5Xde>)CiNqr8^TD%7r1qpMOX& z>Ww#WA#&DRbCloT2)!dB#?NxWUvfbQ%9EsoB?vsmS*At90`W681>AM%tNXBjf@1^P zQm8UBSX?r8r9smw`Wb`nW!32;;r7`QWP}zC&UkAVLiQgS(iamSnWJR>D0(gV-;cLU z5)hs+E~@Brsa}Zho9*{b&Zh>uS$lJ@DF|w!B6hS{NbRuz0pR8>T6AwUpg!Q)Mj7ys&HS!tie9VAHmo`y+D4`%|Y% z3$GPBEwFx(zFeHCR>9yh*_f)(BbO$1R$iwl^B`l#TcZS<9^CW`NwIEsUAg4$yb(D_ zdjX`RKS3c2vJE>sysLpc4_3U+Pl;^kD*?4ho|Hh7!zYrSC_yNjo~o2AM5SP8LO8Hx@}M1m9*E|MMIgZO(&VM1G5Ph-GZ z|9}XS1A5^sb74XzNgW!7&)Vdjb3g{MxK)7zM@r~;S zYZwxovH`{M;Eh%D}3?CmK=eZeFno)sM{$E=+qvHG; z6jiPhAx}7b*4&pzvE=NW~{zP11MM;v!Qi#2bh8Vw;yCvE;V-;chexi<`u0Fs^za9H3@ z5)T3?%_>}6-R>b1c!}qQeS`nn9S5|P9Ht@$(k_3G<|OW8`*PgS_V5JgbF-^BJzYB% z2nIfno~esy1$@l~E-9 zdE%yacF13R{h#>%bCn8-9l8F#sb?Rc)q%J7x`2NK3$r1OH-T? zBXS!OmOa?1Q<8j;_p2b)6aXPj8I!TeOg`#(x`fmA;1|5AR;n|-wD_USk<0Hjzos~-G58!-aB)Negc5@Q6PMuN&pwv zq?=$(ZQevGFfh>MLMNDVEUuX1!~XPyTwwbdN;SCW%(Os_jkw#+9G)*zTmf+{h=#%w z7jnk8+APkTI^-tEwuT%Q9J{}YA1=zADosC2_9j^1}hnjlJo zGDs~d0jD2P2VcqwXPOy%)U2U3XZYs(HD`OP<4xIfHyVRg2jub}zo7PYLdryZX;Nou zWq}tSe{*rUFSCSU{Tzy76w%sDQu#*e`uZq{$ee0Re_Y%1ca6zCyIy<^g4O?pE@Blf z6)1c+6&J^Z;=2}+^KbDEd9O}brtp6*_fQFO$*kvJ#B;ZmiT<>g{MG@G^+Lu0Vbg@( z9^K0V5Dk`K*X(LHBx|%sV{>(-9fB;zN^u$-)TrZcc^~;}-*HghPFnP21txpv z9(C#$&F;SXZMJ3brV>$qV7>+Z_!#K*%cXhbM*A?9v`Ey6BXkM0ybu5~41(NcU=!wK zpjYl9r6_sg#QpRI>B?#9`2u>*m-zHJH75y74=A&i91bJLVbmlnQ*BvQTM$`tIsf_hpxZJ=kHP=HpgCt?0fT6hg^7Caje6U z#U84*BXI*=hHcKZHY%Hawqm*NW+a2rVgCW$;ltH$l*~V z#1|KrF%hI?Xp+)?|5QVq;HXour8au-gMEbq!wvX=h%*gQ^UP7MPAILZNmZefpfDuQ zo=T9llyhuAUr-w6T>>A6f zYD<5q!*>snY%UC0WMOLm()!8FwN{xeojQw)=h3Zi=-x>!$?7h|Eew_oKz!K97~+EV zt#OJt^yMg4xGM5aKkRO6F35yCAv*Nw&>o##TU{MXUtb^Y+&4l2f*^XRth|~gUFO%6 zMI8xT6=wsX<(%-WvZ5Ob6cp5;39G_DFNZ=StTK=%E?N!!r^I#V&O~p$0tY&3#C5c2 zu^Q}LS?raqF9~!QXA@^yi7Z1(K~ocse&X7KhS^J0pGhBqeiQ*p9MSh54CWY3%g^1) z%(-8`GMYb{)Zx!*|LOd$Iu0A>OV1al?tk9yz^l?oLbRZ=xV#kjsd^thTC%*ly5Cv9 zKOa30>|){B>g0@da49DGRba!d^N_=g@$uy_5W}Qk;`3C)gYt34RU}MVD{Rl;B@4}5 zy!Of&l!R`m>(e>HzW=u0XlZD&WehjIea7mzte^xh82CDN)C5|1LiyX?Z+RR#!>jay z5L_M(7NEV)q5ICR;!p#Eg2!L-4q?x*qB#)+&hOC&o~bQ>p-G|;I=|K|5~h!=tQ|fX z)w)euVVRTTDF|^j&-i>F%oB|px?$EKU-VMQ#own#wY1 zRv!m;PEGo6;KD$>z$^UIcEHDW0Dfp1WYwK+kk7w8FnH%thFH8!*vT4g14QBloF~(e zF`1#q#Bf+j6qMC9ruAtx_^0F*m{0pGW7LJ<^d=o-pqrr=Ib;IC!PUajm`VPlY_Cop zoueIk%lTc#Y|}54N5#Sw!fP>6y1*|tK=7K}-acBp*@|_e*|Crzha9*57@yeaq+b&G zu%3D!0qm^fh(=Tp2RQ2NJJK%huKjWqXs}$T8iUWxyz&g4GZmQQjq$aAhn?}5)$`8I zwiPE?aYXI67OrdY8T?%4i#+2f3=t9`i1K7o5*HWuT05M|jJ97ms7o#c`r5d|lSfaC zk7yd<(}Ww(&Z4{SE@hDOd})RWMmFIg9=;Rs_V&IOz~hi8RP{A9#k1>AWU1cIOAZQA z6v`c7K~6?o-vJ7BU*$K^;KrKZvFD3JL4~^LAP*SrZt|i>&$F`xa((&XMTEnwqNP8S zx&4LmreS}W|Vte%hoDzOt-nx<^1H4U$1$>^yH^~#P&-&R{WDxj!(?@ z;2K{6_jIIZoOq9x_i9otW}>5zhd@^L5sK_%pANt=gzbahdelY6MPHq%uo3%Uc}~QS z>@7#S$I)*vI>N_5&W=_lgvs@>M+0ZS2cEP38y=p%Wa1Q2vtkv(V>Rmes5bfEF}jwH z+l>o%zb7e26AlB>(W#DKz2)d6^lt8)e+h$&J|-5tb$b9IJ3Oa5FI>{zJF?_Ye`_po z9$)Y`l)ZVIy7Xl2020S;c=ePP;F5?*8L!;(SfUKgwe7Fa0p`WfpHkv>jefVPLm5J; zG7O>&*5E+F@OR;a;O}H&i+thS`iQ%oSRy)MuB!xw?B_8bQqD{A=A&Qr%?XMR7(b=0 zvP=t@dNum^4KqeZ;2p*(pAXD}xullq#q$-)92L~`kLKDmS$XUhHuQ`fqT>zEk2>OGs-e6;ES18)fg={+Mu>IwcA>hu~;qkNs6xF z{Hcw2k^an+XQwbxv}2Z!&yi8`69*N%RPAQ%&xQ6cxVN2YO>?uG zEEgY#AXHBFZdqsKKbd%SM7`rX_OOmHZJAlrpvQlh(EE)jSdHKJM?6uBVs_l46_{!qmTUr<1Srz#i%6Jl!BuxV-ko`cbEE4e$a ze@IVrh>O%I`N}!S_ac(sT?IA)0ypIF=>MGspp|+8Rmgql;MMX7Dg;#Lg0NF~m5iSj1WY2XdkqJ&x_1)0mK%Xv46V!E!eWMPsOtj`MXzW2kD?xM@!lMn@p5 zpqSv7I4@AvW3@zxj6%}|0Jrra1P}pY26KMiit6Z@2 zI^&}=$GpXHwl~h8dI@(jj5~cSMfjo{8pX+G_h1}O<$6;3NwPjatoUUGgQ0hQ^o!3s z!M`fsV7_UX@vIeHeYZtktKB2>6MXXcl0=Rn6gJY1Ku@>;)sPdVh%de?p{wqNr%rjR zWBGnL3bK{}DWl+Yy}&HOTZ@Jv4qQ+OSKubzK%D%N6Ite&uI!+?D;{h}b)uxQD@szW z%U@(H&MX>ZD_4%V6qy1QjWq(wMEFEA#A0mY3sGuVck9*qezN1w-%s~WY< zox)``KNAoin~rtr+#{z+6z0Xkm+a)Trmd`qHQ9j8SHVG1#IW1QYv&5L)=3*0uOSo}IzF4i{7DZR5iw@b zaR2y_IBj+vHRQwB!Szdq8eW?6SS3wNrVy*4T&el@fX)DtsV*UzRaH4cTn%RigRf!I z#L>yw)d(}Tj3wJ&pAd(7#vFO9>NrgAXX{SW4VFs1V@*9347`p6TB0+v%FH0?`20HF zkw>q9%q+B6bf9Q1KuO;UbjghkrXYZ>O}3XX5;F=o_~80674qXvmS)<8>HEvwn>!J_ z+C_X|v}$BI>ptXYQ1OT=Nvw)h+C)EZw6jk$ON}*G_tiqmSc9=G9xs`%Fr9@u7$%=r zv$>!GNkK_PRF)n&Zd@TrX7i!NX1Bw+CmTFXIev}y`H#~~|JjGdMbGgO=UeJM1Uo>9 zxso70i|r*7TXnoK0lvj2Lu&yli9UMhAQSldW=RUiU4jgq2Z!1C2^BhZReg3m4Qy-) zN-s4{S;{)PaC2jA)I{wV*L88mYtFRalJ??|hG#$UzOiGQc#f7he?#YZyf=%a0n=&Z z6NQWmeQ}8-nw+csm!T6OjfAHArr{OB8JC+*qwi%$KxAZObh*{Pns^vn(1GT<=QhyN z)Wjuqb%|m^%8L45Lc|B`bbC^oO2!I;AU6mxsckuF1UcI8P9FGgQ1CXU65Q1|h*L^F z`d+A8I)nSDK;en_SA;qLYF-jXVaDj(QNq6hW1)5WN}yK5f4=FCX$X+gZA0J^09$?s zp<{9GL&`XwBrZB!a7*a8=LgoaF*i!p+zU<_{Ksvx?zDn?Lkw|j3m~tQ{09w(r zh^F^-z1-uz9r7)sdM{?E3S89r%Hp4qecd79httPHdSvCGn>sIfF@m0HQnL!~zIi~g zG3zWuT|c%~tWFrY^KEZN-AODgHB3?}4H2os#(x$1rfs@mz-xuf7O`X7vp2pjvqPfc zit-!G#wuO32U(y zxsZ>>P#(c4V4XH{B@dur7kB&}MZ=NXpC_sk8_G6^M#z!E+llDnH)Rq+HC$T=ly+=` zEOnA7da)}yk8Yjh!Q?Q7P^U$ciARdY z$CIln$}^g>=o!(C1o+It3WZ}enD!_T<~kYu#rM$6rE(bfbZ7e|%MbA%hXTQ`5ZVlQuCG?T4 z+?)k0tY6Vr?#6L+I1}tE3-ft;H-}1lYH}4f$Y=>Us+_VHf9|U~TU8@_yG_`}Be>Ei4(3ULJn9VK#AA$oHL(nAN>1b5z$NMN)Z-1@T z-O@vg+RZ+ysRz@``c|nD+SuBbmzU=U7zMr=p#oa)l^llH4rkk~P-g_+AzfTb>tX0C zs8IhT$}@q*RuYZGlvK09%s9*h(C4}pk%6+sClSbDPM5Aj@?ZHD!>h=`QVWcw9g9IE zuiW^JL9jY}*lt?Z#NoC}PL%qM!bFL*xHozvx-O}|o(b^xEUVNeF$I!Mzyf^(;cLO08JnH=9)KQRm$74;{4@phAhSRY?i zgJ|kfR9a1PEK{sH6YH02X9VfK6)!nX9XD1LMz{pNQE1q{T88XyfhB4B5+)C|FW)?t zs7Q1|Oz9-~vS||GgC(U=j8173NQP9g$O;T}c$+&F=o^=9&xn!HvZqe}7glF+NecXU!xrTZR;IeXB^;a?+m0d+c-Q zj5jN&X=M*|ol)-aEA0?$ad#+^9W?|slRESXStCIR)C)s*DHS!p{drS@N07jkXSj3% zPD1Wdh0YAAcGw8(Dp?E(BUV^AxY;4Zf@0YVW3vh*m>~$ZI5up)-$h)FM~+jVNeMc^ zADN@+!w!jm*v4zNSYq~8ht%9vD@f`iPwqV>OKIavZ?*ZNim4X0 zW-M;@zA>>Yt}H9{V??VE_w%(GZjcXlXQVeQPeF9N$_cKjPlgAn0s`Ayb(~9&VKQNMOni6<>IAgqTl(UpJw)Y=UVrexk|aU5AO zG7o1ArqDz!VQ^Fu_?aJk!e%3mr7&Hg>cP(ha5g?Li|6+exU8zDSxL*yw>eUlkC$H) zt#U(Gz`K%{{2{kCcI&B9%#s{L=wnwbMN;}~_Lo((_9#)>CqKIf=Rm8#gJ(oLC8&~3 z3UXJc!E#QmD<-Jh_%!=K0*H71Dgw6i$0${G@#95xR$bkacKU^=I-^g^&Lf4VC0aW^ zWzRECk#|fOFCelgIoDLNx^T_Pd*)SlRIRRjxRoPN(g zC9;X*9wTRL2WR^{#a9q_f$2t`#^pcCFw9nwO{phJk|~K%;pU=n#B2kOXfu(0GNV*{ zS{g(#7dYl}xEWT}MRN#)$~*;>WkZvPS?7ku((5SlKmqGH%iFQ&(S~LpOd?B8`ZK^cq~PCG5#9tl5w(Y&q2eC}D&r!xd*1s+X&TKh;bL zVv^km>N@P!(yE?(8xY)zD>kk6`ifK;vapJXrK=VKAEPz38SCq@k=Dz8{BG19DfMJB zv`x;JDP=E=v#k7-oXHf>Ka4~=g2vDIk?nrNfFq%SNm~Q2$$K10`P)9c9ifK=T=Z~4 zj6fjq5J=?iMsPWhi_yU0OB&Yezy&^T)H=2i*vD&4s2WdZ%Y#i6lkdV+!ycu*2JMLK zgZv{pch_-^t=^nE*z2#V1mNCcGKEofi8Enl-+nvPWhHx+8xRUu3X77G^}W;kx3C#f zC>u{*ZOD8e9j6G{KJEaXMBLCL^2PAk-h{h%hOukS_?r4*q=fx`=d9;MAAv4_F8;SI z)up9SCE<`!Tf>MpPlQmWx5vjF&TUsLf52s_o|dL&s1k3=wXH#PlP|AC;qkV?W&~M@ z)16`~+6U6xSO@u^ib{lRXPQKb1o6I|g7i8hd)q8{FmRu|*P-!&BNm zUgKjSkQyKLnbJEELkkh)unNx%A#<7v<(F6+ukwZ`OEQqs9wG-JZM?$$Tn)Q*56_Px z7@eP@^N21=OBrO5sd&!{66iHS&__*^Hos+vI*Ku)WaNt_jM}N1JunfBG9oTEyfHPh z>xDySOPqj#dw8dK@*0wJxJ6ZAr^lPNre+NW|BHSPfcjOl`qr4@%P~e4WppPnvi&5 z=c_Ayc6}u<69Tcm+3S1G2t~ITeUfrL8#k3t67f| z4CwKK->)X7&E==TEowok0U}{1-g16NJBzMvWakB@m}OVm+mbMOz{OXZ&ygIbM3Dxs zN(HI|dY>?#M^V~5RZEk(vCyx_ z1UF&s=t;wWo*_J$Ek6ZHsj23Meg{{;WDNesEKBMTeM#-7COoSsoL-TGjy7XFHRz{u zuyx|g^GNN7I~)&lsJOQDAL^S2M@;{vmsVvVSmSqj0l(`{;ec1%w;WQI z7^7Uqo*1|JF$uscSH0moTZJ?3T#G@B9Q9bh760FW7kQ`b9m>;Aufc7gkXUK1(%*ih zF~2(^?CK93@Ubh`@p8`@VdY2lj|lfJauHU=Nvdy{9d9AWeV^(L-yo+?1A?y#ZO$S) zcVh>IpD8Hux<4IN^GidnvQJaLI$jL}T7%AyYI^++twoGU+_3A={3EX`rw6V!6&@K4 zNk6)xhTwbt5*J+gqxl1+>J4AmE(g#;uJV7$_8)a+tOB>C|0+5T>wQ2@3j&2Y`vhLC z`j2v=0Sn@n{D9%MvuSdEs|@Y0d_mxr%FmlF&bgk%z-GO%k2lLQod#CiFa4l1lD|Dq zB(C{^(+4U|O%mJBQj|4bU#5jWWG_1a!+Lkb&qDc{rC9z;UZK<8tclUvQ7v9rm*QwJ zqP35#crE!Rthd4-jK?qB`RoK50;2c&sTgg?RT2gtQeZP3YV&yz>NymjVjI}Wuu7|0 zN451;M708^@EmI-S=3J03u`e5Z_(`oJbt#G5|tupNGefph-MY0Ax6DxC7%RPUTTl)KF`7zpVre zw%wha&`p(rf#<vHDyIm>gvvxI}@eG-rD|D@;2rDt$u#`ZVh))X`M%@C})oHykFw)zHZaP|O}O`qTE$&cZw zF^jQ}Jxgk#cLK4mUI?cZj(H}mlg&fNyA)X+SEQWF(^n@nz?T{0Enf{M;;OlUfn!%b z&-2yiE-HO_O-;?&hk0kGTu(?~iEx2So6*7J1&;@aZk_ub z!)1<=vZf<&mcUX;4#Jv)!-!+5&+i^%Q<{`u>GSH#L~h6*TR*`|Eaku>m@SQH9h2;- zIB&q8!nl6E6YRIk3v7@l)pXZW;6B8To4X0Xjkcos_v~1y5s8;8x`^7_9bWA2rVIDu z6!)&ZHraP0&8U8qo<2U4&&y-9rp)@dorliea6h+zVD^>yJ$@rfUsoPCz73$xjL8#~ zZafT~&~^&@OQf?MccNaT5ByloC#iT3rV&}HBw_{>ZR2Eh5qg<)xN9U2ORe6goAFi# z*!Ywh>cn6%M{9rSSms!Jrum_BQ?G6r4x!;=i2@5()$AyN!&N3T4(mOPA=5nc#>4%-{8jwWF-s1Q5)vgD~ta_h`|$jc3^<#qZLW$PAA6ej)jm& zy1mYu6x7VT33o}hq_2*K0yBY(Ral3yGz;Gx+f#*fwz?nL33~86TiJK~0xMokBmn3n z0B5-FlBEm(RPbo{f%vj1a}B=(JkFax%0eD23Je4Yz0 zV$TcbGyoJnZ84XQym+PEx0uF`XL}&`R$bK^FUW-{0BJ>Hc9G-#>v)410di9YnxSP4 z$=ee@zzM?TATiYN2kMLc#_YS_fqO^1U=&*nLYL!VKi4D-l2fiPn{Zbaxc7MerDtHE9a5;NaO$)1$Z1vSO!gMTu+xgE6 z;b3Q*V^!5-!5h4A_a^aQSdo9@L-bibDG$k2wX~D^#h{|nia{OeShQKiqc1FheXXrc zg)Bd_*9ui4S~ttP87J}~3yF`}o=;VDm!RAoIqp>zIuA@^TZ?%T?R65pYl4Dn&8I@j zC+&=GQ#*)KDL^XJ$X?P9n)*(64rN9ELk#yn^A)~GGmWb2}>}KzmOS(u+tz3kmAJU^&2+3j3$L3T>l(Pnz)Y;my0(mT?#@?lapMt9GLz-eNcSPWwIW3O!)ARoKKd zbBUE!QNHap)PXaY=kqo6Shd#2)DF9P-hfYa6Cf0qU9odL$IrlG#yO~Ws~IT32-ve9 z28SJ7R*ImX^P%F?*q|N4kq)`cHOIC*des|tV_vmodu+`&cTGUJ^!t+abPxd#Go3Cw zu`~_in@nKx!KBA^IU1qom9y;C`*~d}L`uia_|W&+V+zmADzYNx9LSq25l{gz)c z{afv}+ioBTmj6DvKIuq~OO-g-LIGBd7Y2UhnvpHCZ!_GVwc#66k^0SqC=NFvJZ)Kh zzuncPg>!|4i7;~s4sB%n+ZU(Rv9aIu_X1 zle5@g8Qht*3(*@nBUOmTU#w7?-EyI*bOhXMm1n1?4(hVyY^7EdzS!e3p&6TEh^NZ$ zCJ%F0sInWJMrBftKEB|LpbSgJxmrqw6pIg9Qw+=0k%rI_UXNZly^W6y#IWns2PZqw zTMBX#CedNojL-NTm>#1$eCn@&UGYfMn8QO7 z!+K+*BDJy#oBLk!_7;z#wtV#AKRW!Eh1gO|;T09Z7aMaSAyj9?a9b-8D}eZwHiD;o zIQq9!T}nKCi8paFiXVMp*ww%#<_$YAU&!`F^tYsau?_gy;_$^va2|C=oRce%B<4mP zqK&D&lqegoR6Jy$lL^Y5Lg$K19-RxFXzX>i>r9`uE;R<9V=qv>?}Y$o zpsX>cHX3Yg`?hR~8Voq+>>QC9z1j*CgZEmm4m@*DUON!x?P%)|Ka_jUCjum*!}P}k zu9~Dy)Y7mgKk-%o3n6Pb%wddx-VtA4Z~j&i9dj0@mHafu2k$q>$l#Owgmsa<+(lyZ zHr)AW@iF3f%h&@%wEFs;96@ZF9NwClw)obv3S zf7e(|hSUnVMafJtg~eCgsjEIgboARTy_c73hSKJ~W(cpSlkT5>le3`@{64PCEbQ5F zs#*EFy0P8e75Ba_JHN6X-&TaaTcJw2UBT_@?Zl%w0GTZ?}WNi#ge23fZPpu?;jk=U-$6Z zFSWuTr)>=~@f6Z?C_6kcmR7QU?6w~lnwHhwbe5W&@eWZ=%Nu0O(CB>c{oWo)N;Kee zP|1?|^(dXq_Rfe+c9a3JZSQOT)0K3Jocw}zCd^5DD|3ZPF9%^-^uk3kI<5-v zaku-GlgD)5tW>GVk-MRxNLe5VSf9Gz`F1cE@RSl4qT%V$l{g>p>^3h=TJT5~;5T$; z_Q~aj@B`p{uq z8Z6x!2Q|w0uD9iVQ_lpoS!~#NA?#Tdj^)1Aj1%IFLhHaHw5Z%ux$^#J_H}{4_s$Xj z0cwwj2Fb6na@LGaZ>arm&G~K8g1`z%YWAD=sc5Hmf0Y6{55iFvL0r5rvWua8^;UJ@ z#-vCyTiTRMWiLlVXqAF7u+y!hX>v{ddvj`PNe*F{CSv?Py20lEI}1>#KVp~9>xM(f zHG}#}eBqt_1$Uzkm(>E%+)yEZjd>6IbuzU{_}R5TC>_`P(K+~Cy@4L`%&C8;1=dr zN9F}BG2BtfKDPg(WgQaIpy8X?)2l@BYy_J6GoG;Yg%(J^8&`?`K9LIg;~8posM9jokk^21U%HFxSBKHLVS&yal2yn*YM9}yoEV}ef!{%6~7 zERK9i*EzZUUSsmNO|cCPWpi^lH7UGqQGc&Kgs#$`2OMd;K0uvcss5g^0q$uKg+Gwc zr3b_Mmjk#0pP)R{p2G~OLAR-8@5|CGmZ=sqV4L@{P3DM6CS-KgaK{*e@$I= zSd>q+UK$Yuk!}%yBiinB&0hemTsj(LK>v+2furt=l;jT zH?!ZFbKY}izB6;)`JF_3cDdX3a|xp|>LRIrwRM%y(gjs^~O5A^#2d(@sGt@CI{PWBEt{tYdllN8g+pSC+r!PZV z$@(11?QVjLYK67zc21INyLW8e*{86nPC(84reQV1*twnB3wOM=kd{gNm3F=X^U@FR zV@Nr%Bj9U|zC%03;cw(7agA18xJsJl5$Oo{@y!`N@vf&^l<9LZ+x%UKs**{Z!;;i( z+Z|Dl(UsQeeU(yN#*LRS+|`WW0>?r0Kt%MWur22(%zxA;4jKNnmg&zc+_jcX9_*W* zWSN6DYC`mer3(9xuZ#=SEeC|9~+5968E$^P7_}|c*;X=Yw(>}Ae^ZRlA z-LH?&%qlpFfNh1?M|a387!wmaI{1^KWM97mf(z}{%@(^Q0v|{X5%~QLBDmjg>ucMM znYAX|n$}Z6L3wX<<$T%^gnHmB(xG(AJ?D)0vgjN4&*2{ZqWj5>`z`pE`kroX4Q9MX zvX!Lg_{N^bcl#Y#+r769QA%}GRJZ?So0I*IkmX+@GD}kaVW)QoA6OOFpk$-!3TuQET=G|Ku_a5N{)$Z@>dHZIU;M_j0Wx z-=kBrdZ%~ybHKOfzLO$HN6q(ZTOwi3dn6r7&Eyxa*eB)W6K*RcHhRUIF4It4d`&@Zgj8XR5!>hiLVp66-$0E>tCYt~Yfqo&K6^`MUgy^c zvH%1MjeI8}!86p_ahs8MAtFv2+@R~`m(_dV6TKHfkGXX1*WC0woQVLi>|DH(>isYb z@BT7-Lt%&3sA(A^wx9qPB7G{AU3{o?&wsbD6i7wY%fgE9d(Oq}ci|rkxfcRic%{ud z_yz9)9}xFru$9(x*OFFzUd68y6YqgE-I%3_+*PInABOormQUP6!%oB<*P>PnnGkF{ z%BWpGqv&WrDPV2&z8|&>%mpcPg9R5$N~eOi(mcf(=z*=WXK?QKEyS7H{lQ~{14Ot zYk6^idJORe3$a?pe+(^FOEb>0~pAlXQ8Lw zUU66c*LHa#w`$*tvwvpCngjUpcZ5=Q`S-z=TmQOxwwLlulf*grM(wm+n%}s$KD~eI z(Br=)_|9tYMriK#Lhbs{|4qw*99VnXi-%)md`64>f=A5OK&y`v?0O-BN z#X5=_Jh2K%!YH89q>=ne>m~z15$R#)VXnqDvUIjafk{C{?#s~=1Qeuqs!iJPP#KhT z6+WHyA~ap_V-3ZI-^E2eoP~1a^edCT_BXa_;5}dJ&>~L~tLW?h@ zbH3FMK3KL^XRfBL;0#|rW~>N>F2FbbY*B3<%O_akrDII+|4M`oy~2{0s_H*4P5m;& zTr>VVY1ebnYZp!+E2pNN{{wj?c5abi8XDj-#aPk1x&u zY4HBUKV7N|0Vlcen$c>4Dd_*+rXH~A_OC*9rpYt<9n33Ie`LAMLj}dE_aZFzY?_F(O^*mUUGTF|sj=5@g^XYF_ z@4l05kBo0N4r)3y=y{ur=wzbfLNI~9M!V;=R1=>5TXk#D!RLY(=BcU-ONbf1tKm70 zUNL-Ao7%s>{oq!Gh4^*4UDIWkXY51eP8R43C0lBWO-0St>a_0(qn15$(q7Mw6Oc>H zTGuuqa;8hfXtP7hTw5(Z8Pg*01fG>?ixECu274w>P4ljj_)tUGQ!w18nB1IrnJQ5&LYRH2B^IUy4sJ9`#aJ0Wnzr#r(3ty7ujbpMHna z@$aM%_NurtZtV#QcgX#mOY2Bw6jP#dh{+vaoeE;+ZC#N#zv5jZ5!SMor`Y8v?c#!= zAvaq6U=q|-1xFbqYfYJ_rJvq4~PWtoB58BIuW-kc*BayT2n-^l3aGV?WyI}cJ<*Z?0`7p5X zrT4umtz35Ex7i<|s>c&^ndLH2xJV~KGuuFO(FTdoO?xt=dir@ovZu-5XR1|F=~^e> zdt*r_hJ5xvfPSQ+MQibARGO8(-Ovee3+NxeY$R74O(@dWDQMPy&1xs!?v>f_JK1L6yy>2q?y-u~#uR}X+j}zb`DI{!wKkK= z&~m$|jqv(-^AK+nx5oHvbE4FVI&af`e$!6BaNYOfeIBl_nS6E72H*8e-)3F7N?M26 zF7K3ZH9@R915uQoP~eLrt*e?KQx#L)&z()d-w0bNV$a zh*ZD+BSvIUrzx1}@nA1pT{aeORfKoy=41CzxO+5#lGpmvtfat_LyQ3SEY{ziVLya2ELSk2yOoUtX>&UMjB>A z?aT`^h1lk$3PB=BQ~hjMeYe}(U!&(O-;<#d;lEgX|Iz-W_7M5$^mRj_vIF3_vH5^7qe=B4gA-mGl&F_a zy8KQaE!~K^f>#e?XLO_pT~CwZmD2T+#AoOA&da?J#Q$KkP9{j*@h5CaV2@Y3p#114b4lYQ7d`qiSb9g9`k1aH;%XDcP{`i8G$g!P&n)5Y zjcaioHn_d5Y)>0q5;k;_ZGsB-teh!rGNw|a5KhK!aT4BHUX7AZ zJRf02+g&%yg+wR1c3GTjxRQc9<%RM!I0RWd1f)hL$`~?zNy~=z@;mV*I5DJ|Fq~tk zmwD!3ig#PX6_R{s#FAXyTcO=Go2sFY#q2i_dtkb7U$S^cV>UGIk|?leUr7_R~TPXx~AwvTYPndg#l z0m+6SpS2=g5wRT^=$ZI?Cb6@O9(ZSrVCz6S>x*=7dsVCWwwV)0p^~{DSy*GSDcWH# z4v`g0k;5XiDh_N;_g`V&7Um3~jiZA<{MvM-7cnnbX2@tq!bpIB{>%`8xd6eIed3G7e*mH2FM=q5F<7hpfDfW>}M=R~LY0O|dE02mMy4 z%3DYuZ+5(c;g~MRTr~57%}YUGgVE&Tr$N(`Pc!UVlwKF`DQg@9?0$BZq3Kd}wGv#e z^HuSTRL{7>uj1k|Xqry9q|+}Jv*rK79d;l5`{;9RF>?Q^=>_L)QntnNBI9|?(ufJA zPrOq>o3yJ-a8!@#Z{3&nAK--|(2uq6qgCXGSx3QV*g;`Zj&adayC{>TYAIRhIfhkg zECgTuq)|}?va$5YSd1x^pON&{p-8V?mxz540~z}ViZOOKz8;O8MV7(xJrh8I4XX-o z9!{D_R)f23c{Y2+WLJJL?fe^_-HcWxppyxu77(Q}+fZ|&g>rw4S!?`w3{uvSi_=uT z!){FVomRn>{UbUE8yOR6yTx2j*5M(%?1Ox#L2-h*H3hoh+1t8fyEva0uK`3=*eIdJ zg05PtRG&RPMPzNM-#_0;#3~H*lkLH;$EFvmQ|{6ZvXbD%`aYgRc$*8;OcP#u?R6*f ztRYRcBqgIIcxFaPcTmqb_}%O?swQOVdQwp)aT62H%(0J(c5nHZNbE|Ah&BQ~5t5RE z+1Z!l6WCPX8@o?xP_vYd`+ndM@AKz~-E@Ms@yc@yMR2jOe9Qe!+L`JSv=J~a@Xt6!>IskxxjqiHdQT=ruVPavq@hpK$H@!z}l zyITx~#7KsHWo{`XN2`FHT`U^Ceeq*A#_}qXU+znuLz6hllL-Hp4xV@k}z@rm=scY7^xWmiAwQhMB*ok!e1#}=}*zZ=>8F~QO3J7|^{W@J@9_ab7W zlu>;-zt+OUBbJ?c>?60dT+omvB%F*+MvR@ke{xaiPvC7VZ%Gkp;K7T3v`!ScoiCXp zMRi^h2&3<6ThHgI%Ef>t`agR3s;`pGtr8?2V;dVGnJ)^Rl%~s(`DMG96wD|JPd_Hra(@*Z)8sfCnlZ_|ADJzv=xMtM~ap9FSjDUIRWZB z^1<8rwPCxS*ym>}*TSZzrjuki)@MR$I`AoA#RAlv$QUHJj`{`ITpi}AP-qlrxKCN* zmM^*$RZTf_DdO+Mgfm2@WEuMZpy)HAmddWw%p7 zgvY#>e2`k|4QH}GHMmnwrJV@gaJ8_a^gBqVIY{bx(B7Sw7gTw@!idTjazeB;|E=_I zUug}JH)sq$xE{(7RH{~gDaR#*z(b`)rH#K0E77pgm-Us6V(iuKRDO=ms&3=Ck}8`D zHY{VcPQSN#kCSkae-q09Wgjya%B*HLDpsu_kac9xygb!_E0ZZlI-khduv;lap+PC? z40@cuYbInt`Gr(LXi-tGEm&t3uIq)0dWm85ozNT=Wz1$i2@3Qq(vTJ<@Jw2yd z#KDwbRk2+ub3^luPyWK2UI-EW$WdW@N91+gw_n4;?k#HmP8dw~R(?JE0%THErkn_2y@{aiX0t|VJO@zn#H>QeUn9eu6mIEqS&$6X?) z;{Rk)Z(rqemk|=JMSoo$PhrdVg~?TmTR&x)CT5IVX<#)(wNHyBtvRKYErk-1ErVG# z2_u*}l)FfRreBk(yoU(%i}e)75~e=Ih*(Ww8P=sW>T^+)6L#Qfb6fdTuJwBOE-}*g znj6LP1mnF*|71c`EqcxBLZZdw9BI1SzD=n@s4CX}M+$gqrahWCy7at;Vd8j!RpQu~ z%H}5P$>{{~=sc|)*JqmEF|L2DQh32;I+5dKGftSFL519vdbZU05-R0pB&O0e36hYI zMlmae!V2)BR(pfE5T8LVQI8pEuwP&o8=1M!9;Qy=P?+#3xx4}bv~VaqmnV1eGfcX= zZtX8l0%eb3h+SSz+$@Z@0RVTreE)K%=2@172b|5uShudRfxHfTeob!6{+s&Y(sdRh-i`cemKoBt>`xV2^E4XEV=`37W%*yb|WGQSl@;EYl=HBH5qFC7y$z zYs;QgI!Vt%jk8{NyA|uH8zxO@N9FVA)NzUzsk^h6x>7lwpPjiv40&cWkv%Hq(%uZu zB{n+~BAMV41kszrgW_;!IS z#f?f~Qq;b|ckzSC4{O!ie##S0k_FfZs zhqHkY;*|`(b*(__flAfPQBbUS*t4Ud8U!AZSY(fhI}u(~n{8So^}kHqfX!Cj1XXS_ zoKE(otex$thQz^X-EnT(LljO^=?U(G)KVHbuAdv6g{l!OgXQ&JSy2NlvJwS4vPPxv zmoai^4pH=H{>+BGR8WiKewQn~ngUjEG$2M?kP3K!=&?O_{uFamO64lI(>;kbu1UZf zc2*Jw4*xB*`cxcOtxEZ0?I(~5G&m2DT#`k%4Ao+hm29=Pt>uY6 zqELTiA^KzCaWxNL`b4IaWGS3Ql7iiGiuqTP)2%qxgnp+x;8^1DvbMo;KC zKnXf8^lCmjcmlOzVC&dIC+z~t9Xiroj1~u`m09zljzK^3qU>{GCmP9wgrSi=jXI@- z$X<@W=8Si`>+~GSf<)COoe;C?ce#f?Dg&2nGSNvX{Z(Yq$q;CZX0j)5RZ-&g~5 zW@P8=;^GCWu&&_0tT3Ri3L2!E_Q~@L7;5#N!zr$|xS&W!GNWKPU!!D`N`Gc0vC4yg z$~p$H9McA8vZZBpZ>;&Hu0)?}fRB#~!A4*?2lg{;WtK$8@0+8!;tcR7H=w?;ZYRTS z;NxcN-AACs$GFk(W2Oq|F1{4U$%(Ui8DSp7YD6D(4~ZPy(59_dY)^B|bZyZW0coLn zR8x1|9DBfNH0}2~jU+U*g6U0#Eq716A8B+73(3W7hGti*JycK&oQ0HVax#k5B6671 z(JHrZA^wHWT9(@(J%GFLOy~9f=OdYdGrPt>l|$n+43wTK71rF>B1a`^-CkeUgda7V zXy1G!$ts_@HMf9w2RXxN{69=8PaHwkcaODa7 z3>GRBAkUlX`Mo!XZj?Z*xjh;NJM+SP^sFvPNy(J7`8gu0uMtcYsne4&RwARwsj8f= z8kn@aG-!{^($zDzWw>;@@%A?i4^m({B|@9GF)a&oGVxXg=$+*rIJO@i*#0C$jU_5% z(ex4l(w3os-2A>*^8c65f&*x6tjtwr56;ci=Jv>P@duJfXMik&WYQ14_xQ;x15bs- zNpy8xofDAzsqUj$G^OA`ma2j2Xi$8^O?g9Mtib%PDH&1}O>s@aoi z@tJD*=i#`1he1B4`PBPo>;U6@cf<>NkjHW$hMP;3uokl~E%%Z;U0kDpVfx)==`R5+|2WY7O0-q3o1#enPN^C7m zES%ZxbX$cn=M}I}e)Z~=euJZN-$m0O?1Cwx@?$SSf%pbs*Z0x(h97yOQQs1+k;;Gk z`nrqbP6oI#z)l9ZBOvOn_BWGIr-Cqm)0>4}4Pd|rq)E1;5cMJ=*F8iE6SDjhboMsM zRWJZ>;HM+q-S4ZyXo6=$9w^XF>b3a-zH3)lp0rm_)#gvR4Ga|50#odqo(fS}n`8QyBy1804=eYF$FN0*dAyFj*^Ro+p!A^|Nh@qgg!v*_RusXC1n{v=tIaf zA&z?qyqbBcoQR6%fvMj%)r|U4pA%kVohXm|b#LQ=pEhBB)E?g>0sfWb5UJbM z)WtukY1fP$Noc^PBH0c9e=hWpMfmyV9M39fh#~snvaG{B%`F<|8w`Kk+=V+Dcy&r4}`8x zQxDA2vrLS65Ayyu=Ggz(77e8<4M2auIo!(zH3knJzv$FQnIYu)?ZG+rOupTzU^?*t zvGiQ_IVJs422;R`0Ic>W4@#;g2HfBR2)E$|iVwlrEx-I34F-BBDS1_2Y!S*QH`e8}6pHT%tXC@5W^=$K!q?YZKwu%9IXX%W;A zWaC`W&&oTq!VfV`K+NZh`%^9!zV8T3TYphr!6M}rG2 zWGO(~>33R1)c-o)IZxCao&5=Jtn?0<>zy*wqsRly zFH+zExSOCf+5^Bz0R5lgIT91GI-LwJ)eOHg#n5@sx%mHYv}2A$34(x0J{_%EUW`13FUtd?!}lMt0_jL0k1D3^X!F2#F&=0@{lUZ6bD_ + +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "visualization_msgs/msg/marker_array.hpp" + +#include + +#include + +using autoware_auto_perception_msgs::msg::ObjectClassification; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_perception_msgs::msg::Shape; + +struct TargetObstacle +{ + TargetObstacle( + const rclcpp::Time & arg_time_stamp, const PredictedObject & object, + const double aligned_velocity, const geometry_msgs::msg::Point & arg_collision_point) + { + time_stamp = arg_time_stamp; + orientation_reliable = true; + pose = object.kinematics.initial_pose_with_covariance.pose; + velocity_reliable = true; + velocity = aligned_velocity; + is_classified = true; + classification = object.classification.at(0); + shape = object.shape; + + predicted_paths.clear(); + for (const auto & path : object.kinematics.predicted_paths) { + predicted_paths.push_back(path); + } + + collision_point = arg_collision_point; + } + + rclcpp::Time time_stamp; + bool orientation_reliable; + geometry_msgs::msg::Pose pose; + bool velocity_reliable; + float velocity; + bool is_classified; + ObjectClassification classification; + Shape shape; + std::vector predicted_paths; + geometry_msgs::msg::Point collision_point; +}; + +struct ObstacleCruisePlannerData +{ + rclcpp::Time current_time; + autoware_auto_planning_msgs::msg::Trajectory traj; + geometry_msgs::msg::Pose current_pose; + double current_vel; + double current_acc; + std::vector target_obstacles; +}; + +struct LongitudinalInfo +{ + LongitudinalInfo( + const double arg_max_accel, const double arg_min_accel, const double arg_max_jerk, + const double arg_min_jerk, const double arg_min_strong_accel, const double arg_idling_time, + const double arg_min_ego_accel_for_rss, const double arg_min_object_accel_for_rss, + const double arg_safe_distance_margin) + : max_accel(arg_max_accel), + min_accel(arg_min_accel), + max_jerk(arg_max_jerk), + min_jerk(arg_min_jerk), + min_strong_accel(arg_min_strong_accel), + idling_time(arg_idling_time), + min_ego_accel_for_rss(arg_min_ego_accel_for_rss), + min_object_accel_for_rss(arg_min_object_accel_for_rss), + safe_distance_margin(arg_safe_distance_margin) + { + } + double max_accel; + double min_accel; + double max_jerk; + double min_jerk; + double min_strong_accel; + double idling_time; + double min_ego_accel_for_rss; + double min_object_accel_for_rss; + double safe_distance_margin; +}; + +struct DebugData +{ + std::vector intentionally_ignored_obstacles; + std::vector obstacles_to_stop; + std::vector obstacles_to_cruise; + visualization_msgs::msg::MarkerArray stop_wall_marker; + visualization_msgs::msg::MarkerArray cruise_wall_marker; + std::vector detection_polygons; + std::vector collision_points; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp new file mode 100644 index 0000000000000..3b9db69162d21 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -0,0 +1,165 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__NODE_HPP_ +#define OBSTACLE_CRUISE_PLANNER__NODE_HPP_ + +#include "obstacle_cruise_planner/common_structs.hpp" +#include "obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp" +#include "obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp" +#include "signal_processing/lowpass_filter_1d.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" + +#include + +#include "autoware_auto_perception_msgs/msg/predicted_object.hpp" +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "geometry_msgs/msg/transform_stamped.hpp" +#include "geometry_msgs/msg/twist_stamped.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "tier4_debug_msgs/msg/float32_stamped.hpp" +#include "tier4_planning_msgs/msg/velocity_limit.hpp" +#include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp" +#include "visualization_msgs/msg/marker_array.hpp" + +#include + +#include +#include +#include +#include + +using autoware_auto_perception_msgs::msg::ObjectClassification; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using nav_msgs::msg::Odometry; +using tier4_debug_msgs::msg::Float32Stamped; +using tier4_planning_msgs::msg::StopReasonArray; +using tier4_planning_msgs::msg::VelocityLimit; +using tier4_planning_msgs::msg::VelocityLimitClearCommand; +using vehicle_info_util::VehicleInfo; + +namespace motion_planning +{ +class ObstacleCruisePlannerNode : public rclcpp::Node +{ +public: + explicit ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options); + +private: + // callback functions + rcl_interfaces::msg::SetParametersResult onParam( + const std::vector & parameters); + void onObjects(const PredictedObjects::ConstSharedPtr msg); + void onOdometry(const Odometry::ConstSharedPtr); + void onTrajectory(const Trajectory::ConstSharedPtr msg); + void onSmoothedTrajectory(const Trajectory::ConstSharedPtr msg); + + // member Functions + ObstacleCruisePlannerData createPlannerData( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & current_pose, + DebugData & debug_data); + double calcCurrentAccel() const; + std::vector filterObstacles( + const PredictedObjects & predicted_objects, const Trajectory & traj, + const geometry_msgs::msg::Pose & current_pose, const double current_vel, + DebugData & debug_data); + geometry_msgs::msg::Point calcNearestCollisionPoint( + const size_t & first_within_idx, + const std::vector & collision_points, + const Trajectory & decimated_traj); + double calcCollisionTimeMargin( + const geometry_msgs::msg::Pose & current_pose, const double current_vel, + const geometry_msgs::msg::Point & nearest_collision_point, + const PredictedObject & predicted_object, const size_t first_within_idx, + const Trajectory & decimated_traj, + const std::vector & decimated_traj_polygons); + void publishVelocityLimit(const boost::optional & vel_limit); + void publishDebugData(const DebugData & debug_data) const; + void publishCalculationTime(const double calculation_time) const; + + bool is_showing_debug_info_; + double min_behavior_stop_margin_; + double nearest_dist_deviation_threshold_; + double nearest_yaw_deviation_threshold_; + + // parameter callback result + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + // publisher + rclcpp::Publisher::SharedPtr trajectory_pub_; + rclcpp::Publisher::SharedPtr vel_limit_pub_; + rclcpp::Publisher::SharedPtr clear_vel_limit_pub_; + rclcpp::Publisher::SharedPtr debug_marker_pub_; + rclcpp::Publisher::SharedPtr debug_cruise_wall_marker_pub_; + rclcpp::Publisher::SharedPtr debug_stop_wall_marker_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + + // subscriber + rclcpp::Subscription::SharedPtr trajectory_sub_; + rclcpp::Subscription::SharedPtr smoothed_trajectory_sub_; + rclcpp::Subscription::SharedPtr objects_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + + // self pose listener + tier4_autoware_utils::SelfPoseListener self_pose_listener_; + + // data for callback functions + PredictedObjects::ConstSharedPtr in_objects_ptr_; + geometry_msgs::msg::TwistStamped::SharedPtr current_twist_ptr_; + geometry_msgs::msg::TwistStamped::SharedPtr prev_twist_ptr_; + + // low pass filter of acceleration + std::shared_ptr lpf_acc_ptr_; + + // Vehicle Parameters + VehicleInfo vehicle_info_; + + // planning algorithm + enum class PlanningAlgorithm { OPTIMIZATION_BASE, PID_BASE, INVALID }; + PlanningAlgorithm getPlanningAlgorithmType(const std::string & param) const; + PlanningAlgorithm planning_algorithm_; + + // stop watch + mutable tier4_autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; + + // planner + std::unique_ptr planner_ptr_; + + // obstacle filtering parameter + struct ObstacleFilteringParam + { + double rough_detection_area_expand_width; + double detection_area_expand_width; + double decimate_trajectory_step_length; + double crossing_obstacle_velocity_threshold; + double collision_time_margin; + double ego_obstacle_overlap_time_threshold; + double max_prediction_time_for_collision_check; + double crossing_obstacle_traj_angle_threshold; + std::vector ignored_outside_obstacle_types; + }; + ObstacleFilteringParam obstacle_filtering_param_; + + bool need_to_clear_vel_limit_{false}; +}; +} // namespace motion_planning + +#endif // OBSTACLE_CRUISE_PLANNER__NODE_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/box2d.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/box2d.hpp new file mode 100644 index 0000000000000..84349eca57dec --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/box2d.hpp @@ -0,0 +1,135 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__BOX2D_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__BOX2D_HPP_ + +#include +#include + +#include +#include +#include + +class Box2d +{ +public: + Box2d(const geometry_msgs::msg::Pose & center_pose, const double length, const double width); + + bool hasOverlap(const Box2d & box) const; + + void initCorners(); + + /** + * @brief Getter of the center of the box + * @return The center of the box + */ + const geometry_msgs::msg::Point & center() const { return center_; } + + /** + * @brief Getter of the x-coordinate of the center of the box + * @return The x-coordinate of the center of the box + */ + double getCenterX() const { return center_.x; } + + /** + * @brief Getter of the y-coordinate of the center of the box + * @return The y-coordinate of the center of the box + */ + double getCenterY() const { return center_.y; } + + /** + * @brief Getter of the length + * @return The length of the heading-axis + */ + double length() const { return length_; } + + /** + * @brief Getter of the width + * @return The width of the box taken perpendicularly to the heading + */ + double width() const { return width_; } + + /** + * @brief Getter of half the length + * @return Half the length of the heading-axis + */ + double getHalfLength() const { return half_length_; } + + /** + * @brief Getter of half the width + * @return Half the width of the box taken perpendicularly to the heading + */ + double getHalfWidth() const { return half_width_; } + + /** + * @brief Getter of the heading + * @return The counter-clockwise angle between the x-axis and the heading-axis + */ + double heading() const { return heading_; } + + /** + * @brief Getter of the cosine of the heading + * @return The cosine of the heading + */ + double getCosHeading() const { return cos_heading_; } + + /** + * @brief Getter of the sine of the heading + * @return The sine of the heading + */ + double getSinHeading() const { return sin_heading_; } + + /** + * @brief Getter of the area of the box + * @return The product of its length and width + */ + double area() const { return length_ * width_; } + + /** + * @brief Getter of the size of the diagonal of the box + * @return The diagonal size of the box + */ + double diagonal() const { return std::hypot(length_, width_); } + + /** + * @brief Getter of the corners of the box + * @param corners The vector where the corners are listed + */ + std::vector getAllCorners() const { return corners_; } + + double getMaxX() const { return max_x_; } + double getMinX() const { return min_x_; } + double getMaxY() const { return max_y_; } + double getMinY() const { return min_y_; } + +private: + geometry_msgs::msg::Point center_; + double length_ = 0.0; + double width_ = 0.0; + double half_length_ = 0.0; + double half_width_ = 0.0; + double heading_ = 0.0; + double cos_heading_ = 1.0; + double sin_heading_ = 0.0; + + std::vector corners_; + + double max_x_ = std::numeric_limits::lowest(); + double min_x_ = std::numeric_limits::max(); + double max_y_ = std::numeric_limits::lowest(); + double min_y_ = std::numeric_limits::max(); +}; + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__BOX2D_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp new file mode 100644 index 0000000000000..c8d6b294afd59 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp @@ -0,0 +1,189 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ + +#include "obstacle_cruise_planner/optimization_based_planner/box2d.hpp" +#include "obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp" +#include "obstacle_cruise_planner/optimization_based_planner/st_point.hpp" +#include "obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp" +#include "obstacle_cruise_planner/planner_interface.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include + +using autoware_auto_perception_msgs::msg::ObjectClassification; +using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using tier4_debug_msgs::msg::Float32Stamped; + +class OptimizationBasedPlanner : public PlannerInterface +{ +public: + OptimizationBasedPlanner( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info); + + Trajectory generateTrajectory( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + DebugData & debug_data) override; + +private: + struct TrajectoryData + { + TrajectoryData() {} + + Trajectory traj; + std::vector s; + }; + + struct ObjectData + { + geometry_msgs::msg::Pose pose; + double length; + double width; + double time; + }; + + // Member Functions + std::vector createTimeVector(); + + double getClosestStopDistance( + const ObstacleCruisePlannerData & planner_data, const TrajectoryData & ego_traj_data, + const std::vector & resolutions); + + std::tuple calcInitialMotion( + const double current_vel, const Trajectory & input_traj, const size_t input_closest, + const Trajectory & prev_traj, const double closest_stop_dist); + + TrajectoryPoint calcInterpolatedTrajectoryPoint( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & target_pose); + + bool checkHasReachedGoal(const Trajectory & traj, const size_t closest_idx, const double v0); + + TrajectoryData getTrajectoryData( + const Trajectory & traj, const geometry_msgs::msg::Pose & current_pose); + + TrajectoryData resampleTrajectoryData( + const TrajectoryData & base_traj_data, const double resampling_s_interval, + const double max_traj_length, const double stop_dist); + + Trajectory resampleTrajectory( + const std::vector & base_index, const Trajectory & base_trajectory, + const std::vector & query_index, const bool use_spline_for_pose = false); + + boost::optional getSBoundaries( + const ObstacleCruisePlannerData & planner_data, const TrajectoryData & ego_traj_data, + const std::vector & time_vec); + + boost::optional getSBoundaries( + const rclcpp::Time & current_time, const TrajectoryData & ego_traj_data, + const TargetObstacle & object, const rclcpp::Time & obj_base_time, + const std::vector & time_vec); + + boost::optional getSBoundaries( + const TrajectoryData & ego_traj_data, const std::vector & time_vec, + const double safety_distance, const TargetObstacle & object, + const double dist_to_collision_point); + + boost::optional getSBoundaries( + const rclcpp::Time & current_time, const TrajectoryData & ego_traj_data, + const std::vector & time_vec, const double safety_distance, + const TargetObstacle & object, const rclcpp::Time & obj_base_time, + const PredictedPath & predicted_path); + + bool checkIsFrontObject(const TargetObstacle & object, const Trajectory & traj); + + boost::optional resampledPredictedPath( + const TargetObstacle & object, const rclcpp::Time & obj_base_time, + const rclcpp::Time & current_time, const std::vector & resolutions, + const double horizon); + + boost::optional getDistanceToCollisionPoint( + const TrajectoryData & ego_traj_data, const ObjectData & obj_data, + const double delta_yaw_threshold); + + boost::optional getCollisionIdx( + const TrajectoryData & ego_traj, const Box2d & obj_box, const size_t start_idx, + const size_t end_idx); + + geometry_msgs::msg::Pose transformBaseLink2Center( + const geometry_msgs::msg::Pose & pose_base_link); + + boost::optional processOptimizedResult( + const double v0, const VelocityOptimizer::OptimizationResult & opt_result); + + void publishDebugTrajectory( + const rclcpp::Time & current_time, const Trajectory & traj, const size_t closest_idx, + const std::vector & time_vec, const SBoundaries & s_boundaries, + const VelocityOptimizer::OptimizationResult & opt_result); + + // Calculation time watcher + tier4_autoware_utils::StopWatch stop_watch_; + + Trajectory prev_output_; + + // Velocity Optimizer + std::shared_ptr velocity_optimizer_ptr_; + + // Publisher + rclcpp::Publisher::SharedPtr boundary_pub_; + rclcpp::Publisher::SharedPtr optimized_sv_pub_; + rclcpp::Publisher::SharedPtr optimized_st_graph_pub_; + rclcpp::Publisher::SharedPtr distance_to_closest_obj_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_; + rclcpp::Publisher::SharedPtr debug_wall_marker_pub_; + + // Resampling Parameter + double resampling_s_interval_; + double max_trajectory_length_; + double dense_resampling_time_interval_; + double sparse_resampling_time_interval_; + double dense_time_horizon_; + double max_time_horizon_; + double limit_min_accel_; + + double delta_yaw_threshold_of_nearest_index_; + double delta_yaw_threshold_of_object_and_ego_; + double object_zero_velocity_threshold_; + double object_low_velocity_threshold_; + double external_velocity_limit_; + double collision_time_threshold_; + double safe_distance_margin_; + double t_dangerous_; + double velocity_margin_; + bool enable_adaptive_cruise_; + bool use_object_acceleration_; + + double replan_vel_deviation_; + double engage_velocity_; + double engage_acceleration_; + double engage_exit_ratio_; + double stop_dist_to_prohibit_engage_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/resample.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/resample.hpp new file mode 100644 index 0000000000000..dffe7f181fec5 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/resample.hpp @@ -0,0 +1,50 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__RESAMPLE_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__RESAMPLE_HPP_ + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include "autoware_auto_perception_msgs/msg/predicted_path.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" + +#include "boost/optional.hpp" + +#include + +namespace resampling +{ +std::vector resampledValidRelativeTimeVector( + const rclcpp::Time & start_time, const rclcpp::Time & obj_base_time, + const std::vector & rel_time_vec, const double duration); + +autoware_auto_perception_msgs::msg::PredictedPath resamplePredictedPath( + const autoware_auto_perception_msgs::msg::PredictedPath & input_path, + const std::vector & rel_time_vec); + +geometry_msgs::msg::Pose lerpByPose( + const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Pose & p2, const double t); + +boost::optional lerpByTimeStamp( + const autoware_auto_perception_msgs::msg::PredictedPath & path, + const rclcpp::Duration & rel_time); + +autoware_auto_planning_msgs::msg::Trajectory applyLinearInterpolation( + const std::vector & base_index, + const autoware_auto_planning_msgs::msg::Trajectory & base_trajectory, + const std::vector & out_index, const bool use_spline_for_pose = false); +} // namespace resampling + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__RESAMPLE_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp new file mode 100644 index 0000000000000..1665434ad5969 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp @@ -0,0 +1,33 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_ + +#include +#include + +class SBoundary +{ +public: + SBoundary(const double _max_s, const double _min_s) : max_s(_max_s), min_s(_min_s) {} + SBoundary() : max_s(std::numeric_limits::max()), min_s(0.0) {} + + double max_s = std::numeric_limits::max(); + double min_s = 0.0; + bool is_object = false; +}; + +using SBoundaries = std::vector; + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/st_point.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/st_point.hpp new file mode 100644 index 0000000000000..8ef958c741414 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/st_point.hpp @@ -0,0 +1,31 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__ST_POINT_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__ST_POINT_HPP_ + +#include + +class STPoint +{ +public: + STPoint(const double _s, const double _t) : s(_s), t(_t) {} + STPoint() : s(0.0), t(0.0) {} + + double s; + double t; +}; + +using STPoints = std::vector; + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__ST_POINT_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp new file mode 100644 index 0000000000000..cb7d1baab79b8 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp @@ -0,0 +1,73 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_ +#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_ + +#include "obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp" +#include "osqp_interface/osqp_interface.hpp" + +#include + +class VelocityOptimizer +{ +public: + struct OptimizationData + { + std::vector time_vec; + double s0; + double v0; + double a0; + double v_max; + double a_max; + double a_min; + double limit_a_min; + double j_max; + double j_min; + double t_dangerous; + double idling_time; + double v_margin; + SBoundaries s_boundary; + }; + + struct OptimizationResult + { + std::vector t; + std::vector s; + std::vector v; + std::vector a; + std::vector j; + }; + + VelocityOptimizer( + const double max_s_weight, const double max_v_weight, const double over_s_safety_weight, + const double over_s_ideal_weight, const double over_v_weight, const double over_a_weight, + const double over_j_weight); + + OptimizationResult optimize(const OptimizationData & data); + +private: + // Parameter + double max_s_weight_; + double max_v_weight_; + double over_s_safety_weight_; + double over_s_ideal_weight_; + double over_v_weight_; + double over_a_weight_; + double over_j_weight_; + + // QPSolver + autoware::common::osqp::OSQPInterface qp_solver_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/debug_values.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/debug_values.hpp new file mode 100644 index 0000000000000..ae8a909d3bb51 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/debug_values.hpp @@ -0,0 +1,79 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__DEBUG_VALUES_HPP_ +#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__DEBUG_VALUES_HPP_ + +#include + +class DebugValues +{ +public: + enum class TYPE { + // current + CURRENT_VELOCITY = 0, + CURRENT_ACCELERATION, + CURRENT_JERK, // ignored + // stop + STOP_CURRENT_OBJECT_DISTANCE = 3, + STOP_CURRENT_OBJECT_VELOCITY, + STOP_TARGET_OBJECT_DISTANCE, + STOP_TARGET_VELOCITY, // ignored + STOP_TARGET_ACCELERATION, + STOP_TARGET_JERK, // ignored + STOP_ERROR_OBJECT_DISTANCE, + // cruise + CRUISE_CURRENT_OBJECT_DISTANCE = 10, + CRUISE_CURRENT_OBJECT_VELOCITY, + CRUISE_TARGET_OBJECT_DISTANCE, + CRUISE_TARGET_VELOCITY, + CRUISE_TARGET_ACCELERATION, + CRUISE_TARGET_JERK, + CRUISE_ERROR_OBJECT_DISTANCE, + + SIZE + }; + + /** + * @brief get the index corresponding to the given value TYPE + * @param [in] type the TYPE enum for which to get the index + * @return index of the type + */ + int getValuesIdx(const TYPE type) const { return static_cast(type); } + /** + * @brief get all the debug values as an std::array + * @return array of all debug values + */ + std::array(TYPE::SIZE)> getValues() const { return values_; } + /** + * @brief set the given type to the given value + * @param [in] type TYPE of the value + * @param [in] value value to set + */ + void setValues(const TYPE type, const double val) { values_.at(static_cast(type)) = val; } + /** + * @brief set the given type to the given value + * @param [in] type index of the type + * @param [in] value value to set + */ + void setValues(const int type, const double val) { values_.at(type) = val; } + + void resetValues() { values_.fill(0.0); } + +private: + static constexpr int num_debug_values_ = static_cast(TYPE::SIZE); + std::array(TYPE::SIZE)> values_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__DEBUG_VALUES_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp new file mode 100644 index 0000000000000..7697fd54b1d1a --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp @@ -0,0 +1,138 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_ +#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_ + +#include "obstacle_cruise_planner/pid_based_planner/debug_values.hpp" +#include "obstacle_cruise_planner/pid_based_planner/pid_controller.hpp" +#include "obstacle_cruise_planner/planner_interface.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" + +#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "tier4_planning_msgs/msg/stop_reason_array.hpp" +#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" +#include "visualization_msgs/msg/marker_array.hpp" + +#include + +#include +#include + +using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using tier4_planning_msgs::msg::StopSpeedExceeded; + +class PIDBasedPlanner : public PlannerInterface +{ +public: + struct CruiseObstacleInfo + { + CruiseObstacleInfo( + const TargetObstacle & obstacle_arg, const double dist_to_cruise_arg, + const double normalized_dist_to_cruise_arg) + : obstacle(obstacle_arg), + dist_to_cruise(dist_to_cruise_arg), + normalized_dist_to_cruise(normalized_dist_to_cruise_arg) + { + } + TargetObstacle obstacle; + double dist_to_cruise; + double normalized_dist_to_cruise; + }; + + struct StopObstacleInfo + { + StopObstacleInfo(const TargetObstacle & obstacle_arg, const double dist_to_stop_arg) + : obstacle(obstacle_arg), dist_to_stop(dist_to_stop_arg) + { + } + TargetObstacle obstacle; + double dist_to_stop; + }; + + PIDBasedPlanner( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info); + + Trajectory generateTrajectory( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + DebugData & debug_data) override; + + void updateParam(const std::vector & parameters) override; + +private: + void calcObstaclesToCruiseAndStop( + const ObstacleCruisePlannerData & planner_data, + boost::optional & stop_obstacle_info, + boost::optional & cruise_obstacle_info); + double calcDistanceToObstacle( + const ObstacleCruisePlannerData & planner_data, const TargetObstacle & obstacle); + bool isStopRequired(const TargetObstacle & obstacle); + + void planCruise( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + const boost::optional & cruise_obstacle_info, DebugData & debug_data); + VelocityLimit doCruise( + const ObstacleCruisePlannerData & planner_data, const CruiseObstacleInfo & cruise_obstacle_info, + std::vector & debug_obstacles_to_cruise, + visualization_msgs::msg::MarkerArray & debug_walls_marker); + + Trajectory planStop( + const ObstacleCruisePlannerData & planner_data, + const boost::optional & stop_obstacle_info, DebugData & debug_data); + boost::optional doStop( + const ObstacleCruisePlannerData & planner_data, const StopObstacleInfo & stop_obstacle_info, + std::vector & debug_obstacles_to_stop, + visualization_msgs::msg::MarkerArray & debug_walls_marker) const; + + void publishDebugValues(const ObstacleCruisePlannerData & planner_data) const; + + size_t findExtendedNearestIndex( + const Trajectory traj, const geometry_msgs::msg::Pose & pose) const + { + const auto nearest_idx = tier4_autoware_utils::findNearestIndex( + traj.points, pose, nearest_dist_deviation_threshold_, nearest_yaw_deviation_threshold_); + if (nearest_idx) { + return nearest_idx.get(); + } + return tier4_autoware_utils::findNearestIndex(traj.points, pose.position); + } + + // ROS parameters + double min_accel_during_cruise_; + double vel_to_acc_weight_; + double min_cruise_target_vel_; + double obstacle_velocity_threshold_from_cruise_to_stop_; + // bool use_predicted_obstacle_pose_; + + // pid controller + std::unique_ptr pid_controller_; + double output_ratio_during_accel_; + + // stop watch + tier4_autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; + + // publisher + rclcpp::Publisher::SharedPtr stop_reasons_pub_; + rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; + rclcpp::Publisher::SharedPtr debug_values_pub_; + + boost::optional prev_target_vel_; + + DebugValues debug_values_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp new file mode 100644 index 0000000000000..593fd1f4336d6 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp @@ -0,0 +1,62 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_ +#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_ + +#include + +class PIDController +{ +public: + PIDController(const double kp, const double ki, const double kd) + : kp_(kp), ki_(ki), kd_(kd), error_sum_(0.0) + { + } + + double calc(const double error) + { + error_sum_ += error; + + // TODO(murooka) use time for d gain calculation + const double output = + kp_ * error + ki_ * error_sum_ + (prev_error_ ? kd_ * (error - prev_error_.get()) : 0.0); + prev_error_ = error; + return output; + } + + double getKp() const { return kp_; } + double getKi() const { return ki_; } + double getKd() const { return kd_; } + + void updateParam(const double kp, const double ki, const double kd) + { + kp_ = kp; + ki_ = ki; + kd_ = kd; + + error_sum_ = 0.0; + prev_error_ = {}; + } + +private: + double kp_; + double ki_; + double kd_; + + double error_sum_; + boost::optional prev_error_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp new file mode 100644 index 0000000000000..af31e1d979e4b --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -0,0 +1,192 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ +#define OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ + +#include "obstacle_cruise_planner/common_structs.hpp" +#include "obstacle_cruise_planner/utils.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "tier4_planning_msgs/msg/velocity_limit.hpp" + +#include + +#include +#include + +using autoware_auto_perception_msgs::msg::ObjectClassification; +using autoware_auto_planning_msgs::msg::Trajectory; +using tier4_planning_msgs::msg::VelocityLimit; + +class PlannerInterface +{ +public: + PlannerInterface( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info) + : longitudinal_info_(longitudinal_info), vehicle_info_(vehicle_info) + { + { // cruise obstacle type + if (node.declare_parameter("common.cruise_obstacle_type.unknown")) { + cruise_obstacle_types_.push_back(ObjectClassification::UNKNOWN); + } + if (node.declare_parameter("common.cruise_obstacle_type.car")) { + cruise_obstacle_types_.push_back(ObjectClassification::CAR); + } + if (node.declare_parameter("common.cruise_obstacle_type.truck")) { + cruise_obstacle_types_.push_back(ObjectClassification::TRUCK); + } + if (node.declare_parameter("common.cruise_obstacle_type.bus")) { + cruise_obstacle_types_.push_back(ObjectClassification::BUS); + } + if (node.declare_parameter("common.cruise_obstacle_type.trailer")) { + cruise_obstacle_types_.push_back(ObjectClassification::TRAILER); + } + if (node.declare_parameter("common.cruise_obstacle_type.motorcycle")) { + cruise_obstacle_types_.push_back(ObjectClassification::MOTORCYCLE); + } + if (node.declare_parameter("common.cruise_obstacle_type.bicycle")) { + cruise_obstacle_types_.push_back(ObjectClassification::BICYCLE); + } + if (node.declare_parameter("common.cruise_obstacle_type.pedestrian")) { + cruise_obstacle_types_.push_back(ObjectClassification::PEDESTRIAN); + } + } + + { // stop obstacle type + if (node.declare_parameter("common.stop_obstacle_type.unknown")) { + stop_obstacle_types_.push_back(ObjectClassification::UNKNOWN); + } + if (node.declare_parameter("common.stop_obstacle_type.car")) { + stop_obstacle_types_.push_back(ObjectClassification::CAR); + } + if (node.declare_parameter("common.stop_obstacle_type.truck")) { + stop_obstacle_types_.push_back(ObjectClassification::TRUCK); + } + if (node.declare_parameter("common.stop_obstacle_type.bus")) { + stop_obstacle_types_.push_back(ObjectClassification::BUS); + } + if (node.declare_parameter("common.stop_obstacle_type.trailer")) { + stop_obstacle_types_.push_back(ObjectClassification::TRAILER); + } + if (node.declare_parameter("common.stop_obstacle_type.motorcycle")) { + stop_obstacle_types_.push_back(ObjectClassification::MOTORCYCLE); + } + if (node.declare_parameter("common.stop_obstacle_type.bicycle")) { + stop_obstacle_types_.push_back(ObjectClassification::BICYCLE); + } + if (node.declare_parameter("common.stop_obstacle_type.pedestrian")) { + stop_obstacle_types_.push_back(ObjectClassification::PEDESTRIAN); + } + } + } + + PlannerInterface() = default; + + void setParams( + const bool is_showing_debug_info, const double min_behavior_stop_margin, + const double nearest_dist_deviation_threshold, const double nearest_yaw_deviation_threshold) + { + is_showing_debug_info_ = is_showing_debug_info; + min_behavior_stop_margin_ = min_behavior_stop_margin; + nearest_dist_deviation_threshold_ = nearest_dist_deviation_threshold; + nearest_yaw_deviation_threshold_ = nearest_yaw_deviation_threshold; + } + + /* + // two kinds of velocity planning is supported. + // 1. getZeroVelocityIndexWithVelocityLimit + // returns zero velocity index and velocity limit + // 2. generateTrajectory + // returns trajectory with planned velocity + virtual boost::optional getZeroVelocityIndexWithVelocityLimit( + [[maybe_unused]] const ObstacleCruisePlannerData & planner_data, + [[maybe_unused]] boost::optional & vel_limit) + { + return {}; + }; + */ + + virtual Trajectory generateTrajectory( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + DebugData & debug_data) = 0; + + void updateCommonParam(const std::vector & parameters) + { + auto & i = longitudinal_info_; + + tier4_autoware_utils::updateParam(parameters, "common.max_accel", i.max_accel); + tier4_autoware_utils::updateParam(parameters, "common.min_accel", i.min_accel); + tier4_autoware_utils::updateParam(parameters, "common.max_jerk", i.max_jerk); + tier4_autoware_utils::updateParam(parameters, "common.min_jerk", i.min_jerk); + tier4_autoware_utils::updateParam( + parameters, "common.min_ego_accel_for_rss", i.min_ego_accel_for_rss); + tier4_autoware_utils::updateParam( + parameters, "common.min_object_accel_for_rss", i.min_object_accel_for_rss); + tier4_autoware_utils::updateParam(parameters, "common.idling_time", i.idling_time); + } + + virtual void updateParam([[maybe_unused]] const std::vector & parameters) {} + + // TODO(shimizu) remove this function + void setSmoothedTrajectory(const Trajectory::ConstSharedPtr traj) + { + smoothed_trajectory_ptr_ = traj; + } + + bool isCruiseObstacle(const uint8_t label) + { + const auto & types = cruise_obstacle_types_; + return std::find(types.begin(), types.end(), label) != types.end(); + } + + bool isStopObstacle(const uint8_t label) + { + const auto & types = stop_obstacle_types_; + return std::find(types.begin(), types.end(), label) != types.end(); + } + +protected: + // Parameters + bool is_showing_debug_info_{false}; + LongitudinalInfo longitudinal_info_; + double min_behavior_stop_margin_; + double nearest_dist_deviation_threshold_; + double nearest_yaw_deviation_threshold_; + + // Vehicle Parameters + vehicle_info_util::VehicleInfo vehicle_info_; + + // TODO(shimizu) remove these parameters + Trajectory::ConstSharedPtr smoothed_trajectory_ptr_; + + double calcRSSDistance( + const double ego_vel, const double obj_vel, const double margin = 0.0) const + { + const auto & i = longitudinal_info_; + const double rss_dist_with_margin = + ego_vel * i.idling_time + std::pow(ego_vel, 2) * 0.5 / std::abs(i.min_accel) - + std::pow(obj_vel, 2) * 0.5 / std::abs(i.min_object_accel_for_rss) + margin; + return rss_dist_with_margin; + } + +private: + std::vector cruise_obstacle_types_; + std::vector stop_obstacle_types_; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp new file mode 100644 index 0000000000000..8a34f49172cd2 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp @@ -0,0 +1,62 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_ +#define OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_ + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include "autoware_auto_perception_msgs/msg/predicted_object.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "geometry_msgs/msg/point32.hpp" +#include "geometry_msgs/msg/pose.hpp" + +#include +#include + +#include + +namespace polygon_utils +{ +namespace bg = boost::geometry; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; + +Polygon2d convertObstacleToPolygon( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape); + +boost::optional getFirstCollisionIndex( + const std::vector & traj_polygons, const Polygon2d & obj_polygon, + std::vector & collision_points); + +boost::optional getFirstNonCollisionIndex( + const std::vector & base_polygons, + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const autoware_auto_perception_msgs::msg::Shape & shape, const size_t start_idx); + +bool willCollideWithSurroundObstacle( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const std::vector & traj_polygons, + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const autoware_auto_perception_msgs::msg::Shape & shape, const double max_dist, + const double ego_obstacle_overlap_time_threshold, + const double max_prediction_time_for_collision_check); + +std::vector createOneStepPolygons( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width); +} // namespace polygon_utils + +#endif // OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp new file mode 100644 index 0000000000000..d1e6a0b86e715 --- /dev/null +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp @@ -0,0 +1,49 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 OBSTACLE_CRUISE_PLANNER__UTILS_HPP_ +#define OBSTACLE_CRUISE_PLANNER__UTILS_HPP_ + +#include + +#include "autoware_auto_perception_msgs/msg/object_classification.hpp" +#include "autoware_auto_perception_msgs/msg/predicted_path.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "geometry_msgs/msg/pose.hpp" +#include "visualization_msgs/msg/marker_array.hpp" + +#include + +#include + +namespace obstacle_cruise_utils +{ +using autoware_auto_perception_msgs::msg::ObjectClassification; + +bool isVehicle(const uint8_t label); + +visualization_msgs::msg::Marker getObjectMarker( + const geometry_msgs::msg::Pose & obstacle_pose, size_t idx, const std::string & ns, + const double r, const double g, const double b); + +boost::optional calcForwardPose( + const autoware_auto_planning_msgs::msg::Trajectory & traj, const size_t nearest_idx, + const double target_length); + +boost::optional getCurrentObjectPoseFromPredictedPath( + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const rclcpp::Time & obj_base_time, const rclcpp::Time & current_time); +} // namespace obstacle_cruise_utils + +#endif // OBSTACLE_CRUISE_PLANNER__UTILS_HPP_ diff --git a/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml b/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml new file mode 100644 index 0000000000000..a6c95d65acc6a --- /dev/null +++ b/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/obstacle_cruise_planner/obstacle_cruise_planner-design.md b/planning/obstacle_cruise_planner/obstacle_cruise_planner-design.md new file mode 100644 index 0000000000000..3a78af3827b2e --- /dev/null +++ b/planning/obstacle_cruise_planner/obstacle_cruise_planner-design.md @@ -0,0 +1,326 @@ +# Obstacle Velocity Planner + +## Overview + +The `obstacle_cruise_planner` package has following modules. + +- obstacle stop planning + - inserting a stop point in the trajectory when there is a static obstacle on the trajectory. +- adaptive cruise planning + - sending an external velocity limit to `motion_velocity_smoother` when there is a dynamic obstacle to cruise on the trajectory + +## Interfaces + +### Input topics + +| Name | Type | Description | +| ----------------------------- | ----------------------------------------------- | --------------------------------- | +| `~/input/trajectory` | autoware_auto_planning_msgs::Trajectory | input trajectory | +| `~/input/smoothed_trajectory` | autoware_auto_planning_msgs::Trajectory | trajectory with smoothed velocity | +| `~/input/objects` | autoware_auto_perception_msgs::PredictedObjects | dynamic objects | +| `~/input/odometry` | nav_msgs::msg::Odometry | ego odometry | + +### Output topics + +| Name | Type | Description | +| ------------------------------ | ---------------------------------------------- | ------------------------------------- | +| `~output/trajectory` | autoware_auto_planning_msgs::Trajectory | output trajectory | +| `~output/velocity_limit` | tier4_planning_msgs::VelocityLimit | velocity limit for cruising | +| `~output/clear_velocity_limit` | tier4_planning_msgs::VelocityLimitClearCommand | clear command for velocity limit | +| `~output/stop_reasons` | tier4_planning_msgs::StopReasonArray | reasons that make the vehicle to stop | + +## Design + +Design for the following functions is defined here. + +- Obstacle candidates selection +- Obstacle stop planning +- Adaptive cruise planning + +A data structure for cruise and stop planning is as follows. +This planner data is created first, and then sent to the planning algorithm. + +```cpp +struct ObstacleCruisePlannerData +{ + rclcpp::Time current_time; + autoware_auto_planning_msgs::msg::Trajectory traj; + geometry_msgs::msg::Pose current_pose; + double current_vel; + double current_acc; + std::vector target_obstacles; +}; +``` + +```cpp +struct TargetObstacle +{ + rclcpp::Time time_stamp; + bool orientation_reliable; + geometry_msgs::msg::Pose pose; + bool velocity_reliable; + float velocity; + bool is_classified; + ObjectClassification classification; + Shape shape; + std::vector predicted_paths; + geometry_msgs::msg::Point collision_point; +}; +``` + +### Obstacle candidates selection + +In this function, target obstacles for stopping or cruising are selected based on their pose and velocity. + +By default, objects that realize one of the following conditions are considered to be the target obstacle candidates. +Some terms will be defined in the following subsections. + +- Vehicle objects "inside the detection area" other than "far crossing vehicles". +- non vehicle objects "inside the detection area" +- "Near cut-in vehicles" outside the detection area + +Note that currently the obstacle candidates selection algorithm is for autonomous driving. +However, we have following parameters as well for stop and cruise respectively so that we can extend the obstacles candidates selection algorithm for non vehicle robots. +By default, unknown and vehicles are obstacles to cruise and stop, and non vehicles are obstacles just to stop. + +| Parameter | Type | Description | +| ------------------------------ | ---- | ------------------------------------------------- | +| `cruise_obstacle_type.unknown` | bool | flag to consider unknown objects as being cruised | +| `cruise_obstacle_type.car` | bool | flag to consider unknown objects as being cruised | +| `cruise_obstacle_type.truck` | bool | flag to consider unknown objects as being cruised | +| ... | bool | ... | +| `stop_obstacle_type.unknown` | bool | flag to consider unknown objects as being stopped | +| ... | bool | ... | + +#### Inside the detection area + +To calculate obstacles inside the detection area, firstly, obstacles whose distance to the trajectory is less than `rough_detection_area_expand_width` are selected. +Then, the detection area, which is a trajectory with some lateral margin, is calculated as shown in the figure. +The detection area width is a vehicle's width + `detection_area_expand_width`, and it is represented as a polygon resampled with `decimate_trajectory_step_length` longitudinally. +The roughly selected obstacles inside the detection area are considered as inside the detection area. + +![detection_area](./image/detection_area.png) + +This two-step detection is used for calculation efficiency since collision checking of polygons is heavy. +Boost.Geometry is used as a library to check collision among polygons. + +In the `obstacle_filtering` namespace, + +| Parameter | Type | Description | +| ----------------------------------- | ------ | ----------------------------------------------------------------------------------- | +| `rough_detection_area_expand_width` | double | rough lateral margin for rough detection area expansion [m] | +| `detection_area_expand_width` | double | lateral margin for precise detection area expansion [m] | +| `decimate_trajectory_step_length` | double | longitudinal step length to calculate trajectory polygon for collision checking [m] | + +#### Far crossing vehicles + +Near crossing vehicles (= not far crossing vehicles) are defined as vehicle objects realizing either of following conditions. + +- whose yaw angle against the nearest trajectory point is greater than `crossing_obstacle_traj_angle_threshold` +- whose velocity is less than `crossing_obstacle_velocity_threshold`. + +Assuming `t_1` to be the time for the ego to reach the current crossing obstacle position with the constant velocity motion, and `t_2` to be the time for the crossing obstacle to go outside the detection area, if the following condition is realized, the crossing vehicle will be ignored. + +$$ +t_1 - t_2 > \mathrm{margin\_for\_collision\_time} +$$ + +In the `obstacle_filtering` namespace, + +| Parameter | Type | Description | +| ---------------------------------------- | ------ | ----------------------------------------------------------------------------- | +| `crossing_obstacle_velocity_threshold` | double | velocity threshold to decide crossing obstacle [m/s] | +| `crossing_obstacle_traj_angle_threshold` | double | yaw threshold of crossing obstacle against the nearest trajectory point [rad] | +| `collision_time_margin` | double | time threshold of collision between obstacle and ego [s] | + +#### Near Cut-in vehicles + +Near Cut-in vehicles are defined as vehicle objects + +- whose predicted path's footprints from the current time to `max_prediction_time_for_collision_check` overlap with the detection area longer than `ego_obstacle_overlap_time_threshold`. + +In the `obstacle_filtering` namespace, + +| Parameter | Type | Description | +| ----------------------------------------- | ------ | --------------------------------------------------------------- | +| `ego_obstacle_overlap_time_threshold` | double | time threshold to decide cut-in obstacle for cruise or stop [s] | +| `max_prediction_time_for_collision_check` | double | prediction time to check collision between obstacle and ego [s] | + +### Stop planning + +| Parameter | Type | Description | +| ----------------------------- | ------ | ----------------------------------------- | +| `common.min_strong_accel` | double | ego's minimum acceleration to stop [m/ss] | +| `common.safe_distance_margin` | double | distance with obstacles for stop [m] | + +The role of the stop planning is keeping a safe distance with static vehicle objects or dynamic/static non vehicle objects. + +The stop planning just inserts the stop point in the trajectory to keep a distance with obstacles inside the detection area. +The safe distance is parameterized as `common.safe_distance_margin`. + +When inserting the stop point, the required acceleration for the ego to stop in front of the stop point is calculated. +If the acceleration is less than `common.min_strong_accel`, the stop planning will be cancelled since this package does not assume a strong sudden brake for emergency. + +### Adaptive cruise planning + +| Parameter | Type | Description | +| ----------------------------- | ------ | ---------------------------------------------- | +| `common.safe_distance_margin` | double | minimum distance with obstacles for cruise [m] | + +The role of the adaptive cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. +This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle. + +The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation. + +$$ +d = v_{ego} t_{idling} + \frac{1}{2} a_{ego} t_{idling}^2 + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}}, +$$ + +assuming that $d$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle's deceleration, $v_{ego}$ is the ego's current velocity, $v_{obstacle}$ is the front obstacle's current velocity, $a_{ego}$ is the ego's acceleration, and $a_{obstacle}$ is the obstacle's acceleration. +These values are parameterized as follows. Other common values such as ego's minimum acceleration is defined in `common.param.yaml`. + +| Parameter | Type | Description | +| --------------------------------- | ------ | ----------------------------------------------------------------------------- | +| `common.idling_time` | double | idling time for the ego to detect the front vehicle starting deceleration [s] | +| `common.min_object_accel_for_rss` | double | front obstacle's acceleration [m/ss] | + +## Implementation + +### Flowchart + +Successive functions consist of `obstacle_cruise_planner` as follows. + +Various algorithms for stop and cruise planning will be implemented, and one of them is designated depending on the use cases. +The core algorithm implementation `generateTrajectory` depends on the designated algorithm. + +```plantuml +@startuml +title trajectoryCallback +start + +group createPlannerData + :filterObstacles; +end group + +:generateTrajectory; + +:publishVelocityLimit; + +:publish trajectory; + +:publishDebugData; + +:publish and print calculation time; + +stop +@enduml +``` + +### Algorithm selection + +Currently, only a PID-based planner is supported. +Each planner will be explained in the following. + +| Parameter | Type | Description | +| ------------------------ | ------ | ------------------------------------------------------------ | +| `common.planning_method` | string | cruise and stop planning algorithm, selected from "pid_base" | + +### PID-based planner + +#### Stop planning + +In the `pid_based_planner` namespace, + +| Parameter | Type | Description | +| ------------------------------------------------- | ------ | ------------------------------------------------------------ | +| `obstacle_velocity_threshold_from_cruise_to_stop` | double | obstacle velocity threshold to be stopped from cruised [m/s] | + +Only one obstacle is targeted for the stop planning. +It is the obstacle among obstacle candidates whose velocity is less than `obstacle_velocity_threshold_from_cruise_to_stop`, and which is the nearest to the ego along the trajectory. A stop point is inserted keeping`common.safe_distance_margin` distance between the ego and obstacle. + +Note that, as explained in the stop planning design, a stop planning which requires a strong acceleration (less than `common.min_strong_accel`) will be canceled. + +#### Adaptive cruise planning + +In the `pid_based_planner` namespace, + +| Parameter | Type | Description | +| --------------------------- | ------ | -------------------------------------------------------------------------------------------------------- | +| `kp` | double | p gain for pid control [-] | +| `ki` | double | i gain for pid control [-] | +| `kd` | double | d gain for pid control [-] | +| `output_ratio_during_accel` | double | The output velocity will be multiplied by the ratio during acceleration to follow the front vehicle. [-] | +| `vel_to_acc_weight` | double | target acceleration is target velocity \* `vel_to_acc_weight` [-] | +| `min_cruise_target_vel` | double | minimum target velocity during cruise [m/s] | + +In order to keep the safe distance, the target velocity and acceleration is calculated and sent as an external velocity limit to the velocity smoothing package (`motion_velocity_smoother` by default). +The target velocity and acceleration is respectively calculated with the PID controller according to the error between the reference safe distance and the actual distance. + +### Optimization-based planner + +under construction + +## Minor functions + +### Prioritization of behavior module's stop point + +When stopping for a pedestrian walking on the crosswalk, the behavior module inserts the zero velocity in the trajectory in front of the crosswalk. +Also `obstacle_cruise_planner`'s stop planning also works, and the ego may not reach the behavior module's stop point since the safe distance defined in `obstacle_cruise_planner` may be longer than the behavior module's safe distance. +To resolve this non-alignment of the stop point between the behavior module and `obstacle_cruise_planner`, `common.min_behavior_stop_margin` is defined. +In the case of the crosswalk described above, `obstacle_cruise_planner` inserts the stop point with a distance `common.min_behavior_stop_margin` at minimum between the ego and obstacle. + +| Parameter | Type | Description | +| --------------------------------- | ------ | ---------------------------------------------------------------------- | +| `common.min_behavior_stop_margin` | double | minimum stop margin when stopping with the behavior module enabled [m] | + +## Visualization for debugging + +### Detection area + +Green polygons which is a detection area is visualized by `detection_polygons` in the `~/debug/marker` topic. + +![detection_area](./image/detection_area.png) + +### Collision point + +Red point which is a collision point with obstacle is visualized by `collision_points` in the `~/debug/marker` topic. + +![collision_point](./image/collision_point.png) + +### Obstacle for cruise + +Yellow sphere which is a obstacle for cruise is visualized by `obstacles_to_cruise` in the `~/debug/marker` topic. + +![obstacle_to_cruise](./image/obstacle_to_cruise.png) + +### Obstacle for stop + +Red sphere which is a obstacle for stop is visualized by `obstacles_to_stop` in the `~/debug/marker` topic. + +![obstacle_to_stop](./image/obstacle_to_stop.png) + + + + + + + +### Obstacle cruise wall + +Yellow wall which means a safe distance to cruise if the ego's front meets the wall is visualized in the `~/debug/cruise_wall_marker` topic. + +![obstacle_to_cruise](./image/obstacle_to_cruise.png) + +### Obstacle stop wall + +Red wall which means a safe distance to stop if the ego's front meets the wall is visualized in the `~/debug/stop_wall_marker` topic. + +![obstacle_to_stop](./image/obstacle_to_stop.png) + +## Known Limits + +- Common + - When the obstacle pose or velocity estimation has a delay, the ego sometimes will go close to the front vehicle keeping deceleration. + - Current implementation only uses predicted objects message for static/dynamic obstacles and does not use pointcloud. Therefore, if object recognition is lost, the ego cannot deal with the lost obstacle. +- PID-based planner + - The algorithm strongly depends on the velocity smoothing package (`motion_velocity_smoother` by default) whether or not the ego realizes the designated target speed. If the velocity smoothing package is updated, please take care of the vehicle's behavior as much as possible. diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml new file mode 100644 index 0000000000000..ec261d99a229f --- /dev/null +++ b/planning/obstacle_cruise_planner/package.xml @@ -0,0 +1,40 @@ + + + obstacle_cruise_planner + 0.1.0 + The Stop/Slow down planner for dynamic obstacles + + Takayuki Murooka + + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + geometry_msgs + interpolation + lanelet2_extension + nav_msgs + osqp_interface + rclcpp + rclcpp_components + signal_processing + std_msgs + tf2 + tf2_ros + tier4_autoware_utils + tier4_debug_msgs + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/obstacle_cruise_planner/scripts/trajectory_visualizer.py b/planning/obstacle_cruise_planner/scripts/trajectory_visualizer.py new file mode 100755 index 0000000000000..00833d4e84e83 --- /dev/null +++ b/planning/obstacle_cruise_planner/scripts/trajectory_visualizer.py @@ -0,0 +1,384 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# Copyright 2022 TIER IV, Inc. All rights reserved. +# +# 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. + +from autoware_auto_planning_msgs.msg import Trajectory +from geometry_msgs.msg import Pose +from geometry_msgs.msg import Twist +from geometry_msgs.msg import TwistStamped +from matplotlib import animation +import matplotlib.pyplot as plt +import message_filters +from nav_msgs.msg import Odometry +import numpy as np +import rclpy +from rclpy.node import Node +from tf2_ros.buffer import Buffer +from tf2_ros.transform_listener import TransformListener + +PLOT_MAX_ARCLENGTH = 200 +PATH_ORIGIN_FRAME = "map" +SELF_POSE_FRAME = "base_link" + + +class TrajectoryVisualizer(Node): + def __init__(self): + + super().__init__("trajectory_visualizer") + + self.fig = plt.figure() + + self.max_vel = 0.0 + self.min_vel = 0.0 + + # update flag + self.update_sv_traj = False + self.update_traj = False + self.update_max_traj = False + self.update_boundary = False + self.update_optimized_st_graph = False + + self.tf_buffer = Buffer(node=self) + self.tf_listener = TransformListener( + self.tf_buffer, self, spin_thread=True + ) # For get self-position + self.self_pose = Pose() + self.self_pose_received = False + self.localization_twist = Twist() + self.vehicle_twist = Twist() + + self.sv_trajectory = Trajectory() + self.trajectory = Trajectory() + self.max_trajectory = Trajectory() + self.boundary = Trajectory() + self.optimized_st_graph = Trajectory() + + self.sub_localization_twist = self.create_subscription( + Odometry, "/localization/kinematic_state", self.CallbackLocalizationOdom, 1 + ) + self.sub_vehicle_twist = self.create_subscription( + TwistStamped, "/vehicle/status/twist", self.CallbackVehicleTwist, 1 + ) + + topic_header = "/planning/scenario_planning/lane_driving/motion_planning/" + traj0 = "obstacle_cruise_planner/optimized_sv_trajectory" + self.sub_status0 = message_filters.Subscriber(self, Trajectory, topic_header + traj0) + traj1 = "/planning/scenario_planning/lane_driving/trajectory" + self.sub_status1 = message_filters.Subscriber(self, Trajectory, traj1) + traj2 = "surround_obstacle_checker/trajectory" + self.sub_status2 = message_filters.Subscriber(self, Trajectory, topic_header + traj2) + traj3 = "obstacle_cruise_planner/boundary" + self.sub_status3 = message_filters.Subscriber(self, Trajectory, topic_header + traj3) + traj4 = "obstacle_cruise_planner/optimized_st_graph" + self.sub_status4 = message_filters.Subscriber(self, Trajectory, topic_header + traj4) + + self.ts1 = message_filters.ApproximateTimeSynchronizer( + [self.sub_status0, self.sub_status1, self.sub_status2], 30, 0.5 + ) + self.ts1.registerCallback(self.CallbackMotionVelOptTraj) + self.ts2 = message_filters.ApproximateTimeSynchronizer( + [self.sub_status3, self.sub_status4], 30, 0.5 + ) + self.ts2.registerCallback(self.CallbackMotionVelObsTraj) + + # Main Process + self.ani = animation.FuncAnimation( + self.fig, self.plotTrajectoryVelocity, interval=100, blit=True + ) + self.setPlotTrajectoryVelocity() + + plt.show() + return + + def CallbackLocalizationOdom(self, cmd): + self.localization_twist = cmd.twist.twist + + def CallbackVehicleTwist(self, cmd): + self.vehicle_twist = cmd.twist + + def CallbackMotionVelOptTraj(self, cmd0, cmd1, cmd2): + self.CallbackSVTraj(cmd0) + self.CallbackTraj(cmd1) + self.CallbackMaxTraj(cmd2) + + def CallbackMotionVelObsTraj(self, cmd1, cmd2): + self.CallbackBoundary(cmd1) + self.CallbackOptimizedSTGraph(cmd2) + + def CallbackSVTraj(self, cmd): + self.sv_trajectory = cmd + self.update_sv_traj = True + + def CallbackTraj(self, cmd): + self.trajectory = cmd + self.update_traj = True + + def CallbackMaxTraj(self, cmd): + self.max_trajectory = cmd + self.update_max_traj = True + + def CallbackBoundary(self, cmd): + self.boundary = cmd + self.update_boundary = True + + def CallbackOptimizedSTGraph(self, cmd): + self.optimized_st_graph = cmd + self.update_optimized_st_graph = True + + def setPlotTrajectoryVelocity(self): + self.ax1 = plt.subplot(2, 1, 1) # row, col, index(= 0: + x_closest = x[opt_closest] + self.im3.set_data(x_closest, self.localization_twist.linear.x) + self.im4.set_data(x_closest, self.vehicle_twist.linear.x) + + opt_zero_vel_id = -1 + for i in range(opt_closest, len(trajectory.points)): + if trajectory.points[i].longitudinal_velocity_mps < 1e-3: + opt_zero_vel_id = i + break + else: + opt_zero_vel_id = len(trajectory.points) - 1 + + opt_pos = self.CalcPartArcLength(trajectory, opt_closest, opt_zero_vel_id + 1) + opt_time = self.CalcTime(trajectory, opt_closest, opt_zero_vel_id + 1) + self.im6.set_data(opt_time, opt_pos) + + if self.update_max_traj: + x = self.CalcArcLength(max_trajectory) + y = self.ToVelList(max_trajectory) + self.im1.set_data(x, y) + self.update_max_traj = False + + max_closest = self.calcClosestTrajectory(max_trajectory) + if max_closest >= 0: + max_zero_vel_id = -1 + for i in range(max_closest, len(max_trajectory.points)): + if max_trajectory.points[i].longitudinal_velocity_mps < 1e-3: + max_zero_vel_id = i + break + else: + max_zero_vel_id = len(max_trajectory.points) - 1 + + max_pos = self.CalcPartArcLength(max_trajectory, max_closest, max_zero_vel_id + 1) + max_time = self.CalcTime(max_trajectory, max_closest, max_zero_vel_id + 1) + self.im5.set_data(max_time, max_pos) + + if self.update_boundary: + self.update_boundary = False + s_list = [] + t_list = [] + for p in self.boundary.points: + s_list.append(p.pose.position.x) + t_list.append(p.pose.position.y) + self.im7.set_data(t_list, s_list) + + if self.update_optimized_st_graph: + self.update_optimized_st_graph = False + s_list = [] + t_list = [] + for p in self.optimized_st_graph.points: + s_list.append(p.pose.position.x) + t_list.append(p.pose.position.y) + self.im8.set_data(t_list, s_list) + + # change y-range + self.ax1.set_ylim([-1.0, 50.0]) + + return ( + self.im0, + self.im1, + self.im2, + self.im3, + self.im4, + self.im5, + self.im6, + self.im7, + self.im8, + ) + + def CalcArcLength(self, traj): + return self.CalcPartArcLength(traj, 0, len(traj.points)) + + def CalcPartArcLength(self, traj, start, end): + assert start <= end + s_arr = [] + ds = 0.0 + s_sum = 0.0 + + if len(traj.points) > 0: + s_arr.append(s_sum) + + for i in range(start + 1, end): + p0 = traj.points[i - 1] + p1 = traj.points[i] + dx = p1.pose.position.x - p0.pose.position.x + dy = p1.pose.position.y - p0.pose.position.y + ds = np.sqrt(dx**2 + dy**2) + s_sum += ds + s_arr.append(s_sum) + return s_arr + + def CalcTrajectoryInterval(self, traj, start, end): + ds_arr = [] + + for i in range(start + 1, end): + p0 = traj.points[i - 1] + p1 = traj.points[i] + dx = p1.pose.position.x - p0.pose.position.x + dy = p1.pose.position.y - p0.pose.position.y + ds = np.sqrt(dx**2 + dy**2) + ds_arr.append(ds) + return ds_arr + + def CalcTime(self, traj, start, end): + t_arr = [] + t_sum = 0.0 + ds_arr = self.CalcTrajectoryInterval(traj, start, end) + + if len(traj.points) > 0: + t_arr.append(t_sum) + + for i in range(start, end - 1): + v = traj.points[i].longitudinal_velocity_mps + ds = ds_arr[i - start] + dt = ds / max(v, 0.1) + t_sum += dt + t_arr.append(t_sum) + return t_arr + + def ToVelList(self, traj): + v_list = [] + for p in traj.points: + v_list.append(p.longitudinal_velocity_mps) + return v_list + + def updatePose(self, from_link, to_link): + try: + tf = self.tf_buffer.lookup_transform(from_link, to_link, rclpy.time.Time()) + self.self_pose.position.x = tf.transform.translation.x + self.self_pose.position.y = tf.transform.translation.y + self.self_pose.position.z = tf.transform.translation.z + self.self_pose.orientation.x = tf.transform.rotation.x + self.self_pose.orientation.y = tf.transform.rotation.y + self.self_pose.orientation.z = tf.transform.rotation.z + self.self_pose.orientation.w = tf.transform.rotation.w + self.self_pose_received = True + return + except BaseException: + self.get_logger().warn( + "lookup transform failed: from {} to {}".format(from_link, to_link) + ) + return + + def calcClosestTrajectory(self, path): + closest = -1 + min_dist_squared = 1.0e10 + for i in range(0, len(path.points)): + dist_sq = self.calcSquaredDist2d(self.self_pose, path.points[i].pose) + if dist_sq < min_dist_squared: + min_dist_squared = dist_sq + closest = i + return closest + + def calcSquaredDist2d(self, p1, p2): + dx = p1.position.x - p2.position.x + dy = p1.position.y - p2.position.y + return dx * dx + dy * dy + + +def main(args=None): + try: + rclpy.init(args=args) + node = TrajectoryVisualizer() + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp new file mode 100644 index 0000000000000..45bab678c98b7 --- /dev/null +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -0,0 +1,780 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/node.hpp" + +#include "obstacle_cruise_planner/polygon_utils.hpp" +#include "obstacle_cruise_planner/utils.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" +#include "tier4_autoware_utils/trajectory/tmp_conversion.hpp" + +#include + +#include +#include + +namespace +{ +VelocityLimitClearCommand createVelocityLimitClearCommandMsg(const rclcpp::Time & current_time) +{ + VelocityLimitClearCommand msg; + msg.stamp = current_time; + msg.sender = "obstacle_cruise_planner"; + msg.command = true; + return msg; +} + +// TODO(murooka) make this function common +size_t findExtendedNearestIndex( + const Trajectory traj, const geometry_msgs::msg::Pose & pose, const double max_dist, + const double max_yaw) +{ + const auto nearest_idx = + tier4_autoware_utils::findNearestIndex(traj.points, pose, max_dist, max_yaw); + if (nearest_idx) { + return nearest_idx.get(); + } + return tier4_autoware_utils::findNearestIndex(traj.points, pose.position); +} + +Trajectory trimTrajectoryFrom(const Trajectory & input, const double nearest_idx) +{ + Trajectory output{}; + + for (size_t i = nearest_idx; i < input.points.size(); ++i) { + output.points.push_back(input.points.at(i)); + } + + return output; +} + +bool isFrontObstacle( + const Trajectory & traj, const size_t ego_idx, const geometry_msgs::msg::Point & obj_pos) +{ + size_t obj_idx = tier4_autoware_utils::findNearestSegmentIndex(traj.points, obj_pos); + + const double ego_to_obj_distance = + tier4_autoware_utils::calcSignedArcLength(traj.points, ego_idx, obj_idx); + + if (obj_idx == 0 && ego_to_obj_distance < 0) { + return false; + } + + return true; +} + +TrajectoryPoint calcLinearPoint( + const TrajectoryPoint & p_from, const TrajectoryPoint & p_to, const double length) +{ + TrajectoryPoint output; + const double dx = p_to.pose.position.x - p_from.pose.position.x; + const double dy = p_to.pose.position.y - p_from.pose.position.y; + const double norm = std::hypot(dx, dy); + + output = p_to; + output.pose.position.x += length * dx / norm; + output.pose.position.y += length * dy / norm; + + return output; +} + +// TODO(murooka) replace with spline interpolation +Trajectory decimateTrajectory(const Trajectory & input, const double step_length) +{ + Trajectory output{}; + + if (input.points.empty()) { + return output; + } + + double trajectory_length_sum = 0.0; + double next_length = 0.0; + + for (int i = 0; i < static_cast(input.points.size()) - 1; ++i) { + const auto & p_front = input.points.at(i); + const auto & p_back = input.points.at(i + 1); + constexpr double epsilon = 1e-3; + + if (next_length <= trajectory_length_sum + epsilon) { + const auto p_interpolate = + calcLinearPoint(p_front, p_back, next_length - trajectory_length_sum); + output.points.push_back(p_interpolate); + next_length += step_length; + continue; + } + + trajectory_length_sum += tier4_autoware_utils::calcDistance2d(p_front, p_back); + } + + output.points.push_back(input.points.back()); + + return output; +} + +PredictedPath getHighestConfidencePredictedPath(const PredictedObject & predicted_object) +{ + const auto reliable_path = std::max_element( + predicted_object.kinematics.predicted_paths.begin(), + predicted_object.kinematics.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + return *reliable_path; +} + +bool isAngleAlignedWithTrajectory( + const Trajectory & traj, const geometry_msgs::msg::Pose & pose, const double threshold_angle) +{ + if (traj.points.empty()) { + return false; + } + + const double obj_yaw = tf2::getYaw(pose.orientation); + + const size_t nearest_idx = tier4_autoware_utils::findNearestIndex(traj.points, pose.position); + const double traj_yaw = tf2::getYaw(traj.points.at(nearest_idx).pose.orientation); + + const double diff_yaw = tier4_autoware_utils::normalizeRadian(obj_yaw - traj_yaw); + + const bool is_aligned = std::abs(diff_yaw) <= threshold_angle; + return is_aligned; +} + +double calcAlignedAdaptiveCruise( + const PredictedObject & predicted_object, const Trajectory & trajectory) +{ + const auto & object_pos = predicted_object.kinematics.initial_pose_with_covariance.pose.position; + const auto & object_vel = + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; + + const size_t object_idx = tier4_autoware_utils::findNearestIndex(trajectory.points, object_pos); + + const double object_yaw = + tf2::getYaw(predicted_object.kinematics.initial_pose_with_covariance.pose.orientation); + const double traj_yaw = tf2::getYaw(trajectory.points.at(object_idx).pose.orientation); + + return object_vel * std::cos(object_yaw - traj_yaw); +} +} // namespace + +namespace motion_planning +{ +ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options) +: Node("obstacle_cruise_planner", node_options), + self_pose_listener_(this), + in_objects_ptr_(nullptr), + lpf_acc_ptr_(nullptr), + vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) +{ + using std::placeholders::_1; + + // subscriber + trajectory_sub_ = create_subscription( + "~/input/trajectory", rclcpp::QoS{1}, + std::bind(&ObstacleCruisePlannerNode::onTrajectory, this, _1)); + smoothed_trajectory_sub_ = create_subscription( + "/planning/scenario_planning/trajectory", rclcpp::QoS{1}, + std::bind(&ObstacleCruisePlannerNode::onSmoothedTrajectory, this, _1)); + objects_sub_ = create_subscription( + "~/input/objects", rclcpp::QoS{1}, std::bind(&ObstacleCruisePlannerNode::onObjects, this, _1)); + odom_sub_ = create_subscription( + "~/input/odometry", rclcpp::QoS{1}, + std::bind(&ObstacleCruisePlannerNode::onOdometry, this, std::placeholders::_1)); + + // publisher + trajectory_pub_ = create_publisher("~/output/trajectory", 1); + vel_limit_pub_ = + create_publisher("~/output/velocity_limit", rclcpp::QoS{1}.transient_local()); + clear_vel_limit_pub_ = create_publisher( + "~/output/clear_velocity_limit", rclcpp::QoS{1}.transient_local()); + debug_calculation_time_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_cruise_wall_marker_pub_ = + create_publisher("~/debug/cruise_wall_marker", 1); + debug_stop_wall_marker_pub_ = + create_publisher("~/virtual_wall", 1); + debug_marker_pub_ = create_publisher("~/debug/marker", 1); + + // longitudinal_info + const auto longitudinal_info = [&]() { + const double max_accel = declare_parameter("normal.max_acc"); + const double min_accel = declare_parameter("normal.min_acc"); + const double max_jerk = declare_parameter("normal.max_jerk"); + const double min_jerk = declare_parameter("normal.min_jerk"); + + const double min_strong_accel = declare_parameter("common.min_strong_accel"); + const double min_ego_accel_for_rss = declare_parameter("common.min_ego_accel_for_rss"); + const double min_object_accel_for_rss = + declare_parameter("common.min_object_accel_for_rss"); + const double idling_time = declare_parameter("common.idling_time"); + const double safe_distance_margin = declare_parameter("common.safe_distance_margin"); + + return LongitudinalInfo( + max_accel, min_accel, max_jerk, min_jerk, min_strong_accel, idling_time, + min_ego_accel_for_rss, min_object_accel_for_rss, safe_distance_margin); + }(); + + const bool is_showing_debug_info_ = declare_parameter("common.is_showing_debug_info"); + + // low pass filter for ego acceleration + const double lpf_gain_for_accel = declare_parameter("common.lpf_gain_for_accel"); + lpf_acc_ptr_ = std::make_shared(0.0, lpf_gain_for_accel); + + { // Obstacle filtering parameters + obstacle_filtering_param_.rough_detection_area_expand_width = + declare_parameter("obstacle_filtering.rough_detection_area_expand_width"); + obstacle_filtering_param_.detection_area_expand_width = + declare_parameter("obstacle_filtering.detection_area_expand_width"); + obstacle_filtering_param_.decimate_trajectory_step_length = + declare_parameter("obstacle_filtering.decimate_trajectory_step_length"); + obstacle_filtering_param_.crossing_obstacle_velocity_threshold = + declare_parameter("obstacle_filtering.crossing_obstacle_velocity_threshold"); + obstacle_filtering_param_.collision_time_margin = + declare_parameter("obstacle_filtering.collision_time_margin"); + obstacle_filtering_param_.ego_obstacle_overlap_time_threshold = + declare_parameter("obstacle_filtering.ego_obstacle_overlap_time_threshold"); + obstacle_filtering_param_.max_prediction_time_for_collision_check = + declare_parameter("obstacle_filtering.max_prediction_time_for_collision_check"); + obstacle_filtering_param_.crossing_obstacle_traj_angle_threshold = + declare_parameter("obstacle_filtering.crossing_obstacle_traj_angle_threshold"); + + { + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.unknown")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::UNKNOWN); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.car")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::CAR); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.truck")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::TRUCK); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.bus")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::BUS); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.trailer")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::TRAILER); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.motorcycle")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::MOTORCYCLE); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.bicycle")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::BICYCLE); + } + if (declare_parameter("obstacle_filtering.ignored_outside_obstacle_type.pedestrian")) { + obstacle_filtering_param_.ignored_outside_obstacle_types.push_back( + ObjectClassification::PEDESTRIAN); + } + } + } + + { // planning algorithm + const std::string planning_algorithm_param = + declare_parameter("common.planning_algorithm"); + planning_algorithm_ = getPlanningAlgorithmType(planning_algorithm_param); + + if (planning_algorithm_ == PlanningAlgorithm::OPTIMIZATION_BASE) { + planner_ptr_ = + std::make_unique(*this, longitudinal_info, vehicle_info_); + } else if (planning_algorithm_ == PlanningAlgorithm::PID_BASE) { + planner_ptr_ = std::make_unique(*this, longitudinal_info, vehicle_info_); + } else { + std::logic_error("Designated algorithm is not supported."); + } + + min_behavior_stop_margin_ = declare_parameter("common.min_behavior_stop_margin"); + nearest_dist_deviation_threshold_ = + declare_parameter("common.nearest_dist_deviation_threshold"); + nearest_yaw_deviation_threshold_ = + declare_parameter("common.nearest_yaw_deviation_threshold"); + planner_ptr_->setParams( + is_showing_debug_info_, min_behavior_stop_margin_, nearest_dist_deviation_threshold_, + nearest_yaw_deviation_threshold_); + } + + // wait for first self pose + self_pose_listener_.waitForFirstPose(); + + // set parameter callback + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&ObstacleCruisePlannerNode::onParam, this, std::placeholders::_1)); +} + +ObstacleCruisePlannerNode::PlanningAlgorithm ObstacleCruisePlannerNode::getPlanningAlgorithmType( + const std::string & param) const +{ + if (param == "pid_base") { + return PlanningAlgorithm::PID_BASE; + } else if (param == "optimization_base") { + return PlanningAlgorithm::OPTIMIZATION_BASE; + } + return PlanningAlgorithm::INVALID; +} + +rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( + const std::vector & parameters) +{ + planner_ptr_->updateCommonParam(parameters); + planner_ptr_->updateParam(parameters); + + tier4_autoware_utils::updateParam( + parameters, "common.is_showing_debug_info", is_showing_debug_info_); + planner_ptr_->setParams( + is_showing_debug_info_, min_behavior_stop_margin_, nearest_dist_deviation_threshold_, + nearest_yaw_deviation_threshold_); + + // obstacle_filtering + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.rough_detection_area_expand_width", + obstacle_filtering_param_.rough_detection_area_expand_width); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.detection_area_expand_width", + obstacle_filtering_param_.detection_area_expand_width); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.decimate_trajectory_step_length", + obstacle_filtering_param_.decimate_trajectory_step_length); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.crossing_obstacle_velocity_threshold", + obstacle_filtering_param_.crossing_obstacle_velocity_threshold); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.collision_time_margin", + obstacle_filtering_param_.collision_time_margin); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.ego_obstacle_overlap_time_threshold", + obstacle_filtering_param_.ego_obstacle_overlap_time_threshold); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.max_prediction_time_for_collision_check", + obstacle_filtering_param_.max_prediction_time_for_collision_check); + tier4_autoware_utils::updateParam( + parameters, "obstacle_filtering.crossing_obstacle_traj_angle_threshold", + obstacle_filtering_param_.crossing_obstacle_traj_angle_threshold); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} + +void ObstacleCruisePlannerNode::onObjects(const PredictedObjects::ConstSharedPtr msg) +{ + in_objects_ptr_ = msg; +} + +void ObstacleCruisePlannerNode::onOdometry(const Odometry::ConstSharedPtr msg) +{ + if (current_twist_ptr_) { + prev_twist_ptr_ = current_twist_ptr_; + } + + current_twist_ptr_ = std::make_unique(); + current_twist_ptr_->header = msg->header; + current_twist_ptr_->twist = msg->twist.twist; +} + +void ObstacleCruisePlannerNode::onSmoothedTrajectory(const Trajectory::ConstSharedPtr msg) +{ + planner_ptr_->setSmoothedTrajectory(msg); +} + +void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg) +{ + const auto current_pose_ptr = self_pose_listener_.getCurrentPose(); + + // check if subscribed variables are ready + if ( + msg->points.empty() || !current_twist_ptr_ || !prev_twist_ptr_ || !in_objects_ptr_ || + !current_pose_ptr) { + return; + } + + stop_watch_.tic(__func__); + + // create algorithmic data + DebugData debug_data; + const auto planner_data = createPlannerData(*msg, current_pose_ptr->pose, debug_data); + + // generate Trajectory + boost::optional vel_limit; + const auto output_traj = planner_ptr_->generateTrajectory(planner_data, vel_limit, debug_data); + + // publisher external velocity limit if required + publishVelocityLimit(vel_limit); + + // Publish trajectory + trajectory_pub_->publish(output_traj); + + // publish debug data + publishDebugData(debug_data); + + // publish and print calculation time + const double calculation_time = stop_watch_.toc(__func__); + publishCalculationTime(calculation_time); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner"), is_showing_debug_info_, "%s := %f [ms]", __func__, + calculation_time); +} + +ObstacleCruisePlannerData ObstacleCruisePlannerNode::createPlannerData( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & current_pose, + DebugData & debug_data) +{ + stop_watch_.tic(__func__); + + const double current_vel = current_twist_ptr_->twist.linear.x; + const double current_accel = calcCurrentAccel(); + + // create planner_data + ObstacleCruisePlannerData planner_data; + planner_data.current_time = now(); + planner_data.traj = trajectory; + planner_data.current_pose = current_pose; + planner_data.current_vel = current_vel; + planner_data.current_acc = current_accel; + planner_data.target_obstacles = + filterObstacles(*in_objects_ptr_, trajectory, current_pose, current_vel, debug_data); + + // print calculation time + const double calculation_time = stop_watch_.toc(__func__); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner"), is_showing_debug_info_, " %s := %f [ms]", + __func__, calculation_time); + + return planner_data; +} + +double ObstacleCruisePlannerNode::calcCurrentAccel() const +{ + const double diff_vel = current_twist_ptr_->twist.linear.x - prev_twist_ptr_->twist.linear.x; + const double diff_time = std::max( + (rclcpp::Time(current_twist_ptr_->header.stamp) - rclcpp::Time(prev_twist_ptr_->header.stamp)) + .seconds(), + 1e-03); + + const double accel = diff_vel / diff_time; + + return lpf_acc_ptr_->filter(accel); +} + +std::vector ObstacleCruisePlannerNode::filterObstacles( + const PredictedObjects & predicted_objects, const Trajectory & traj, + const geometry_msgs::msg::Pose & current_pose, const double current_vel, DebugData & debug_data) +{ + const auto time_stamp = rclcpp::Time(predicted_objects.header.stamp); + + const size_t ego_idx = findExtendedNearestIndex( + traj, current_pose, nearest_dist_deviation_threshold_, nearest_yaw_deviation_threshold_); + + // calculate decimated trajectory + const auto trimmed_traj = trimTrajectoryFrom(traj, ego_idx); + const auto decimated_traj = + decimateTrajectory(trimmed_traj, obstacle_filtering_param_.decimate_trajectory_step_length); + if (decimated_traj.points.size() < 2) { + return {}; + } + + // calculate decimated trajectory polygons + const auto decimated_traj_polygons = polygon_utils::createOneStepPolygons( + decimated_traj, vehicle_info_, obstacle_filtering_param_.detection_area_expand_width); + debug_data.detection_polygons = decimated_traj_polygons; + + std::vector target_obstacles; + for (const auto & predicted_object : predicted_objects.objects) { + // filter object whose label is not cruised or stopped + const bool is_target_obstacle = + planner_ptr_->isStopObstacle(predicted_object.classification.front().label) || + planner_ptr_->isCruiseObstacle(predicted_object.classification.front().label); + if (!is_target_obstacle) { + RCLCPP_INFO_EXPRESSION( + get_logger(), is_showing_debug_info_, "Ignore obstacles since its label is not target."); + continue; + } + + const auto & object_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; + const auto & object_velocity = + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; + + const bool is_front_obstacle = isFrontObstacle(traj, ego_idx, object_pose.position); + if (!is_front_obstacle) { + RCLCPP_INFO_EXPRESSION( + get_logger(), is_showing_debug_info_, "Ignore obstacles since its not front obstacle."); + continue; + } + + // rough detection area filtering without polygons + const double dist_from_obstacle_to_traj = [&]() { + return tier4_autoware_utils::calcLateralOffset(decimated_traj.points, object_pose.position); + }(); + if (dist_from_obstacle_to_traj > obstacle_filtering_param_.rough_detection_area_expand_width) { + RCLCPP_INFO_EXPRESSION( + get_logger(), is_showing_debug_info_, + "Ignore obstacles since it is far from the trajectory."); + continue; + } + + // calculate collision points + const auto obstacle_polygon = + polygon_utils::convertObstacleToPolygon(object_pose, predicted_object.shape); + std::vector collision_points; + const auto first_within_idx = polygon_utils::getFirstCollisionIndex( + decimated_traj_polygons, obstacle_polygon, collision_points); + + // precise detection area filtering with polygons + geometry_msgs::msg::Point nearest_collision_point; + if (first_within_idx) { // obstacles inside the trajectory + // calculate nearest collision point + nearest_collision_point = + calcNearestCollisionPoint(first_within_idx.get(), collision_points, decimated_traj); + debug_data.collision_points.push_back(nearest_collision_point); + + const bool is_angle_aligned = isAngleAlignedWithTrajectory( + decimated_traj, object_pose, + obstacle_filtering_param_.crossing_obstacle_traj_angle_threshold); + const double has_high_speed = + std::abs(object_velocity) > obstacle_filtering_param_.crossing_obstacle_velocity_threshold; + + // ignore running vehicle crossing the ego trajectory with high speed with some condition + if (!is_angle_aligned && has_high_speed) { + const double collision_time_margin = calcCollisionTimeMargin( + current_pose, current_vel, nearest_collision_point, predicted_object, + first_within_idx.get(), decimated_traj, decimated_traj_polygons); + if (collision_time_margin > obstacle_filtering_param_.collision_time_margin) { + // Ignore condition 1 + // Ignore vehicle obstacles inside the trajectory, which is crossing the trajectory with + // high speed and does not collide with ego in a certain time. + RCLCPP_INFO_EXPRESSION( + get_logger(), is_showing_debug_info_, + "Ignore inside obstacles since it will not collide with the ego."); + + debug_data.intentionally_ignored_obstacles.push_back(predicted_object); + continue; + } + } + } else { // obstacles outside the trajectory + const auto & types = obstacle_filtering_param_.ignored_outside_obstacle_types; + if ( + std::find(types.begin(), types.end(), predicted_object.classification.front().label) != + types.end()) { + continue; + } + + const auto predicted_path_with_highest_confidence = + getHighestConfidencePredictedPath(predicted_object); + + const bool will_collide = polygon_utils::willCollideWithSurroundObstacle( + decimated_traj, decimated_traj_polygons, predicted_path_with_highest_confidence, + predicted_object.shape, obstacle_filtering_param_.rough_detection_area_expand_width, + obstacle_filtering_param_.ego_obstacle_overlap_time_threshold, + obstacle_filtering_param_.max_prediction_time_for_collision_check); + + // TODO(murooka) think later + nearest_collision_point = object_pose.position; + + if (!will_collide) { + // Ignore condition 2 + // Ignore vehicle obstacles outside the trajectory, whose predicted path + // overlaps the ego trajectory in a certain time. + RCLCPP_INFO_EXPRESSION( + get_logger(), is_showing_debug_info_, + "Ignore outside obstacles since it will not collide with the ego."); + + debug_data.intentionally_ignored_obstacles.push_back(predicted_object); + continue; + } + } + + // convert to obstacle type + const double trajectory_aligned_adaptive_cruise = + calcAlignedAdaptiveCruise(predicted_object, traj); + const auto target_obstacle = TargetObstacle( + time_stamp, predicted_object, trajectory_aligned_adaptive_cruise, nearest_collision_point); + target_obstacles.push_back(target_obstacle); + } + + return target_obstacles; +} + +geometry_msgs::msg::Point ObstacleCruisePlannerNode::calcNearestCollisionPoint( + const size_t & first_within_idx, const std::vector & collision_points, + const Trajectory & decimated_traj) +{ + std::array segment_points; + if (first_within_idx == 0) { + const auto & traj_front_pose = decimated_traj.points.at(0).pose; + segment_points.at(0) = traj_front_pose.position; + + const auto front_pos = tier4_autoware_utils::calcOffsetPose( + traj_front_pose, vehicle_info_.max_longitudinal_offset_m, 0.0, 0.0) + .position; + segment_points.at(1) = front_pos; + } else { + const size_t seg_idx = first_within_idx - 1; + segment_points.at(0) = decimated_traj.points.at(seg_idx).pose.position; + segment_points.at(1) = decimated_traj.points.at(seg_idx + 1).pose.position; + } + + size_t min_idx = 0; + double min_dist = std::numeric_limits::max(); + for (size_t cp_idx = 0; cp_idx < collision_points.size(); ++cp_idx) { + const auto & collision_point = collision_points.at(cp_idx); + const double dist = + tier4_autoware_utils::calcLongitudinalOffsetToSegment(segment_points, 0, collision_point); + if (dist < min_dist) { + min_dist = dist; + min_idx = cp_idx; + } + } + + return collision_points.at(min_idx); +} + +double ObstacleCruisePlannerNode::calcCollisionTimeMargin( + const geometry_msgs::msg::Pose & current_pose, const double current_vel, + const geometry_msgs::msg::Point & nearest_collision_point, + const PredictedObject & predicted_object, const size_t first_within_idx, + const Trajectory & decimated_traj, + const std::vector & decimated_traj_polygons) +{ + const auto & object_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; + const auto & object_velocity = + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; + const auto predicted_path_with_highest_confidence = + getHighestConfidencePredictedPath(predicted_object); + + const double time_to_collision = [&]() { + const double dist_from_ego_to_obstacle = + tier4_autoware_utils::calcSignedArcLength( + decimated_traj.points, current_pose.position, nearest_collision_point) - + vehicle_info_.max_longitudinal_offset_m; + return dist_from_ego_to_obstacle / std::max(1e-6, current_vel); + }(); + + const double time_to_obstacle_getting_out = [&]() { + const auto obstacle_getting_out_idx = polygon_utils::getFirstNonCollisionIndex( + decimated_traj_polygons, predicted_path_with_highest_confidence, predicted_object.shape, + first_within_idx); + if (!obstacle_getting_out_idx) { + return std::numeric_limits::max(); + } + + const double dist_to_obstacle_getting_out = tier4_autoware_utils::calcSignedArcLength( + decimated_traj.points, object_pose.position, obstacle_getting_out_idx.get()); + + return dist_to_obstacle_getting_out / object_velocity; + }(); + + return time_to_collision - time_to_obstacle_getting_out; +} + +void ObstacleCruisePlannerNode::publishVelocityLimit( + const boost::optional & vel_limit) +{ + if (vel_limit) { + vel_limit_pub_->publish(vel_limit.get()); + need_to_clear_vel_limit_ = true; + } else { + if (need_to_clear_vel_limit_) { + const auto clear_vel_limit_msg = createVelocityLimitClearCommandMsg(now()); + clear_vel_limit_pub_->publish(clear_vel_limit_msg); + need_to_clear_vel_limit_ = false; + } + } +} + +void ObstacleCruisePlannerNode::publishDebugData(const DebugData & debug_data) const +{ + stop_watch_.tic(__func__); + + visualization_msgs::msg::MarkerArray debug_marker; + const auto current_time = now(); + + // obstacles to cruise + for (size_t i = 0; i < debug_data.obstacles_to_cruise.size(); ++i) { + const auto marker = obstacle_cruise_utils::getObjectMarker( + debug_data.obstacles_to_cruise.at(i).pose, i, "obstacles_to_cruise", 0.7, 0.7, 0.0); + debug_marker.markers.push_back(marker); + } + + // obstacles to stop + for (size_t i = 0; i < debug_data.obstacles_to_stop.size(); ++i) { + const auto marker = obstacle_cruise_utils::getObjectMarker( + debug_data.obstacles_to_stop.at(i).pose, i, "obstacles_to_stop", 1.0, 0.0, 0.0); + debug_marker.markers.push_back(marker); + } + + // intentionally ignored obstacles to cruise or stop + for (size_t i = 0; i < debug_data.intentionally_ignored_obstacles.size(); ++i) { + const auto marker = obstacle_cruise_utils::getObjectMarker( + debug_data.intentionally_ignored_obstacles.at(i).kinematics.initial_pose_with_covariance.pose, + i, "intentionally_ignored_obstacles", 0.0, 1.0, 0.0); + debug_marker.markers.push_back(marker); + } + + { // footprint polygons + auto marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "detection_polygons", 0, visualization_msgs::msg::Marker::LINE_LIST, + tier4_autoware_utils::createMarkerScale(0.01, 0.0, 0.0), + tier4_autoware_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999)); + + for (const auto & detection_polygon : debug_data.detection_polygons) { + for (size_t dp_idx = 0; dp_idx < detection_polygon.outer().size(); ++dp_idx) { + const auto & current_point = detection_polygon.outer().at(dp_idx); + const auto & next_point = + detection_polygon.outer().at((dp_idx + 1) % detection_polygon.outer().size()); + + marker.points.push_back( + tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), 0.0)); + marker.points.push_back( + tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), 0.0)); + } + } + debug_marker.markers.push_back(marker); + } + + { // collision points + for (size_t i = 0; i < debug_data.collision_points.size(); ++i) { + auto marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "collision_points", i, visualization_msgs::msg::Marker::SPHERE, + tier4_autoware_utils::createMarkerScale(0.25, 0.25, 0.25), + tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + marker.pose.position = debug_data.collision_points.at(i); + debug_marker.markers.push_back(marker); + } + } + + debug_marker_pub_->publish(debug_marker); + + // wall for cruise and stop + debug_cruise_wall_marker_pub_->publish(debug_data.cruise_wall_marker); + debug_stop_wall_marker_pub_->publish(debug_data.stop_wall_marker); + + // print calculation time + const double calculation_time = stop_watch_.toc(__func__); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner"), is_showing_debug_info_, " %s := %f [ms]", + __func__, calculation_time); +} + +void ObstacleCruisePlannerNode::publishCalculationTime(const double calculation_time) const +{ + Float32Stamped calculation_time_msg; + calculation_time_msg.stamp = now(); + calculation_time_msg.data = calculation_time; + debug_calculation_time_pub_->publish(calculation_time_msg); +} +} // namespace motion_planning +#include +RCLCPP_COMPONENTS_REGISTER_NODE(motion_planning::ObstacleCruisePlannerNode) diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/box2d.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/box2d.cpp new file mode 100644 index 0000000000000..6fc5900e7ccab --- /dev/null +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/box2d.cpp @@ -0,0 +1,101 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/optimization_based_planner/box2d.hpp" + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include + +Box2d::Box2d(const geometry_msgs::msg::Pose & center_pose, const double length, const double width) +: center_(center_pose.position), + length_(length), + width_(width), + half_length_(length / 2.0), + half_width_(width / 2.0) +{ + max_x_ = std::numeric_limits::min(); + max_y_ = std::numeric_limits::min(); + min_x_ = std::numeric_limits::max(); + min_y_ = std::numeric_limits::max(); + heading_ = tf2::getYaw(center_pose.orientation); + cos_heading_ = std::cos(heading_); + sin_heading_ = std::sin(heading_); + initCorners(); +} + +void Box2d::initCorners() +{ + const double dx1 = cos_heading_ * half_length_; + const double dy1 = sin_heading_ * half_length_; + const double dx2 = sin_heading_ * half_width_; + const double dy2 = -cos_heading_ * half_width_; + + const auto p1 = + tier4_autoware_utils::createPoint(center_.x + dx1 + dx2, center_.y + dy1 + dy2, center_.z); + const auto p2 = + tier4_autoware_utils::createPoint(center_.x + dx1 - dx2, center_.y + dy1 - dy2, center_.z); + const auto p3 = + tier4_autoware_utils::createPoint(center_.x - dx1 - dx2, center_.y - dy1 - dy2, center_.z); + const auto p4 = + tier4_autoware_utils::createPoint(center_.x - dx1 + dx2, center_.y - dy1 + dy2, center_.z); + corners_.clear(); + corners_.resize(4); + corners_.at(0) = p1; + corners_.at(1) = p2; + corners_.at(2) = p3; + corners_.at(3) = p4; + + for (auto & corner : corners_) { + max_x_ = std::fmax(corner.x, max_x_); + min_x_ = std::fmin(corner.x, min_x_); + max_y_ = std::fmax(corner.y, max_y_); + min_y_ = std::fmin(corner.y, min_y_); + } +} + +bool Box2d::hasOverlap(const Box2d & box) const +{ + if ( + box.getMaxX() < getMinX() || box.getMinX() > getMaxX() || box.getMaxY() < getMinY() || + box.getMinY() > getMaxY()) { + return false; + } + + const double shift_x = box.getCenterX() - center_.x; + const double shift_y = box.getCenterY() - center_.y; + + const double dx1 = cos_heading_ * half_length_; + const double dy1 = sin_heading_ * half_length_; + const double dx2 = sin_heading_ * half_width_; + const double dy2 = -cos_heading_ * half_width_; + const double dx3 = box.getCosHeading() * box.getHalfLength(); + const double dy3 = box.getSinHeading() * box.getHalfLength(); + const double dx4 = box.getSinHeading() * box.getHalfWidth(); + const double dy4 = -box.getCosHeading() * box.getHalfWidth(); + + return std::abs(shift_x * cos_heading_ + shift_y * sin_heading_) <= + std::abs(dx3 * cos_heading_ + dy3 * sin_heading_) + + std::abs(dx4 * cos_heading_ + dy4 * sin_heading_) + half_length_ && + std::abs(shift_x * sin_heading_ - shift_y * cos_heading_) <= + std::abs(dx3 * sin_heading_ - dy3 * cos_heading_) + + std::abs(dx4 * sin_heading_ - dy4 * cos_heading_) + half_width_ && + std::abs(shift_x * box.getCosHeading() + shift_y * box.getSinHeading()) <= + std::abs(dx1 * box.getCosHeading() + dy1 * box.getSinHeading()) + + std::abs(dx2 * box.getCosHeading() + dy2 * box.getSinHeading()) + + box.getHalfLength() && + std::abs(shift_x * box.getSinHeading() - shift_y * box.getCosHeading()) <= + std::abs(dx1 * box.getSinHeading() - dy1 * box.getCosHeading()) + + std::abs(dx2 * box.getSinHeading() - dy2 * box.getCosHeading()) + box.getHalfWidth(); +} diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp new file mode 100644 index 0000000000000..08806fd0dc43a --- /dev/null +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp @@ -0,0 +1,1370 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp" + +#include "interpolation/linear_interpolation.hpp" +#include "interpolation/spline_interpolation.hpp" +#include "obstacle_cruise_planner/optimization_based_planner/resample.hpp" +#include "obstacle_cruise_planner/utils.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +constexpr double ZERO_VEL_THRESHOLD = 0.01; +constexpr double CLOSE_S_DIST_THRESHOLD = 1e-3; + +// TODO(shimizu) Is is ok to use planner_data.current_time instead of get_clock()->now()? +namespace +{ +[[maybe_unused]] std::string toHexString(const unique_identifier_msgs::msg::UUID & id) +{ + std::stringstream ss; + for (auto i = 0; i < 16; ++i) { + ss << std::hex << std::setfill('0') << std::setw(2) << +id.uuid[i]; + } + return ss.str(); +} + +inline void convertEulerAngleToMonotonic(std::vector & a) +{ + for (unsigned int i = 1; i < a.size(); ++i) { + const double da = a[i] - a[i - 1]; + a[i] = a[i - 1] + tier4_autoware_utils::normalizeRadian(da); + } +} + +inline tf2::Vector3 getTransVector3( + const geometry_msgs::msg::Pose & from, const geometry_msgs::msg::Pose & to) +{ + double dx = to.position.x - from.position.x; + double dy = to.position.y - from.position.y; + double dz = to.position.z - from.position.z; + return tf2::Vector3(dx, dy, dz); +} + +// TODO(shimizu) consider dist/yaw threshold for nearest index +boost::optional calcForwardPose( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const geometry_msgs::msg::Point & point, const double target_length) +{ + if (traj.points.empty()) { + return {}; + } + + const size_t nearest_idx = tier4_autoware_utils::findNearestIndex(traj.points, point); + + size_t search_idx = nearest_idx; + double length_to_search_idx = 0.0; + for (; search_idx < traj.points.size(); ++search_idx) { + length_to_search_idx = + tier4_autoware_utils::calcSignedArcLength(traj.points, nearest_idx, search_idx); + if (length_to_search_idx > target_length) { + break; + } else if (search_idx == traj.points.size() - 1) { + return {}; + } + } + + if (search_idx == 0 && !traj.points.empty()) { + return traj.points.at(0).pose; + } + + const auto & pre_pose = traj.points.at(search_idx - 1).pose; + const auto & next_pose = traj.points.at(search_idx).pose; + + geometry_msgs::msg::Pose target_pose; + + // lerp position + const double seg_length = + tier4_autoware_utils::calcDistance2d(pre_pose.position, next_pose.position); + const double lerp_ratio = (length_to_search_idx - target_length) / seg_length; + target_pose.position.x = + pre_pose.position.x + (next_pose.position.x - pre_pose.position.x) * lerp_ratio; + target_pose.position.y = + pre_pose.position.y + (next_pose.position.y - pre_pose.position.y) * lerp_ratio; + target_pose.position.z = + pre_pose.position.z + (next_pose.position.z - pre_pose.position.z) * lerp_ratio; + + // lerp orientation + const double pre_yaw = tf2::getYaw(pre_pose.orientation); + const double next_yaw = tf2::getYaw(next_pose.orientation); + target_pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(pre_yaw + (next_yaw - pre_yaw) * lerp_ratio); + + return target_pose; +} +} // namespace + +OptimizationBasedPlanner::OptimizationBasedPlanner( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info) +: PlannerInterface(node, longitudinal_info, vehicle_info) +{ + // parameter + resampling_s_interval_ = + node.declare_parameter("optimization_based_planner.resampling_s_interval"); + max_trajectory_length_ = + node.declare_parameter("optimization_based_planner.max_trajectory_length"); + dense_resampling_time_interval_ = + node.declare_parameter("optimization_based_planner.dense_resampling_time_interval"); + sparse_resampling_time_interval_ = + node.declare_parameter("optimization_based_planner.sparse_resampling_time_interval"); + dense_time_horizon_ = + node.declare_parameter("optimization_based_planner.dense_time_horizon"); + max_time_horizon_ = node.declare_parameter("optimization_based_planner.max_time_horizon"); + limit_min_accel_ = node.declare_parameter("optimization_based_planner.limit_min_accel"); + + delta_yaw_threshold_of_nearest_index_ = + tier4_autoware_utils::deg2rad(node.declare_parameter( + "optimization_based_planner.delta_yaw_threshold_of_nearest_index")); + delta_yaw_threshold_of_object_and_ego_ = + tier4_autoware_utils::deg2rad(node.declare_parameter( + "optimization_based_planner.delta_yaw_threshold_of_object_and_ego")); + object_zero_velocity_threshold_ = + node.declare_parameter("optimization_based_planner.object_zero_velocity_threshold"); + object_low_velocity_threshold_ = + node.declare_parameter("optimization_based_planner.object_low_velocity_threshold"); + external_velocity_limit_ = + node.declare_parameter("optimization_based_planner.external_velocity_limit"); + collision_time_threshold_ = + node.declare_parameter("optimization_based_planner.collision_time_threshold"); + safe_distance_margin_ = + node.declare_parameter("optimization_based_planner.safe_distance_margin"); + t_dangerous_ = node.declare_parameter("optimization_based_planner.t_dangerous"); + velocity_margin_ = node.declare_parameter("optimization_based_planner.velocity_margin"); + enable_adaptive_cruise_ = + node.declare_parameter("optimization_based_planner.enable_adaptive_cruise"); + use_object_acceleration_ = + node.declare_parameter("optimization_based_planner.use_object_acceleration"); + + replan_vel_deviation_ = + node.declare_parameter("optimization_based_planner.replan_vel_deviation"); + engage_velocity_ = node.declare_parameter("optimization_based_planner.engage_velocity"); + engage_acceleration_ = + node.declare_parameter("optimization_based_planner.engage_acceleration"); + engage_exit_ratio_ = + node.declare_parameter("optimization_based_planner.engage_exit_ratio"); + stop_dist_to_prohibit_engage_ = + node.declare_parameter("optimization_based_planner.stop_dist_to_prohibit_engage"); + + const double max_s_weight = + node.declare_parameter("optimization_based_planner.max_s_weight"); + const double max_v_weight = + node.declare_parameter("optimization_based_planner.max_v_weight"); + const double over_s_safety_weight = + node.declare_parameter("optimization_based_planner.over_s_safety_weight"); + const double over_s_ideal_weight = + node.declare_parameter("optimization_based_planner.over_s_ideal_weight"); + const double over_v_weight = + node.declare_parameter("optimization_based_planner.over_v_weight"); + const double over_a_weight = + node.declare_parameter("optimization_based_planner.over_a_weight"); + const double over_j_weight = + node.declare_parameter("optimization_based_planner.over_j_weight"); + + // velocity optimizer + velocity_optimizer_ptr_ = std::make_shared( + max_s_weight, max_v_weight, over_s_safety_weight, over_s_ideal_weight, over_v_weight, + over_a_weight, over_j_weight); + + // publisher + optimized_sv_pub_ = node.create_publisher("~/optimized_sv_trajectory", 1); + optimized_st_graph_pub_ = node.create_publisher("~/optimized_st_graph", 1); + boundary_pub_ = node.create_publisher("~/boundary", 1); + distance_to_closest_obj_pub_ = + node.create_publisher("~/distance_to_closest_obj", 1); + debug_calculation_time_ = node.create_publisher("~/calculation_time", 1); + debug_wall_marker_pub_ = + node.create_publisher("~/debug/wall_marker", 1); +} + +Trajectory OptimizationBasedPlanner::generateTrajectory( + const ObstacleCruisePlannerData & planner_data, + [[maybe_unused]] boost::optional & vel_limit, + [[maybe_unused]] DebugData & debug_data) +{ + // Create Time Vector defined by resampling time interval + const std::vector time_vec = createTimeVector(); + if (time_vec.size() < 2) { + RCLCPP_ERROR( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Resolution size is not enough"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Get the nearest point on the trajectory + const auto closest_idx = tier4_autoware_utils::findNearestIndex( + planner_data.traj.points, planner_data.current_pose, delta_yaw_threshold_of_nearest_index_); + if (!closest_idx) { // Check validity of the closest index + RCLCPP_ERROR( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Closest Index is Invalid"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Transform original trajectory to TrajectoryData + const auto base_traj_data = getTrajectoryData(planner_data.traj, planner_data.current_pose); + if (base_traj_data.traj.points.size() < 2) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "The number of points on the trajectory data is too small"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Get Closest Stop Point for static obstacles + double closest_stop_dist = getClosestStopDistance(planner_data, base_traj_data, time_vec); + + // Compute maximum velocity + double v_max = 0.0; + for (const auto & point : planner_data.traj.points) { + v_max = std::max(v_max, static_cast(point.longitudinal_velocity_mps)); + } + + // Get Current Velocity + double v0; + double a0; + std::tie(v0, a0) = calcInitialMotion( + planner_data.current_vel, planner_data.traj, *closest_idx, prev_output_, closest_stop_dist); + a0 = std::min(longitudinal_info_.max_accel, std::max(a0, longitudinal_info_.min_accel)); + + // If closest distance is too close, return zero velocity + if (closest_stop_dist < 0.01) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Closest Stop Point is too close"); + + auto output_traj = planner_data.traj; + output_traj.points.at(*closest_idx).longitudinal_velocity_mps = v0; + for (size_t i = *closest_idx + 1; i < output_traj.points.size(); ++i) { + output_traj.points.at(i).longitudinal_velocity_mps = 0.0; + } + prev_output_ = output_traj; + return output_traj; + } + + // Check trajectory size + if (planner_data.traj.points.size() - *closest_idx <= 2) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "The number of points on the trajectory is too small"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Check if reached goal + if (checkHasReachedGoal(planner_data.traj, *closest_idx, v0) || !enable_adaptive_cruise_) { + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Resample base trajectory data by time + const auto resampled_traj_data = resampleTrajectoryData( + base_traj_data, resampling_s_interval_, max_trajectory_length_, closest_stop_dist); + if (resampled_traj_data.traj.points.size() < 2) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "The number of points on the resampled trajectory data is too small"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Get S Boundaries from the obstacle + const auto s_boundaries = getSBoundaries(planner_data, resampled_traj_data, time_vec); + if (!s_boundaries) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "No Dangerous Objects around the ego vehicle"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Optimization + VelocityOptimizer::OptimizationData data; + data.time_vec = time_vec; + data.s0 = resampled_traj_data.s.front(); + data.a0 = a0; + data.v_max = v_max; + data.a_max = longitudinal_info_.max_accel; + data.a_min = longitudinal_info_.min_accel; + data.limit_a_min = limit_min_accel_; + data.j_max = longitudinal_info_.max_jerk; + data.j_min = longitudinal_info_.min_jerk; + data.t_dangerous = t_dangerous_; + data.idling_time = longitudinal_info_.idling_time; + data.v_margin = velocity_margin_; + data.s_boundary = *s_boundaries; + data.v0 = v0; + RCLCPP_DEBUG(rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), "v0 %f", v0); + + stop_watch_.tic(); + + const auto optimized_result = velocity_optimizer_ptr_->optimize(data); + + Float32Stamped calculation_time_data{}; + calculation_time_data.stamp = planner_data.current_time; + calculation_time_data.data = stop_watch_.toc(); + debug_calculation_time_->publish(calculation_time_data); + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Optimization Time; %f[ms]", calculation_time_data.data); + + // Publish Debug trajectories + publishDebugTrajectory( + planner_data.current_time, planner_data.traj, *closest_idx, time_vec, *s_boundaries, + optimized_result); + + // Transformation from t to s + const auto processed_result = processOptimizedResult(data.v0, optimized_result); + if (!processed_result) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Processed Result is empty"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + const auto & opt_position = processed_result->s; + const auto & opt_velocity = processed_result->v; + + // Check Size + if (opt_position.size() == 1 && opt_velocity.front() < ZERO_VEL_THRESHOLD) { + auto output = planner_data.traj; + output.points.at(*closest_idx).longitudinal_velocity_mps = data.v0; + for (size_t i = *closest_idx + 1; i < output.points.size(); ++i) { + output.points.at(i).longitudinal_velocity_mps = 0.0; + } + prev_output_ = output; + return output; + } else if (opt_position.size() == 1) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Optimized Trajectory is too small"); + prev_output_ = planner_data.traj; + return planner_data.traj; + } + + // Get Zero Velocity Position + for (size_t i = 0; i < opt_velocity.size(); ++i) { + if (opt_velocity.at(i) < ZERO_VEL_THRESHOLD) { + const double zero_vel_s = opt_position.at(i); + closest_stop_dist = std::min(closest_stop_dist, zero_vel_s); + break; + } + } + + size_t break_id = base_traj_data.s.size(); + bool has_insert_stop_point = false; + std::vector resampled_opt_position = {base_traj_data.s.front()}; + for (size_t i = 1; i < base_traj_data.s.size(); ++i) { + const double query_s = base_traj_data.s.at(i); + if ( + !has_insert_stop_point && query_s > closest_stop_dist && + closest_stop_dist < opt_position.back()) { + const double prev_query_s = resampled_opt_position.back(); + if (closest_stop_dist - prev_query_s > CLOSE_S_DIST_THRESHOLD) { + resampled_opt_position.push_back(closest_stop_dist); + } else { + resampled_opt_position.back() = closest_stop_dist; + } + has_insert_stop_point = true; + } + + if (query_s > opt_position.back()) { + break_id = i; + break; + } + + const double prev_query_s = resampled_opt_position.back(); + if (query_s - prev_query_s > 1e-3) { + resampled_opt_position.push_back(query_s); + } + } + const auto resampled_opt_velocity = + interpolation::lerp(opt_position, opt_velocity, resampled_opt_position); + + // Push positions after the last position of the opt position + for (size_t i = break_id; i < base_traj_data.s.size(); ++i) { + const double query_s = base_traj_data.s.at(i); + const double prev_query_s = resampled_opt_position.back(); + if (query_s - prev_query_s > CLOSE_S_DIST_THRESHOLD) { + resampled_opt_position.push_back(query_s); + } + } + + auto resampled_traj = resampling::applyLinearInterpolation( + base_traj_data.s, base_traj_data.traj, resampled_opt_position); + for (size_t i = 0; i < resampled_opt_velocity.size(); ++i) { + resampled_traj.points.at(i).longitudinal_velocity_mps = std::min( + resampled_opt_velocity.at(i), + static_cast(resampled_traj.points.at(i).longitudinal_velocity_mps)); + } + for (size_t i = 0; i < resampled_opt_position.size(); ++i) { + if (resampled_opt_position.at(i) >= closest_stop_dist) { + resampled_traj.points.at(i).longitudinal_velocity_mps = 0.0; + } + } + + Trajectory output; + output.header = planner_data.traj.header; + for (size_t i = 0; i < *closest_idx; ++i) { + auto point = planner_data.traj.points.at(i); + point.longitudinal_velocity_mps = data.v0; + output.points.push_back(point); + } + for (const auto & resampled_point : resampled_traj.points) { + if (output.points.empty()) { + output.points.push_back(resampled_point); + } else { + const auto prev_point = output.points.back(); + const double dist = tier4_autoware_utils::calcDistance2d( + prev_point.pose.position, resampled_point.pose.position); + if (dist > 1e-3) { + output.points.push_back(resampled_point); + } else { + output.points.back() = resampled_point; + } + } + } + output.points.back().longitudinal_velocity_mps = 0.0; // terminal velocity is zero + + prev_output_ = output; + return output; +} + +std::vector OptimizationBasedPlanner::createTimeVector() +{ + std::vector time_vec; + for (double t = 0.0; t < dense_time_horizon_; t += dense_resampling_time_interval_) { + time_vec.push_back(t); + } + if (dense_time_horizon_ - time_vec.back() < 1e-3) { + time_vec.back() = dense_time_horizon_; + } else { + time_vec.push_back(dense_time_horizon_); + } + + for (double t = dense_time_horizon_ + sparse_resampling_time_interval_; t < max_time_horizon_; + t += sparse_resampling_time_interval_) { + time_vec.push_back(t); + } + if (max_time_horizon_ - time_vec.back() < 1e-3) { + time_vec.back() = max_time_horizon_; + } else { + time_vec.push_back(max_time_horizon_); + } + + return time_vec; +} + +double OptimizationBasedPlanner::getClosestStopDistance( + const ObstacleCruisePlannerData & planner_data, const TrajectoryData & ego_traj_data, + const std::vector & resolutions) +{ + const auto & current_time = planner_data.current_time; + double closest_stop_dist = ego_traj_data.s.back(); + const auto closest_stop_id = + tier4_autoware_utils::searchZeroVelocityIndex(ego_traj_data.traj.points); + closest_stop_dist = closest_stop_id + ? std::min(closest_stop_dist, ego_traj_data.s.at(*closest_stop_id)) + : closest_stop_dist; + + double closest_obj_distance = ego_traj_data.s.back(); + boost::optional closest_obj; + for (const auto & obj : planner_data.target_obstacles) { + const auto obj_base_time = obj.time_stamp; + + // Step1. Ignore obstacles that are not vehicles + if ( + obj.classification.label != ObjectClassification::CAR && + obj.classification.label != ObjectClassification::TRUCK && + obj.classification.label != ObjectClassification::BUS && + obj.classification.label != ObjectClassification::MOTORCYCLE) { + continue; + } + + // Step2 Check object position + if (!checkIsFrontObject(obj, ego_traj_data.traj)) { + continue; + } + + // Get the predicted path, which has the most high confidence + const auto predicted_path = + resampledPredictedPath(obj, obj_base_time, current_time, resolutions, max_time_horizon_); + if (!predicted_path) { + continue; + } + + // Get current pose from object's predicted path + const auto current_object_pose = obstacle_cruise_utils::getCurrentObjectPoseFromPredictedPath( + *predicted_path, obj_base_time, current_time); + if (!current_object_pose) { + continue; + } + + // Get current object.kinematics + ObjectData obj_data; + obj_data.pose = current_object_pose.get(); + obj_data.length = obj.shape.dimensions.x; + obj_data.width = obj.shape.dimensions.y; + obj_data.time = std::max((obj_base_time - current_time).seconds(), 0.0); + const double current_delta_yaw_threshold = 3.14; + const auto dist_to_collision_point = + getDistanceToCollisionPoint(ego_traj_data, obj_data, current_delta_yaw_threshold); + + // Calculate Safety Distance + const double ego_vehicle_offset = vehicle_info_.wheel_base_m + vehicle_info_.front_overhang_m; + const double object_offset = obj_data.length / 2.0; + const double safety_distance = ego_vehicle_offset + object_offset + safe_distance_margin_; + + // If the object is on the current ego trajectory, + // we assume the object travels along ego trajectory + const double obj_vel = std::abs(obj.velocity); + if (dist_to_collision_point && obj_vel < object_zero_velocity_threshold_) { + const double current_stop_point = std::max(*dist_to_collision_point - safety_distance, 0.0); + closest_stop_dist = std::min(current_stop_point, closest_stop_dist); + } + + // Update Distance to the closest object on the ego trajectory + if (dist_to_collision_point) { + const double current_obj_distance = std::max( + *dist_to_collision_point - safety_distance + safe_distance_margin_, -safety_distance); + closest_obj_distance = std::min(closest_obj_distance, current_obj_distance); + closest_obj = obj; + } + } + + // Publish distance from the ego vehicle to the object which is on the trajectory + if (closest_obj && closest_obj_distance < ego_traj_data.s.back()) { + Float32Stamped dist_to_obj; + dist_to_obj.stamp = planner_data.current_time; + dist_to_obj.data = closest_obj_distance; + distance_to_closest_obj_pub_->publish(dist_to_obj); + + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Closest Object Distance %f", closest_obj_distance); + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Closest Object Velocity %f", closest_obj.get().velocity); + } + + return closest_stop_dist; +} + +// v0, a0 +std::tuple OptimizationBasedPlanner::calcInitialMotion( + const double current_vel, const Trajectory & input_traj, const size_t input_closest, + const Trajectory & prev_traj, const double closest_stop_dist) +{ + const double vehicle_speed{std::abs(current_vel)}; + const double target_vel{std::abs(input_traj.points.at(input_closest).longitudinal_velocity_mps)}; + + double initial_vel{}; + double initial_acc{}; + + // first time + if (prev_traj.points.empty()) { + initial_vel = vehicle_speed; + initial_acc = 0.0; + return std::make_tuple(initial_vel, initial_acc); + } + + TrajectoryPoint prev_output_closest_point; + if (smoothed_trajectory_ptr_) { + prev_output_closest_point = calcInterpolatedTrajectoryPoint( + *smoothed_trajectory_ptr_, input_traj.points.at(input_closest).pose); + } else { + prev_output_closest_point = + calcInterpolatedTrajectoryPoint(prev_traj, input_traj.points.at(input_closest).pose); + } + + // when velocity tracking deviation is large + const double desired_vel{prev_output_closest_point.longitudinal_velocity_mps}; + const double vel_error{vehicle_speed - std::abs(desired_vel)}; + if (std::abs(vel_error) > replan_vel_deviation_) { + initial_vel = vehicle_speed; // use current vehicle speed + initial_acc = prev_output_closest_point.acceleration_mps2; + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "calcInitialMotion : Large deviation error for speed control. Use current speed for " + "initial value, desired_vel = %f, vehicle_speed = %f, vel_error = %f, error_thr = %f", + desired_vel, vehicle_speed, vel_error, replan_vel_deviation_); + return std::make_tuple(initial_vel, initial_acc); + } + + // if current vehicle velocity is low && base_desired speed is high, + // use engage_velocity for engage vehicle + const double engage_vel_thr = engage_velocity_ * engage_exit_ratio_; + if (vehicle_speed < engage_vel_thr) { + if (target_vel >= engage_velocity_) { + const auto idx = tier4_autoware_utils::searchZeroVelocityIndex(input_traj.points); + const double zero_vel_dist = + idx ? tier4_autoware_utils::calcDistance2d( + input_traj.points.at(*idx), input_traj.points.at(input_closest)) + : 0.0; + const double stop_dist = std::min(zero_vel_dist, closest_stop_dist); + if (!idx || stop_dist > stop_dist_to_prohibit_engage_) { + initial_vel = engage_velocity_; + initial_acc = engage_acceleration_; + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "calcInitialMotion : vehicle speed is low (%.3f), and desired speed is high (%.3f). Use " + "engage speed (%.3f) until vehicle speed reaches engage_vel_thr (%.3f). stop_dist = %.3f", + vehicle_speed, target_vel, engage_velocity_, engage_vel_thr, stop_dist); + return std::make_tuple(initial_vel, initial_acc); + } else { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "calcInitialMotion : stop point is close (%.3f[m]). no engage.", stop_dist); + } + } else if (target_vel > 0.0) { + auto clock{rclcpp::Clock{RCL_ROS_TIME}}; + RCLCPP_WARN_THROTTLE( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), clock, 3000, + "calcInitialMotion : target velocity(%.3f[m/s]) is lower than engage velocity(%.3f[m/s]). ", + target_vel, engage_velocity_); + } + } + + // normal update: use closest in prev_output + initial_vel = prev_output_closest_point.longitudinal_velocity_mps; + initial_acc = prev_output_closest_point.acceleration_mps2; + /* + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "calcInitialMotion : normal update. v0 = %f, a0 = %f, vehicle_speed = %f, target_vel = %f", + initial_vel, initial_acc, vehicle_speed, target_vel); + */ + return std::make_tuple(initial_vel, initial_acc); +} + +TrajectoryPoint OptimizationBasedPlanner::calcInterpolatedTrajectoryPoint( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & target_pose) +{ + TrajectoryPoint traj_p{}; + traj_p.pose = target_pose; + + if (trajectory.points.empty()) { + traj_p.longitudinal_velocity_mps = 0.0; + traj_p.acceleration_mps2 = 0.0; + return traj_p; + } + + if (trajectory.points.size() == 1) { + traj_p.longitudinal_velocity_mps = trajectory.points.at(0).longitudinal_velocity_mps; + traj_p.acceleration_mps2 = trajectory.points.at(0).acceleration_mps2; + return traj_p; + } + + const size_t segment_idx = + tier4_autoware_utils::findNearestSegmentIndex(trajectory.points, target_pose.position); + + auto v1 = getTransVector3( + trajectory.points.at(segment_idx).pose, trajectory.points.at(segment_idx + 1).pose); + auto v2 = getTransVector3(trajectory.points.at(segment_idx).pose, target_pose); + // calc internal proportion + const double prop{std::max(0.0, std::min(1.0, v1.dot(v2) / v1.length2()))}; + + auto interpolate = [&prop](double x1, double x2) { return prop * x1 + (1.0 - prop) * x2; }; + + { + const auto & seg_pt = trajectory.points.at(segment_idx); + const auto & next_pt = trajectory.points.at(segment_idx + 1); + traj_p.longitudinal_velocity_mps = + interpolate(next_pt.longitudinal_velocity_mps, seg_pt.longitudinal_velocity_mps); + traj_p.acceleration_mps2 = interpolate(next_pt.acceleration_mps2, seg_pt.acceleration_mps2); + traj_p.pose.position.x = interpolate(next_pt.pose.position.x, seg_pt.pose.position.x); + traj_p.pose.position.y = interpolate(next_pt.pose.position.y, seg_pt.pose.position.y); + traj_p.pose.position.z = interpolate(next_pt.pose.position.z, seg_pt.pose.position.z); + } + + return traj_p; +} + +bool OptimizationBasedPlanner::checkHasReachedGoal( + const Trajectory & traj, const size_t closest_idx, const double v0) +{ + // If goal is close and current velocity is low, we don't optimize trajectory + const auto closest_stop_id = tier4_autoware_utils::searchZeroVelocityIndex(traj.points); + if (closest_stop_id) { + const double closest_stop_dist = + tier4_autoware_utils::calcSignedArcLength(traj.points, closest_idx, *closest_stop_id); + if (closest_stop_dist < 0.5 && v0 < 0.6) { + return true; + } + } + + return false; +} + +OptimizationBasedPlanner::TrajectoryData OptimizationBasedPlanner::getTrajectoryData( + const Trajectory & traj, const geometry_msgs::msg::Pose & current_pose) +{ + TrajectoryData base_traj; + const auto closest_segment_idx = + tier4_autoware_utils::findNearestSegmentIndex(traj.points, current_pose.position); + const auto interpolated_point = calcInterpolatedTrajectoryPoint(traj, current_pose); + const auto dist = tier4_autoware_utils::calcDistance2d( + interpolated_point.pose.position, traj.points.at(closest_segment_idx).pose.position); + const auto current_point = + dist > CLOSE_S_DIST_THRESHOLD ? interpolated_point : traj.points.at(closest_segment_idx); + base_traj.traj.points.push_back(current_point); + base_traj.s.push_back(0.0); + + for (size_t id = closest_segment_idx + 1; id < traj.points.size(); ++id) { + const auto prev_point = base_traj.traj.points.back(); + const double ds = tier4_autoware_utils::calcDistance2d( + prev_point.pose.position, traj.points.at(id).pose.position); + if (ds < CLOSE_S_DIST_THRESHOLD) { + continue; + } + const double current_s = base_traj.s.back() + ds; + + base_traj.traj.points.push_back(traj.points.at(id)); + base_traj.s.push_back(current_s); + } + + return base_traj; +} + +OptimizationBasedPlanner::TrajectoryData OptimizationBasedPlanner::resampleTrajectoryData( + const TrajectoryData & base_traj_data, const double resampling_s_interval, + const double max_traj_length, const double stop_dist) +{ + // Create Base Keys + std::vector base_s(base_traj_data.s.size()); + for (size_t i = 0; i < base_s.size(); ++i) { + base_s.at(i) = base_traj_data.s.at(i); + } + + // Obtain trajectory length until the velocity is zero or stop dist + const auto closest_stop_id = + tier4_autoware_utils::searchZeroVelocityIndex(base_traj_data.traj.points); + const double closest_stop_dist = + closest_stop_id ? std::min(stop_dist, base_traj_data.s.at(*closest_stop_id)) : stop_dist; + const double traj_length = std::min(closest_stop_dist, std::min(base_s.back(), max_traj_length)); + + // Create Query Keys + std::vector resampled_s; + for (double s = 0.0; s < traj_length; s += resampling_s_interval) { + resampled_s.push_back(s); + } + + if (traj_length - resampled_s.back() < CLOSE_S_DIST_THRESHOLD) { + resampled_s.back() = traj_length; + } else { + resampled_s.push_back(traj_length); + } + + if (resampled_s.empty()) { + return TrajectoryData{}; + } + + // Resample trajectory + const auto resampled_traj = resampleTrajectory(base_s, base_traj_data.traj, resampled_s); + + // Store Data + TrajectoryData resampled_traj_data; + resampled_traj_data.traj = resampled_traj; + resampled_traj_data.s = resampled_s; + + return resampled_traj_data; +} + +// TODO(shimizu) what is the difference with apply linear interpolation +Trajectory OptimizationBasedPlanner::resampleTrajectory( + const std::vector & base_index, const Trajectory & base_trajectory, + const std::vector & query_index, const bool use_spline_for_pose) +{ + std::vector px, py, pz, pyaw, tlx, taz, alx; + for (const auto & p : base_trajectory.points) { + px.push_back(p.pose.position.x); + py.push_back(p.pose.position.y); + pz.push_back(p.pose.position.z); + pyaw.push_back(tf2::getYaw(p.pose.orientation)); + tlx.push_back(p.longitudinal_velocity_mps); + taz.push_back(p.heading_rate_rps); + alx.push_back(p.acceleration_mps2); + } + + convertEulerAngleToMonotonic(pyaw); + + std::vector px_p, py_p, pz_p, pyaw_p; + if (use_spline_for_pose) { + px_p = interpolation::slerp(base_index, px, query_index); + py_p = interpolation::slerp(base_index, py, query_index); + pz_p = interpolation::slerp(base_index, pz, query_index); + pyaw_p = interpolation::slerp(base_index, pyaw, query_index); + } else { + px_p = interpolation::lerp(base_index, px, query_index); + py_p = interpolation::lerp(base_index, py, query_index); + pz_p = interpolation::lerp(base_index, pz, query_index); + pyaw_p = interpolation::lerp(base_index, pyaw, query_index); + } + const auto tlx_p = interpolation::lerp(base_index, tlx, query_index); + const auto taz_p = interpolation::lerp(base_index, taz, query_index); + const auto alx_p = interpolation::lerp(base_index, alx, query_index); + + Trajectory resampled_trajectory; + resampled_trajectory.header = base_trajectory.header; + resampled_trajectory.points.resize(query_index.size()); + + for (size_t i = 0; i < query_index.size(); ++i) { + TrajectoryPoint point; + point.pose.position.x = px_p.at(i); + point.pose.position.y = py_p.at(i); + point.pose.position.z = pz_p.at(i); + point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(pyaw_p.at(i)); + + point.longitudinal_velocity_mps = tlx_p.at(i); + point.heading_rate_rps = taz_p.at(i); + point.acceleration_mps2 = alx_p.at(i); + resampled_trajectory.points.at(i) = point; + } + return resampled_trajectory; +} + +boost::optional OptimizationBasedPlanner::getSBoundaries( + const ObstacleCruisePlannerData & planner_data, const TrajectoryData & ego_traj_data, + const std::vector & time_vec) +{ + if (ego_traj_data.traj.points.empty()) { + return boost::none; + } + + const auto & current_time = planner_data.current_time; + + SBoundaries s_boundaries(time_vec.size()); + for (size_t i = 0; i < s_boundaries.size(); ++i) { + s_boundaries.at(i).max_s = ego_traj_data.s.back(); + } + + double min_slow_down_point_length = std::numeric_limits::max(); + boost::optional min_slow_down_idx = {}; + for (size_t o_idx = 0; o_idx < planner_data.target_obstacles.size(); ++o_idx) { + const auto obj_base_time = planner_data.target_obstacles.at(o_idx).time_stamp; + + const auto & obj = planner_data.target_obstacles.at(o_idx); + // Step1 Check object position + if (!checkIsFrontObject(obj, ego_traj_data.traj)) { + continue; + } + + // Step2 Get S boundary from the obstacle + const auto obj_s_boundaries = + getSBoundaries(planner_data.current_time, ego_traj_data, obj, obj_base_time, time_vec); + if (!obj_s_boundaries) { + continue; + } + + // Step3 update s boundaries + for (size_t i = 0; i < obj_s_boundaries->size(); ++i) { + if (obj_s_boundaries->at(i).max_s < s_boundaries.at(i).max_s) { + s_boundaries.at(i) = obj_s_boundaries->at(i); + } + } + + // Step4 add object to marker + // const auto marker = getObjectMarkerArray(obj.pose, o_idx, "objects_to_follow", 0.7, 0.7, + // 0.0); tier4_autoware_utils::appendMarkerArray(marker, &msg); + + // Step5 search nearest obstacle to follow for rviz marker + const double object_offset = obj.shape.dimensions.x / 2.0; + + const auto predicted_path = + resampledPredictedPath(obj, obj_base_time, current_time, time_vec, max_time_horizon_); + + const auto current_object_pose = obstacle_cruise_utils::getCurrentObjectPoseFromPredictedPath( + *predicted_path, obj_base_time, current_time); + + const double obj_vel = std::abs(obj.velocity); + const double rss_dist = calcRSSDistance(planner_data.current_vel, obj_vel); + + const double ego_obj_length = tier4_autoware_utils::calcSignedArcLength( + ego_traj_data.traj.points, planner_data.current_pose.position, + current_object_pose.get().position); + const double slow_down_point_length = + ego_obj_length - (rss_dist + object_offset + safe_distance_margin_); + + if (slow_down_point_length < min_slow_down_point_length) { + min_slow_down_point_length = slow_down_point_length; + min_slow_down_idx = o_idx; + } + } + + // Publish wall marker for slowing down or stopping + if (min_slow_down_idx) { + const auto & obj = planner_data.target_obstacles.at(min_slow_down_idx.get()); + + const auto predicted_path = + resampledPredictedPath(obj, obj.time_stamp, current_time, time_vec, max_time_horizon_); + + const auto current_object_pose = obstacle_cruise_utils::getCurrentObjectPoseFromPredictedPath( + *predicted_path, obj.time_stamp, current_time); + + const auto marker_pose = calcForwardPose( + ego_traj_data.traj, planner_data.current_pose.position, min_slow_down_point_length); + + if (marker_pose) { + visualization_msgs::msg::MarkerArray wall_msg; + + const double obj_vel = std::abs(obj.velocity); + if (obj_vel < object_zero_velocity_threshold_) { + const auto markers = tier4_autoware_utils::createStopVirtualWallMarker( + marker_pose.get(), "obstacle to follow", current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &wall_msg); + } else { + const auto markers = tier4_autoware_utils::createSlowDownVirtualWallMarker( + marker_pose.get(), "obstacle to follow", current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &wall_msg); + } + + // publish rviz marker + debug_wall_marker_pub_->publish(wall_msg); + } + } + + return s_boundaries; +} + +boost::optional OptimizationBasedPlanner::getSBoundaries( + const rclcpp::Time & current_time, const TrajectoryData & ego_traj_data, + const TargetObstacle & object, const rclcpp::Time & obj_base_time, + const std::vector & time_vec) +{ + // Get the predicted path, which has the most high confidence + const double max_horizon = time_vec.back(); + const auto predicted_path = + resampledPredictedPath(object, obj_base_time, current_time, time_vec, max_horizon); + if (!predicted_path) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Closest Obstacle does not have a predicted path"); + return boost::none; + } + + // Get current pose from object's predicted path + const auto current_object_pose = obstacle_cruise_utils::getCurrentObjectPoseFromPredictedPath( + *predicted_path, obj_base_time, current_time); + if (!current_object_pose) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Failed to get current pose from the predicted path"); + return boost::none; + } + + // Check current object.kinematics + ObjectData obj_data; + obj_data.pose = current_object_pose.get(); + obj_data.length = object.shape.dimensions.x; + obj_data.width = object.shape.dimensions.y; + obj_data.time = std::max((obj_base_time - current_time).seconds(), 0.0); + const double current_delta_yaw_threshold = 3.14; + const auto current_collision_dist = + getDistanceToCollisionPoint(ego_traj_data, obj_data, current_delta_yaw_threshold); + + // Calculate Safety Distance + const double ego_vehicle_offset = vehicle_info_.wheel_base_m + vehicle_info_.front_overhang_m; + const double object_offset = obj_data.length / 2.0; + const double safety_distance = ego_vehicle_offset + object_offset + safe_distance_margin_; + + // If the object is on the current ego trajectory, + // we assume the object travels along ego trajectory + if (current_collision_dist) { + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "On Trajectory Object"); + + return getSBoundaries( + ego_traj_data, time_vec, safety_distance, object, *current_collision_dist); + } + + // Ignore low velocity objects that are not on the trajectory + const double obj_vel = std::abs(object.velocity); + if (obj_vel > object_low_velocity_threshold_) { + // RCLCPP_DEBUG(rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), "Off + // Trajectory Object"); + return getSBoundaries( + current_time, ego_traj_data, time_vec, safety_distance, object, obj_base_time, + *predicted_path); + } + + return boost::none; +} + +boost::optional OptimizationBasedPlanner::getSBoundaries( + const TrajectoryData & ego_traj_data, const std::vector & time_vec, + const double safety_distance, const TargetObstacle & object, const double dist_to_collision_point) +{ + const double & min_object_accel_for_rss = longitudinal_info_.min_object_accel_for_rss; + + SBoundaries s_boundaries(time_vec.size()); + for (size_t i = 0; i < s_boundaries.size(); ++i) { + s_boundaries.at(i).max_s = ego_traj_data.s.back(); + } + + const double v_obj = std::abs(object.velocity); + const double a_obj = 0.0; + + double current_v_obj = v_obj < object_zero_velocity_threshold_ ? 0.0 : v_obj; + double current_s_obj = std::max(dist_to_collision_point - safety_distance, 0.0); + const double initial_s_obj = current_s_obj; + const double initial_s_upper_bound = + current_s_obj + (current_v_obj * current_v_obj) / (2 * std::fabs(min_object_accel_for_rss)); + s_boundaries.front().max_s = std::clamp(initial_s_upper_bound, 0.0, s_boundaries.front().max_s); + s_boundaries.front().is_object = true; + for (size_t i = 1; i < time_vec.size(); ++i) { + const double dt = time_vec.at(i) - time_vec.at(i - 1); + if (i * dt <= 1.0 && use_object_acceleration_) { + current_s_obj = + std::max(current_s_obj + current_v_obj * dt + 0.5 * a_obj * dt * dt, initial_s_obj); + current_v_obj = std::max(current_v_obj + a_obj * dt, 0.0); + } else { + current_s_obj = current_s_obj + current_v_obj * dt; + } + + const double s_upper_bound = + current_s_obj + (current_v_obj * current_v_obj) / (2 * std::fabs(min_object_accel_for_rss)); + s_boundaries.at(i).max_s = std::clamp(s_upper_bound, 0.0, s_boundaries.at(i).max_s); + s_boundaries.at(i).is_object = true; + } + + return s_boundaries; +} + +boost::optional OptimizationBasedPlanner::getSBoundaries( + const rclcpp::Time & current_time, const TrajectoryData & ego_traj_data, + const std::vector & time_vec, const double safety_distance, const TargetObstacle & object, + const rclcpp::Time & obj_base_time, const PredictedPath & predicted_path) +{ + const double & min_object_accel_for_rss = longitudinal_info_.min_object_accel_for_rss; + + const double abs_obj_vel = std::abs(object.velocity); + const double v_obj = abs_obj_vel < object_zero_velocity_threshold_ ? 0.0 : abs_obj_vel; + + SBoundaries s_boundaries(time_vec.size()); + for (size_t i = 0; i < s_boundaries.size(); ++i) { + s_boundaries.at(i).max_s = ego_traj_data.s.back(); + } + + for (size_t predicted_path_id = 0; predicted_path_id < predicted_path.path.size(); + ++predicted_path_id) { + const auto predicted_pose = predicted_path.path.at(predicted_path_id); + const double object_time = (obj_base_time - current_time).seconds(); + if (object_time < 0) { + // Ignore Past Positions + continue; + } + + ObjectData obj_data; + obj_data.pose = predicted_pose; + obj_data.length = object.shape.dimensions.x; + obj_data.width = object.shape.dimensions.y; + obj_data.time = object_time; + + const auto dist_to_collision_point = + getDistanceToCollisionPoint(ego_traj_data, obj_data, delta_yaw_threshold_of_object_and_ego_); + if (!dist_to_collision_point) { + continue; + } + + const double current_s_obj = std::max(*dist_to_collision_point - safety_distance, 0.0); + const double s_upper_bound = + current_s_obj + (v_obj * v_obj) / (2 * std::fabs(min_object_accel_for_rss)); + for (size_t i = 0; i < predicted_path_id; ++i) { + if (s_upper_bound < s_boundaries.at(i).max_s) { + s_boundaries.at(i).max_s = std::max(0.0, s_upper_bound); + s_boundaries.at(i).is_object = true; + } + } + } + + return s_boundaries; +} + +boost::optional OptimizationBasedPlanner::getDistanceToCollisionPoint( + const TrajectoryData & ego_traj_data, const ObjectData & obj_data, + const double delta_yaw_threshold) +{ + const auto obj_pose = obj_data.pose; + const auto obj_length = obj_data.length; + const auto obj_width = obj_data.width; + + // check diff yaw + const size_t nearest_idx = + tier4_autoware_utils::findNearestIndex(ego_traj_data.traj.points, obj_pose.position); + const double ego_yaw = tf2::getYaw(ego_traj_data.traj.points.at(nearest_idx).pose.orientation); + const double obj_yaw = tf2::getYaw(obj_pose.orientation); + const double diff_yaw = tier4_autoware_utils::normalizeRadian(obj_yaw - ego_yaw); + if (diff_yaw > delta_yaw_threshold) { + // ignore object whose yaw difference from ego is too large + RCLCPP_DEBUG( + rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"), + "Ignore object since the yaw difference is above the threshold"); + return boost::none; + } + + const auto object_box = Box2d(obj_pose, obj_length, obj_width); + const auto object_points = object_box.getAllCorners(); + + // Get nearest segment index for each point + size_t min_nearest_idx = ego_traj_data.s.size(); + size_t max_nearest_idx = 0; + for (const auto & obj_p : object_points) { + size_t nearest_idx = + tier4_autoware_utils::findNearestSegmentIndex(ego_traj_data.traj.points, obj_p); + min_nearest_idx = std::min(nearest_idx, min_nearest_idx); + max_nearest_idx = std::max(nearest_idx, max_nearest_idx); + } + + double min_len = 0.0; + size_t start_idx = 0; + for (size_t i = min_nearest_idx; i > 0; --i) { + min_len += (ego_traj_data.s.at(i) - ego_traj_data.s.at(i - 1)); + if (min_len > 5.0) { + start_idx = i - 1; + break; + } + } + + double max_len = 0.0; + size_t end_idx = ego_traj_data.s.size() - 1; + for (size_t i = max_nearest_idx; i < ego_traj_data.s.size() - 1; ++i) { + max_len += (ego_traj_data.s.at(i + 1) - ego_traj_data.s.at(i)); + if (max_len > 5.0) { + end_idx = i + 1; + break; + } + } + + // Check collision + const auto collision_idx = getCollisionIdx(ego_traj_data, object_box, start_idx, end_idx); + + if (collision_idx) { + // TODO(shimizu) Consider the time difference between ego vehicle and objects + return tier4_autoware_utils::calcSignedArcLength( + ego_traj_data.traj.points, ego_traj_data.traj.points.front().pose.position, + obj_pose.position); + } + + return boost::none; +} + +boost::optional OptimizationBasedPlanner::getCollisionIdx( + const TrajectoryData & ego_traj, const Box2d & obj_box, const size_t start_idx, + const size_t end_idx) +{ + for (size_t ego_idx = start_idx; ego_idx <= end_idx; ++ego_idx) { + const auto ego_center_pose = transformBaseLink2Center(ego_traj.traj.points.at(ego_idx).pose); + const auto ego_box = + Box2d(ego_center_pose, vehicle_info_.vehicle_length_m, vehicle_info_.vehicle_width_m); + if (ego_box.hasOverlap(obj_box)) { + return ego_idx; + } + } + + return boost::none; +} + +bool OptimizationBasedPlanner::checkIsFrontObject( + const TargetObstacle & object, const Trajectory & traj) +{ + const auto point = object.pose.position; + + // Get nearest segment index + size_t nearest_idx = tier4_autoware_utils::findNearestSegmentIndex(traj.points, point); + + // Calculate longitudinal length + const double l = + tier4_autoware_utils::calcLongitudinalOffsetToSegment(traj.points, nearest_idx, point); + + if (nearest_idx == 0 && l < 0) { + return false; + } + + return true; +} + +boost::optional OptimizationBasedPlanner::resampledPredictedPath( + const TargetObstacle & object, const rclcpp::Time & obj_base_time, + const rclcpp::Time & current_time, const std::vector & resolutions, const double horizon) +{ + if (object.predicted_paths.empty()) { + return boost::none; + } + + // Get the most reliable path + const auto reliable_path = std::max_element( + object.predicted_paths.begin(), object.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + + // Resample Predicted Path + const double duration = std::min( + std::max( + (obj_base_time + + rclcpp::Duration(reliable_path->time_step) * + (static_cast(reliable_path->path.size()) - 1) - + current_time) + .seconds(), + 0.0), + horizon); + + // Calculate relative valid time vector + // rel_valid_time_vec is relative to obj_base_time. + const auto rel_valid_time_vec = resampling::resampledValidRelativeTimeVector( + current_time, obj_base_time, resolutions, duration); + + return resampling::resamplePredictedPath(*reliable_path, rel_valid_time_vec); +} + +geometry_msgs::msg::Pose OptimizationBasedPlanner::transformBaseLink2Center( + const geometry_msgs::msg::Pose & pose_base_link) +{ + tf2::Transform tf_map2base; + tf2::fromMsg(pose_base_link, tf_map2base); + + // set vertices at map coordinate + tf2::Vector3 base2center; + base2center.setX(std::abs(vehicle_info_.vehicle_length_m / 2.0 - vehicle_info_.rear_overhang_m)); + base2center.setY(0.0); + base2center.setZ(0.0); + base2center.setW(1.0); + + // transform vertices from map coordinate to object coordinate + const auto map2center = tf_map2base * base2center; + + geometry_msgs::msg::Pose center_pose; + center_pose.position = + tier4_autoware_utils::createPoint(map2center.x(), map2center.y(), map2center.z()); + center_pose.orientation = pose_base_link.orientation; + + return center_pose; +} + +boost::optional +OptimizationBasedPlanner::processOptimizedResult( + const double v0, const VelocityOptimizer::OptimizationResult & opt_result) +{ + if ( + opt_result.t.empty() || opt_result.s.empty() || opt_result.v.empty() || opt_result.a.empty() || + opt_result.j.empty()) { + return boost::none; + } + + size_t break_id = opt_result.s.size(); + VelocityOptimizer::OptimizationResult processed_result; + processed_result.t.push_back(0.0); + processed_result.s.push_back(0.0); + processed_result.v.push_back(v0); + processed_result.a.push_back(opt_result.a.front()); + processed_result.j.push_back(opt_result.j.front()); + + for (size_t i = 1; i < opt_result.s.size(); ++i) { + const double prev_s = processed_result.s.back(); + const double current_s = std::max(opt_result.s.at(i), 0.0); + const double current_v = opt_result.v.at(i); + if (prev_s >= current_s) { + processed_result.v.back() = 0.0; + break_id = i; + break; + } else if (current_v < ZERO_VEL_THRESHOLD) { + break_id = i; + break; + } else if (std::fabs(current_s - prev_s) < CLOSE_S_DIST_THRESHOLD) { + processed_result.v.back() = current_v; + processed_result.s.back() = prev_s > 0.0 ? current_s : prev_s; + continue; + } + + processed_result.t.push_back(opt_result.t.at(i)); + processed_result.s.push_back(current_s); + processed_result.v.push_back(current_v); + processed_result.a.push_back(opt_result.a.at(i)); + processed_result.j.push_back(opt_result.j.at(i)); + } + + // Padding Zero Velocity after break id + for (size_t i = break_id; i < opt_result.s.size(); ++i) { + const double prev_s = processed_result.s.back(); + const double current_s = std::max(opt_result.s.at(i), 0.0); + if (prev_s >= current_s) { + processed_result.v.back() = 0.0; + continue; + } else if (std::fabs(current_s - prev_s) < CLOSE_S_DIST_THRESHOLD) { + processed_result.v.back() = 0.0; + processed_result.s.back() = prev_s > 0.0 ? current_s : prev_s; + continue; + } + processed_result.t.push_back(opt_result.t.at(i)); + processed_result.s.push_back(current_s); + processed_result.v.push_back(0.0); + processed_result.a.push_back(0.0); + processed_result.j.push_back(0.0); + } + + return processed_result; +} + +void OptimizationBasedPlanner::publishDebugTrajectory( + const rclcpp::Time & current_time, const Trajectory & traj, const size_t closest_idx, + const std::vector & time_vec, const SBoundaries & s_boundaries, + const VelocityOptimizer::OptimizationResult & opt_result) +{ + const std::vector time = opt_result.t; + // Publish optimized result and boundary + Trajectory boundary_traj; + boundary_traj.header.stamp = current_time; + boundary_traj.points.resize(s_boundaries.size()); + double boundary_s_max = 0.0; + for (size_t i = 0; i < s_boundaries.size(); ++i) { + const double bound_s = s_boundaries.at(i).max_s; + const double bound_t = time_vec.at(i); + boundary_traj.points.at(i).pose.position.x = bound_s; + boundary_traj.points.at(i).pose.position.y = bound_t; + boundary_s_max = std::max(bound_s, boundary_s_max); + } + boundary_pub_->publish(boundary_traj); + + const double s_before = tier4_autoware_utils::calcSignedArcLength(traj.points, 0, closest_idx); + Trajectory optimized_sv_traj; + optimized_sv_traj.header.stamp = current_time; + optimized_sv_traj.points.resize(opt_result.s.size()); + for (size_t i = 0; i < opt_result.s.size(); ++i) { + const double s = opt_result.s.at(i); + const double v = opt_result.v.at(i); + optimized_sv_traj.points.at(i).pose.position.x = s + s_before; + optimized_sv_traj.points.at(i).pose.position.y = v; + } + optimized_sv_pub_->publish(optimized_sv_traj); + + Trajectory optimized_st_graph; + optimized_st_graph.header.stamp = current_time; + optimized_st_graph.points.resize(opt_result.s.size()); + for (size_t i = 0; i < opt_result.s.size(); ++i) { + const double bound_s = opt_result.s.at(i); + const double bound_t = opt_result.t.at(i); + optimized_st_graph.points.at(i).pose.position.x = bound_s; + optimized_st_graph.points.at(i).pose.position.y = bound_t; + } + optimized_st_graph_pub_->publish(optimized_st_graph); +} diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp new file mode 100644 index 0000000000000..a629abca7f0dd --- /dev/null +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp @@ -0,0 +1,220 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/optimization_based_planner/resample.hpp" + +#include "interpolation/linear_interpolation.hpp" +#include "interpolation/spline_interpolation.hpp" + +#include + +namespace +{ +[[maybe_unused]] rclcpp::Duration safeSubtraction(const rclcpp::Time & t1, const rclcpp::Time & t2) +{ + rclcpp::Duration duration = rclcpp::Duration::from_seconds(0.0); + try { + duration = t1 - t2; + } catch (std::runtime_error & err) { + if (t1 > t2) { + duration = rclcpp::Duration::max() * -1.0; + } else { + duration = rclcpp::Duration::max(); + } + } + return duration; +} + +// tf2::toMsg does not have this type of function +geometry_msgs::msg::Point toMsg(tf2::Vector3 vec) +{ + geometry_msgs::msg::Point point; + point.x = vec.x(); + point.y = vec.y(); + point.z = vec.z(); + return point; +} +} // namespace + +namespace resampling +{ +std::vector resampledValidRelativeTimeVector( + const rclcpp::Time & start_time, const rclcpp::Time & obj_base_time, + const std::vector & rel_time_vec, const double duration) +{ + const auto prediction_duration = rclcpp::Duration::from_seconds(duration); + const auto end_time = start_time + prediction_duration; + + // NOTE: rel_time_vec is relative time to start_time. + // rel_valid_time_vec is relative to obj_base_time, which is time stamp in predicted object. + std::vector rel_valid_time_vec; + for (const auto & time : rel_time_vec) { + // absolute target time + const auto target_time = start_time + rclcpp::Duration::from_seconds(time); + if (target_time > end_time) { + break; + } + + // relative target time + const auto rel_target_time = target_time - obj_base_time; + if (rel_target_time < rclcpp::Duration::from_seconds(0.0)) { + continue; + } + + rel_valid_time_vec.push_back(rel_target_time); + } + + return rel_valid_time_vec; +} + +autoware_auto_perception_msgs::msg::PredictedPath resamplePredictedPath( + const autoware_auto_perception_msgs::msg::PredictedPath & input_path, + const std::vector & rel_time_vec) +{ + autoware_auto_perception_msgs::msg::PredictedPath resampled_path; + resampled_path.time_step = input_path.time_step; + + for (const auto & rel_time : rel_time_vec) { + const auto opt_pose = lerpByTimeStamp(input_path, rel_time); + if (!opt_pose) { + continue; + } + + resampled_path.path.push_back(opt_pose.get()); + } + + return resampled_path; +} + +geometry_msgs::msg::Pose lerpByPose( + const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Pose & p2, const double t) +{ + tf2::Transform tf_transform1, tf_transform2; + tf2::fromMsg(p1, tf_transform1); + tf2::fromMsg(p2, tf_transform2); + const auto & tf_point = tf2::lerp(tf_transform1.getOrigin(), tf_transform2.getOrigin(), t); + const auto & tf_quaternion = + tf2::slerp(tf_transform1.getRotation(), tf_transform2.getRotation(), t); + + geometry_msgs::msg::Pose pose; + pose.position = ::toMsg(tf_point); + pose.orientation = tf2::toMsg(tf_quaternion); + return pose; +} + +boost::optional lerpByTimeStamp( + const autoware_auto_perception_msgs::msg::PredictedPath & path, const rclcpp::Duration & rel_time) +{ + auto clock{rclcpp::Clock{RCL_ROS_TIME}}; + if (path.path.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + rclcpp::get_logger("DynamicAvoidance.resample"), clock, 1000, + "Empty path. Failed to interpolate path by time!"); + return {}; + } + if (rel_time < rclcpp::Duration::from_seconds(0.0)) { + RCLCPP_DEBUG_STREAM( + rclcpp::get_logger("DynamicAvoidance.resample"), "failed to interpolate path by time!" + << std::endl + << "query time: " << rel_time.seconds()); + + return {}; + } + + if (rel_time > rclcpp::Duration(path.time_step) * (static_cast(path.path.size()) - 1)) { + RCLCPP_DEBUG_STREAM( + rclcpp::get_logger("DynamicAvoidance.resample"), + "failed to interpolate path by time!" + << std::endl + << "path max duration: " << path.path.size() * rclcpp::Duration(path.time_step).seconds() + << std::endl + << "query time : " << rel_time.seconds()); + + return {}; + } + + for (size_t i = 1; i < path.path.size(); ++i) { + const auto & pt = path.path.at(i); + const auto & prev_pt = path.path.at(i - 1); + if (rel_time <= rclcpp::Duration(path.time_step) * static_cast(i)) { + const auto offset = rel_time - rclcpp::Duration(path.time_step) * static_cast(i - 1); + const auto ratio = offset.seconds() / rclcpp::Duration(path.time_step).seconds(); + return lerpByPose(prev_pt, pt, ratio); + } + } + + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("DynamicAvoidance.resample"), "Something failed in function: " << __func__); + return {}; +} + +inline void convertEulerAngleToMonotonic(std::vector & a) +{ + for (unsigned int i = 1; i < a.size(); ++i) { + const double da = a[i] - a[i - 1]; + a[i] = a[i - 1] + tier4_autoware_utils::normalizeRadian(da); + } +} + +autoware_auto_planning_msgs::msg::Trajectory applyLinearInterpolation( + const std::vector & base_index, + const autoware_auto_planning_msgs::msg::Trajectory & base_trajectory, + const std::vector & out_index, const bool use_spline_for_pose) +{ + std::vector px, py, pz, pyaw, tlx, taz, alx; + for (const auto & p : base_trajectory.points) { + px.push_back(p.pose.position.x); + py.push_back(p.pose.position.y); + pz.push_back(p.pose.position.z); + pyaw.push_back(tf2::getYaw(p.pose.orientation)); + tlx.push_back(p.longitudinal_velocity_mps); + taz.push_back(p.heading_rate_rps); + alx.push_back(p.acceleration_mps2); + } + + convertEulerAngleToMonotonic(pyaw); + + std::vector px_p, py_p, pz_p, pyaw_p; + if (use_spline_for_pose) { + px_p = interpolation::slerp(base_index, px, out_index); + py_p = interpolation::slerp(base_index, py, out_index); + pz_p = interpolation::slerp(base_index, pz, out_index); + pyaw_p = interpolation::slerp(base_index, pyaw, out_index); + } else { + px_p = interpolation::lerp(base_index, px, out_index); + py_p = interpolation::lerp(base_index, py, out_index); + pz_p = interpolation::lerp(base_index, pz, out_index); + pyaw_p = interpolation::lerp(base_index, pyaw, out_index); + } + const auto tlx_p = interpolation::lerp(base_index, tlx, out_index); + const auto taz_p = interpolation::lerp(base_index, taz, out_index); + const auto alx_p = interpolation::lerp(base_index, alx, out_index); + + autoware_auto_planning_msgs::msg::Trajectory out_trajectory; + out_trajectory.header = base_trajectory.header; + autoware_auto_planning_msgs::msg::TrajectoryPoint point; + for (unsigned int i = 0; i < out_index.size(); ++i) { + point.pose.position.x = px_p.at(i); + point.pose.position.y = py_p.at(i); + point.pose.position.z = pz_p.at(i); + point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(pyaw_p.at(i)); + + point.longitudinal_velocity_mps = tlx_p.at(i); + point.heading_rate_rps = taz_p.at(i); + point.acceleration_mps2 = alx_p.at(i); + out_trajectory.points.push_back(point); + } + return out_trajectory; +} +} // namespace resampling diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp new file mode 100644 index 0000000000000..990e30842e6ea --- /dev/null +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp @@ -0,0 +1,276 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp" + +#include + +#include + +VelocityOptimizer::VelocityOptimizer( + const double max_s_weight, const double max_v_weight, const double over_s_safety_weight, + const double over_s_ideal_weight, const double over_v_weight, const double over_a_weight, + const double over_j_weight) +: max_s_weight_(max_s_weight), + max_v_weight_(max_v_weight), + over_s_safety_weight_(over_s_safety_weight), + over_s_ideal_weight_(over_s_ideal_weight), + over_v_weight_(over_v_weight), + over_a_weight_(over_a_weight), + over_j_weight_(over_j_weight) +{ + qp_solver_.updateMaxIter(200000); + qp_solver_.updateRhoInterval(0); // 0 means automatic + qp_solver_.updateEpsRel(1.0e-4); // def: 1.0e-4 + qp_solver_.updateEpsAbs(1.0e-8); // def: 1.0e-4 + qp_solver_.updateVerbose(false); +} + +VelocityOptimizer::OptimizationResult VelocityOptimizer::optimize(const OptimizationData & data) +{ + const std::vector time_vec = data.time_vec; + const size_t N = time_vec.size(); + const double s0 = data.s0; + const double v0 = data.v0; + const double a0 = data.a0; + const double v_max = std::max(data.v_max, 0.1); + const double a_max = data.a_max; + const double a_min = data.a_min; + const double limit_a_min = data.limit_a_min; + const double j_max = data.j_max; + const double j_min = data.j_min; + const double a_range = std::max(a_max - a_min, 0.1); + const double j_range = std::max(j_max - j_min, 0.1); + const double t_dangerous = data.t_dangerous; + const double t_idling = data.idling_time; + const double v_margin = data.v_margin; + const auto s_boundary = data.s_boundary; + + // Variables: s_i, v_i, a_i, j_i, over_s_safety_i, over_s_ideal_i, over_v_i, over_a_i, over_j_i + const int IDX_S0 = 0; + const int IDX_V0 = N; + const int IDX_A0 = 2 * N; + const int IDX_J0 = 3 * N; + const int IDX_OVER_S_SAFETY0 = 4 * N; + const int IDX_OVER_S_IDEAL0 = 5 * N; + const int IDX_OVER_V0 = 6 * N; + const int IDX_OVER_A0 = 7 * N; + const int IDX_OVER_J0 = 8 * N; + const int l_variables = 9 * N; + const int l_constraints = 7 * N + 3 * (N - 1) + 3; + + // the matrix size depends on constraint numbers. + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(l_constraints, l_variables); + std::vector lower_bound(l_constraints, 0.0); + std::vector upper_bound(l_constraints, 0.0); + + // Object Variables + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(l_variables, l_variables); + std::vector q(l_variables, 0.0); + + // Object Function + // min w_s*(s_i - s_ideal_i)^2 + w_v * v0 * ((v_i - v_max)^2 / v_max^2) + // + over_s_safety^2 + over_s_ideal^2 + over_v_ideal^2 + over_a_ideal^2 + // + over_j_ideal^2 + constexpr double MINIMUM_MAX_S_BOUND = 0.01; + for (size_t i = 0; i < N; ++i) { + const double dt = + i < N - 1 ? time_vec.at(i + 1) - time_vec.at(i) : time_vec.at(N - 1) - time_vec.at(N - 2); + const double max_s = std::max(s_boundary.at(i).max_s, MINIMUM_MAX_S_BOUND); + const double v_coeff = v0 / (2 * std::fabs(a_min)) + t_idling; + if (s_boundary.at(i).is_object) { + q.at(IDX_S0 + i) += -max_s_weight_ / max_s * dt; + q.at(IDX_V0 + i) += -max_s_weight_ / max_s * v_coeff * dt; + } else { + q.at(IDX_S0 + i) += -max_s_weight_ / max_s * dt; + } + + q.at(IDX_V0 + i) += -max_v_weight_ / v_max * dt; + } + + for (size_t i = 0; i < N; ++i) { + const double dt = + i < N - 1 ? time_vec.at(i + 1) - time_vec.at(i) : time_vec.at(N - 1) - time_vec.at(N - 2); + const double max_s = std::max(s_boundary.at(i).max_s, MINIMUM_MAX_S_BOUND); + P(IDX_OVER_S_SAFETY0 + i, IDX_OVER_S_SAFETY0 + i) += + over_s_safety_weight_ / (max_s * max_s) * dt; + P(IDX_OVER_S_IDEAL0 + i, IDX_OVER_S_IDEAL0 + i) += over_s_ideal_weight_ / (max_s * max_s) * dt; + P(IDX_OVER_V0 + i, IDX_OVER_V0 + i) += over_v_weight_ / (v_max * v_max) * dt; + P(IDX_OVER_A0 + i, IDX_OVER_A0 + i) += over_a_weight_ / a_range * dt; + P(IDX_OVER_J0 + i, IDX_OVER_J0 + i) += over_j_weight_ / j_range * dt; + + if (s_boundary.at(i).is_object) { + const double v_coeff = v0 / (2 * std::fabs(a_min)) + t_idling; + P(IDX_S0 + i, IDX_S0 + i) += max_s_weight_ / (max_s * max_s) * dt; + P(IDX_V0 + i, IDX_V0 + i) += max_s_weight_ / (max_s * max_s) * v_coeff * v_coeff * dt; + P(IDX_S0 + i, IDX_V0 + i) += max_s_weight_ / (max_s * max_s) * v_coeff * dt; + P(IDX_V0 + i, IDX_S0 + i) += max_s_weight_ / (max_s * max_s) * v_coeff * dt; + } else { + P(IDX_S0 + i, IDX_S0 + i) += max_s_weight_ / (max_s * max_s) * dt; + } + + P(IDX_V0 + i, IDX_V0 + i) += max_v_weight_ / (v_max * v_max) * dt; + } + + // Constraint + size_t constr_idx = 0; + + // Safety Position Constraint: s_boundary_min < s_i + v_i*t_dangerous + v0*v_i/(2*|a_min|) - + // over_s_safety_i < s_boundary_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + const double v_coeff = v0 / (2 * std::fabs(a_min)) + t_dangerous; + A(constr_idx, IDX_S0 + i) = 1.0; // s_i + if (s_boundary.at(i).is_object) { + A(constr_idx, IDX_V0 + i) = v_coeff; // v_i * (t_dangerous + v0/(2*|a_min|)) + } + A(constr_idx, IDX_OVER_S_SAFETY0 + i) = -1.0; // over_s_safety_i + upper_bound.at(constr_idx) = s_boundary.at(i).max_s; + lower_bound.at(constr_idx) = 0.0; + } + + // Ideal Position Constraint: s_boundary_min < s_i + v_i * t_idling + v0*v_i/(2*|a_min|) - + // over_s_ideal_i < s_boundary_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + const double v_coeff = v0 / (2 * std::fabs(a_min)) + t_idling; + A(constr_idx, IDX_S0 + i) = 1.0; // s_i + if (s_boundary.at(i).is_object) { + A(constr_idx, IDX_V0 + i) = v_coeff; // v_i * (t_idling + v0/(2*|a_min|)) + } + A(constr_idx, IDX_OVER_S_IDEAL0 + i) = -1.0; // over_s_ideal_i + upper_bound.at(constr_idx) = s_boundary.at(i).max_s; + lower_bound.at(constr_idx) = 0.0; + } + + // Soft Velocity Constraint: 0 < v_i - over_v_i < v_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + A(constr_idx, IDX_V0 + i) = 1.0; // v_i + A(constr_idx, IDX_OVER_V0 + i) = -1.0; // over_v_i + upper_bound.at(constr_idx) = i == N - 1 ? 0.0 : v_max; + lower_bound.at(constr_idx) = 0.0; + } + + // Soft Acceleration Constraint: a_min < a_i - over_a_i < a_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + A(constr_idx, IDX_A0 + i) = 1.0; // a_i + A(constr_idx, IDX_OVER_A0 + i) = -1.0; // over_a_i + upper_bound.at(constr_idx) = i == N - 1 ? 0.0 : a_max; + lower_bound.at(constr_idx) = i == N - 1 ? 0.0 : a_min; + } + + // Hard Acceleration Constraint: limit_a_min < a_i < a_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + A(constr_idx, IDX_A0 + i) = 1.0; // a_i + upper_bound.at(constr_idx) = a_max; + lower_bound.at(constr_idx) = limit_a_min; + } + + // Soft Jerk Constraint: j_min < j_i - over_j_i < j_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + A(constr_idx, IDX_J0 + i) = 1.0; // j_i + A(constr_idx, IDX_OVER_J0 + i) = -1.0; // over_j_i + upper_bound.at(constr_idx) = i == N - 1 ? 0.0 : j_max; + lower_bound.at(constr_idx) = i == N - 1 ? 0.0 : j_min; + } + + // Hard Jerk Constraint: limit_j_min < j_i < limit_j_max + for (size_t i = 0; i < N; ++i, ++constr_idx) { + A(constr_idx, IDX_J0 + i) = 1.0; // j_i + upper_bound.at(constr_idx) = 1.5; + lower_bound.at(constr_idx) = -1.5; + } + + // Dynamic Constraint + // s_i+1 = s_i + v_i * dt + 0.5 * a_i * dt^2 + 1/6 * j_i * dt^3 + for (size_t i = 0; i < N - 1; ++i, ++constr_idx) { + const double dt = time_vec.at(i + 1) - time_vec.at(i); + A(constr_idx, IDX_S0 + i + 1) = 1.0; // s_i+1 + A(constr_idx, IDX_S0 + i) = -1.0; // -s_i + A(constr_idx, IDX_V0 + i) = -dt; // -v_i*dt + A(constr_idx, IDX_A0 + i) = -0.5 * dt * dt; // -0.5 * a_i * dt^2 + A(constr_idx, IDX_J0 + i) = -1.0 / 6.0 * dt * dt * dt; // -1.0/6.0 * j_i * dt^3 + upper_bound.at(constr_idx) = 0.0; + lower_bound.at(constr_idx) = 0.0; + } + + // v_i+1 = v_i + a_i * dt + 0.5 * j_i * dt^2 + for (size_t i = 0; i < N - 1; ++i, ++constr_idx) { + const double dt = time_vec.at(i + 1) - time_vec.at(i); + A(constr_idx, IDX_V0 + i + 1) = 1.0; // v_i+1 + A(constr_idx, IDX_V0 + i) = -1.0; // -v_i + A(constr_idx, IDX_A0 + i) = -dt; // -a_i * dt + A(constr_idx, IDX_J0 + i) = -0.5 * dt * dt; // -0.5 * j_i * dt^2 + upper_bound.at(constr_idx) = 0.0; + lower_bound.at(constr_idx) = 0.0; + } + + // a_i+1 = a_i + j_i * dt + for (size_t i = 0; i < N - 1; ++i, ++constr_idx) { + const double dt = time_vec.at(i + 1) - time_vec.at(i); + A(constr_idx, IDX_A0 + i + 1) = 1.0; // a_i+1 + A(constr_idx, IDX_A0 + i) = -1.0; // -a_i + A(constr_idx, IDX_J0 + i) = -dt; // -j_i * dt + upper_bound.at(constr_idx) = 0.0; + lower_bound.at(constr_idx) = 0.0; + } + + // initial condition + { + A(constr_idx, IDX_S0) = 1.0; // s0 + upper_bound[constr_idx] = s0; + lower_bound[constr_idx] = s0; + ++constr_idx; + + A(constr_idx, IDX_V0) = 1.0; // v0 + upper_bound[constr_idx] = v0; + lower_bound[constr_idx] = v0; + ++constr_idx; + + A(constr_idx, IDX_A0) = 1.0; // a0 + upper_bound[constr_idx] = a0; + lower_bound[constr_idx] = a0; + } + + // execute optimization + const auto result = qp_solver_.optimize(P, A, q, lower_bound, upper_bound); + const std::vector optval = std::get<0>(result); + + const int status_val = std::get<3>(result); + if (status_val != 1) { + std::cerr << "optimization failed : " << qp_solver_.getStatusMessage().c_str() << std::endl; + } + + std::vector opt_time = time_vec; + std::vector opt_pos(N); + std::vector opt_vel(N); + std::vector opt_acc(N); + std::vector opt_jerk(N); + for (size_t i = 0; i < N; ++i) { + opt_pos.at(i) = optval.at(IDX_S0 + i); + opt_vel.at(i) = std::max(optval.at(IDX_V0 + i), 0.0); + opt_vel.at(i) = + opt_vel.at(i) > 0.01 ? std::min(opt_vel.at(i) + v_margin, v_max) : opt_vel.at(i); + opt_acc.at(i) = optval.at(IDX_A0 + i); + opt_jerk.at(i) = optval.at(IDX_J0 + i); + } + opt_vel.back() = 0.0; + + OptimizationResult optimized_result; + optimized_result.t = opt_time; + optimized_result.s = opt_pos; + optimized_result.v = opt_vel; + optimized_result.a = opt_acc; + optimized_result.j = opt_jerk; + + return optimized_result; +} diff --git a/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp new file mode 100644 index 0000000000000..5d2a6ba7920af --- /dev/null +++ b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -0,0 +1,537 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp" + +#include "obstacle_cruise_planner/utils.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include "tier4_planning_msgs/msg/velocity_limit.hpp" + +namespace +{ +StopSpeedExceeded createStopSpeedExceededMsg( + const rclcpp::Time & current_time, const bool stop_flag) +{ + StopSpeedExceeded msg{}; + msg.stamp = current_time; + msg.stop_speed_exceeded = stop_flag; + return msg; +} + +VelocityLimit createVelocityLimitMsg( + const rclcpp::Time & current_time, const double vel, const double acc, const double max_jerk, + const double min_jerk) +{ + VelocityLimit msg; + msg.stamp = current_time; + msg.sender = "obstacle_cruise_planner"; + msg.use_constraints = true; + + msg.max_velocity = vel; + if (acc < 0) { + msg.constraints.min_acceleration = acc; + } + msg.constraints.max_jerk = max_jerk; + msg.constraints.min_jerk = min_jerk; + + return msg; +} + +Float32MultiArrayStamped convertDebugValuesToMsg( + const rclcpp::Time & current_time, const DebugValues & debug_values) +{ + Float32MultiArrayStamped debug_msg{}; + debug_msg.stamp = current_time; + for (const auto & v : debug_values.getValues()) { + debug_msg.data.push_back(v); + } + return debug_msg; +} + +template +size_t getIndexWithLongitudinalOffset( + const T & points, const double longitudinal_offset, boost::optional start_idx) +{ + if (points.empty()) { + throw std::logic_error("points is empty."); + } + + if (start_idx) { + if (/*start_idx.get() < 0 || */ points.size() <= start_idx.get()) { + throw std::out_of_range("start_idx is out of range."); + } + } else { + if (longitudinal_offset > 0) { + start_idx = 0; + } else { + start_idx = points.size() - 1; + } + } + + double sum_length = 0.0; + if (longitudinal_offset > 0) { + for (size_t i = start_idx.get(); i < points.size() - 1; ++i) { + const double segment_length = + tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i + 1)); + sum_length += segment_length; + if (sum_length >= longitudinal_offset) { + const double front_length = segment_length; + const double back_length = sum_length - longitudinal_offset; + if (front_length < back_length) { + return i; + } else { + return i + 1; + } + } + } + return points.size() - 1; + } + + for (size_t i = start_idx.get(); i > 0; --i) { + const double segment_length = + tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i + 1)); + sum_length += segment_length; + if (sum_length >= -longitudinal_offset) { + const double front_length = segment_length; + const double back_length = sum_length + longitudinal_offset; + if (front_length < back_length) { + return i; + } else { + return i + 1; + } + } + } + return 0; +} + +double calcMinimumDistanceToStop(const double initial_vel, const double min_acc) +{ + return -std::pow(initial_vel, 2) / 2.0 / min_acc; +} + +tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( + const rclcpp::Time & current_time, const geometry_msgs::msg::Pose & stop_pose, + const boost::optional & stop_obstacle_info) +{ + // create header + std_msgs::msg::Header header; + header.frame_id = "map"; + header.stamp = current_time; + + // create stop factor + tier4_planning_msgs::msg::StopFactor stop_factor; + stop_factor.stop_pose = stop_pose; + if (stop_obstacle_info) { + stop_factor.stop_factor_points.emplace_back(stop_obstacle_info->obstacle.collision_point); + } + + // create stop reason stamped + tier4_planning_msgs::msg::StopReason stop_reason_msg; + stop_reason_msg.reason = tier4_planning_msgs::msg::StopReason::OBSTACLE_STOP; + stop_reason_msg.stop_factors.emplace_back(stop_factor); + + // create stop reason array + tier4_planning_msgs::msg::StopReasonArray stop_reason_array; + stop_reason_array.header = header; + stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); + return stop_reason_array; +} +} // namespace + +PIDBasedPlanner::PIDBasedPlanner( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info) +: PlannerInterface(node, longitudinal_info, vehicle_info) +{ + min_accel_during_cruise_ = + node.declare_parameter("pid_based_planner.min_accel_during_cruise"); + + // pid controller + const double kp = node.declare_parameter("pid_based_planner.kp"); + const double ki = node.declare_parameter("pid_based_planner.ki"); + const double kd = node.declare_parameter("pid_based_planner.kd"); + pid_controller_ = std::make_unique(kp, ki, kd); + output_ratio_during_accel_ = + node.declare_parameter("pid_based_planner.output_ratio_during_accel"); + + // some parameters + // use_predicted_obstacle_pose_ = + // node.declare_parameter("pid_based_planner.use_predicted_obstacle_pose"); + + vel_to_acc_weight_ = node.declare_parameter("pid_based_planner.vel_to_acc_weight"); + + min_cruise_target_vel_ = + node.declare_parameter("pid_based_planner.min_cruise_target_vel"); + + obstacle_velocity_threshold_from_cruise_to_stop_ = node.declare_parameter( + "pid_based_planner.obstacle_velocity_threshold_from_cruise_to_stop"); + + // publisher + stop_reasons_pub_ = + node.create_publisher("~/output/stop_reasons", 1); + stop_speed_exceeded_pub_ = + node.create_publisher("~/output/stop_speed_exceeded", 1); + debug_values_pub_ = node.create_publisher("~/debug/values", 1); +} + +Trajectory PIDBasedPlanner::generateTrajectory( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + DebugData & debug_data) +{ + stop_watch_.tic(__func__); + debug_values_.resetValues(); + + // calc obstacles to cruise and stop + boost::optional stop_obstacle_info; + boost::optional cruise_obstacle_info; + calcObstaclesToCruiseAndStop(planner_data, stop_obstacle_info, cruise_obstacle_info); + + // plan cruise + planCruise(planner_data, vel_limit, cruise_obstacle_info, debug_data); + + // plan stop + const auto output_traj = planStop(planner_data, stop_obstacle_info, debug_data); + + // publish debug values + publishDebugValues(planner_data); + + const double calculation_time = stop_watch_.toc(__func__); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), is_showing_debug_info_, + " %s := %f [ms]", __func__, calculation_time); + + return output_traj; +} + +void PIDBasedPlanner::calcObstaclesToCruiseAndStop( + const ObstacleCruisePlannerData & planner_data, + boost::optional & stop_obstacle_info, + boost::optional & cruise_obstacle_info) +{ + debug_values_.setValues(DebugValues::TYPE::CURRENT_VELOCITY, planner_data.current_vel); + debug_values_.setValues(DebugValues::TYPE::CURRENT_ACCELERATION, planner_data.current_acc); + + // search highest probability obstacle for stop and cruise + for (const auto & obstacle : planner_data.target_obstacles) { + // NOTE: from ego's front to obstacle's back + const double dist_to_obstacle = calcDistanceToObstacle(planner_data, obstacle); + + const bool is_stop_required = isStopRequired(obstacle); + if (is_stop_required) { // stop + // calculate error distance (= distance to stop) + const double error_dist = dist_to_obstacle - longitudinal_info_.safe_distance_margin; + if (stop_obstacle_info) { + if (error_dist > stop_obstacle_info->dist_to_stop) { + return; + } + } + stop_obstacle_info = StopObstacleInfo(obstacle, error_dist); + + // update debug values + debug_values_.setValues(DebugValues::TYPE::STOP_CURRENT_OBJECT_DISTANCE, dist_to_obstacle); + debug_values_.setValues(DebugValues::TYPE::STOP_CURRENT_OBJECT_VELOCITY, obstacle.velocity); + debug_values_.setValues( + DebugValues::TYPE::STOP_TARGET_OBJECT_DISTANCE, longitudinal_info_.safe_distance_margin); + debug_values_.setValues( + DebugValues::TYPE::STOP_TARGET_ACCELERATION, longitudinal_info_.min_strong_accel); + debug_values_.setValues(DebugValues::TYPE::STOP_ERROR_OBJECT_DISTANCE, error_dist); + } else { // cruise + // calculate distance between ego and obstacle based on RSS + const double rss_dist = calcRSSDistance( + planner_data.current_vel, obstacle.velocity, longitudinal_info_.safe_distance_margin); + + // calculate error distance and normalized one + const double error_dist = dist_to_obstacle - rss_dist; + if (cruise_obstacle_info) { + if (error_dist > cruise_obstacle_info->dist_to_cruise) { + return; + } + } + const double normalized_dist_to_cruise = error_dist / dist_to_obstacle; + cruise_obstacle_info = CruiseObstacleInfo(obstacle, error_dist, normalized_dist_to_cruise); + + // update debug values + debug_values_.setValues(DebugValues::TYPE::CRUISE_CURRENT_OBJECT_VELOCITY, obstacle.velocity); + debug_values_.setValues(DebugValues::TYPE::CRUISE_CURRENT_OBJECT_DISTANCE, dist_to_obstacle); + debug_values_.setValues(DebugValues::TYPE::CRUISE_TARGET_OBJECT_DISTANCE, rss_dist); + debug_values_.setValues(DebugValues::TYPE::CRUISE_ERROR_OBJECT_DISTANCE, error_dist); + } + } +} + +double PIDBasedPlanner::calcDistanceToObstacle( + const ObstacleCruisePlannerData & planner_data, const TargetObstacle & obstacle) +{ + const double offset = vehicle_info_.max_longitudinal_offset_m; + + // TODO(murooka) enable this option considering collision_point (precise obstacle point to measure + // distance) if (use_predicted_obstacle_pose_) { + // // interpolate current obstacle pose from predicted path + // const auto current_interpolated_obstacle_pose = + // obstacle_cruise_utils::getCurrentObjectPoseFromPredictedPath( + // obstacle.predicted_paths.at(0), obstacle.time_stamp, planner_data.current_time); + // if (current_interpolated_obstacle_pose) { + // return tier4_autoware_utils::calcSignedArcLength( + // planner_data.traj.points, planner_data.current_pose.position, + // current_interpolated_obstacle_pose->position) - offset; + // } + // + // RCLCPP_INFO_EXPRESSION( + // rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), true, + // "Failed to interpolated obstacle pose from predicted path. Use non-interpolated obstacle + // pose."); + // } + + const size_t ego_idx = findExtendedNearestIndex(planner_data.traj, planner_data.current_pose); + return tier4_autoware_utils::calcSignedArcLength( + planner_data.traj.points, ego_idx, obstacle.collision_point) - + offset; +} + +// Note: If stop planning is not required, cruise planning will be done instead. +bool PIDBasedPlanner::isStopRequired(const TargetObstacle & obstacle) +{ + const bool is_cruise_obstacle = isCruiseObstacle(obstacle.classification.label); + const bool is_stop_obstacle = isStopObstacle(obstacle.classification.label); + + if (is_cruise_obstacle) { + return std::abs(obstacle.velocity) < obstacle_velocity_threshold_from_cruise_to_stop_; + } else if (is_stop_obstacle && !is_cruise_obstacle) { + return true; + } + + return false; +} + +Trajectory PIDBasedPlanner::planStop( + const ObstacleCruisePlannerData & planner_data, + const boost::optional & stop_obstacle_info, DebugData & debug_data) +{ + bool will_collide_with_obstacle = false; + + size_t zero_vel_idx = 0; + bool zero_vel_found = false; + if (stop_obstacle_info) { + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), is_showing_debug_info_, + "stop planning"); + + auto local_stop_obstacle_info = stop_obstacle_info.get(); + + // check if the ego will collide with the obstacle with a limit acceleration + const double feasible_dist_to_stop = + calcMinimumDistanceToStop(planner_data.current_vel, longitudinal_info_.min_strong_accel); + if (local_stop_obstacle_info.dist_to_stop < feasible_dist_to_stop) { + will_collide_with_obstacle = true; + local_stop_obstacle_info.dist_to_stop = feasible_dist_to_stop; + } + + // set zero velocity index + const auto opt_zero_vel_idx = doStop( + planner_data, local_stop_obstacle_info, debug_data.obstacles_to_stop, + debug_data.stop_wall_marker); + if (opt_zero_vel_idx) { + zero_vel_idx = opt_zero_vel_idx.get(); + zero_vel_found = true; + } + } + + // generate output trajectory + auto output_traj = planner_data.traj; + if (zero_vel_found) { + // publish stop reason + const auto stop_pose = planner_data.traj.points.at(zero_vel_idx).pose; + const auto stop_reasons_msg = + makeStopReasonArray(planner_data.current_time, stop_pose, stop_obstacle_info); + stop_reasons_pub_->publish(stop_reasons_msg); + + // insert zero_velocity + for (size_t traj_idx = zero_vel_idx; traj_idx < output_traj.points.size(); ++traj_idx) { + output_traj.points.at(traj_idx).longitudinal_velocity_mps = 0.0; + } + } + + // publish stop_speed_exceeded if the ego will collide with the obstacle + const auto stop_speed_exceeded_msg = + createStopSpeedExceededMsg(planner_data.current_time, will_collide_with_obstacle); + stop_speed_exceeded_pub_->publish(stop_speed_exceeded_msg); + + return output_traj; +} + +boost::optional PIDBasedPlanner::doStop( + const ObstacleCruisePlannerData & planner_data, const StopObstacleInfo & stop_obstacle_info, + std::vector & debug_obstacles_to_stop, + visualization_msgs::msg::MarkerArray & debug_wall_marker) const +{ + const size_t ego_idx = findExtendedNearestIndex(planner_data.traj, planner_data.current_pose); + + // TODO(murooka) Should I use interpolation? + const auto modified_stop_info = [&]() -> boost::optional> { + const double dist_to_stop = stop_obstacle_info.dist_to_stop; + + const size_t obstacle_zero_vel_idx = + getIndexWithLongitudinalOffset(planner_data.traj.points, dist_to_stop, ego_idx); + + // check if there is already stop line between obstacle and zero_vel_idx + const auto behavior_zero_vel_idx = + tier4_autoware_utils::searchZeroVelocityIndex(planner_data.traj.points); + if (behavior_zero_vel_idx) { + const double zero_vel_diff_length = tier4_autoware_utils::calcSignedArcLength( + planner_data.traj.points, obstacle_zero_vel_idx, behavior_zero_vel_idx.get()); + if ( + 0 < zero_vel_diff_length && + zero_vel_diff_length < longitudinal_info_.safe_distance_margin) { + const double modified_dist_to_stop = + dist_to_stop + longitudinal_info_.safe_distance_margin - min_behavior_stop_margin_; + const size_t modified_obstacle_zero_vel_idx = + getIndexWithLongitudinalOffset(planner_data.traj.points, modified_dist_to_stop, ego_idx); + return std::make_pair(modified_obstacle_zero_vel_idx, modified_dist_to_stop); + } + } + + return std::make_pair(obstacle_zero_vel_idx, dist_to_stop); + }(); + if (!modified_stop_info) { + return {}; + } + const size_t modified_zero_vel_idx = modified_stop_info->first; + const double modified_dist_to_stop = modified_stop_info->second; + + // virtual wall marker for stop + const auto marker_pose = obstacle_cruise_utils::calcForwardPose( + planner_data.traj, ego_idx, modified_dist_to_stop + vehicle_info_.max_longitudinal_offset_m); + if (marker_pose) { + visualization_msgs::msg::MarkerArray wall_msg; + const auto markers = tier4_autoware_utils::createStopVirtualWallMarker( + marker_pose.get(), "obstacle stop", planner_data.current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &debug_wall_marker); + } + + debug_obstacles_to_stop.push_back(stop_obstacle_info.obstacle); + return modified_zero_vel_idx; +} + +void PIDBasedPlanner::planCruise( + const ObstacleCruisePlannerData & planner_data, boost::optional & vel_limit, + const boost::optional & cruise_obstacle_info, DebugData & debug_data) +{ + // do cruise + if (cruise_obstacle_info) { + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), is_showing_debug_info_, + "cruise planning"); + + vel_limit = doCruise( + planner_data, cruise_obstacle_info.get(), debug_data.obstacles_to_cruise, + debug_data.cruise_wall_marker); + + // update debug values + debug_values_.setValues(DebugValues::TYPE::CRUISE_TARGET_VELOCITY, vel_limit->max_velocity); + debug_values_.setValues( + DebugValues::TYPE::CRUISE_TARGET_ACCELERATION, vel_limit->constraints.min_acceleration); + } else { + // reset previous target velocity if adaptive cruise is not enabled + prev_target_vel_ = {}; + } +} + +VelocityLimit PIDBasedPlanner::doCruise( + const ObstacleCruisePlannerData & planner_data, const CruiseObstacleInfo & cruise_obstacle_info, + std::vector & debug_obstacles_to_cruise, + visualization_msgs::msg::MarkerArray & debug_wall_marker) +{ + const double dist_to_cruise = cruise_obstacle_info.dist_to_cruise; + const double normalized_dist_to_cruise = cruise_obstacle_info.normalized_dist_to_cruise; + + const size_t ego_idx = findExtendedNearestIndex(planner_data.traj, planner_data.current_pose); + + // calculate target velocity with acceleration limit by PID controller + const double pid_output_vel = pid_controller_->calc(normalized_dist_to_cruise); + [[maybe_unused]] const double prev_vel = + prev_target_vel_ ? prev_target_vel_.get() : planner_data.current_vel; + + const double additional_vel = [&]() { + if (normalized_dist_to_cruise > 0) { + return pid_output_vel * output_ratio_during_accel_; + } + return pid_output_vel; + }(); + + const double positive_target_vel = + std::max(min_cruise_target_vel_, planner_data.current_vel + additional_vel); + + // calculate target acceleration + const double target_acc = vel_to_acc_weight_ * additional_vel; + const double target_acc_with_acc_limit = + std::clamp(target_acc, min_accel_during_cruise_, longitudinal_info_.max_accel); + + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), is_showing_debug_info_, + "target_velocity %f", positive_target_vel); + + prev_target_vel_ = positive_target_vel; + + // set target longitudinal motion + const auto vel_limit = createVelocityLimitMsg( + planner_data.current_time, positive_target_vel, target_acc_with_acc_limit, + longitudinal_info_.max_jerk, longitudinal_info_.min_jerk); + + // virtual wall marker for cruise + const double dist_to_rss_wall = dist_to_cruise + vehicle_info_.max_longitudinal_offset_m; + const size_t wall_idx = + getIndexWithLongitudinalOffset(planner_data.traj.points, dist_to_rss_wall, ego_idx); + + const auto markers = tier4_autoware_utils::createSlowDownVirtualWallMarker( + planner_data.traj.points.at(wall_idx).pose, "obstacle cruise", planner_data.current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &debug_wall_marker); + + debug_obstacles_to_cruise.push_back(cruise_obstacle_info.obstacle); + + return vel_limit; +} + +void PIDBasedPlanner::publishDebugValues(const ObstacleCruisePlannerData & planner_data) const +{ + const auto debug_values_msg = convertDebugValuesToMsg(planner_data.current_time, debug_values_); + debug_values_pub_->publish(debug_values_msg); +} + +void PIDBasedPlanner::updateParam(const std::vector & parameters) +{ + tier4_autoware_utils::updateParam( + parameters, "pid_based_planner.min_accel_during_cruise", min_accel_during_cruise_); + + // pid controller + double kp = pid_controller_->getKp(); + double ki = pid_controller_->getKi(); + double kd = pid_controller_->getKd(); + + tier4_autoware_utils::updateParam(parameters, "pid_based_planner.kp", kp); + tier4_autoware_utils::updateParam(parameters, "pid_based_planner.ki", ki); + tier4_autoware_utils::updateParam(parameters, "pid_based_planner.kd", kd); + tier4_autoware_utils::updateParam( + parameters, "pid_based_planner.output_ratio_during_accel", output_ratio_during_accel_); + + // vel_to_acc_weight + tier4_autoware_utils::updateParam( + parameters, "pid_based_planner.vel_to_acc_weight", vel_to_acc_weight_); + + // min_cruise_target_vel + tier4_autoware_utils::updateParam( + parameters, "pid_based_planner.min_cruise_target_vel", min_cruise_target_vel_); + + pid_controller_->updateParam(kp, ki, kd); +} diff --git a/planning/obstacle_cruise_planner/src/polygon_utils.cpp b/planning/obstacle_cruise_planner/src/polygon_utils.cpp new file mode 100644 index 0000000000000..444e9007303d3 --- /dev/null +++ b/planning/obstacle_cruise_planner/src/polygon_utils.cpp @@ -0,0 +1,309 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/polygon_utils.hpp" + +namespace +{ +namespace bg = boost::geometry; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; + +void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) +{ + Point2d point; + point.x() = geom_point.x; + point.y() = geom_point.y; + + bg::append(polygon.outer(), point); +} + +void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point32 & geom_point) +{ + Point2d point; + point.x() = geom_point.x; + point.y() = geom_point.y; + + bg::append(polygon.outer(), point); +} + +void appendPointToPolygon(Polygon2d & polygon, const Point2d point) +{ + bg::append(polygon.outer(), point); +} + +bool isClockWise(const Polygon2d & polygon) +{ + const int n = polygon.outer().size(); + const double x_offset = polygon.outer().at(0).x(); + const double y_offset = polygon.outer().at(0).y(); + double sum = 0.0; + for (std::size_t i = 0; i < polygon.outer().size(); ++i) { + sum += + (polygon.outer().at(i).x() - x_offset) * (polygon.outer().at((i + 1) % n).y() - y_offset) - + (polygon.outer().at(i).y() - y_offset) * (polygon.outer().at((i + 1) % n).x() - x_offset); + } + + return sum < 0.0; +} + +Polygon2d inverseClockWise(const Polygon2d & polygon) +{ + Polygon2d inverted_polygon; + for (int i = polygon.outer().size() - 1; 0 <= i; --i) { + inverted_polygon.outer().push_back(polygon.outer().at(i)); + } + return inverted_polygon; +} + +Polygon2d createOneStepPolygon( + const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) +{ + Polygon2d polygon; + + const double longitudinal_offset = vehicle_info.max_longitudinal_offset_m; + const double width = vehicle_info.vehicle_width_m / 2.0 + expand_width; + const double rear_overhang = vehicle_info.rear_overhang_m; + + { // base step + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0).position); + } + + { // next step + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0).position); + } + + polygon = isClockWise(polygon) ? polygon : inverseClockWise(polygon); + + Polygon2d hull_polygon; + bg::convex_hull(polygon, hull_polygon); + + return hull_polygon; +} +} // namespace + +namespace polygon_utils +{ +Polygon2d convertObstacleToPolygon( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape) +{ + Polygon2d polygon; + + if (shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + const auto point0 = tier4_autoware_utils::calcOffsetPose( + pose, shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) + .position; + const auto point1 = tier4_autoware_utils::calcOffsetPose( + pose, -shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) + .position; + const auto point2 = tier4_autoware_utils::calcOffsetPose( + pose, -shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) + .position; + const auto point3 = tier4_autoware_utils::calcOffsetPose( + pose, shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) + .position; + + appendPointToPolygon(polygon, point0); + appendPointToPolygon(polygon, point1); + appendPointToPolygon(polygon, point2); + appendPointToPolygon(polygon, point3); + + // NOTE: push back the first point in order to close polygon + appendPointToPolygon(polygon, polygon.outer().front()); + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + const double radius = shape.dimensions.x / 2.0; + constexpr int circle_discrete_num = 6; + for (int i = 0; i < circle_discrete_num; ++i) { + geometry_msgs::msg::Point point; + point.x = std::cos( + (static_cast(i) / static_cast(circle_discrete_num)) * 2.0 * M_PI + + M_PI / static_cast(circle_discrete_num)) * + radius + + pose.position.x; + point.y = std::sin( + (static_cast(i) / static_cast(circle_discrete_num)) * 2.0 * M_PI + + M_PI / static_cast(circle_discrete_num)) * + radius + + pose.position.y; + appendPointToPolygon(polygon, point); + } + + // NOTE: push back the first point in order to close polygon + appendPointToPolygon(polygon, polygon.outer().front()); + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + for (const auto point : shape.footprint.points) { + appendPointToPolygon(polygon, point); + } + if (polygon.outer().size() > 0) { + // NOTE: push back the first point in order to close polygon + appendPointToPolygon(polygon, polygon.outer().front()); + } + } else { + throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); + } + + return isClockWise(polygon) ? polygon : inverseClockWise(polygon); +} + +boost::optional getFirstCollisionIndex( + const std::vector & traj_polygons, const Polygon2d & obj_polygon, + std::vector & collision_geom_points) +{ + for (size_t i = 0; i < traj_polygons.size(); ++i) { + std::deque collision_polygons; + boost::geometry::intersection(traj_polygons.at(i), obj_polygon, collision_polygons); + + bool has_collision = false; + for (const auto & collision_polygon : collision_polygons) { + if (boost::geometry::area(collision_polygon) > 0.0) { + has_collision = true; + + for (const auto & collision_point : collision_polygon.outer()) { + geometry_msgs::msg::Point collision_geom_point; + collision_geom_point.x = collision_point.x(); + collision_geom_point.y = collision_point.y(); + collision_geom_points.push_back(collision_geom_point); + } + } + } + + if (has_collision) { + return i; + } + } + + return {}; +} + +boost::optional getFirstNonCollisionIndex( + const std::vector & traj_polygons, + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const autoware_auto_perception_msgs::msg::Shape & shape, const size_t start_idx) +{ + constexpr double epsilon = 1e-3; + + size_t latest_collision_idx = start_idx; + for (const auto & path_point : predicted_path.path) { + const auto obj_polygon = convertObstacleToPolygon(path_point, shape); + for (size_t i = start_idx; i < traj_polygons.size(); ++i) { + const double dist = bg::distance(traj_polygons.at(i), obj_polygon); + if (dist <= epsilon) { + latest_collision_idx = i; + break; + } + if (i == traj_polygons.size() - 1) { + return latest_collision_idx; + } + } + } + return {}; +} + +bool willCollideWithSurroundObstacle( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const std::vector & traj_polygons, + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const autoware_auto_perception_msgs::msg::Shape & shape, const double max_dist, + const double ego_obstacle_overlap_time_threshold, + const double max_prediction_time_for_collision_check) +{ + constexpr double epsilon = 1e-3; + + bool is_found = false; + size_t start_predicted_path_idx = 0; + for (size_t i = 0; i < predicted_path.path.size(); ++i) { + const auto & path_point = predicted_path.path.at(i); + if ( + max_prediction_time_for_collision_check < + rclcpp::Duration(predicted_path.time_step).seconds() * static_cast(i)) { + return false; + } + + for (size_t j = 0; j < traj.points.size(); ++j) { + const auto & traj_point = traj.points.at(j); + const double approximated_dist = + tier4_autoware_utils::calcDistance2d(path_point.position, traj_point.pose.position); + if (approximated_dist > max_dist) { + continue; + } + + const auto & traj_polygon = traj_polygons.at(j); + const auto obj_polygon = polygon_utils::convertObstacleToPolygon(path_point, shape); + const double dist = bg::distance(traj_polygon, obj_polygon); + + if (dist < epsilon) { + if (!is_found) { + start_predicted_path_idx = i; + is_found = true; + } else { + const double overlap_time = (static_cast(i) - start_predicted_path_idx) * + rclcpp::Duration(predicted_path.time_step).seconds(); + if (ego_obstacle_overlap_time_threshold < overlap_time) { + return true; + } + } + } else { + is_found = false; + } + } + } + + return false; +} +std::vector createOneStepPolygons( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) +{ + std::vector polygons; + + for (size_t i = 0; i < traj.points.size(); ++i) { + const auto polygon = [&]() { + if (i == 0) { + return createOneStepPolygon( + traj.points.at(i).pose, traj.points.at(i).pose, vehicle_info, expand_width); + } + return createOneStepPolygon( + traj.points.at(i - 1).pose, traj.points.at(i).pose, vehicle_info, expand_width); + }(); + + polygons.push_back(polygon); + } + return polygons; +} +} // namespace polygon_utils diff --git a/planning/obstacle_cruise_planner/src/utils.cpp b/planning/obstacle_cruise_planner/src/utils.cpp new file mode 100644 index 0000000000000..41be60c4e8726 --- /dev/null +++ b/planning/obstacle_cruise_planner/src/utils.cpp @@ -0,0 +1,111 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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 "obstacle_cruise_planner/utils.hpp" + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +namespace obstacle_cruise_utils +{ +bool isVehicle(const uint8_t label) +{ + return label == ObjectClassification::CAR || label == ObjectClassification::TRUCK || + label == ObjectClassification::BUS || label == ObjectClassification::MOTORCYCLE; +} + +visualization_msgs::msg::Marker getObjectMarker( + const geometry_msgs::msg::Pose & obstacle_pose, size_t idx, const std::string & ns, + const double r, const double g, const double b) +{ + const auto current_time = rclcpp::Clock().now(); + + auto marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, ns, idx, visualization_msgs::msg::Marker::SPHERE, + tier4_autoware_utils::createMarkerScale(2.0, 2.0, 2.0), + tier4_autoware_utils::createMarkerColor(r, g, b, 0.8)); + + marker.lifetime = rclcpp::Duration::from_seconds(0.8); + marker.pose = obstacle_pose; + + return marker; +} + +boost::optional calcForwardPose( + const autoware_auto_planning_msgs::msg::Trajectory & traj, const size_t nearest_idx, + const double target_length) +{ + if (traj.points.empty()) { + return {}; + } + + size_t search_idx = nearest_idx; + double length_to_search_idx = 0.0; + for (; search_idx < traj.points.size(); ++search_idx) { + length_to_search_idx = + tier4_autoware_utils::calcSignedArcLength(traj.points, nearest_idx, search_idx); + if (length_to_search_idx > target_length) { + break; + } else if (search_idx == traj.points.size() - 1) { + return {}; + } + } + + if (search_idx == 0 && !traj.points.empty()) { + return traj.points.at(0).pose; + } + + const auto & pre_pose = traj.points.at(search_idx - 1).pose; + const auto & next_pose = traj.points.at(search_idx).pose; + + geometry_msgs::msg::Pose target_pose; + + // lerp position + const double seg_length = + tier4_autoware_utils::calcDistance2d(pre_pose.position, next_pose.position); + const double lerp_ratio = (length_to_search_idx - target_length) / seg_length; + target_pose.position.x = + pre_pose.position.x + (next_pose.position.x - pre_pose.position.x) * lerp_ratio; + target_pose.position.y = + pre_pose.position.y + (next_pose.position.y - pre_pose.position.y) * lerp_ratio; + target_pose.position.z = + pre_pose.position.z + (next_pose.position.z - pre_pose.position.z) * lerp_ratio; + + // lerp orientation + const double pre_yaw = tf2::getYaw(pre_pose.orientation); + const double next_yaw = tf2::getYaw(next_pose.orientation); + target_pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(pre_yaw + (next_yaw - pre_yaw) * lerp_ratio); + + return target_pose; +} + +boost::optional getCurrentObjectPoseFromPredictedPath( + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const rclcpp::Time & obj_base_time, const rclcpp::Time & current_time) +{ + for (size_t i = 0; i < predicted_path.path.size(); ++i) { + const auto & obj_p = predicted_path.path.at(i); + + const double object_time = + (obj_base_time + rclcpp::Duration(predicted_path.time_step) * static_cast(i) - + current_time) + .seconds(); + if (object_time >= 0) { + return obj_p; + } + } + + return boost::none; +} +} // namespace obstacle_cruise_utils