From 2a1a3ece9c5644e347f245f9542f2d95743523ce Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 00:42:57 +0900 Subject: [PATCH 001/266] fix(dynamic_avoidance): not avoid objects on ego's path (#4407) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance/dynamic_avoidance_module.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 444515f6cd398..e4f121bb9d62d 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -372,7 +372,10 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const bool is_object_on_ego_path = obj_dist_to_path < planner_data_->parameters.vehicle_width / 2.0 + parameters_->min_obj_lat_offset_to_ego_path; - if (is_object_on_ego_path && std::abs(obj_angle) < parameters_->max_front_object_angle) { + const bool is_object_aligned_to_path = + std::abs(obj_angle) < parameters_->max_front_object_angle || + M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); + if (is_object_on_ego_path && is_object_aligned_to_path) { continue; } From a57cabc6ecb0ffd2a3a2ad8600a6bb723ae37fa5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 00:43:28 +0900 Subject: [PATCH 002/266] fix(planning_evaluator): fix typo (#4405) Signed-off-by: Takayuki Murooka --- evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp b/evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp index b9b86e6bd2d12..4d97757c3c33e 100644 --- a/evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp +++ b/evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp @@ -64,10 +64,10 @@ Stat calcTimeToCollision( const double dt = traj_dist / std::abs(p0.longitudinal_velocity_mps); t += dt; for (auto obstacle : obstacles.objects) { - const double obst_dist = + const double obstacle_dist = calcDistance2d(p, obstacle.kinematics.initial_pose_with_covariance.pose); // TODO(Maxime CLEMENT): take shape into consideration - if (obst_dist <= distance_threshold) { + if (obstacle_dist <= distance_threshold) { stat.add(t); break; } From 66e0e139ac7857335ac05f09aa4a9767c8014cae Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 27 Jul 2023 01:53:02 +0900 Subject: [PATCH 003/266] fix(start_planner): not finish start planner when the path is not safe (#4401) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 84b974427005a..d43d73318c570 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -681,7 +681,7 @@ bool StartPlannerModule::isOverlappedWithLane( bool StartPlannerModule::hasFinishedPullOut() const { - if (!status_.back_finished) { + if (!status_.back_finished || !status_.is_safe) { return false; } From ffd2a4b99a128604b42efd40b6228f2b0c0b7cce Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 27 Jul 2023 04:53:39 +0900 Subject: [PATCH 004/266] fix(autoware_auto_geometry): fix typo (#4396) Signed-off-by: kminoda --- .../include/geometry/bounding_box/eigenbox_2d.hpp | 2 +- .../autoware_auto_geometry/test/include/test_bounding_box.hpp | 2 +- .../autoware_auto_geometry/test/include/test_spatial_hash.hpp | 4 ++-- common/autoware_auto_geometry/test/src/test_convex_hull.cpp | 2 +- common/autoware_auto_geometry/test/src/test_hull_pockets.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp b/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp index ae142badec4eb..f050628f32f25 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp +++ b/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp @@ -98,7 +98,7 @@ Covariance2d covariance_2d(const IT begin, const IT end) /// \param[out] eig_vec1 First eigenvector /// \param[out] eig_vec2 Second eigenvector /// \tparam PointT Point type that has at least float members x and y -/// \return A pairt of eigenvalues: The first is the larger eigenvalue +/// \return A pair of eigenvalues: The first is the larger eigenvalue /// \throw std::runtime error if you would get degenerate covariance template std::pair eig_2d( diff --git a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp b/common/autoware_auto_geometry/test/include/test_bounding_box.hpp index 84fa359295613..5e42622b19ce9 100644 --- a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp +++ b/common/autoware_auto_geometry/test/include/test_bounding_box.hpp @@ -336,7 +336,7 @@ TYPED_TEST(BoxTest, Line3) /_/ <-- first guess is suboptimal */ -TYPED_TEST(BoxTest, SuboptInit) +TYPED_TEST(BoxTest, SuboptimalInit) { this->points.insert( this->points.begin(), diff --git a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp b/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp index 8e2c20f10ac73..50e946c416270 100644 --- a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp +++ b/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp @@ -145,9 +145,9 @@ TYPED_TEST(TypedSpatialHashTest, Oob) // loop through all points float32_t r = dr + this->EPS; const uint32_t n_pts = PTS_PER_RING; - const auto & nbrs = hash.near(this->ref, r); + const auto & neighbors = hash.near(this->ref, r); uint32_t points_seen = 0U; - for (const auto itd : nbrs) { + for (const auto itd : neighbors) { const PointT & pt = itd; const float32_t dist = sqrtf((pt.x * pt.x) + (pt.y * pt.y)); ASSERT_LT(dist, r); diff --git a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp b/common/autoware_auto_geometry/test/src/test_convex_hull.cpp index 35ae240863b10..43e3a3ad08adf 100644 --- a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp +++ b/common/autoware_auto_geometry/test/src/test_convex_hull.cpp @@ -139,7 +139,7 @@ TYPED_TEST(TypedConvexHullTest, Quadrilateral) } // test that things get reordered to ccw -TYPED_TEST(TypedConvexHullTest, Quadhull) +TYPED_TEST(TypedConvexHullTest, QuadHull) { std::vector data( {this->make(1, 1, 1), this->make(5, 1, 2), this->make(2, 6, 3), this->make(3, 3, 4), diff --git a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp b/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp index 7e8f510b1272e..2b79d4ff0f22b 100644 --- a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp +++ b/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp @@ -110,7 +110,7 @@ TYPED_TEST(TypedHullPocketsTest, Box) // | | // +------------------------------+ // This should come up with a single box on the top left. -TYPED_TEST(TypedHullPocketsTest, Ushape) +TYPED_TEST(TypedHullPocketsTest, UShape) { const auto polygon = std::vectormake(0, 0, 0))>{ this->make(0, 0, 0), this->make(5, 0, 0), this->make(5, 4.5, 0), this->make(4, 5, 0), From e181dce8de067af5da7e4eb881eea6b233b98ec1 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 27 Jul 2023 05:38:04 +0900 Subject: [PATCH 005/266] refactor(behavior_velocity_stop_line_module): clean stop line module (#4394) Signed-off-by: yutaka --- .../behavior_velocity_stop_line_module/README.md | 12 +++++++----- .../config/stop_line.param.yaml | 3 +-- .../behavior_velocity_stop_line_module/src/debug.cpp | 2 +- .../src/manager.cpp | 4 ++-- .../behavior_velocity_stop_line_module/src/scene.hpp | 2 +- 5 files changed, 12 insertions(+), 11 deletions(-) diff --git a/planning/behavior_velocity_stop_line_module/README.md b/planning/behavior_velocity_stop_line_module/README.md index 5be11c00e814d..3db639c77a7ca 100644 --- a/planning/behavior_velocity_stop_line_module/README.md +++ b/planning/behavior_velocity_stop_line_module/README.md @@ -12,11 +12,13 @@ This module is activated when there is a stop line in a target lane. ### Module Parameters -| Parameter | Type | Description | -| --------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `stop_margin` | double | a margin that the vehicle tries to stop before stop_line | -| `stop_check_dist` | double | when the vehicle is within `stop_check_dist` from stop_line and stopped, move to STOPPED state | -| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) | +| Parameter | Type | Description | +| -------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `stop_margin` | double | a margin that the vehicle tries to stop before stop_line | +| `stop_duration_sec` | double | [s] time parameter for the ego vehicle to stop in front of a stop line | +| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING | +| `use_initialization_stop_state` | bool | A flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. | +| `show_stop_line_collision_check` | bool | A flag to determine whether to show the debug information of collision check with a stop line | ### Inner-workings / Algorithms diff --git a/planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml b/planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml index 12967d753e25b..7b1d82a46f652 100644 --- a/planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml +++ b/planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml @@ -2,10 +2,9 @@ ros__parameters: stop_line: stop_margin: 0.0 - stop_check_dist: 2.0 stop_duration_sec: 1.0 use_initialization_stop_line_state: true hold_stop_margin_distance: 2.0 debug: - show_stopline_collision_check: false # [-] whether to show stopline collision + show_stop_line_collision_check: false # [-] whether to show stopline collision diff --git a/planning/behavior_velocity_stop_line_module/src/debug.cpp b/planning/behavior_velocity_stop_line_module/src/debug.cpp index c3576db3607f6..09949751f4e93 100644 --- a/planning/behavior_velocity_stop_line_module/src/debug.cpp +++ b/planning/behavior_velocity_stop_line_module/src/debug.cpp @@ -87,7 +87,7 @@ visualization_msgs::msg::MarkerArray createStopLineCollisionCheck( visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray() { visualization_msgs::msg::MarkerArray debug_marker_array; - if (planner_param_.show_stopline_collision_check) { + if (planner_param_.show_stop_line_collision_check) { appendMarkerArray( createStopLineCollisionCheck(debug_data_, module_id_), &debug_marker_array, this->clock_->now()); diff --git a/planning/behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_stop_line_module/src/manager.cpp index 86db87ad602cc..390550fc9e563 100644 --- a/planning/behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_stop_line_module/src/manager.cpp @@ -34,8 +34,8 @@ StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node) p.use_initialization_stop_line_state = node.declare_parameter(ns + ".use_initialization_stop_line_state"); // debug - p.show_stopline_collision_check = - node.declare_parameter(ns + ".debug.show_stopline_collision_check"); + p.show_stop_line_collision_check = + node.declare_parameter(ns + ".debug.show_stop_line_collision_check"); } std::vector StopLineModuleManager::getStopLinesWithLaneIdOnPath( diff --git a/planning/behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_stop_line_module/src/scene.hpp index d211d2ef17706..70c67df623c85 100644 --- a/planning/behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_stop_line_module/src/scene.hpp @@ -74,7 +74,7 @@ class StopLineModule : public SceneModuleInterface double stop_duration_sec; double hold_stop_margin_distance; bool use_initialization_stop_line_state; - bool show_stopline_collision_check; + bool show_stop_line_collision_check; }; public: From f72b71bc2a72d199fbb302c26230a19cafd3e9e8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 27 Jul 2023 12:40:46 +0900 Subject: [PATCH 006/266] fix(planning): fix `-Werror=deprecated-declaration` (#4414) fix(planning): fix build error Signed-off-by: satoshi-ota --- .../src/motion_velocity_smoother_node.cpp | 7 ++++--- .../include/obstacle_avoidance_planner/node.hpp | 4 ++-- planning/obstacle_avoidance_planner/src/node.cpp | 4 ++-- .../include/path_smoother/elastic_band_smoother.hpp | 4 ++-- planning/path_smoother/src/elastic_band_smoother.cpp | 4 ++-- 5 files changed, 12 insertions(+), 11 deletions(-) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index b77af629ad7c3..d3c77aa0faa84 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -62,11 +62,12 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions "~/input/external_velocity_limit_mps", 1, std::bind(&MotionVelocitySmootherNode::onExternalVelocityLimit, this, _1)); sub_current_acceleration_ = create_subscription( - "~/input/acceleration", 1, - [this](const AccelWithCovarianceStamped::SharedPtr msg) { current_acceleration_ptr_ = msg; }); + "~/input/acceleration", 1, [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { + current_acceleration_ptr_ = msg; + }); sub_operation_mode_ = create_subscription( "~/input/operation_mode_state", 1, - [this](const OperationModeState::SharedPtr msg) { operation_mode_ = *msg; }); + [this](const OperationModeState::ConstSharedPtr msg) { operation_mode_ = *msg; }); // parameter update set_param_res_ = this->add_on_set_parameters_callback( diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 68e9733bcc12f..97607be30de3f 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -76,7 +76,7 @@ class ObstacleAvoidancePlanner : public rclcpp::Node EgoNearestParam ego_nearest_param_{}; // variables for subscribers - Odometry::SharedPtr ego_state_ptr_; + Odometry::ConstSharedPtr ego_state_ptr_; // interface publisher rclcpp::Publisher::SharedPtr traj_pub_; @@ -97,7 +97,7 @@ class ObstacleAvoidancePlanner : public rclcpp::Node OnSetParametersCallbackHandle::SharedPtr set_param_res_; // subscriber callback function - void onPath(const Path::SharedPtr); + void onPath(const Path::ConstSharedPtr path_ptr); // reset functions void initializePlanning(); diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 42a4c7ab78e65..a135ffdcfa4b7 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -75,7 +75,7 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n path_sub_ = create_subscription( "~/input/path", 1, std::bind(&ObstacleAvoidancePlanner::onPath, this, std::placeholders::_1)); odom_sub_ = create_subscription( - "~/input/odometry", 1, [this](const Odometry::SharedPtr msg) { ego_state_ptr_ = msg; }); + "~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; }); // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); @@ -189,7 +189,7 @@ void ObstacleAvoidancePlanner::resetPreviousData() mpt_optimizer_ptr_->resetPreviousData(); } -void ObstacleAvoidancePlanner::onPath(const Path::SharedPtr path_ptr) +void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) { time_keeper_ptr_->init(); time_keeper_ptr_->tic(__func__); diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index 26bc3b71d8245..1e8f9d76f53f9 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -65,7 +65,7 @@ class ElasticBandSmoother : public rclcpp::Node EgoNearestParam ego_nearest_param_{}; // variables for subscribers - Odometry::SharedPtr ego_state_ptr_; + Odometry::ConstSharedPtr ego_state_ptr_; // variables for previous information std::shared_ptr> prev_optimized_traj_points_ptr_; @@ -88,7 +88,7 @@ class ElasticBandSmoother : public rclcpp::Node OnSetParametersCallbackHandle::SharedPtr set_param_res_; // subscriber callback function - void onPath(const Path::SharedPtr); + void onPath(const Path::ConstSharedPtr path_ptr); // reset functions void initializePlanning(); diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp index 4120b8aba75b8..a959f45e5fbbf 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -71,7 +71,7 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option path_sub_ = create_subscription( "~/input/path", 1, std::bind(&ElasticBandSmoother::onPath, this, std::placeholders::_1)); odom_sub_ = create_subscription( - "~/input/odometry", 1, [this](const Odometry::SharedPtr msg) { ego_state_ptr_ = msg; }); + "~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; }); // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); @@ -134,7 +134,7 @@ void ElasticBandSmoother::resetPreviousData() prev_optimized_traj_points_ptr_ = nullptr; } -void ElasticBandSmoother::onPath(const Path::SharedPtr path_ptr) +void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) { time_keeper_ptr_->init(); time_keeper_ptr_->tic(__func__); From a567bb2177b00c2c48c2d12587d838727b731460 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:45:29 +0900 Subject: [PATCH 007/266] refactor(avoidance): use common safety checker (#4388) * refactor(avoidance): use common safety checker Signed-off-by: satoshi-ota * docs(avoidance): rename params Signed-off-by: satoshi-ota * chore(avoidance): rename variables Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 21 +- .../behavior_path_planner_avoidance_design.md | 44 +- .../avoidance/avoidance_module.hpp | 61 +-- .../utils/avoidance/avoidance_module_data.hpp | 37 +- .../utils/avoidance/utils.hpp | 21 + .../avoidance/avoidance_module.cpp | 377 ++---------------- .../src/scene_module/avoidance/manager.cpp | 20 +- .../src/utils/avoidance/utils.cpp | 177 ++++++++ 8 files changed, 295 insertions(+), 463 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 3a36fcea62e41..3b9165194a3bf 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -13,7 +13,6 @@ enable_bound_clipping: false enable_update_path_when_object_is_gone: false enable_force_avoidance_for_stopped_vehicle: false - enable_safety_check: true enable_yield_maneuver: true enable_yield_maneuver_during_shifting: false disable_path_update: false @@ -133,10 +132,18 @@ # For safety check safety_check: + # safety check configuration + enable: true # [-] + check_current_lane: false # [-] + check_shift_side_lane: true # [-] + check_other_side_lane: false # [-] + check_unavoidable_object: false # [-] + check_other_object: true # [-] + # collision check parameters + check_all_predicted_path: false # [-] + time_resolution: 0.5 # [s] + time_horizon: 10.0 # [s] safety_check_backward_distance: 100.0 # [m] - safety_check_time_horizon: 10.0 # [s] - safety_check_idling_time: 1.5 # [s] - safety_check_accel_for_rss: 2.5 # [m/ss] safety_check_hysteresis_factor: 2.0 # [-] safety_check_ego_offset: 1.0 # [m] @@ -186,12 +193,6 @@ max_jerk: 1.0 # [m/sss] max_acceleration: 1.0 # [m/ss] - target_velocity_matrix: - col_size: 2 - matrix: - [2.78, 13.9, # velocity [m/s] - 0.50, 1.00] # margin [m] - shift_line_pipeline: trim: quantize_filter_threshold: 0.2 diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index 7436c26533000..9be99f705f560 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -485,15 +485,22 @@ The hatched road marking is defined on Lanelet map. See [here](https://github.co ### Safety check -The avoidance module has a safety check logic. The result of safe check is used for yield maneuver. It is enable by setting `enable_safety_check` as `true`. +The avoidance module has a safety check logic. The result of safe check is used for yield maneuver. It is enable by setting `enable` as `true`. ```yaml -enable_safety_check: false - -# For safety check +# safety check configuration +enable: true # [-] +check_current_lane: false # [-] +check_shift_side_lane: true # [-] +check_other_side_lane: false # [-] +check_unavoidable_object: false # [-] +check_other_object: true # [-] + +# collision check parameters +check_all_predicted_path: false # [-] +time_horizon: 10.0 # [s] +idling_time: 1.5 # [s] safety_check_backward_distance: 50.0 # [m] -safety_check_time_horizon: 10.0 # [s] -safety_check_idling_time: 1.5 # [s] safety_check_accel_for_rss: 2.5 # [m/ss] ``` @@ -621,12 +628,9 @@ namespace: `avoidance.` | detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | | detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | | enable_update_path_when_object_is_gone | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | -| enable_safety_check | [-] | bool | Flag to enable safety check. | false | | enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | | enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | -**NOTE:** It has to set both `enable_safety_check` and `enable_yield_maneuver` to enable yield maneuver. - | Name | Unit | Type | Description | Default value | | :------------------------ | ---- | ---- | ----------------------------------------------------------------------------------------------------------------------- | ------------- | | enable_bound_clipping | [-] | bool | Enable clipping left and right bound of drivable area when obstacles are in the drivable area | false | @@ -695,14 +699,20 @@ namespace: `avoidance.target_filtering.` namespace: `avoidance.safety_check.` -| Name | Unit | Type | Description | Default value | -| :----------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | -| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | -| safety_check_time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | -| safety_check_idling_time | [t] | double | Time delay constant that be use for longitudinal margin calculation based on RSS. | 1.5 | -| safety_check_accel_for_rss | [m/ss] | double | Accel constant that be used for longitudinal margin calculation based on RSS. | 2.5 | -| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | -| safety_check_ego_offset | [m] | double | Output new avoidance path **only when** the offset between ego and previous output path is less than this. | 1.0 | +| Name | Unit | Type | Description | Default value | +| :----------------------------- | ---- | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | +| enable | [-] | bool | Enable to use safety check feature. | true | +| check_current_lane | [-] | bool | Check objects on current driving lane. | false | +| check_shift_side_lane | [-] | bool | Check objects on shift side lane. | true | +| check_other_side_lane | [-] | bool | Check objects on other side lane. | false | +| check_unavoidable_object | [-] | bool | Check collision between ego and unavoidable objects. | false | +| check_other_object | [-] | bool | Check collision between ego and non avoidance target objects. | false | +| check_all_predicted_path | [-] | bool | Check all prediction path of safety check target objects. | false | +| time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | +| time_resolution | [s] | double | Time resolution to check lateral/longitudinal margin is enough or not. | 0.5 | +| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | +| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | +| safety_check_ego_offset | [m] | double | Output new avoidance path **only when** the offset between ego and previous output path is less than this. | 1.0 | ### Avoidance maneuver parameters diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index ee81915ea7944..743f0b3b1b804 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -19,6 +19,7 @@ #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner/utils/avoidance/helper.hpp" +#include "behavior_path_planner/utils/safety_check.hpp" #include @@ -256,12 +257,6 @@ class AvoidanceModule : public SceneModuleInterface ObjectData createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const; - /** - * @brief get objects that are driving on adjacent lanes. - * @param left or right lanelets. - */ - ObjectDataArray getAdjacentLaneObjects(const lanelet::ConstLanelets & adjacent_lanes) const; - /** * @brief fill additional data so that the module judges target objects. * @param avoidance data. @@ -481,65 +476,13 @@ class AvoidanceModule : public SceneModuleInterface // safety check - /** - * @brief get shift side adjacent lanes. - * @param path shifter. - * @param forward distance to get. - * @param backward distance to get. - * @return adjacent lanes. - */ - lanelet::ConstLanelets getAdjacentLane( - const PathShifter & path_shifter, const double forward_distance, - const double backward_distance) const; - - /** - * @brief calculate lateral margin from avoidance velocity for safety check. - * @param target velocity. - */ - double getLateralMarginFromVelocity(const double velocity) const; - - /** - * @brief calculate rss longitudinal distance for safety check. - * @param ego velocity. - * @param object velocity. - * @param option for rss calculation. - * @return rss longitudinal distance. - */ - double getRSSLongitudinalDistance( - const double v_ego, const double v_obj, const bool is_front_object) const; - - /** - * @brief check avoidance path safety for surround moving objects. - * @param path shifter. - * @param avoidance path. - * @param debug data. - * @return result. - */ - bool isSafePath( - const PathShifter & path_shifter, ShiftedPath & shifted_path, DebugData & debug) const; - /** * @brief check avoidance path safety for surround moving objects. * @param avoidance path. - * @param shift side lanes. * @param debug data. * @return result. */ - bool isSafePath( - const PathWithLaneId & path, const lanelet::ConstLanelets & check_lanes, - DebugData & debug) const; - - /** - * @brief check predicted points safety. - * @param predicted points. - * @param future time. - * @param object data. - * @param margin data for debug. - * @return result. - */ - bool isEnoughMargin( - const PathPointWithLaneId & p_ego, const double t, const ObjectData & object, - MarginData & margin_data) const; + bool isSafePath(ShiftedPath & shifted_path, DebugData & debug) const; // post process diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 3c01ad20bcebd..b590d452ae03e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -15,6 +15,7 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ +#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include @@ -46,6 +47,8 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; +using marker_utils::CollisionCheckDebug; + struct ObjectParameter { bool is_target{false}; @@ -95,9 +98,6 @@ struct AvoidanceParameters // enable avoidance for all parking vehicle bool enable_force_avoidance_for_stopped_vehicle{false}; - // enable safety check. if avoidance path is NOT safe, the ego will execute yield maneuver - bool enable_safety_check{false}; - // enable yield maneuver. bool enable_yield_maneuver{false}; @@ -177,20 +177,23 @@ struct AvoidanceParameters // for longitudinal direction double longitudinal_collision_margin_time; - // find adjacent lane vehicles - double safety_check_backward_distance; - - // minimum longitudinal margin for vehicles in adjacent lane - double safety_check_min_longitudinal_margin; + // parameters for safety check area + bool enable_safety_check{false}; + bool check_current_lane{false}; + bool check_shift_side_lane{false}; + bool check_other_side_lane{false}; - // safety check time horizon - double safety_check_time_horizon; + // parameters for safety check target. + bool check_unavoidable_object{false}; + bool check_other_object{false}; - // use in RSS calculation - double safety_check_idling_time; + // parameters for collision check. + bool check_all_predicted_path{false}; + double safety_check_time_horizon{0.0}; + double safety_check_time_resolution{0.0}; - // use in RSS calculation - double safety_check_accel_for_rss; + // find adjacent lane vehicles + double safety_check_backward_distance; // transit hysteresis (unsafe to safe) double safety_check_hysteresis_factor; @@ -280,12 +283,6 @@ struct AvoidanceParameters // Maximum lateral acceleration limitation map. std::vector lateral_max_accel_map; - // target velocity matrix - std::vector target_velocity_matrix; - - // matrix col size - size_t col_size; - // parameters depend on object class std::unordered_map object_parameters; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 69803e4cc4dec..8c229b4f26949 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -17,7 +17,9 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_planner/utils/safety_check.hpp" +#include #include #include #include @@ -25,6 +27,10 @@ namespace behavior_path_planner::utils::avoidance { using behavior_path_planner::PlannerData; +using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; +using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; +using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; +using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; bool isOnRight(const ObjectData & obj); @@ -79,11 +85,19 @@ std::vector generateObstaclePolygonsForDrivableArea( const ObjectDataArray & objects, const std::shared_ptr & parameters, const double vehicle_width); +std::vector convertToPredictedPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); + double getLongitudinalVelocity(const Pose & p_ref, const Pose & p_target, const double v); bool isCentroidWithinLanelets( const PredictedObject & object, const lanelet::ConstLanelets & target_lanelets); +lanelet::ConstLanelets getAdjacentLane( + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters, const bool is_right_shift); + lanelet::ConstLanelets getTargetLanelets( const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, const double left_offset, const double right_offset); @@ -139,6 +153,13 @@ AvoidLine fillAdditionalInfo(const AvoidancePlanningData & data, const AvoidLine AvoidLineArray combineRawShiftLinesWithUniqueCheck( const AvoidLineArray & base_lines, const AvoidLineArray & added_lines); + +ExtendedPredictedObject transform( + const PredictedObject & object, const std::shared_ptr & parameters); + +std::vector getSafetyCheckTargetObjects( + const AvoidancePlanningData & data, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters, const bool is_right_shift); } // namespace behavior_path_planner::utils::avoidance #endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 34977b0933019..06ebd6e01b48b 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -44,6 +44,7 @@ namespace behavior_path_planner { +using marker_utils::CollisionCheckDebug; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; @@ -465,7 +466,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de * Check avoidance path safety. For each target objects and the objects in adjacent lanes, * check that there is a certain amount of margin in the lateral and longitudinal direction. */ - data.safe = isSafePath(path_shifter, data.candidate_path, debug); + data.safe = isSafePath(data.candidate_path, debug); } void AvoidanceModule::fillEgoStatus( @@ -1832,371 +1833,55 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) } bool AvoidanceModule::isSafePath( - const PathShifter & path_shifter, ShiftedPath & shifted_path, DebugData & debug) const + ShiftedPath & shifted_path, [[maybe_unused]] DebugData & debug) const { - const auto & p = parameters_; + const auto & p = planner_data_->parameters; - if (!p->enable_safety_check) { + if (!parameters_->enable_safety_check) { return true; // if safety check is disabled, it always return safe. } - const auto & forward_check_distance = p->object_check_forward_distance; - const auto & backward_check_distance = p->safety_check_backward_distance; - const auto check_lanes = - getAdjacentLane(path_shifter, forward_check_distance, backward_check_distance); - - auto path_with_current_velocity = shifted_path.path; - - const size_t ego_idx = planner_data_->findEgoIndex(path_with_current_velocity.points); - utils::clipPathLength(path_with_current_velocity, ego_idx, forward_check_distance, 0.0); - - constexpr double MIN_EGO_VEL_IN_PREDICTION = 1.38; // 5km/h - for (auto & p : path_with_current_velocity.points) { - p.point.longitudinal_velocity_mps = std::max(getEgoSpeed(), MIN_EGO_VEL_IN_PREDICTION); - } - - { - debug_data_.path_with_planned_velocity = path_with_current_velocity; - } - - return isSafePath(path_with_current_velocity, check_lanes, debug); -} - -bool AvoidanceModule::isSafePath( - const PathWithLaneId & path, const lanelet::ConstLanelets & check_lanes, DebugData & debug) const -{ - if (path.points.empty()) { - return true; - } - - const auto path_with_time = [&path]() { - std::vector> ret{}; - - float travel_time = 0.0; - ret.emplace_back(path.points.front(), travel_time); + const auto ego_predicted_path = + utils::avoidance::convertToPredictedPath(shifted_path.path, planner_data_, parameters_); - for (size_t i = 1; i < path.points.size(); ++i) { - const auto & p1 = path.points.at(i - 1); - const auto & p2 = path.points.at(i); + const auto ego_idx = planner_data_->findEgoIndex(shifted_path.path.points); + const auto is_right_shift = [&]() -> std::optional { + for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { + const auto length = shifted_path.shift_length.at(i); - const auto v = std::max(p1.point.longitudinal_velocity_mps, float{1.0}); - const auto ds = calcDistance2d(p1, p2); - - travel_time += ds / v; - - ret.emplace_back(p2, travel_time); - } - - return ret; - }(); - - const auto move_objects = getAdjacentLaneObjects(check_lanes); - - { - debug.unsafe_objects.clear(); - debug.margin_data_array.clear(); - debug.exist_adjacent_objects = !move_objects.empty(); - } - - bool is_safe = true; - for (const auto & p : path_with_time) { - MarginData margin_data{}; - margin_data.pose = getPose(p.first); - - if (p.second > parameters_->safety_check_time_horizon) { - break; - } - - for (const auto & o : move_objects) { - const auto is_enough_margin = isEnoughMargin(p.first, p.second, o, margin_data); - - if (!is_enough_margin) { - debug.unsafe_objects.push_back(o); + if (parameters_->lateral_avoid_check_threshold < length) { + return false; } - is_safe = is_safe && is_enough_margin; - } - - debug.margin_data_array.push_back(margin_data); - } - - return is_safe; -} - -bool AvoidanceModule::isEnoughMargin( - const PathPointWithLaneId & p_ego, const double t, const ObjectData & object, - MarginData & margin_data) const -{ - const auto & common_param = planner_data_->parameters; - const auto & vehicle_width = common_param.vehicle_width; - const auto & base_link2front = common_param.base_link2front; - const auto & base_link2rear = common_param.base_link2rear; - - const auto p_ref = [this, &p_ego]() { - const auto idx = findNearestIndex(avoidance_data_.reference_path.points, getPoint(p_ego)); - return getPose(avoidance_data_.reference_path.points.at(idx)); - }(); - - const auto & v_ego = p_ego.point.longitudinal_velocity_mps; - const auto & v_ego_lon = utils::avoidance::getLongitudinalVelocity(p_ref, getPose(p_ego), v_ego); - const auto & v_obj = object.object.kinematics.initial_twist_with_covariance.twist.linear.x; - - if (!utils::avoidance::isTargetObjectType(object.object, parameters_)) { - return true; - } - - // | centerline - // | ^ x - // | +-------+ | - // | | | | - // | | | D1 | D2 D4 - // | | obj |<-->|<---------->|<->| - // | | | D3 | +-------+ - // | | |<----------->| | - // | +-------+ | | | - // | | | ego | - // | | | | - // | | | | - // | | +-------+ - // | y <----+ - // D1: overhang_dist (signed value) - // D2: shift_length (signed value) - // D3: lateral_distance (should be larger than margin that's calculated from relative velocity.) - // D4: vehicle_width (unsigned value) - - const auto reliable_path = std::max_element( - object.object.kinematics.predicted_paths.begin(), - object.object.kinematics.predicted_paths.end(), - [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); - - if (reliable_path == object.object.kinematics.predicted_paths.end()) { - return true; - } - - const auto p_obj = [&t, &reliable_path]() { - boost::optional ret{boost::none}; - - const auto dt = rclcpp::Duration(reliable_path->time_step).seconds(); - const auto idx = static_cast(std::floor(t / dt)); - const auto res = t - dt * idx; - - if (idx > reliable_path->path.size() - 2) { - return ret; + if (parameters_->lateral_avoid_check_threshold < -1.0 * length) { + return true; + } } - const auto & p_src = reliable_path->path.at(idx); - const auto & p_dst = reliable_path->path.at(idx + 1); - ret = calcInterpolatedPose(p_src, p_dst, res / dt); - return ret; + return std::nullopt; }(); - if (!p_obj) { - return true; - } - - const auto v_obj_lon = utils::avoidance::getLongitudinalVelocity(p_ref, p_obj.get(), v_obj); - - double hysteresis_factor = 1.0; - if (avoidance_data_.state == AvoidanceState::YIELD) { - hysteresis_factor = parameters_->safety_check_hysteresis_factor; - } - - const auto shift_length = calcLateralDeviation(p_ref, getPoint(p_ego)); - const auto lateral_distance = std::abs(object.overhang_dist - shift_length) - 0.5 * vehicle_width; - const auto lateral_margin = getLateralMarginFromVelocity(std::abs(v_ego_lon - v_obj_lon)); - - if (lateral_distance > lateral_margin * hysteresis_factor) { - return true; - } - - const auto lon_deviation = calcLongitudinalDeviation(getPose(p_ego), p_obj.get().position); - const auto is_front_object = lon_deviation > 0.0; - const auto longitudinal_margin = - getRSSLongitudinalDistance(v_ego_lon, v_obj_lon, is_front_object); - const auto vehicle_offset = is_front_object ? base_link2front : base_link2rear; - const auto longitudinal_distance = - std::abs(lon_deviation) - vehicle_offset - 0.5 * object.object.shape.dimensions.x; - - { - margin_data.pose.orientation = p_ref.orientation; - margin_data.enough_lateral_margin = false; - margin_data.longitudinal_distance = - std::min(margin_data.longitudinal_distance, longitudinal_distance); - margin_data.longitudinal_margin = - std::max(margin_data.longitudinal_margin, longitudinal_margin); - margin_data.vehicle_width = vehicle_width; - margin_data.base_link2front = base_link2front; - margin_data.base_link2rear = base_link2rear; - } - - if (longitudinal_distance > longitudinal_margin * hysteresis_factor) { + if (!is_right_shift.has_value()) { return true; } - return false; -} - -double AvoidanceModule::getLateralMarginFromVelocity(const double velocity) const -{ - const auto & p = parameters_; - - if (p->col_size < 2 || p->col_size * 2 != p->target_velocity_matrix.size()) { - throw std::logic_error("invalid matrix col size."); - } - - if (velocity < p->target_velocity_matrix.front()) { - return p->target_velocity_matrix.at(p->col_size); - } - - if (velocity > p->target_velocity_matrix.at(p->col_size - 1)) { - return p->target_velocity_matrix.back(); - } - - for (size_t i = 1; i < p->col_size; ++i) { - if (velocity < p->target_velocity_matrix.at(i)) { - const auto v1 = p->target_velocity_matrix.at(i - 1); - const auto v2 = p->target_velocity_matrix.at(i); - const auto m1 = p->target_velocity_matrix.at(i - 1 + p->col_size); - const auto m2 = p->target_velocity_matrix.at(i + p->col_size); - - const auto v_clamp = std::clamp(velocity, v1, v2); - return m1 + (m2 - m1) * (v_clamp - v1) / (v2 - v1); - } - } - - return p->target_velocity_matrix.back(); -} + const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects( + avoidance_data_, planner_data_, parameters_, is_right_shift.value()); -double AvoidanceModule::getRSSLongitudinalDistance( - const double v_ego, const double v_obj, const bool is_front_object) const -{ - const auto & accel_for_rss = parameters_->safety_check_accel_for_rss; - const auto & idling_time = parameters_->safety_check_idling_time; - - const auto opposite_lane_vehicle = v_obj < 0.0; - - /** - * object and ego already pass each other. - * ======================================= - * Ego--> - * --------------------------------------- - * <--Obj - * ======================================= - */ - if (!is_front_object && opposite_lane_vehicle) { - return 0.0; - } - - /** - * object drive opposite direction. - * ======================================= - * Ego--> - * --------------------------------------- - * <--Obj - * ======================================= - */ - if (is_front_object && opposite_lane_vehicle) { - return v_ego * idling_time + 0.5 * accel_for_rss * std::pow(idling_time, 2.0) + - std::pow(v_ego + accel_for_rss * idling_time, 2.0) / (2.0 * accel_for_rss) + - std::abs(v_obj) * idling_time + 0.5 * accel_for_rss * std::pow(idling_time, 2.0) + - std::pow(v_obj + accel_for_rss * idling_time, 2.0) / (2.0 * accel_for_rss); - } - - /** - * object is in front of ego, and drive same direction. - * ======================================= - * Ego--> - * --------------------------------------- - * Obj--> - * ======================================= - */ - if (is_front_object && !opposite_lane_vehicle) { - return v_ego * idling_time + 0.5 * accel_for_rss * std::pow(idling_time, 2.0) + - std::pow(v_ego + accel_for_rss * idling_time, 2.0) / (2.0 * accel_for_rss) - - std::pow(v_obj, 2.0) / (2.0 * accel_for_rss); - } - - /** - * object is behind ego, and drive same direction. - * ======================================= - * Ego--> - * --------------------------------------- - * Obj--> - * ======================================= - */ - if (!is_front_object && !opposite_lane_vehicle) { - return v_obj * idling_time + 0.5 * accel_for_rss * std::pow(idling_time, 2.0) + - std::pow(v_obj + accel_for_rss * idling_time, 2.0) / (2.0 * accel_for_rss) - - std::pow(v_ego, 2.0) / (2.0 * accel_for_rss); - } - - return 0.0; -} - -lanelet::ConstLanelets AvoidanceModule::getAdjacentLane( - const PathShifter & path_shifter, const double forward_distance, - const double backward_distance) const -{ - const auto & rh = planner_data_->route_handler; - - bool has_left_shift = false; - bool has_right_shift = false; - - for (const auto & sp : path_shifter.getShiftLines()) { - if (sp.end_shift_length > 0.01) { - has_left_shift = true; - continue; - } - - if (sp.end_shift_length < -0.01) { - has_right_shift = true; - continue; - } - } - - lanelet::ConstLanelet current_lane; - if (!rh->getClosestLaneletWithinRoute(getEgoPose(), ¤t_lane)) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("avoidance"), - "failed to find closest lanelet within route!!!"); - return {}; // TODO(Satoshi Ota) - } - - const auto ego_succeeding_lanes = - rh->getLaneletSequence(current_lane, getEgoPose(), backward_distance, forward_distance); - - lanelet::ConstLanelets check_lanes{}; - for (const auto & lane : ego_succeeding_lanes) { - const auto opt_left_lane = rh->getLeftLanelet(lane); - if (has_left_shift && opt_left_lane) { - check_lanes.push_back(opt_left_lane.get()); - } - - const auto opt_right_lane = rh->getRightLanelet(lane); - if (has_right_shift && opt_right_lane) { - check_lanes.push_back(opt_right_lane.get()); - } - - const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane); - if (has_right_shift && !right_opposite_lanes.empty()) { - check_lanes.push_back(right_opposite_lanes.front()); - } - } - - return check_lanes; -} - -ObjectDataArray AvoidanceModule::getAdjacentLaneObjects( - const lanelet::ConstLanelets & adjacent_lanes) const -{ - ObjectDataArray objects; - for (const auto & o : avoidance_data_.other_objects) { - if (utils::avoidance::isCentroidWithinLanelets(o.object, adjacent_lanes)) { - objects.push_back(o); + for (const auto & object : safety_check_target_objects) { + const auto obj_predicted_paths = + utils::getPredictedPathFromObj(object, parameters_->check_all_predicted_path); + for (const auto & obj_path : obj_predicted_paths) { + CollisionCheckDebug collision{}; + if (!utils::safety_check::checkCollision( + shifted_path.path, ego_predicted_path, object, obj_path, p, + p.expected_front_deceleration, p.expected_rear_deceleration, collision)) { + return false; + } } } - return objects; + return true; } void AvoidanceModule::generateExtendedDrivableArea(BehaviorModuleOutput & output) const diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 1ba7c588c84d6..29b3535331547 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -59,7 +59,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( get_parameter(node, ns + "enable_update_path_when_object_is_gone"); p.enable_force_avoidance_for_stopped_vehicle = get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); - p.enable_safety_check = get_parameter(node, ns + "enable_safety_check"); p.enable_yield_maneuver = get_parameter(node, ns + "enable_yield_maneuver"); p.enable_yield_maneuver_during_shifting = get_parameter(node, ns + "enable_yield_maneuver_during_shifting"); @@ -140,11 +139,17 @@ AvoidanceModuleManager::AvoidanceModuleManager( // safety check { std::string ns = "avoidance.safety_check."; + p.enable_safety_check = get_parameter(node, ns + "enable"); + p.check_current_lane = get_parameter(node, ns + "check_current_lane"); + p.check_shift_side_lane = get_parameter(node, ns + "check_shift_side_lane"); + p.check_other_side_lane = get_parameter(node, ns + "check_other_side_lane"); + p.check_unavoidable_object = get_parameter(node, ns + "check_unavoidable_object"); + p.check_other_object = get_parameter(node, ns + "check_other_object"); + p.check_all_predicted_path = get_parameter(node, ns + "check_all_predicted_path"); + p.safety_check_time_horizon = get_parameter(node, ns + "time_horizon"); + p.safety_check_time_resolution = get_parameter(node, ns + "time_resolution"); p.safety_check_backward_distance = get_parameter(node, ns + "safety_check_backward_distance"); - p.safety_check_time_horizon = get_parameter(node, ns + "safety_check_time_horizon"); - p.safety_check_idling_time = get_parameter(node, ns + "safety_check_idling_time"); - p.safety_check_accel_for_rss = get_parameter(node, ns + "safety_check_accel_for_rss"); p.safety_check_hysteresis_factor = get_parameter(node, ns + "safety_check_hysteresis_factor"); p.safety_check_ego_offset = get_parameter(node, ns + "safety_check_ego_offset"); @@ -227,13 +232,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( } } - // velocity matrix - { - std::string ns = "avoidance.target_velocity_matrix."; - p.col_size = get_parameter(node, ns + "col_size"); - p.target_velocity_matrix = get_parameter>(node, ns + "matrix"); - } - // shift line pipeline { std::string ns = "avoidance.shift_line_pipeline."; diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index d3c31d688557d..58beaf9cf3a87 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -1367,4 +1367,181 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck( return combined; } + +std::vector convertToPredictedPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + if (path.points.empty()) { + return {}; + } + + const auto & acceleration = parameters->max_acceleration; + const auto & vehicle_pose = planner_data->self_odometry->pose.pose; + const auto & initial_velocity = std::abs(planner_data->self_odometry->twist.twist.linear.x); + const auto & time_horizon = parameters->safety_check_time_horizon; + const auto & time_resolution = parameters->safety_check_time_resolution; + + const size_t ego_seg_idx = planner_data->findEgoSegmentIndex(path.points); + std::vector predicted_path; + const auto vehicle_pose_frenet = + convertToFrenetPoint(path.points, vehicle_pose.position, ego_seg_idx); + + for (double t = 0.0; t < time_horizon + 1e-3; t += time_resolution) { + const double velocity = + std::max(initial_velocity + acceleration * t, parameters->min_slow_down_speed); + const double length = initial_velocity * t + 0.5 * acceleration * t * t; + const auto pose = + motion_utils::calcInterpolatedPose(path.points, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); + } + + return predicted_path; +} + +ExtendedPredictedObject transform( + const PredictedObject & object, const std::shared_ptr & parameters) +{ + ExtendedPredictedObject extended_object; + extended_object.uuid = object.object_id; + extended_object.initial_pose = object.kinematics.initial_pose_with_covariance; + extended_object.initial_twist = object.kinematics.initial_twist_with_covariance; + extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; + extended_object.shape = object.shape; + + const auto & obj_velocity = extended_object.initial_twist.twist.linear.x; + const auto & time_horizon = parameters->safety_check_time_horizon; + const auto & time_resolution = parameters->safety_check_time_resolution; + + extended_object.predicted_paths.resize(object.kinematics.predicted_paths.size()); + for (size_t i = 0; i < object.kinematics.predicted_paths.size(); ++i) { + const auto & path = object.kinematics.predicted_paths.at(i); + extended_object.predicted_paths.at(i).confidence = path.confidence; + + // create path + for (double t = 0.0; t < time_horizon + 1e-3; t += time_resolution) { + const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); + if (obj_pose) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(*obj_pose, object.shape); + extended_object.predicted_paths.at(i).path.emplace_back( + t, *obj_pose, obj_velocity, obj_polygon); + } + } + } + + return extended_object; +} + +lanelet::ConstLanelets getAdjacentLane( + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters, const bool is_right_shift) +{ + const auto & rh = planner_data->route_handler; + const auto & forward_distance = parameters->object_check_forward_distance; + const auto & backward_distance = parameters->safety_check_backward_distance; + const auto & vehicle_pose = planner_data->self_odometry->pose.pose; + + lanelet::ConstLanelet current_lane; + if (!rh->getClosestLaneletWithinRoute(vehicle_pose, ¤t_lane)) { + RCLCPP_ERROR( + rclcpp::get_logger("behavior_path_planner").get_child("avoidance"), + "failed to find closest lanelet within route!!!"); + return {}; // TODO(Satoshi Ota) + } + + const auto ego_succeeding_lanes = + rh->getLaneletSequence(current_lane, vehicle_pose, backward_distance, forward_distance); + + lanelet::ConstLanelets lanes{}; + for (const auto & lane : ego_succeeding_lanes) { + const auto opt_left_lane = rh->getLeftLanelet(lane); + if (!is_right_shift && opt_left_lane) { + lanes.push_back(opt_left_lane.get()); + } + + const auto opt_right_lane = rh->getRightLanelet(lane); + if (is_right_shift && opt_right_lane) { + lanes.push_back(opt_right_lane.get()); + } + + const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane); + if (is_right_shift && !right_opposite_lanes.empty()) { + lanes.push_back(right_opposite_lanes.front()); + } + } + + return lanes; +} + +std::vector getSafetyCheckTargetObjects( + const AvoidancePlanningData & data, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters, const bool is_right_shift) +{ + const auto & p = parameters; + const auto check_right_lanes = + (is_right_shift && p->check_shift_side_lane) || (!is_right_shift && p->check_other_side_lane); + const auto check_left_lanes = + (!is_right_shift && p->check_shift_side_lane) || (is_right_shift && p->check_other_side_lane); + + std::vector target_objects; + + const auto append_target_objects = [&](const auto & check_lanes, const auto & objects) { + std::for_each(objects.begin(), objects.end(), [&](const auto & object) { + if (isCentroidWithinLanelets(object.object, check_lanes)) { + target_objects.push_back(utils::avoidance::transform(object.object, p)); + } + }); + }; + + const auto unavoidable_objects = [&data]() { + ObjectDataArray ret; + std::for_each(data.target_objects.begin(), data.target_objects.end(), [&](const auto & object) { + if (!object.is_avoidable) { + ret.push_back(object); + } + }); + return ret; + }(); + + // check right lanes + if (check_right_lanes) { + const auto check_lanes = getAdjacentLane(planner_data, p, true); + + if (p->check_other_object) { + append_target_objects(check_lanes, data.other_objects); + } + + if (p->check_unavoidable_object) { + append_target_objects(check_lanes, unavoidable_objects); + } + } + + // check left lanes + if (check_left_lanes) { + const auto check_lanes = getAdjacentLane(planner_data, p, false); + + if (p->check_other_object) { + append_target_objects(check_lanes, data.other_objects); + } + + if (p->check_unavoidable_object) { + append_target_objects(check_lanes, unavoidable_objects); + } + } + + // check current lanes + if (p->check_current_lane) { + const auto check_lanes = data.current_lanelets; + + if (p->check_other_object) { + append_target_objects(check_lanes, data.other_objects); + } + + if (p->check_unavoidable_object) { + append_target_objects(check_lanes, unavoidable_objects); + } + } + + return target_objects; +} } // namespace behavior_path_planner::utils::avoidance From 59c67ccc05b84c7a4d6be264c4ba8e9481236921 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:55:16 +0900 Subject: [PATCH 008/266] ci: enable spell-check-partial for common (#4397) Signed-off-by: kminoda Co-authored-by: Kotaro Yoshimoto --- .cspell-partial.json | 1 - 1 file changed, 1 deletion(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index 209882ddc2f99..ae92ec76f9546 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -1,6 +1,5 @@ { "ignorePaths": [ - "**/common/**", "**/control/**", "**/evaluator/**", "**/launch/**", From 311353995c2ea8916e63327f684f4e61d873c213 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 27 Jul 2023 14:40:18 +0900 Subject: [PATCH 009/266] fix(start_planner): fix status and candidate path when generationStopOutput (#4408) Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.hpp | 4 +- .../start_planner/pull_out_planner_base.hpp | 1 + .../start_planner/start_planner_module.cpp | 56 +++++++++---------- 3 files changed, 30 insertions(+), 31 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 205b3c6d4db46..6f2598de355e5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -152,8 +152,8 @@ class StartPlannerModule : public SceneModuleInterface // check if the goal is located behind the ego in the same route segment. bool IsGoalBehindOfEgoInSameRouteSegment() const; - // generate BehaviorPathOutput with stopping path. - BehaviorModuleOutput generateStopOutput() const; + // generate BehaviorPathOutput with stopping path and update status + BehaviorModuleOutput generateStopOutput(); void setDebugData() const; }; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp index b95d247b6d23f..3a2087083b427 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp @@ -39,6 +39,7 @@ enum class PlannerType { NONE = 0, SHIFT = 1, GEOMETRIC = 2, + STOP = 3, }; class PullOutPlannerBase diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index d43d73318c570..e2d62ec5c0d3f 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -166,7 +166,9 @@ BehaviorModuleOutput StartPlannerModule::plan() if (IsGoalBehindOfEgoInSameRouteSegment()) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); - return generateStopOutput(); + const auto output = generateStopOutput(); + setDebugData(); // use status updated in generateStopOutput() + return output; } if (isWaitingApproval()) { @@ -181,18 +183,8 @@ BehaviorModuleOutput StartPlannerModule::plan() if (!status_.is_safe) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); - // the path of getCurrent() is generated by generateStopPath() - const PathWithLaneId stop_path = getCurrentPath(); - output.path = std::make_shared(stop_path); - - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = status_.lanes; - output.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); - - output.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = std::make_shared(stop_path); - path_reference_ = getPreviousModuleOutput().reference_path; + const auto output = generateStopOutput(); + setDebugData(); // use status updated in generateStopOutput() return output; } @@ -312,18 +304,20 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() if (IsGoalBehindOfEgoInSameRouteSegment()) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); - path_reference_ = getPreviousModuleOutput().reference_path; clearWaitingApproval(); - return generateStopOutput(); + const auto output = generateStopOutput(); + setDebugData(); // use status updated in generateStopOutput() + return output; } BehaviorModuleOutput output; if (!status_.is_safe) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); - path_reference_ = getPreviousModuleOutput().reference_path; clearWaitingApproval(); - return generateStopOutput(); + const auto output = generateStopOutput(); + setDebugData(); // use status updated in generateStopOutput() + return output; } waitApproval(); @@ -578,16 +572,6 @@ void StartPlannerModule::updatePullOutStatus() std::vector start_pose_candidates = searchPullOutStartPoses(); planWithPriority(start_pose_candidates, goal_pose, parameters_->search_priority); - if (!status_.is_safe) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 5000, "Not found safe pull out path, generate stop path"); - status_.back_finished = true; // no need to drive backward - status_.pull_out_path.partial_paths.clear(); - status_.pull_out_path.partial_paths.push_back(generateStopPath()); - status_.pull_out_path.start_pose = current_pose; - status_.pull_out_path.end_pose = current_pose; - } - checkBackFinished(); if (!status_.back_finished) { status_.backward_path = start_planner_utils::getBackwardPath( @@ -881,10 +865,11 @@ bool StartPlannerModule::IsGoalBehindOfEgoInSameRouteSegment() const } // NOTE: this must be called after updatePullOutStatus(). This must be fixed. -BehaviorModuleOutput StartPlannerModule::generateStopOutput() const +BehaviorModuleOutput StartPlannerModule::generateStopOutput() { BehaviorModuleOutput output; - output.path = std::make_shared(generateStopPath()); + const PathWithLaneId stop_path = generateStopPath(); + output.path = std::make_shared(stop_path); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = status_.lanes; @@ -892,6 +877,19 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() const current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); output.reference_path = getPreviousModuleOutput().reference_path; + + status_.back_finished = true; + status_.planner_type = PlannerType::STOP; + status_.pull_out_path.partial_paths.clear(); + status_.pull_out_path.partial_paths.push_back(stop_path); + const Pose & current_pose = planner_data_->self_odometry->pose.pose; + status_.pull_out_start_pose = current_pose; + status_.pull_out_path.start_pose = current_pose; + status_.pull_out_path.end_pose = current_pose; + + path_candidate_ = std::make_shared(stop_path); + path_reference_ = getPreviousModuleOutput().reference_path; + return output; } From 935484d00ca48912201619346771b07e776c01bb Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Thu, 27 Jul 2023 14:56:21 +0900 Subject: [PATCH 010/266] fix(image_projection_based_fusion): revert the swap of postprocess and publish (#4400) fix: revert the swap of postprocess and publish Signed-off-by: tzhong518 --- .../image_projection_based_fusion/src/fusion_node.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index f76af5060316c..9ce34d8482fbd 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -166,8 +166,8 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ if (sub_std_pair_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); timer_->cancel(); - publish(*(sub_std_pair_.second)); postprocess(*(sub_std_pair_.second)); + publish(*(sub_std_pair_.second)); sub_std_pair_.second = nullptr; std::fill(is_fused_.begin(), is_fused_.end(), false); @@ -260,8 +260,8 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ // Msg if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast(rois_number_)) { timer_->cancel(); - publish(*output_msg); postprocess(*output_msg); + publish(*output_msg); std::fill(is_fused_.begin(), is_fused_.end(), false); sub_std_pair_.second = nullptr; @@ -322,8 +322,8 @@ void FusionNode::roiCallback( if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast(rois_number_)) { timer_->cancel(); - publish(*(sub_std_pair_.second)); postprocess(*(sub_std_pair_.second)); + publish(*(sub_std_pair_.second)); std::fill(is_fused_.begin(), is_fused_.end(), false); sub_std_pair_.second = nullptr; @@ -362,8 +362,8 @@ void FusionNode::timer_callback() if (sub_std_pair_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); - publish(*(sub_std_pair_.second)); postprocess(*(sub_std_pair_.second)); + publish(*(sub_std_pair_.second)); // add processing time for debug if (debug_publisher_) { From 0205955e4418fd2390b16ac1c46c77bfdae5e659 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 27 Jul 2023 15:50:27 +0900 Subject: [PATCH 011/266] refactor(behavior_path_planner): clean up interface (#4415) * refactor(interface): remove unused functions Signed-off-by: satoshi-ota * refactor(utils): move to utils Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../avoidance/avoidance_module.hpp | 1 - .../dynamic_avoidance_module.hpp | 1 - .../goal_planner/goal_planner_module.hpp | 1 - .../scene_module/scene_module_interface.hpp | 37 +------------------ .../side_shift/side_shift_module.hpp | 1 - .../start_planner/start_planner_module.hpp | 1 - .../behavior_path_planner/utils/utils.hpp | 4 ++ .../goal_planner/goal_planner_module.cpp | 6 ++- .../start_planner/start_planner_module.cpp | 6 ++- .../behavior_path_planner/src/utils/utils.cpp | 10 +++++ 10 files changed, 24 insertions(+), 44 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 743f0b3b1b804..e4349c68cc0f5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -52,7 +52,6 @@ class AvoidanceModule : public SceneModuleInterface const std::unordered_map > & rtc_interface_ptr_map); ModuleStatus updateState() override; - ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index d43e1d08050e7..4d90c15e7de4e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -132,7 +132,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool isExecutionRequested() const override; bool isExecutionReady() const override; ModuleStatus updateState() override; - ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } BehaviorModuleOutput plan() override; CandidateOutput planCandidate() const override; BehaviorModuleOutput planWaitingApproval() override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 178ae5bc79e2b..abad4b9f2959f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -101,7 +101,6 @@ class GoalPlannerModule : public SceneModuleInterface bool isExecutionRequested() const override; bool isExecutionReady() const override; ModuleStatus updateState() override; - ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; void processOnEntry() override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 98dd98c707a23..371169c86db4e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -100,12 +100,6 @@ class SceneModuleInterface */ virtual void updateCurrentState() { current_state_ = updateState(); } - /** - * @brief If the module plan customized reference path while waiting approval, it should output - * SUCCESS. Otherwise, it should output FAILURE to check execution request of next module. - */ - virtual ModuleStatus getNodeStatusWhileWaitingApproval() const { return ModuleStatus::FAILURE; } - /** * @brief Return true if the module has request for execution (not necessarily feasible) */ @@ -135,8 +129,8 @@ class SceneModuleInterface // for new architecture const auto lanes = utils::getLaneletsFromPath(*out.path, planner_data_->route_handler); const auto drivable_lanes = utils::generateDrivableLanes(lanes); - out.drivable_area_info.drivable_lanes = - getNonOverlappingExpandedLanes(*out.path, drivable_lanes); + out.drivable_area_info.drivable_lanes = utils::getNonOverlappingExpandedLanes( + *out.path, drivable_lanes, planner_data_->drivable_area_expansion_parameters); return out; } @@ -381,21 +375,6 @@ class SceneModuleInterface BehaviorModuleOutput previous_module_output_; protected: - // TODO(murooka) Remove this function when BT-based architecture will be removed - std::unordered_map> createRTCInterfaceMap( - rclcpp::Node & node, const std::string & name, const std::vector & rtc_types) - { - std::unordered_map> rtc_interface_ptr_map; - for (const auto & rtc_type : rtc_types) { - const auto snake_case_name = utils::convertToSnakeCase(name); - const auto rtc_interface_name = - rtc_type.empty() ? snake_case_name : (snake_case_name + "_" + rtc_type); - rtc_interface_ptr_map.emplace( - rtc_type, std::make_shared(&node, rtc_interface_name)); - } - return rtc_interface_ptr_map; - } - virtual void updateRTCStatus(const double start_distance, const double finish_distance) { for (auto itr = rtc_interface_ptr_map_.begin(); itr != rtc_interface_ptr_map_.end(); ++itr) { @@ -460,18 +439,6 @@ class SceneModuleInterface return std::abs(planner_data_->self_odometry->twist.twist.linear.x); } - std::vector getNonOverlappingExpandedLanes( - PathWithLaneId & path, const std::vector & lanes) const - { - const auto & dp = planner_data_->drivable_area_expansion_parameters; - - const auto shorten_lanes = utils::cutOverlappedLanes(path, lanes); - const auto expanded_lanes = utils::expandLanelets( - shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - return expanded_lanes; - } - bool is_simultaneously_executable_as_approved_module_{false}; bool is_simultaneously_executable_as_candidate_module_{false}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index 8118d05ef225d..bc6f55008fa93 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -51,7 +51,6 @@ class SideShiftModule : public SceneModuleInterface const double & min_request_time_sec, bool override_requests = false) const noexcept; ModuleStatus updateState() override; void updateData() override; - ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 6f2598de355e5..e17834326965d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -81,7 +81,6 @@ class StartPlannerModule : public SceneModuleInterface bool isExecutionRequested() const override; bool isExecutionReady() const override; ModuleStatus updateState() override; - ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index ea217c8f7d0d4..07ec7c5db6605 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -70,6 +70,7 @@ using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; +using drivable_area_expansion::DrivableAreaExpansionParameters; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; @@ -229,6 +230,9 @@ boost::optional getLeftLanelet( std::vector generateDrivableLanes(const lanelet::ConstLanelets & current_lanes); std::vector generateDrivableLanesWithShoulderLanes( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes); +std::vector getNonOverlappingExpandedLanes( + PathWithLaneId & path, const std::vector & lanes, + const DrivableAreaExpansionParameters & parameters); std::vector calcBound( const std::shared_ptr route_handler, const std::vector & drivable_lanes, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index f0aec7ba62d2f..7af27f400bcbe 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -664,7 +664,8 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const output.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(*output.path, status_.lanes); + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + *output.path, status_.lanes, planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -854,7 +855,8 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(*out.path, status_.lanes); + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + *out.path, status_.lanes, planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index e2d62ec5c0d3f..bc3ce480476ee 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -199,7 +199,8 @@ BehaviorModuleOutput StartPlannerModule::plan() path = status_.backward_path; } - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(path, status_.lanes); + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + path, status_.lanes, planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -529,7 +530,8 @@ PathWithLaneId StartPlannerModule::generateStopPath() const path.points.push_back(toPathPointWithLaneId(moved_pose)); // generate drivable area - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(path, status_.lanes); + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + path, status_.lanes, planner_data_->drivable_area_expansion_parameters); return path; } diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index dcab96069a0a8..44b575e2cdf44 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1212,6 +1212,16 @@ std::vector generateDrivableLanesWithShoulderLanes( return drivable_lanes; } +std::vector getNonOverlappingExpandedLanes( + PathWithLaneId & path, const std::vector & lanes, + const DrivableAreaExpansionParameters & parameters) +{ + const auto shorten_lanes = utils::cutOverlappedLanes(path, lanes); + return utils::expandLanelets( + shorten_lanes, parameters.drivable_area_left_bound_offset, + parameters.drivable_area_right_bound_offset, parameters.drivable_area_types_to_skip); +} + boost::optional getOverlappedLaneletId(const std::vector & lanes) { auto overlaps = [](const DrivableLanes & lanes, const DrivableLanes & target_lanes) { From 9f6fdce89136035ed7ef287b31b54d06e1b2ce9e Mon Sep 17 00:00:00 2001 From: Mehmet Dogru <48479081+mehmetdogru@users.noreply.github.com> Date: Thu, 27 Jul 2023 11:56:39 +0300 Subject: [PATCH 012/266] fix(bpp-goal_planner): fix turn signal info for the right side pulling over (#4410) Signed-off-by: Mehmet Dogru --- .../scene_module/goal_planner/goal_planner_module.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 7af27f400bcbe..6915b2be16819 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1110,8 +1110,15 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const const double distance_to_end = calcSignedArcLength(full_path.points, current_pose.position, end_pose.position); const bool is_before_end_pose = distance_to_end >= 0.0; - turn_signal.turn_signal.command = - is_before_end_pose ? TurnIndicatorsCommand::ENABLE_LEFT : TurnIndicatorsCommand::NO_COMMAND; + if (is_before_end_pose) { + if (left_side_parking_) { + turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; + } else { + turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; + } + } else { + turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND; + } } // calc desired/required start/end point From 0bc09c8dea0fe447da367c24fbcb61935deef616 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 27 Jul 2023 19:12:52 +0900 Subject: [PATCH 013/266] chore: update CODEOWNERS (#4179) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/CODEOWNERS | 39 +++++++++++++++++++++++++-------------- 1 file changed, 25 insertions(+), 14 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index ca03cd9a56adc..10b1309eac2ea 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -2,27 +2,28 @@ ### Automatically generated from package.xml ### common/autoware_ad_api_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp -common/autoware_auto_common/** opensource@apex.ai +common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_auto_geometry/** satoshi.ota@tier4.jp common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp -common/autoware_auto_tf2/** jit.ray.c@gmail.com +common/autoware_auto_tf2/** jit.ray.c@gmail.com satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_point_types/** taichi.higashide@tier4.jp -common/autoware_testing/** adam.dabrowski@robotec.ai +common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp common/component_interface_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp -common/fake_test_node/** opensource@apex.ai +common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/grid_map_utils/** maxime.clement@tier4.jp common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +common/object_recognition_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/path_distance_calculator/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp -common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp +common/perception_utils/** mingyu.li@tier4.jp satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yusuke.muramatsu@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @@ -45,8 +46,9 @@ common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp -common/time_utils/** christopherj.ho@gmail.com +common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp +common/traffic_light_utils/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp yusuke.muramatsu@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @@ -64,10 +66,9 @@ control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@ti control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp -evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai -evaluator/localization_evaluator/** dominik.jargot@robotec.ai +evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp -launch/map4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohei.sasaki@map.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp @@ -116,11 +117,17 @@ perception/map_based_prediction/** shunsuke.miura@tier4.jp tomoya.kimura@tier4.j perception/multi_object_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_merger/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_range_splitter/** yukihiro.saito@tier4.jp +perception/object_velocity_splitter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/occupancy_grid_map_outlier_filter/** abrahammonrroy@yahoo.com yoshi.ri@tier4.jp yukihiro.saito@tier4.jp -perception/probabilistic_occupancy_grid_map/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/probabilistic_occupancy_grid_map/** mamoru.sobue@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/radar_crossing_objects_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/radar_fusion_to_detected_object/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +perception/radar_object_clustering/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp +perception/radar_object_tracker/** satoshi.tanaka@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/radar_tracks_msgs_converter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp perception/shape_estimation/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp +perception/tensorrt_classifier/** mingyu.li@tier4.jp perception/tensorrt_yolo/** daisuke.nishimatsu@tier4.jp perception/tensorrt_yolox/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp @@ -128,17 +135,18 @@ perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@ti perception/traffic_light_fine_detector/** mingyu.li@tier4.jp perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp perception/traffic_light_multi_camera_fusion/** mingyu.li@tier4.jp +perception/traffic_light_occlusion_predictor/** mingyu.li@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_crosswalk_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_crosswalk_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_intersection_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai +planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp planning/behavior_velocity_planner_common/** isamu.takagi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_run_out_module/** makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @@ -146,6 +154,7 @@ planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakab planning/behavior_velocity_stop_line_module/** shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp planning/external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @@ -156,6 +165,7 @@ planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@ planning/obstacle_cruise_planner/** takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp +planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp planning/planning_validator/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @@ -180,6 +190,7 @@ sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4 sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +sensing/radar_tracks_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp sensing/tier4_pcl_extensions/** ryu.yamamoto@tier4.jp sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp @@ -201,7 +212,7 @@ system/system_error_monitor/** fumihito.ito@tier4.jp system/system_monitor/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp system/velodyne_monitor/** fumihito.ito@tier4.jp -tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai +tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp From 01a560d24273842de914573ecc5343f0f4fdd169 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 27 Jul 2023 19:23:31 +0900 Subject: [PATCH 014/266] refactor(rtc_interafce): add const (#4420) Signed-off-by: satoshi-ota --- .../include/rtc_interface/rtc_interface.hpp | 9 +++++---- planning/rtc_interface/src/rtc_interface.cpp | 4 ++-- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index 1661ac9ebef3a..4929d0f8e27f3 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -53,8 +53,8 @@ class RTCInterface const rclcpp::Time & stamp); void removeCooperateStatus(const UUID & uuid); void clearCooperateStatus(); - bool isActivated(const UUID & uuid); - bool isRegistered(const UUID & uuid); + bool isActivated(const UUID & uuid) const; + bool isRegistered(const UUID & uuid) const; void lockCommandUpdate(); void unlockCommandUpdate(); @@ -74,10 +74,9 @@ class RTCInterface rclcpp::Publisher::SharedPtr pub_statuses_; rclcpp::Service::SharedPtr srv_commands_; rclcpp::Service::SharedPtr srv_auto_mode_; - - std::mutex mutex_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::Logger logger_; + Module module_; CooperateStatusArray registered_status_; std::vector stored_commands_; @@ -87,6 +86,8 @@ class RTCInterface std::string cooperate_status_namespace_ = "/planning/cooperate_status"; std::string cooperate_commands_namespace_ = "/planning/cooperate_commands"; std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode/internal"; + + mutable std::mutex mutex_; }; } // namespace rtc_interface diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index f4a95d0acf9d1..dbc82113d403b 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -251,7 +251,7 @@ void RTCInterface::clearCooperateStatus() stored_commands_.clear(); } -bool RTCInterface::isActivated(const UUID & uuid) +bool RTCInterface::isActivated(const UUID & uuid) const { std::lock_guard lock(mutex_); const auto itr = std::find_if( @@ -271,7 +271,7 @@ bool RTCInterface::isActivated(const UUID & uuid) return false; } -bool RTCInterface::isRegistered(const UUID & uuid) +bool RTCInterface::isRegistered(const UUID & uuid) const { std::lock_guard lock(mutex_); const auto itr = std::find_if( From b2e992fdccf619914440e5e1522511f77eaf74bf Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 27 Jul 2023 20:14:32 +0900 Subject: [PATCH 015/266] docs(behavior_velocity_stop_line_module): update document (#4417) --- planning/behavior_velocity_stop_line_module/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_stop_line_module/README.md b/planning/behavior_velocity_stop_line_module/README.md index 3db639c77a7ca..f373afc2351bf 100644 --- a/planning/behavior_velocity_stop_line_module/README.md +++ b/planning/behavior_velocity_stop_line_module/README.md @@ -25,7 +25,7 @@ This module is activated when there is a stop line in a target lane. - Gets a stop line from map information. - insert a stop point on the path from the stop line defined in the map and the ego vehicle length. - Sets velocities of the path after the stop point to 0[m/s]. -- Release the inserted stop velocity when the vehicle stops within a radius of 2[m] from the stop point. +- Release the inserted stop velocity when the vehicle stops at the stop point for `stop_duration_sec` seconds. #### Flowchart @@ -50,13 +50,13 @@ endif if (state is APPROACH) then (yes) :set stop velocity; - if (vehicle is within stop_check_dist?) then (yes) + if (vehicle is within hold_stop_margin_distance?) then (yes) if (vehicle is stopped?) then (yes) :change state to STOPPED; endif endif else if (state is STOPPED) then (yes) - if (vehicle started to move?) then (yes) + if (stopping time is longer than stop_duration_sec ?) then (yes) :change state to START; endif else if (state is START) then (yes) From 8f5cbd0e18aa8e420df6f9ab255f1b084b24b64f Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 27 Jul 2023 20:59:29 +0900 Subject: [PATCH 016/266] docs(default_ad_api): fix autoware state compatibility table (#4399) fix(default_ad_api): fix autoware state compatibility table Signed-off-by: Takagi, Isamu --- .../images/autoware-state-table.drawio.svg | 86 ++++++++++--------- 1 file changed, 44 insertions(+), 42 deletions(-) diff --git a/system/default_ad_api/document/images/autoware-state-table.drawio.svg b/system/default_ad_api/document/images/autoware-state-table.drawio.svg index ab21c1b865407..2b57830f6b869 100644 --- a/system/default_ad_api/document/images/autoware-state-table.drawio.svg +++ b/system/default_ad_api/document/images/autoware-state-table.drawio.svg @@ -3,14 +3,14 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="721px" + width="921px" height="201px" - viewBox="-0.5 -0.5 721 201" - content="<mxfile><diagram id="DGwK_OstZrDMA8GPxkck" name="Page-1">3Zpdk5owFIZ/DffyIbqXravbXnSm073Y61QiZBoTJwY/9tc3QEDMWafMmkYmOuPACVF4OEne92AQL7anF4F2xQ+eYRpEk+wUxM9BFM1mU/VZBc5NIJmlTSAXJGtC4SXwSt6xDk50tCQZ3l8dKDmnkuyug2vOGF7LqxgSgh+vD9twev2rO5RjEHhdIwqjbySThY6G6dOl4RsmeaF/eh7NmoYtag/WV7IvUMaPvVC8DOKF4Fw2W9vTAtOKXcul6be60dqdmMBMDukQ6TM+IFrqi9MnJs/t1QpesgxXHSZB/PVYEIlfd2hdtR7V7VWxQm6p2gvV5oZQuuCUi7pvvJlW7yrOmezFm5eK76Xgf3CvJa1fqkWfGBYSn25eXdgxU7mG+RZLcVaH6A5pojHrPEv17rF309o7UfTu15OOIZ0neffNF5RqQ9O8QRaAfUNEEpavuPjFS4k94mxg7pj+i3NkgXMMOFOuRip5R5JwVhNGXsGO5te0E4ewEwBbcayS2kPOyeRxnKeAM99h0Wb0Vq2nHoGeRo8DnQLQqJS8YzxBB0Qo+k194m2uii55zwBvwtSqWM3X9SxyD2QLaML0c4LBBpo5nFtLxsZIZT6QSphYwAIFasm6nFEQHg3HXI6HwrGRMq0fGutwMtmEE5dwwttwRpg3g0VzB/EuONCelGyPZRAtGo9MDiNgZEowp8YihM6iBjQ2JkOX79QGEyhMx5orkdO5BuqaDWFjmYbN9TtyOoygrtlLvns4FNN1DB5HNkRNCFUN47IGMkY0LjVN+x39oYTo/k4DZoGKaZsGJ4wVKlDMSFGOEIpLxxRBEfPdmvwdlWX/ZB3bxpL/UYEVlWxdBP6V/MyF0ukIh7XVnxRZKACMivBD51AoXi+PZJYsrx76+Uva6cQMy6rPyiX4ncpORRL0G18aH/bCEfUXslNT90FFdmXJ1I2asdOnt1Dte0QWqOOhc4QN4RZDy+ARWrPc41ISx9B3eETWdP9Dyc5tkIVmw2Oyg1czGyWnGPoLj9CC6q/TRQwaC4/Qmg+q3KKFTsJjtP/Ro6ndy79K67beX3Pj5V8=</diagram></mxfile>" + viewBox="-0.5 -0.5 921 201" + content="<mxfile><diagram id="DGwK_OstZrDMA8GPxkck" name="Page-1">3ZpNc5swEIZ/Sw/cAdnEObbOR3voTKc55JhRjWw0FZJHFraTX18JhI1ZMmESVWFkz9iw4ksPi3bfRRFalsd7ibfFT5ETFqVxfozQTZSmyXw+13/G8txYsuukMWwkze1GZ8MDfSHWGFtrRXOyu9hQCcEU3V4aV4JzslIXNiylOFxuthbs8qxbvCHA8LDCDFofaa4Ka02y63PDd0I3hT31Ir1qGkrcbmx7sitwLg4dE7qN0FIKoZql8rgkzMBruTT73b3SerowSbgas0Nqr3iPWWU7Zy9MPbe9laLiOTE7xBH6diioIg9bvDKtB31/ta1QJdNriV5cU8aWgglZ74vWc/M1dsFVx958tH2npPhLOi1Z/dEtsCu2d3siFTl2TLZr90SURMlnvYltXcws5tbP7Oqhc9PaO1F07te1tWHrJ5vTkc8o9YKl+QpZAPYRU0X55k7I36JSJCDOPcwnpm9xTh1wRoAzE/pJpS9YUcFrwjgo2OnikvbMI+wZgK05GqcOkPMs/jzOc8BZbIlsPbrUATUg0PP0TdDof4HOAGhcKXFiHOM9pgz/YSHx7kdFn459BXhTrqOiGa/rUeQjkB2gSbL3JQwu0Czg2FpxPkUqi5FUkpkDLDBBrfjJZzSEz4bTD8dj4bhwmVYPTfVx6rNJYp9wktfhTNBvRifNJ4gfggPlScV3REXpstHIdD8BRv0UzKuwSKCyqAFNjcnY8J25YAIT06n6Sup1rIF5zZryqQzD/fiden2MYF5D2O6D+bQDKH3VMfQcITQAxUVSk8LAvcZToNLXBqNHFxeuksKIrWQ1QSg+ZUEKI/UPZznepHTpO4u1LuLaUBURV3xVROHVtfrRwOsTDguIvxh2oHInRfhTx1CYoZ3fO9zyjXmzFS5prwMzrB3e6FQ4bFf2Wd0YKBZ+bcTGvcAsXMhelctA2fHOkXKZNGOvryhhth8QWZAdjx0jXCRuCEqGgND2axo+U2IEdUdAZPvqf4Ds4DvHhQuyUGwETHYomg2idVFXQVBfBIQWlDi9BjEoLAJC238b4xctVBIBo/Wp0RCUEHZix5d6TRMW28icKcOlgdj8gtXYzAo5aApPK41QCvZEuJkVkpt99YHqY7mqVQK0AzdgfFl7IBtzNZtGr55nqtZtnfm+6PYf</diagram></mxfile>" > - + @@ -62,13 +62,13 @@ routing state - +
@@ -77,16 +77,16 @@
- operation mode + operation mode - +
@@ -95,7 +95,7 @@
- auto mode available + auto mode available @@ -260,49 +260,31 @@ finalizing - +
- stop + else
- stop + else
- +
-
-
- not stop -
-
-
-
- not stop -
-
- - - - -
@@ -311,16 +293,16 @@
- false + false - +
@@ -329,7 +311,7 @@
- true + true @@ -440,18 +422,38 @@ Finalizing - + - - + + + + + + +
+
+
+ mode != stop && autoware_control_enabled == true +
+
+
+
+ + mode != stop && autoware_control_enabled == true + +
+
- Viewer does not support full SVG 1.1 + Text is not SVG - cannot display From 19520e0386d2eda862bd483793bd8ce1f15bad61 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 27 Jul 2023 21:15:56 +0900 Subject: [PATCH 017/266] perf(path_smoother): add ReplanChecker to decrease computation cost (#4416) * perf(path_smoother): add ReplanChecker to decrease computation cost Signed-off-by: Maxime CLEMENT * Add replan checker parameters to default path_smoother config Signed-off-by: Maxime CLEMENT --------- Signed-off-by: Maxime CLEMENT --- planning/path_smoother/CMakeLists.txt | 7 +- .../config/elastic_band_smoother.param.yaml | 10 + .../include/path_smoother/common_structs.hpp | 14 +- .../path_smoother/elastic_band_smoother.hpp | 2 + .../include/path_smoother/replan_checker.hpp | 71 ++++++ .../include/path_smoother/type_alias.hpp | 2 - .../src/elastic_band_smoother.cpp | 24 +- planning/path_smoother/src/replan_checker.cpp | 210 ++++++++++++++++++ 8 files changed, 323 insertions(+), 17 deletions(-) create mode 100644 planning/path_smoother/include/path_smoother/replan_checker.hpp create mode 100644 planning/path_smoother/src/replan_checker.cpp diff --git a/planning/path_smoother/CMakeLists.txt b/planning/path_smoother/CMakeLists.txt index 30f06f7b87f81..b2fcf9076a7b3 100644 --- a/planning/path_smoother/CMakeLists.txt +++ b/planning/path_smoother/CMakeLists.txt @@ -7,12 +7,7 @@ autoware_package() find_package(Eigen3 REQUIRED) ament_auto_add_library(path_smoother SHARED - # node - src/elastic_band_smoother.cpp - # algorithms - src/elastic_band.cpp - # utils - src/utils/trajectory_utils.cpp + DIRECTORY src ) target_include_directories(path_smoother diff --git a/planning/path_smoother/config/elastic_band_smoother.param.yaml b/planning/path_smoother/config/elastic_band_smoother.param.yaml index 730bc3053e7a3..8e77420dd4ae9 100644 --- a/planning/path_smoother/config/elastic_band_smoother.param.yaml +++ b/planning/path_smoother/config/elastic_band_smoother.param.yaml @@ -35,3 +35,13 @@ # nearest search ego_nearest_dist_threshold: 3.0 # [m] ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] + # replanning & trimming trajectory param outside algorithm + replan: + enable: true # if true, only perform smoothing when the input changes significantly + max_path_shape_around_ego_lat_dist: 2.0 # threshold of path shape change around ego [m] + max_path_shape_forward_lon_dist: 100.0 # forward point to check lateral distance difference [m] + max_path_shape_forward_lat_dist: 0.1 # threshold of path shape change around forward point [m] + max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] + # make max_goal_moving_dist long to keep start point fixed for pull over + max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] + max_delta_time_sec: 1.0 # threshold of delta time for replan [second] diff --git a/planning/path_smoother/include/path_smoother/common_structs.hpp b/planning/path_smoother/include/path_smoother/common_structs.hpp index 17c6bc6f162af..94f4d62c4a6fd 100644 --- a/planning/path_smoother/include/path_smoother/common_structs.hpp +++ b/planning/path_smoother/include/path_smoother/common_structs.hpp @@ -30,15 +30,15 @@ struct Bounds; struct PlannerData { - // input - Header header; - std::vector traj_points; // converted from the input path - std::vector left_bound; - std::vector right_bound; - - // ego + std::vector traj_points; geometry_msgs::msg::Pose ego_pose; double ego_vel{}; + + PlannerData( + std::vector traj_points_, geometry_msgs::msg::Pose ego_pose_, double ego_vel_) + : traj_points(traj_points_), ego_pose(ego_pose_), ego_vel(ego_vel_) + { + } }; struct TimeKeeper diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index 1e8f9d76f53f9..1085ca3815728 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -18,6 +18,7 @@ #include "motion_utils/motion_utils.hpp" #include "path_smoother/common_structs.hpp" #include "path_smoother/elastic_band.hpp" +#include "path_smoother/replan_checker.hpp" #include "path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" @@ -59,6 +60,7 @@ class ElasticBandSmoother : public rclcpp::Node // algorithms std::shared_ptr eb_path_smoother_ptr_{nullptr}; + std::shared_ptr replan_checker_ptr_{nullptr}; // parameters CommonParam common_param_{}; diff --git a/planning/path_smoother/include/path_smoother/replan_checker.hpp b/planning/path_smoother/include/path_smoother/replan_checker.hpp new file mode 100644 index 0000000000000..d06cbc093a0c8 --- /dev/null +++ b/planning/path_smoother/include/path_smoother/replan_checker.hpp @@ -0,0 +1,71 @@ +// Copyright 2023 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 PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#define PATH_SMOOTHER__REPLAN_CHECKER_HPP_ + +#include "path_smoother/common_structs.hpp" +#include "path_smoother/type_alias.hpp" + +#include + +#include +#include + +namespace path_smoother +{ +class ReplanChecker +{ +public: + explicit ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param); + void onParam(const std::vector & parameters); + + bool isResetRequired(const PlannerData & planner_data) const; + + bool isReplanRequired(const PlannerData & planner_data, const rclcpp::Time & current_time) const; + + void updateData( + const PlannerData & planner_data, const bool is_replan_required, + const rclcpp::Time & current_time); + +private: + EgoNearestParam ego_nearest_param_; + rclcpp::Logger logger_; + + // previous variables for isResetRequired + std::shared_ptr> prev_traj_points_ptr_{nullptr}; + std::shared_ptr prev_ego_pose_ptr_{nullptr}; + + // previous variable for isReplanRequired + std::shared_ptr prev_replanned_time_ptr_{nullptr}; + + // algorithm parameters + bool enable_; + double max_path_shape_around_ego_lat_dist_; + double max_path_shape_forward_lat_dist_; + double max_path_shape_forward_lon_dist_; + double max_ego_moving_dist_; + double max_goal_moving_dist_; + double max_delta_time_sec_; + + bool isPathAroundEgoChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const; + bool isPathForwardChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const; + bool isPathGoalChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const; +}; +} // namespace path_smoother + +#endif // PATH_SMOOTHER__REPLAN_CHECKER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/type_alias.hpp b/planning/path_smoother/include/path_smoother/type_alias.hpp index d6434c3935d1e..75bf1cff20857 100644 --- a/planning/path_smoother/include/path_smoother/type_alias.hpp +++ b/planning/path_smoother/include/path_smoother/type_alias.hpp @@ -20,8 +20,6 @@ #include "autoware_auto_planning_msgs/msg/trajectory.hpp" #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/point.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "geometry_msgs/msg/twist.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" #include "tier4_debug_msgs/msg/string_stamped.hpp" diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp index a959f45e5fbbf..dbd0f2de92f29 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -87,6 +87,7 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option eb_path_smoother_ptr_ = std::make_shared( this, enable_debug_info_, ego_nearest_param_, common_param_, time_keeper_ptr_); + replan_checker_ptr_ = std::make_shared(this, ego_nearest_param_); // reset planners initializePlanning(); @@ -109,6 +110,7 @@ rcl_interfaces::msg::SetParametersResult ElasticBandSmoother::onParam( // parameters for core algorithms eb_path_smoother_ptr_->onParam(parameters); + replan_checker_ptr_->onParam(parameters); // reset planners initializePlanning(); @@ -162,11 +164,29 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) const auto input_traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); // 1. calculate trajectory with Elastic Band + // 1.a check if replan (= optimization) is required + PlannerData planner_data( + input_traj_points, ego_state_ptr_->pose.pose, ego_state_ptr_->twist.twist.linear.x); + const bool is_replan_required = [&]() { + if (replan_checker_ptr_->isResetRequired(planner_data)) { + // NOTE: always replan when resetting previous optimization + resetPreviousData(); + return true; + } + // check replan when not resetting previous optimization + return !prev_optimized_traj_points_ptr_ || + replan_checker_ptr_->isReplanRequired(planner_data, now()); + }(); + replan_checker_ptr_->updateData(planner_data, is_replan_required, now()); time_keeper_ptr_->tic(__func__); - auto smoothed_traj_points = - eb_path_smoother_ptr_->smoothTrajectory(input_traj_points, ego_state_ptr_->pose.pose); + auto smoothed_traj_points = is_replan_required ? eb_path_smoother_ptr_->smoothTrajectory( + input_traj_points, ego_state_ptr_->pose.pose) + : *prev_optimized_traj_points_ptr_; time_keeper_ptr_->toc(__func__, " "); + prev_optimized_traj_points_ptr_ = + std::make_shared>(smoothed_traj_points); + // 2. update velocity applyInputVelocity(smoothed_traj_points, input_traj_points, ego_state_ptr_->pose.pose); diff --git a/planning/path_smoother/src/replan_checker.cpp b/planning/path_smoother/src/replan_checker.cpp new file mode 100644 index 0000000000000..95c4e1eb1c002 --- /dev/null +++ b/planning/path_smoother/src/replan_checker.cpp @@ -0,0 +1,210 @@ +// Copyright 2023 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 "path_smoother/replan_checker.hpp" + +#include "motion_utils/motion_utils.hpp" +#include "path_smoother/utils/trajectory_utils.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include + +namespace path_smoother +{ +ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param) +: ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker")) +{ + enable_ = node->declare_parameter("replan.enable"); + max_path_shape_around_ego_lat_dist_ = + node->declare_parameter("replan.max_path_shape_around_ego_lat_dist"); + max_path_shape_forward_lat_dist_ = + node->declare_parameter("replan.max_path_shape_forward_lat_dist"); + max_path_shape_forward_lon_dist_ = + node->declare_parameter("replan.max_path_shape_forward_lon_dist"); + max_ego_moving_dist_ = node->declare_parameter("replan.max_ego_moving_dist"); + max_goal_moving_dist_ = node->declare_parameter("replan.max_goal_moving_dist"); + max_delta_time_sec_ = node->declare_parameter("replan.max_delta_time_sec"); +} + +void ReplanChecker::onParam(const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + + updateParam(parameters, "replan.enable", enable_); + updateParam( + parameters, "replan.max_path_shape_around_ego_lat_dist", max_path_shape_around_ego_lat_dist_); + updateParam( + parameters, "replan.max_path_shape_forward_lat_dist", max_path_shape_forward_lat_dist_); + updateParam( + parameters, "replan.max_path_shape_forward_lon_dist", max_path_shape_forward_lon_dist_); + updateParam(parameters, "replan.max_ego_moving_dist", max_ego_moving_dist_); + updateParam(parameters, "replan.max_goal_moving_dist", max_goal_moving_dist_); + updateParam(parameters, "replan.max_delta_time_sec", max_delta_time_sec_); +} + +bool ReplanChecker::isResetRequired(const PlannerData & planner_data) const +{ + const auto & p = planner_data; + + const bool reset_required = [&]() { + // guard for invalid variables + if (!prev_traj_points_ptr_ || !prev_ego_pose_ptr_) { + return true; + } + const auto & prev_traj_points = *prev_traj_points_ptr_; + + // path shape changes + if (isPathAroundEgoChanged(planner_data, prev_traj_points)) { + RCLCPP_INFO( + logger_, "Replan with resetting optimization since path shape around ego changed."); + return true; + } + + // path goal changes + if (isPathGoalChanged(planner_data, prev_traj_points)) { + RCLCPP_INFO(logger_, "Replan with resetting optimization since path goal changed."); + return true; + } + + // ego pose is lost or new ego pose is designated in simulation + const double delta_dist = + tier4_autoware_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position); + if (max_ego_moving_dist_ < delta_dist) { + RCLCPP_INFO( + logger_, + "Replan with resetting optimization since current ego pose is far from previous ego pose."); + return true; + } + + return false; + }(); + + return reset_required; +} + +bool ReplanChecker::isReplanRequired( + const PlannerData & planner_data, const rclcpp::Time & current_time) const +{ + if (!enable_) return true; + + // guard for invalid variables + if (!prev_replanned_time_ptr_ || !prev_traj_points_ptr_) return true; + const auto & prev_traj_points = *prev_traj_points_ptr_; + + // time elapses + const double delta_time_sec = (current_time - *prev_replanned_time_ptr_).seconds(); + if (max_delta_time_sec_ < delta_time_sec) return true; + + // path shape changes + if (isPathForwardChanged(planner_data, prev_traj_points)) { + RCLCPP_INFO(logger_, "Replan since path forward shape changed."); + return true; + } + + return false; +} + +void ReplanChecker::updateData( + const PlannerData & planner_data, const bool is_replan_required, + const rclcpp::Time & current_time) +{ + const auto & p = planner_data; + + // update previous information required in this function + prev_traj_points_ptr_ = std::make_shared>(p.traj_points); + prev_ego_pose_ptr_ = std::make_shared(p.ego_pose); + + // update previous information required in this function + if (is_replan_required) { + prev_replanned_time_ptr_ = std::make_shared(current_time); + } +} + +bool ReplanChecker::isPathAroundEgoChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const +{ + const auto & p = planner_data; + + // calculate ego's lateral offset to previous trajectory points + const auto prev_ego_seg_idx = + trajectory_utils::findEgoSegmentIndex(prev_traj_points, p.ego_pose, ego_nearest_param_); + const double prev_ego_lat_offset = + motion_utils::calcLateralOffset(prev_traj_points, p.ego_pose.position, prev_ego_seg_idx); + + // calculate ego's lateral offset to current trajectory points + const auto ego_seg_idx = + trajectory_utils::findEgoSegmentIndex(p.traj_points, p.ego_pose, ego_nearest_param_); + const double ego_lat_offset = + motion_utils::calcLateralOffset(p.traj_points, p.ego_pose.position, ego_seg_idx); + + const double diff_ego_lat_offset = prev_ego_lat_offset - ego_lat_offset; + if (std::abs(diff_ego_lat_offset) < max_path_shape_around_ego_lat_dist_) { + return false; + } + + return true; +} + +bool ReplanChecker::isPathForwardChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const +{ + const auto & p = planner_data; + + // calculate forward point of previous trajectory points + const size_t prev_ego_seg_idx = + trajectory_utils::findEgoSegmentIndex(prev_traj_points, p.ego_pose, ego_nearest_param_); + + // check if distance is larger than the threshold + constexpr double lon_dist_interval = 10.0; + for (double lon_dist = lon_dist_interval; lon_dist <= max_path_shape_forward_lon_dist_; + lon_dist += lon_dist_interval) { + const auto prev_forward_point = + motion_utils::calcLongitudinalOffsetPoint(prev_traj_points, prev_ego_seg_idx, lon_dist); + if (!prev_forward_point) { + continue; + } + + // calculate lateral offset of current trajectory points to prev forward point + const auto forward_seg_idx = + motion_utils::findNearestSegmentIndex(p.traj_points, *prev_forward_point); + const double forward_lat_offset = + motion_utils::calcLateralOffset(p.traj_points, *prev_forward_point, forward_seg_idx); + if (max_path_shape_forward_lat_dist_ < std::abs(forward_lat_offset)) { + return true; + } + } + + return false; +} + +bool ReplanChecker::isPathGoalChanged( + const PlannerData & planner_data, const std::vector & prev_traj_points) const +{ + const auto & p = planner_data; + + // check if the vehicle is stopping + constexpr double min_vel = 1e-3; + if (min_vel < std::abs(p.ego_vel)) { + return false; + } + + const double goal_moving_dist = + tier4_autoware_utils::calcDistance2d(p.traj_points.back(), prev_traj_points.back()); + if (goal_moving_dist < max_goal_moving_dist_) { + return false; + } + + return true; +} +} // namespace path_smoother From 44415bc7ab65e8461a3e2dbf66b280e074a241e6 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 27 Jul 2023 21:24:22 +0900 Subject: [PATCH 018/266] refactor(ndt_scan_matcher): fixed as pointed out by clang-tidy (#4286) Fixed as pointed out by clang-tidy Signed-off-by: Shintaro SAKODA --- .../include/ndt_scan_matcher/map_module.hpp | 2 +- .../ndt_scan_matcher/map_update_module.hpp | 2 +- .../pose_array_interpolator.hpp | 10 +++++----- localization/ndt_scan_matcher/src/debug.cpp | 6 +++--- .../ndt_scan_matcher/src/map_module.cpp | 2 +- .../src/map_update_module.cpp | 20 +++++++++---------- .../src/pose_array_interpolator.cpp | 8 ++++---- .../ndt_scan_matcher/src/util_func.cpp | 14 ++++++------- 8 files changed, 32 insertions(+), 32 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp index 5253879a28937..79454e89b9ed0 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp @@ -39,7 +39,7 @@ class MapModule rclcpp::CallbackGroup::SharedPtr map_callback_group); private: - void callback_map_points(sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud2_msg_ptr); + void callback_map_points(sensor_msgs::msg::PointCloud2::ConstSharedPtr map_points_msg_ptr); rclcpp::Subscription::SharedPtr map_points_sub_; std::shared_ptr ndt_ptr_; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 61034e02e9c91..4f630bb8c5898 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -63,7 +63,7 @@ class MapUpdateModule const std::vector & maps_to_add, const std::vector & map_ids_to_remove); void update_map(const geometry_msgs::msg::Point & position); - bool should_update_map(const geometry_msgs::msg::Point & position) const; + [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position) const; void publish_partial_pcd_map(); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp index e88862781225d..f1e7dfb3f544b 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp @@ -30,18 +30,18 @@ class PoseArrayInterpolator public: PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time target_ros_time, + rclcpp::Node * node, const rclcpp::Time & target_ros_time, const std::deque & pose_msg_ptr_array, const double & pose_timeout_sec, const double & pose_distance_tolerance_meters); PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time target_ros_time, + rclcpp::Node * node, const rclcpp::Time & target_ros_time, const std::deque & pose_msg_ptr_array); PoseWithCovarianceStamped get_current_pose(); PoseWithCovarianceStamped get_old_pose(); PoseWithCovarianceStamped get_new_pose(); - bool is_success(); + [[nodiscard]] bool is_success() const; private: rclcpp::Logger logger_; @@ -51,10 +51,10 @@ class PoseArrayInterpolator PoseWithCovarianceStamped::SharedPtr new_pose_ptr_; bool success_; - bool validate_time_stamp_difference( + [[nodiscard]] bool validate_time_stamp_difference( const rclcpp::Time & target_time, const rclcpp::Time & reference_time, const double time_tolerance_sec) const; - bool validate_position_difference( + [[nodiscard]] bool validate_position_difference( const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_) const; }; diff --git a/localization/ndt_scan_matcher/src/debug.cpp b/localization/ndt_scan_matcher/src/debug.cpp index cec62c850372a..9c82e06d89b80 100644 --- a/localization/ndt_scan_matcher/src/debug.cpp +++ b/localization/ndt_scan_matcher/src/debug.cpp @@ -30,7 +30,7 @@ visualization_msgs::msg::MarkerArray make_debug_markers( marker.type = visualization_msgs::msg::Marker::ARROW; marker.action = visualization_msgs::msg::Marker::ADD; marker.scale = scale; - marker.id = i; + marker.id = static_cast(i); marker.lifetime = rclcpp::Duration::from_seconds(10.0); // 10.0 is the lifetime in seconds. marker.ns = "initial_pose_transform_probability_color_marker"; @@ -45,7 +45,7 @@ visualization_msgs::msg::MarkerArray make_debug_markers( marker.ns = "initial_pose_index_color_marker"; marker.pose = particle.initial_pose; - marker.color = exchange_color_crc((1.0 * i) / 100); + marker.color = exchange_color_crc(static_cast(i) / 100.0); marker_array.markers.push_back(marker); marker.ns = "result_pose_transform_probability_color_marker"; @@ -60,7 +60,7 @@ visualization_msgs::msg::MarkerArray make_debug_markers( marker.ns = "result_pose_index_color_marker"; marker.pose = particle.result_pose; - marker.color = exchange_color_crc((1.0 * i) / 100); + marker.color = exchange_color_crc(static_cast(i) / 100.0); marker_array.markers.push_back(marker); return marker_array; diff --git a/localization/ndt_scan_matcher/src/map_module.cpp b/localization/ndt_scan_matcher/src/map_module.cpp index e036f8f81d482..d6088a1b14949 100644 --- a/localization/ndt_scan_matcher/src/map_module.cpp +++ b/localization/ndt_scan_matcher/src/map_module.cpp @@ -18,7 +18,7 @@ MapModule::MapModule( rclcpp::Node * node, std::mutex * ndt_ptr_mutex, std::shared_ptr ndt_ptr, rclcpp::CallbackGroup::SharedPtr map_callback_group) -: ndt_ptr_(ndt_ptr), ndt_ptr_mutex_(ndt_ptr_mutex) +: ndt_ptr_(std::move(ndt_ptr)), ndt_ptr_mutex_(ndt_ptr_mutex) { auto map_sub_opt = rclcpp::SubscriptionOptions(); map_sub_opt.callback_group = map_callback_group; diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 26c2fd30d9198..9c94467dc94c0 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -28,13 +28,13 @@ MapUpdateModule::MapUpdateModule( std::shared_ptr tf2_listener_module, std::string map_frame, rclcpp::CallbackGroup::SharedPtr main_callback_group, std::shared_ptr> state_ptr) -: ndt_ptr_(ndt_ptr), +: ndt_ptr_(std::move(ndt_ptr)), ndt_ptr_mutex_(ndt_ptr_mutex), - map_frame_(map_frame), + map_frame_(std::move(map_frame)), logger_(node->get_logger()), clock_(node->get_clock()), - tf2_listener_module_(tf2_listener_module), - state_ptr_(state_ptr), + tf2_listener_module_(std::move(tf2_listener_module)), + state_ptr_(std::move(state_ptr)), dynamic_map_loading_update_distance_( node->declare_parameter("dynamic_map_loading_update_distance")), dynamic_map_loading_map_radius_( @@ -112,9 +112,9 @@ bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & positi void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) { auto request = std::make_shared(); - request->area.center_x = position.x; - request->area.center_y = position.y; - request->area.radius = dynamic_map_loading_map_radius_; + request->area.center_x = static_cast(position.x); + request->area.center_y = static_cast(position.y); + request->area.radius = static_cast(dynamic_map_loading_map_radius_); request->cached_ids = ndt_ptr_->getCurrentMapIDs(); // // send a request to map_loader @@ -163,9 +163,9 @@ void MapUpdateModule::update_ndt( backup_ndt.createVoxelKdtree(); const auto exe_end_time = std::chrono::system_clock::now(); - const double exe_time = - std::chrono::duration_cast(exe_end_time - exe_start_time).count() / - 1000.0; + const auto duration_micro_sec = + std::chrono::duration_cast(exe_end_time - exe_start_time).count(); + const auto exe_time = static_cast(duration_micro_sec) / 1000.0; RCLCPP_INFO(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time); // swap diff --git a/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp b/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp index d7635c052142f..59ecedc18cb5a 100644 --- a/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp +++ b/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp @@ -15,7 +15,7 @@ #include "ndt_scan_matcher/pose_array_interpolator.hpp" PoseArrayInterpolator::PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time target_ros_time, + rclcpp::Node * node, const rclcpp::Time & target_ros_time, const std::deque & pose_msg_ptr_array) : logger_(node->get_logger()), clock_(*node->get_clock()), @@ -33,7 +33,7 @@ PoseArrayInterpolator::PoseArrayInterpolator( } PoseArrayInterpolator::PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time target_ros_time, + rclcpp::Node * node, const rclcpp::Time & target_ros_time, const std::deque & pose_msg_ptr_array, const double & pose_timeout_sec, const double & pose_distance_tolerance_meters) : PoseArrayInterpolator(node, target_ros_time, pose_msg_ptr_array) @@ -50,7 +50,7 @@ PoseArrayInterpolator::PoseArrayInterpolator( pose_distance_tolerance_meters); // all validations must be true - if (!(is_old_pose_valid & is_new_pose_valid & is_pose_diff_valid)) { + if (!(is_old_pose_valid && is_new_pose_valid && is_pose_diff_valid)) { RCLCPP_WARN(logger_, "Validation error."); } } @@ -70,7 +70,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped PoseArrayInterpolator::get_new_pos return *new_pose_ptr_; } -bool PoseArrayInterpolator::is_success() +bool PoseArrayInterpolator::is_success() const { return success_; } diff --git a/localization/ndt_scan_matcher/src/util_func.cpp b/localization/ndt_scan_matcher/src/util_func.cpp index 2db6b51540d51..d947c56dfe183 100644 --- a/localization/ndt_scan_matcher/src/util_func.cpp +++ b/localization/ndt_scan_matcher/src/util_func.cpp @@ -28,19 +28,19 @@ std_msgs::msg::ColorRGBA exchange_color_crc(double x) if (x <= 0.25) { color.b = 1.0; - color.g = std::sin(x * 2.0 * M_PI); + color.g = static_cast(std::sin(x * 2.0 * M_PI)); color.r = 0; } else if (x > 0.25 && x <= 0.5) { - color.b = std::sin(x * 2 * M_PI); + color.b = static_cast(std::sin(x * 2 * M_PI)); color.g = 1.0; color.r = 0; } else if (x > 0.5 && x <= 0.75) { color.b = 0; color.g = 1.0; - color.r = -std::sin(x * 2.0 * M_PI); + color.r = static_cast(-std::sin(x * 2.0 * M_PI)); } else { color.b = 0; - color.g = -std::sin(x * 2.0 * M_PI); + color.g = static_cast(-std::sin(x * 2.0 * M_PI)); color.r = 1.0; } color.a = 0.999; @@ -58,9 +58,9 @@ double calc_diff_for_radian(const double lhs_rad, const double rhs_rad) return diff_rad; } -Eigen::Map makeEigenCovariance(const std::array & covariance) +Eigen::Map make_eigen_covariance(const std::array & covariance) { - return Eigen::Map(covariance.data(), 6, 6); + return {covariance.data(), 6, 6}; } // x: roll, y: pitch, z: yaw @@ -242,7 +242,7 @@ std::vector create_random_pose_array( { std::default_random_engine engine(seed_gen()); const Eigen::Map covariance = - makeEigenCovariance(base_pose_with_cov.pose.covariance); + make_eigen_covariance(base_pose_with_cov.pose.covariance); std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance(0, 0))); std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance(1, 1))); From 83330193167727e76609747d68b6e77328289c75 Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Thu, 27 Jul 2023 22:17:06 +0900 Subject: [PATCH 019/266] fix(traffic_light_occlusion_predictor): bug fix (#4426) fix traffic_light_occlusion_predictor bug Signed-off-by: Mingyu Li --- perception/traffic_light_occlusion_predictor/src/nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp index 36f09be943144..366820a725018 100644 --- a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -117,7 +117,7 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback( if ( in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr || in_roi_msg->rois.size() != in_signal_msg->signals.size()) { - occlusion_ratios.resize(in_roi_msg->rois.size(), 0); + occlusion_ratios.resize(out_msg.signals.size(), 0); } else { cloud_occlusion_predictor_->predict( in_cam_info_msg, in_roi_msg, in_cloud_msg, tf_buffer_, traffic_light_position_map_, From c846d91a10b33cfcb06f49309301b4144563e98d Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Thu, 27 Jul 2023 22:19:42 +0900 Subject: [PATCH 020/266] fix(image_projection_based_fusion): fix pointpainting error caused by empty pointcloud (#4427) * fix(image_projection_based_fusion): fix pointpainting error caused by empty pointcloud Signed-off-by: yukke42 * style(pre-commit): autofix --------- Signed-off-by: yukke42 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/pointpainting_fusion/node.cpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 3641b42db461a..01ec679a82efc 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -180,6 +180,12 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) { + if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + return; + } + sensor_msgs::msg::PointCloud2 tmp; tmp = painted_pointcloud_msg; @@ -232,6 +238,12 @@ void PointPaintingFusionNode::fuseOnSingleImage( const sensor_msgs::msg::CameraInfo & camera_info, sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) { + if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + return; + } + auto num_bbox = (input_roi_msg.feature_objects).size(); if (num_bbox == 0) { return; @@ -342,6 +354,12 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte return; } + if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + return; + } + std::vector det_boxes3d; bool is_success = detector_ptr_->detect(painted_pointcloud_msg, tf_buffer_, det_boxes3d); if (!is_success) { From 812541634251aa58c9da16d741ce64f3fbee6116 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 27 Jul 2023 22:52:22 +0900 Subject: [PATCH 021/266] feat(yabloc): change namespace (#4389) * fix(yabloc): update namespace Signed-off-by: kminoda * fix --------- Signed-off-by: kminoda --- .../pose_twist_estimator/yabloc.launch.xml | 52 ++++++++++--------- .../launch/pose_initializer.launch.xml | 2 +- .../launch/overlay.launch.xml | 6 +-- .../launch/yabloc_particle_filter.launch.xml | 10 ++-- .../launch/yabloc_pose_initializer.launch.xml | 10 ++-- 5 files changed, 42 insertions(+), 38 deletions(-) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml index ebee784510435..447219085df7f 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml @@ -21,33 +21,37 @@ - - - - + - - - - - + + + + + - - - - - - - - - + + + + + - - - - - - + + + + + + + + + + + + + + + + + diff --git a/localization/pose_initializer/launch/pose_initializer.launch.xml b/localization/pose_initializer/launch/pose_initializer.launch.xml index 5b7713d7c4afd..43e8d48c4fda0 100644 --- a/localization/pose_initializer/launch/pose_initializer.launch.xml +++ b/localization/pose_initializer/launch/pose_initializer.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml b/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml index bf9a0abc08f8e..150ffed58138d 100644 --- a/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml +++ b/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml @@ -1,9 +1,9 @@ - + - - + + diff --git a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml index 60bb501fd1ae7..f38264b828d34 100644 --- a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml +++ b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml @@ -9,7 +9,7 @@ - + @@ -19,9 +19,9 @@ - - - + + + @@ -47,7 +47,7 @@ - + diff --git a/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml b/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml index 1f40fb619b0b7..a1d5d59b46094 100644 --- a/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml +++ b/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml @@ -1,17 +1,17 @@ - - + + - - + + - + From 404d084fee3198b52cea7de53ab11e2c24d59f33 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 27 Jul 2023 23:15:52 +0900 Subject: [PATCH 022/266] fix(traffic_light_arbiter): publish traffic light info even when a map without traffic lights is subscribed (#4428) * fix(traffic_light_arbiter): publish traffic light info even when a map without traffic lights is subscribed Signed-off-by: tomoya.kimura * feat: publish empty message if the size of elemsents_set is 0 Signed-off-by: tomoya.kimura * Update perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp Co-authored-by: Kenzo Lobos Tsunekawa * Update perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp Co-authored-by: Kenzo Lobos Tsunekawa --------- Signed-off-by: tomoya.kimura Co-authored-by: Kenzo Lobos Tsunekawa --- .../traffic_light_arbiter.hpp | 3 ++- .../src/traffic_light_arbiter.cpp | 19 +++++++++++++------ 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp index afb5984c288fc..485ce84c5fea6 100644 --- a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp +++ b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp @@ -22,6 +22,7 @@ #include +#include #include class TrafficLightArbiter : public rclcpp::Node @@ -45,7 +46,7 @@ class TrafficLightArbiter : public rclcpp::Node void onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg); void arbitrateAndPublish(const builtin_interfaces::msg::Time & stamp); - std::unordered_set map_regulatory_elements_set_; + std::unique_ptr> map_regulatory_elements_set_; double external_time_tolerance_; double perception_time_tolerance_; diff --git a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp index eb940fc18c32d..dfa01878bb81f 100644 --- a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -72,9 +72,10 @@ void TrafficLightArbiter::onMap(const LaneletMapBin::ConstSharedPtr msg) lanelet::utils::conversion::fromBinMsg(*msg, map); const auto signals = lanelet::filter_traffic_signals(map); - map_regulatory_elements_set_.clear(); + map_regulatory_elements_set_ = std::make_unique>(); + for (const auto & signal : signals) { - map_regulatory_elements_set_.emplace(signal->id()); + map_regulatory_elements_set_->emplace(signal->id()); } } @@ -109,14 +110,22 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim using ElementAndPriority = std::pair; std::unordered_map> regulatory_element_signals_map; - if (map_regulatory_elements_set_.empty()) { + if (map_regulatory_elements_set_ == nullptr) { RCLCPP_WARN(get_logger(), "Received traffic signal messages before a map"); return; } + TrafficSignalArray output_signals_msg; + output_signals_msg.stamp = stamp; + + if (map_regulatory_elements_set_->empty()) { + pub_->publish(output_signals_msg); + return; + } + auto add_signal_function = [&](const auto & signal, bool priority) { const auto id = signal.traffic_signal_id; - if (!map_regulatory_elements_set_.count(id)) { + if (!map_regulatory_elements_set_->count(id)) { RCLCPP_WARN( get_logger(), "Received a traffic signal not present in the current map (%lu)", id); return; @@ -165,8 +174,6 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim return highest_score_elements_vector; }; - TrafficSignalArray output_signals_msg; - output_signals_msg.stamp = stamp; output_signals_msg.signals.reserve(regulatory_element_signals_map.size()); for (const auto & [regulatory_element_id, elements] : regulatory_element_signals_map) { From 14f11438f05fccb6ed92e0c2b22947b8c980e2ed Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 27 Jul 2023 23:23:10 +0900 Subject: [PATCH 023/266] fix(traffic_light): fix traffic_light_arbiter pipeline (#4393) * fix(traffic_light): fix traffic_light_arbiter pipeline Signed-off-by: 1222-takeshi * style(pre-commit): autofix * fix: output topic name Signed-off-by: 1222-takeshi --------- Signed-off-by: 1222-takeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_recognition/traffic_light.launch.xml | 3 ++- .../launch/traffic_light_arbiter.launch.xml | 10 +++++++--- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 4dae46cbacb0a..38501cc059c1e 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -9,6 +9,7 @@ + @@ -130,7 +131,7 @@ - + diff --git a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml index 42944450378d6..f8c7b8a78fac6 100644 --- a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml +++ b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml @@ -1,11 +1,15 @@ + + + + - - - + + + From ade79c2ac36e6e6265f15ad64f1735178be40191 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 23:29:41 +0900 Subject: [PATCH 024/266] chore(pure_pursuit): fix typo (#4403) fix(pure_pursuit): fix typo Signed-off-by: Takayuki Murooka --- .../include/pure_pursuit/pure_pursuit.hpp | 10 +++++----- .../src/pure_pursuit_core/pure_pursuit.cpp | 11 ++++++----- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp b/control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp index 717c1ecac6c77..99b1a82ab2dce 100644 --- a/control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp +++ b/control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp @@ -47,7 +47,7 @@ namespace pure_pursuit class PurePursuit { public: - PurePursuit() : lookahead_distance_(0.0), clst_thr_dist_(3.0), clst_thr_ang_(M_PI / 4) {} + PurePursuit() : lookahead_distance_(0.0), closest_thr_dist_(3.0), closest_thr_ang_(M_PI / 4) {} ~PurePursuit() = default; rclcpp::Logger logger = rclcpp::get_logger("pure_pursuit"); @@ -55,10 +55,10 @@ class PurePursuit void setCurrentPose(const geometry_msgs::msg::Pose & msg); void setWaypoints(const std::vector & msg); void setLookaheadDistance(double ld) { lookahead_distance_ = ld; } - void setClosestThreshold(double clst_thr_dist, double clst_thr_ang) + void setClosestThreshold(double closest_thr_dist, double closest_thr_ang) { - clst_thr_dist_ = clst_thr_dist; - clst_thr_ang_ = clst_thr_ang; + closest_thr_dist_ = closest_thr_dist; + closest_thr_ang_ = closest_thr_ang; } // getter @@ -74,7 +74,7 @@ class PurePursuit geometry_msgs::msg::Point loc_next_tgt_; // variables got from outside - double lookahead_distance_, clst_thr_dist_, clst_thr_ang_; + double lookahead_distance_, closest_thr_dist_, closest_thr_ang_; std::shared_ptr> curr_wps_ptr_; std::shared_ptr curr_pose_ptr_; diff --git a/control/pure_pursuit/src/pure_pursuit_core/pure_pursuit.cpp b/control/pure_pursuit/src/pure_pursuit_core/pure_pursuit.cpp index 0b186a0c4514b..0ee96e970782c 100644 --- a/control/pure_pursuit/src/pure_pursuit_core/pure_pursuit.cpp +++ b/control/pure_pursuit/src/pure_pursuit_core/pure_pursuit.cpp @@ -55,16 +55,17 @@ std::pair PurePursuit::run() return std::make_pair(false, std::numeric_limits::quiet_NaN()); } - auto clst_pair = planning_utils::findClosestIdxWithDistAngThr( - *curr_wps_ptr_, *curr_pose_ptr_, clst_thr_dist_, clst_thr_ang_); + auto closest_pair = planning_utils::findClosestIdxWithDistAngThr( + *curr_wps_ptr_, *curr_pose_ptr_, closest_thr_dist_, closest_thr_ang_); - if (!clst_pair.first) { + if (!closest_pair.first) { RCLCPP_WARN( - logger, "cannot find, curr_bool: %d, clst_idx: %d", clst_pair.first, clst_pair.second); + logger, "cannot find, curr_bool: %d, closest_idx: %d", closest_pair.first, + closest_pair.second); return std::make_pair(false, std::numeric_limits::quiet_NaN()); } - int32_t next_wp_idx = findNextPointIdx(clst_pair.second); + int32_t next_wp_idx = findNextPointIdx(closest_pair.second); if (next_wp_idx == -1) { RCLCPP_WARN(logger, "lost next waypoint"); return std::make_pair(false, std::numeric_limits::quiet_NaN()); From 9311b89dfef5a591fc297339924d70f9ad15dcd3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 23:29:56 +0900 Subject: [PATCH 025/266] chore(mpc_lateral_controller): fix typo (#4404) fix(mpc_lateral_controller): fix typo Signed-off-by: Takayuki Murooka --- control/mpc_lateral_controller/CMakeLists.txt | 2 +- ...er_unconstr_fast.hpp => qp_solver_unconstraint_fast.hpp} | 6 +++--- .../model_predictive_control_algorithm.md | 2 +- .../mpc_lateral_controller/src/mpc_lateral_controller.cpp | 2 +- ...er_unconstr_fast.cpp => qp_solver_unconstraint_fast.cpp} | 2 +- control/mpc_lateral_controller/test/test_mpc.cpp | 2 +- 6 files changed, 8 insertions(+), 8 deletions(-) rename control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/{qp_solver_unconstr_fast.hpp => qp_solver_unconstraint_fast.hpp} (92%) rename control/mpc_lateral_controller/src/qp_solver/{qp_solver_unconstr_fast.cpp => qp_solver_unconstraint_fast.cpp} (94%) diff --git a/control/mpc_lateral_controller/CMakeLists.txt b/control/mpc_lateral_controller/CMakeLists.txt index 2437e8cacb386..e4a3683ea1fdc 100644 --- a/control/mpc_lateral_controller/CMakeLists.txt +++ b/control/mpc_lateral_controller/CMakeLists.txt @@ -17,7 +17,7 @@ ament_auto_add_library(${MPC_LAT_CON_LIB} SHARED src/mpc_trajectory.cpp src/mpc_utils.cpp src/qp_solver/qp_solver_osqp.cpp - src/qp_solver/qp_solver_unconstr_fast.cpp + src/qp_solver/qp_solver_unconstraint_fast.cpp src/vehicle_model/vehicle_model_bicycle_dynamics.cpp src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp src/vehicle_model/vehicle_model_bicycle_kinematics.cpp diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp similarity index 92% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp rename to control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp index e9ef492c80c88..3a6bd2b25832b 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTR_FAST_HPP_ -#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTR_FAST_HPP_ +#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ +#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ #include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" @@ -55,4 +55,4 @@ class QPSolverEigenLeastSquareLLT : public QPSolverInterface const Eigen::VectorXd & ub_a, Eigen::VectorXd & u) override; }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTR_FAST_HPP_ +#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ diff --git a/control/mpc_lateral_controller/model_predictive_control_algorithm.md b/control/mpc_lateral_controller/model_predictive_control_algorithm.md index 9dec0def2e477..4568fb9882817 100644 --- a/control/mpc_lateral_controller/model_predictive_control_algorithm.md +++ b/control/mpc_lateral_controller/model_predictive_control_algorithm.md @@ -344,7 +344,7 @@ $$ \end{align} $$ -Discretisizing $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply both sides by dt the resulting constraint become linear and convex +Discretizing $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply both sides by dt the resulting constraint become linear and convex $$ \begin{align} diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index c7fbce7411f1e..af680b5050037 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -16,7 +16,7 @@ #include "motion_utils/motion_utils.hpp" #include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp" +#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" diff --git a/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstr_fast.cpp b/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp similarity index 94% rename from control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstr_fast.cpp rename to control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp index 3c54ba6ffdc48..b0357138cd646 100644 --- a/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstr_fast.cpp +++ b/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp" +#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" #include diff --git a/control/mpc_lateral_controller/test/test_mpc.cpp b/control/mpc_lateral_controller/test/test_mpc.cpp index 72066003696d8..6066cd3419ef3 100644 --- a/control/mpc_lateral_controller/test/test_mpc.cpp +++ b/control/mpc_lateral_controller/test/test_mpc.cpp @@ -15,7 +15,7 @@ #include "gtest/gtest.h" #include "mpc_lateral_controller/mpc.hpp" #include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstr_fast.hpp" +#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" From a272d8660dd100442ded355a6b4baa5bd82beee3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 23:32:30 +0900 Subject: [PATCH 026/266] feat(dynamic_avoidance): add debug info for obstacle filtering (#4390) * feat(dynamic_avoidance): add debug info for obstacle filtering Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 3 ++ .../dynamic_avoidance_module.hpp | 3 ++ .../dynamic_avoidance_module.cpp | 50 ++++++++++++++----- .../dynamic_avoidance/manager.cpp | 10 ++++ 4 files changed, 53 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 845f9c38e269b..4b92567a35be5 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -1,6 +1,9 @@ /**: ros__parameters: dynamic_avoidance: + common: + enable_debug_info: true + # avoidance is performed for the object type with true target_object: car: true diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 4d90c15e7de4e..17c4644332291 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -37,6 +37,9 @@ namespace behavior_path_planner { struct DynamicAvoidanceParameters { + // common + bool enable_debug_info{true}; + // obstacle types to avoid bool avoid_car{true}; bool avoid_truck{true}; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index e4f121bb9d62d..aa05a789f7328 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -364,6 +364,10 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const bool is_crossing_object_to_ignore = parameters_->min_crossing_object_vel < std::abs(obj_vel) && is_obstacle_crossing_path; if (is_crossing_object_to_ignore) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since it crosses the ego's path.", + obj_uuid.c_str()); continue; } @@ -376,29 +380,57 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() std::abs(obj_angle) < parameters_->max_front_object_angle || M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); if (is_object_on_ego_path && is_object_aligned_to_path) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since it is to be followed.", obj_uuid.c_str()); continue; } // 5. check if object lateral offset to ego's path is large enough const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); if (is_object_far_from_path) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since lateral offset is large.", obj_uuid.c_str()); continue; } // 6. calculate which side object exists against ego's path - const bool is_left = isLeft(prev_module_path->points, obj_pose.position); + // TODO(murooka) use obj_path.back() instead of obj_pose for the case where the object crosses + // the ego's path + const bool is_left = isLeft(prev_module_path->points, obj_path.path.back().position); // 6. check if object will not cut in or cut out const bool will_object_cut_in = willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel); const bool will_object_cut_out = willObjectCutOut(obj_tangent_vel, obj_normal_vel, is_left); - if (will_object_cut_in || will_object_cut_out) { + if (will_object_cut_in) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since it will cut in.", obj_uuid.c_str()); + continue; + } + if (will_object_cut_out) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since it will cut out.", obj_uuid.c_str()); continue; } // 7. check if time to collision const double time_to_collision = calcTimeToCollision(prev_module_path->points, obj_pose, obj_tangent_vel); + if ( + (0 <= obj_tangent_vel && + parameters_->max_time_to_collision_overtaking_object < time_to_collision) || + (obj_tangent_vel <= 0 && + parameters_->max_time_to_collision_oncoming_object < time_to_collision)) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision is large.", + obj_uuid.c_str()); + continue; + } // 8. calculate alive counter for filtering objects const auto prev_target_object_candidate = @@ -625,18 +657,9 @@ std::optional DynamicAvoidanceModule::calcDynam return std::nullopt; } - if (0 <= object.vel) { - const double limited_time_to_collision = - std::min(parameters_->max_time_to_collision_overtaking_object, object.time_to_collision); - return std::make_pair( - raw_min_obj_lon_offset + object.vel * limited_time_to_collision, - raw_max_obj_lon_offset + object.vel * limited_time_to_collision); - } - - const double limited_time_to_collision = - std::min(parameters_->max_time_to_collision_oncoming_object, object.time_to_collision); return std::make_pair( - raw_min_obj_lon_offset + object.vel * limited_time_to_collision, raw_max_obj_lon_offset); + raw_min_obj_lon_offset + object.vel * object.time_to_collision, + raw_max_obj_lon_offset + object.vel * object.time_to_collision); }(); if (!obj_lon_offset) { @@ -647,6 +670,7 @@ std::optional DynamicAvoidanceModule::calcDynam // calculate bound start and end index const bool is_object_overtaking = (0.0 <= object.vel); + // TODO(murooka) use getEgoSpeed() instead of object.vel const double start_length_to_avoid = std::abs(object.vel) * (is_object_overtaking ? parameters_->start_duration_to_avoid_overtaking_object diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index eddb93094574d..056598ccc7026 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -29,6 +29,11 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( { DynamicAvoidanceParameters p{}; + { // common + std::string ns = "dynamic_avoidance.common."; + p.enable_debug_info = node->declare_parameter(ns + "enable_debug_info"); + } + { // target object std::string ns = "dynamic_avoidance.target_object."; p.avoid_car = node->declare_parameter(ns + "car"); @@ -88,6 +93,11 @@ void DynamicAvoidanceModuleManager::updateModuleParams( using tier4_autoware_utils::updateParam; auto & p = parameters_; + { // common + const std::string ns = "dynamic_avoidance.common."; + updateParam(parameters, ns + "enable_debug_info", p->enable_debug_info); + } + { // target object const std::string ns = "dynamic_avoidance.target_object."; From 7fb9b8ad61c10da4d06b2ba5d39c9236c919dc3f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 27 Jul 2023 23:47:37 +0900 Subject: [PATCH 027/266] chore(tier4_perception_launch): fix typo (#4406) * fix(tier4_perception_launch): fix typo Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../launch/traffic_light_recognition/traffic_light.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 38501cc059c1e..1f86a89ddfc7a 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -28,7 +28,7 @@ - + @@ -78,7 +78,7 @@ - + From 917ead5e714c3bcb3f761759a172c4bf6e10c2cc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E3=81=90=E3=82=8B=E3=81=90=E3=82=8B?= Date: Thu, 27 Jul 2023 23:48:02 +0900 Subject: [PATCH 028/266] refactor(yabloc): replace deprecated rosidl API (#4423) * refactor(yabloc_particle_filter): remove deprecated cmake ros2idl API Signed-off-by: f0reachARR * refactor(yabloc_pose_initializer): remove deprecated cmake ros2idl API Signed-off-by: f0reachARR --------- Signed-off-by: f0reachARR --- .../yabloc/yabloc_particle_filter/CMakeLists.txt | 12 ++++++++++-- .../yabloc/yabloc_pose_initializer/CMakeLists.txt | 9 ++++++++- 2 files changed, 18 insertions(+), 3 deletions(-) diff --git a/localization/yabloc/yabloc_particle_filter/CMakeLists.txt b/localization/yabloc/yabloc_particle_filter/CMakeLists.txt index 5f56186077d48..1284c52690795 100644 --- a/localization/yabloc/yabloc_particle_filter/CMakeLists.txt +++ b/localization/yabloc/yabloc_particle_filter/CMakeLists.txt @@ -49,7 +49,6 @@ ament_auto_add_library( ) target_include_directories(abstract_corrector SYSTEM PRIVATE ${PCL_INCLUDE_DIRS}) target_link_libraries(abstract_corrector Sophus::Sophus ${PCL_LIBRARIES}) -rosidl_target_interfaces(abstract_corrector ${PROJECT_NAME} "rosidl_typesupport_cpp") # Prediction library ament_auto_add_library(predictor @@ -60,7 +59,16 @@ ament_auto_add_library(predictor ) target_include_directories(predictor SYSTEM PRIVATE ${PCL_INCLUDE_DIRS}) target_link_libraries(predictor Sophus::Sophus ${PCL_LIBRARIES}) -rosidl_target_interfaces(predictor ${PROJECT_NAME} "rosidl_typesupport_cpp") + +# ros2idl typesupport +if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) + rosidl_target_interfaces(abstract_corrector ${PROJECT_NAME} "rosidl_typesupport_cpp") + rosidl_target_interfaces(predictor ${PROJECT_NAME} "rosidl_typesupport_cpp") +else() + rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(abstract_corrector "${cpp_typesupport_target}") + target_link_libraries(predictor "${cpp_typesupport_target}") +endif() # Cost map Library ament_auto_add_library(ll2_cost_map diff --git a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt index a2aaba44b6626..cd54a3c5f2ef2 100644 --- a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt +++ b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt @@ -44,9 +44,16 @@ ament_auto_add_executable(${TARGET} src/camera/camera_pose_initializer_node.cpp) target_include_directories(${TARGET} PUBLIC include) target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) -rosidl_target_interfaces(${TARGET} ${PROJECT_NAME} "rosidl_typesupport_cpp") target_link_libraries(${TARGET} ${PCL_LIBRARIES} Sophus::Sophus) +# ros2idl typesupport +if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) + rosidl_target_interfaces(${TARGET} ${PROJECT_NAME} "rosidl_typesupport_cpp") +else() + rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(${TARGET} "${cpp_typesupport_target}") +endif() + # Semantic segmentation install(PROGRAMS src/semantic_segmentation/semantic_segmentation_core.py From 19dc46e5e045a737818024f8e6bd8cb1f9e42e94 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 28 Jul 2023 00:14:30 +0900 Subject: [PATCH 029/266] feat: add openai-pr-reviewer (#4424) * feat: add openai-pr-reviewer Signed-off-by: Yukihito Saito * add OPENAI_API_ORG Signed-off-by: Yukihito Saito * change openai_heavy_model Signed-off-by: Yukihito Saito * remove OPENAI_API_ORG Signed-off-by: Yukihito Saito * Change action name Signed-off-by: Yukihito Saito --------- Signed-off-by: Yukihito Saito --- .github/workflows/openai-pr-reviewer.yaml | 31 +++++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 .github/workflows/openai-pr-reviewer.yaml diff --git a/.github/workflows/openai-pr-reviewer.yaml b/.github/workflows/openai-pr-reviewer.yaml new file mode 100644 index 0000000000000..8445b0debb17e --- /dev/null +++ b/.github/workflows/openai-pr-reviewer.yaml @@ -0,0 +1,31 @@ +name: Code Review By ChatGPT + +permissions: + contents: read + pull-requests: write + +on: + pull_request: + pull_request_review_comment: + types: [created] + +concurrency: + group: ${{ github.repository }}-${{ github.event.number || github.head_ref || + github.sha }}-${{ github.workflow }}-${{ github.event_name == + 'pull_request_review_comment' && 'pr_comment' || 'pr' }} + cancel-in-progress: ${{ github.event_name != 'pull_request_review_comment' }} + +jobs: + review: + runs-on: ubuntu-latest + steps: + - uses: fluxninja/openai-pr-reviewer@latest + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + OPENAI_API_KEY: ${{ secrets.OPENAI_API_KEY }} + with: + debug: false + review_simple_changes: false + review_comment_lgtm: false + openai_light_model: gpt-3.5-turbo-0613 + openai_heavy_model: gpt-3.5-turbo-0613 # The default is to use GPT4, which needs to be changed to join ChatGPT Plus. From 8f905a1b38f4fadab8c943ef7b148e0d8f4e462c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 28 Jul 2023 09:11:09 +0900 Subject: [PATCH 030/266] fix(dynamic_avoidance): avoid cut-in object close to the ego (#4412) * fix(dynamic_avoidance): avoid cut-in object close to the ego Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 4 ++ .../dynamic_avoidance_module.hpp | 15 ++++- .../dynamic_avoidance_module.cpp | 55 ++++++++++++++++++- .../dynamic_avoidance/manager.cpp | 11 ++++ 4 files changed, 82 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 4b92567a35be5..336879185f48e 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -22,6 +22,10 @@ min_obj_lat_offset_to_ego_path: 0.0 # [m] max_obj_lat_offset_to_ego_path: 1.0 # [m] + cut_in_object: + min_time_to_start_cut_in: 1.0 # [s] + min_lon_offset_ego_to_object: 0.0 # [m] + crossing_object: min_object_vel: 1.0 max_object_angle: 1.05 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 17c4644332291..f8830212a8222 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -55,6 +55,8 @@ struct DynamicAvoidanceParameters double min_obj_lat_offset_to_ego_path{0.0}; double max_obj_lat_offset_to_ego_path{0.0}; + double min_time_to_start_cut_in{0.0}; + double min_lon_offset_ego_to_cut_in_object{0.0}; double max_front_object_angle{0.0}; double min_crossing_object_vel{0.0}; double max_crossing_object_angle{0.0}; @@ -145,11 +147,20 @@ class DynamicAvoidanceModule : public SceneModuleInterface } private: + struct LatLonOffset + { + const size_t nearest_idx; + const double max_lat_offset; + const double min_lat_offset; + const double max_lon_offset; + const double min_lon_offset; + }; + bool isLabelTargetObstacle(const uint8_t label) const; std::vector calcTargetObjectsCandidate(); bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, - const double obj_tangent_vel) const; + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; bool willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_left) const; bool isObjectFarFromPath( @@ -159,6 +170,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double obj_tangent_vel) const; std::optional> calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const; + LatLonOffset getLateralLongitudinalOffset( + const std::vector & ego_path, const PredictedObject & object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index aa05a789f7328..b1aa372c42ac5 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -399,10 +399,12 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() // TODO(murooka) use obj_path.back() instead of obj_pose for the case where the object crosses // the ego's path const bool is_left = isLeft(prev_module_path->points, obj_path.path.back().position); + const auto lat_lon_offset = + getLateralLongitudinalOffset(prev_module_path->points, predicted_object); // 6. check if object will not cut in or cut out const bool will_object_cut_in = - willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel); + willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel, lat_lon_offset); const bool will_object_cut_out = willObjectCutOut(obj_tangent_vel, obj_normal_vel, is_left); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( @@ -516,7 +518,7 @@ bool DynamicAvoidanceModule::isObjectFarFromPath( bool DynamicAvoidanceModule::willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, - const double obj_tangent_vel) const + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const { constexpr double epsilon_path_lat_diff = 0.3; @@ -525,6 +527,20 @@ bool DynamicAvoidanceModule::willObjectCutIn( return false; } + // Ignore object close to the ego + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(ego_path); + const double relative_velocity = getEgoSpeed() - obj_tangent_vel; + const double lon_offset_ego_to_obj = + motion_utils::calcSignedArcLength( + ego_path, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx) + + lat_lon_offset.min_lon_offset; + if ( + lon_offset_ego_to_obj < std::max( + parameters_->min_lon_offset_ego_to_cut_in_object, + relative_velocity * parameters_->min_time_to_start_cut_in)) { + return false; + } + for (const auto & predicted_path_point : predicted_path.path) { const double paths_lat_diff = motion_utils::calcLateralOffset(ego_path, predicted_path_point.position); @@ -596,6 +612,41 @@ std::pair DynamicAvoidanceModule return std::make_pair(right_lanes, left_lanes); } +DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudinalOffset( + const std::vector & ego_path, const PredictedObject & object) const +{ + const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; + + const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); + const auto obj_points = tier4_autoware_utils::toPolygon2d(obj_pose, object.shape); + + // TODO(murooka) calculation is not so accurate. + std::vector obj_lat_offset_vec; + std::vector obj_lon_offset_vec; + for (size_t i = 0; i < obj_points.outer().size(); ++i) { + const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); + const size_t obj_point_seg_idx = + motion_utils::findNearestSegmentIndex(ego_path, geom_obj_point); + + // calculate lateral offset + const double obj_point_lat_offset = + motion_utils::calcLateralOffset(ego_path, geom_obj_point, obj_point_seg_idx); + obj_lat_offset_vec.push_back(obj_point_lat_offset); + + // calculate longitudinal offset + const double lon_offset = + motion_utils::calcLongitudinalOffsetToSegment(ego_path, obj_seg_idx, geom_obj_point); + obj_lon_offset_vec.push_back(lon_offset); + } + + const auto obj_lat_min_max_offset = getMinMaxValues(obj_lat_offset_vec); + const auto obj_lon_min_max_offset = getMinMaxValues(obj_lon_offset_vec); + + return LatLonOffset{ + obj_seg_idx, obj_lat_min_max_offset.second, obj_lat_min_max_offset.first, + obj_lon_min_max_offset.second, obj_lon_min_max_offset.first}; +} + // NOTE: object does not have const only to update min_bound_lat_offset. std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 056598ccc7026..27b467b3c9a74 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -53,6 +53,11 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.max_obj_lat_offset_to_ego_path = node->declare_parameter(ns + "max_obj_lat_offset_to_ego_path"); + p.min_time_to_start_cut_in = + node->declare_parameter(ns + "cut_in_object.min_time_to_start_cut_in"); + p.min_lon_offset_ego_to_cut_in_object = + node->declare_parameter(ns + "cut_in_object.min_lon_offset_ego_to_object"); + p.max_front_object_angle = node->declare_parameter(ns + "front_object.max_object_angle"); @@ -121,6 +126,12 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "max_obj_lat_offset_to_ego_path", p->max_obj_lat_offset_to_ego_path); + updateParam( + parameters, ns + "cut_in_object.min_time_to_start_cut_in", p->min_time_to_start_cut_in); + updateParam( + parameters, ns + "cut_in_object.min_lon_offset_ego_to_object", + p->min_lon_offset_ego_to_cut_in_object); + updateParam( parameters, ns + "front_object.max_object_angle", p->max_front_object_angle); From 7a4a8f896cc6d2a35670963a082134e9ead1b34f Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 28 Jul 2023 10:37:51 +0900 Subject: [PATCH 031/266] ci: add prevent-no-label-execution for openai-pr-reviewer (#4437) * ci: add prevent-no-label-execution for openai-pr-reviewer Signed-off-by: Ryohsuke Mitsudome * ci: add checks for labels to trigger openai-pr-reviwer Signed-off-by: Ryohsuke Mitsudome * ci: fix label name for openai-pr-reviewer Signed-off-by: Ryohsuke Mitsudome --------- Signed-off-by: Ryohsuke Mitsudome --- .github/workflows/openai-pr-reviewer.yaml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/.github/workflows/openai-pr-reviewer.yaml b/.github/workflows/openai-pr-reviewer.yaml index 8445b0debb17e..ecd8d85769a95 100644 --- a/.github/workflows/openai-pr-reviewer.yaml +++ b/.github/workflows/openai-pr-reviewer.yaml @@ -6,6 +6,10 @@ permissions: on: pull_request: + types: + - opened + - synchronize + - labeled pull_request_review_comment: types: [created] @@ -16,7 +20,13 @@ concurrency: cancel-in-progress: ${{ github.event_name != 'pull_request_review_comment' }} jobs: + prevent-no-label-execution: + uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 + with: + label: openai-pr-reviewer review: + needs: prevent-no-label-execution + if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }} runs-on: ubuntu-latest steps: - uses: fluxninja/openai-pr-reviewer@latest From dd8e1d65e77a31e7b565e76fcdde0c82b8a4da22 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Muhammed=20Yavuz=20K=C3=B6seo=C4=9Flu?= Date: Fri, 28 Jul 2023 12:08:08 +0300 Subject: [PATCH 032/266] refactor(tier4_localization_launch): change input/pointcloud param (#4411) * refactor(tier4_localization_launch): change input/pointcloud param * parameter renaming moved util.launch.py --- launch/tier4_localization_launch/launch/localization.launch.xml | 2 +- launch/tier4_localization_launch/launch/util/util.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index 550c9b5ff7fff..8538179253480 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/launch/tier4_localization_launch/launch/util/util.launch.py b/launch/tier4_localization_launch/launch/util/util.launch.py index ef9f25e43cf90..1a34429f438ed 100644 --- a/launch/tier4_localization_launch/launch/util/util.launch.py +++ b/launch/tier4_localization_launch/launch/util/util.launch.py @@ -34,7 +34,7 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_measurement_range", remappings=[ - ("input", LaunchConfiguration("input/pointcloud")), + ("input", LaunchConfiguration("input_pointcloud")), ("output", "measurement_range/pointcloud"), ], parameters=[ From 5e47d839741bf57c538cceace3dc95b855f8bbc6 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 28 Jul 2023 19:22:56 +0900 Subject: [PATCH 033/266] refactor(map_based_prediction): fix typo (#4440) --- .../map_based_prediction/src/map_based_prediction_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index a7762815f9e69..9292476e80c8e 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -227,7 +227,7 @@ lanelet::ConstLanelets getRightLineSharingLanelets( for (auto & candidate : right_lane_candidates) { // exclude self lanelet if (candidate == current_lanelet) continue; - // if candidate has linestring as leftbound, assign it to output + // if candidate has linestring as left bound, assign it to output if (candidate.leftBound() == current_lanelet.rightBound()) { output_lanelets.push_back(candidate); } @@ -254,7 +254,7 @@ lanelet::ConstLanelets getLeftLineSharingLanelets( for (auto & candidate : left_lane_candidates) { // exclude self lanelet if (candidate == current_lanelet) continue; - // if candidate has linestring as rightbound, assign it to output + // if candidate has linestring as right bound, assign it to output if (candidate.rightBound() == current_lanelet.leftBound()) { output_lanelets.push_back(candidate); } @@ -287,7 +287,7 @@ lanelet::routing::LaneletPaths getPossiblePathsForIsolatedLanelet( lanelet::ConstLanelets possible_lanelets; possible_lanelets.push_back(lanelet); lanelet::routing::LaneletPaths possible_paths; - // need to init path with constlanelets + // need to initialize path with constant lanelets lanelet::routing::LaneletPath possible_path(possible_lanelets); possible_paths.push_back(possible_path); return possible_paths; From 7a764697190f100550dc0c03c6fefaa7a10ed445 Mon Sep 17 00:00:00 2001 From: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Date: Fri, 28 Jul 2023 22:57:35 +0900 Subject: [PATCH 034/266] feat(default_ad_api): add object recognition api (#2887) * add object recognition api Signed-off-by: tkhmy * add unorder map Signed-off-by: tkhmy * pre-commit Signed-off-by: tkhmy * add missing time_span Signed-off-by: tkhmy * change naming Signed-off-by: tkhmy * update message Signed-off-by: tkhmy * change style Signed-off-by: tkhmy * change topic naming Signed-off-by: tkhmy --------- Signed-off-by: tkhmy Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .../autoware_ad_api_specs/perception.hpp | 36 +++++++ .../component_interface_specs/perception.hpp | 36 +++++++ system/default_ad_api/CMakeLists.txt | 2 + .../launch/default_ad_api.launch.py | 1 + system/default_ad_api/package.xml | 1 + system/default_ad_api/src/perception.cpp | 93 +++++++++++++++++++ system/default_ad_api/src/perception.hpp | 52 +++++++++++ 7 files changed, 221 insertions(+) create mode 100644 common/autoware_ad_api_specs/include/autoware_ad_api_specs/perception.hpp create mode 100644 common/component_interface_specs/include/component_interface_specs/perception.hpp create mode 100644 system/default_ad_api/src/perception.cpp create mode 100644 system/default_ad_api/src/perception.hpp diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/perception.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/perception.hpp new file mode 100644 index 0000000000000..5711c9a86d12a --- /dev/null +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/perception.hpp @@ -0,0 +1,36 @@ +// 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 AUTOWARE_AD_API_SPECS__PERCEPTION_HPP_ +#define AUTOWARE_AD_API_SPECS__PERCEPTION_HPP_ + +#include + +#include + +namespace autoware_ad_api::perception +{ + +struct DynamicObjectArray +{ + using Message = autoware_adapi_v1_msgs::msg::DynamicObjectArray; + static constexpr char name[] = "/api/perception/objects"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +} // namespace autoware_ad_api::perception + +#endif // AUTOWARE_AD_API_SPECS__PERCEPTION_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/perception.hpp b/common/component_interface_specs/include/component_interface_specs/perception.hpp new file mode 100644 index 0000000000000..8665b9c35157d --- /dev/null +++ b/common/component_interface_specs/include/component_interface_specs/perception.hpp @@ -0,0 +1,36 @@ +// 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 COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#define COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ + +#include + +#include + +namespace perception_interface +{ + +struct ObjectRecognition +{ + using Message = autoware_auto_perception_msgs::msg::PredictedObjects; + static constexpr char name[] = "/perception/object_recognition/objects"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +} // namespace perception_interface + +#endif // COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index 7bb80164bb9a0..7b9ad47d3782c 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -10,6 +10,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/localization.cpp src/motion.cpp src/operation_mode.cpp + src/perception.cpp src/planning.cpp src/routing.cpp src/vehicle.cpp @@ -25,6 +26,7 @@ rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::LocalizationNode" "default_ad_api::MotionNode" "default_ad_api::OperationModeNode" + "default_ad_api::PerceptionNode" "default_ad_api::PlanningNode" "default_ad_api::RoutingNode" "default_ad_api::VehicleNode" diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index fdb79d517206d..57a8557eb7e0a 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -47,6 +47,7 @@ def generate_launch_description(): create_api_node("localization", "LocalizationNode"), create_api_node("motion", "MotionNode"), create_api_node("operation_mode", "OperationModeNode"), + create_api_node("perception", "PerceptionNode"), create_api_node("planning", "PlanningNode"), create_api_node("routing", "RoutingNode"), create_api_node("vehicle", "VehicleNode"), diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index 032335fdddfd2..dfceeabe41122 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -28,6 +28,7 @@ nav_msgs rclcpp rclcpp_components + shape_msgs std_srvs tier4_api_msgs tier4_control_msgs diff --git a/system/default_ad_api/src/perception.cpp b/system/default_ad_api/src/perception.cpp new file mode 100644 index 0000000000000..61d09444c70a4 --- /dev/null +++ b/system/default_ad_api/src/perception.cpp @@ -0,0 +1,93 @@ +// 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 "perception.hpp" + +#include + +namespace default_ad_api +{ + +using DynamicObjectArray = autoware_ad_api::perception::DynamicObjectArray; +using ObjectClassification = autoware_adapi_v1_msgs::msg::ObjectClassification; +using DynamicObject = autoware_adapi_v1_msgs::msg::DynamicObject; +using DynamicObjectPath = autoware_adapi_v1_msgs::msg::DynamicObjectPath; +using API_Shape = shape_msgs::msg::SolidPrimitive; +using Shape = autoware_auto_perception_msgs::msg::Shape; + +std::unordered_map shape_type_ = { + {Shape::BOUNDING_BOX, API_Shape::BOX}, + {Shape::CYLINDER, API_Shape::CYLINDER}, + {Shape::POLYGON, API_Shape::PRISM}, +}; + +PerceptionNode::PerceptionNode(const rclcpp::NodeOptions & options) : Node("perception", options) +{ + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_pub(pub_object_recognized_); + adaptor.init_sub(sub_object_recognized_, this, &PerceptionNode::object_recognize); +} + +uint8_t PerceptionNode::mapping( + std::unordered_map hash_map, uint8_t input, uint8_t default_value) +{ + if (hash_map.find(input) == hash_map.end()) { + return default_value; + } else { + return hash_map[input]; + } +} + +void PerceptionNode::object_recognize( + const perception_interface::ObjectRecognition::Message::ConstSharedPtr msg) +{ + DynamicObjectArray::Message objects; + objects.header = msg->header; + for (const auto & msg_object : msg->objects) { + DynamicObject object; + object.id = msg_object.object_id; + object.existence_probability = msg_object.existence_probability; + for (const auto & msg_classification : msg_object.classification) { + ObjectClassification classification; + classification.label = msg_classification.label; + classification.probability = msg_classification.probability; + object.classification.insert(object.classification.begin(), classification); + } + object.kinematics.pose = msg_object.kinematics.initial_pose_with_covariance.pose; + object.kinematics.twist = msg_object.kinematics.initial_twist_with_covariance.twist; + object.kinematics.accel = msg_object.kinematics.initial_acceleration_with_covariance.accel; + for (const auto & msg_predicted_path : msg_object.kinematics.predicted_paths) { + DynamicObjectPath predicted_path; + for (const auto & msg_path : msg_predicted_path.path) { + predicted_path.path.insert(predicted_path.path.begin(), msg_path); + } + predicted_path.time_step = msg_predicted_path.time_step; + predicted_path.confidence = msg_predicted_path.confidence; + object.kinematics.predicted_paths.insert( + object.kinematics.predicted_paths.begin(), predicted_path); + } + object.shape.type = mapping(shape_type_, msg_object.shape.type, API_Shape::PRISM); + object.shape.dimensions = { + msg_object.shape.dimensions.x, msg_object.shape.dimensions.y, msg_object.shape.dimensions.z}; + object.shape.polygon = msg_object.shape.footprint; + objects.objects.insert(objects.objects.begin(), object); + } + + pub_object_recognized_->publish(objects); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::PerceptionNode) diff --git a/system/default_ad_api/src/perception.hpp b/system/default_ad_api/src/perception.hpp new file mode 100644 index 0000000000000..d1c71fdb08025 --- /dev/null +++ b/system/default_ad_api/src/perception.hpp @@ -0,0 +1,52 @@ +// 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 PERCEPTION_HPP_ +#define PERCEPTION_HPP_ + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +// This file should be included after messages. +#include "utils/types.hpp" + +namespace default_ad_api +{ + +class PerceptionNode : public rclcpp::Node +{ +public: + explicit PerceptionNode(const rclcpp::NodeOptions & options); + +private: + Pub pub_object_recognized_; + Sub sub_object_recognized_; + void object_recognize(const perception_interface::ObjectRecognition::Message::ConstSharedPtr msg); + uint8_t mapping( + std::unordered_map hash_map, uint8_t input, uint8_t default_value); +}; + +} // namespace default_ad_api + +#endif // PERCEPTION_HPP_ From b8aad734cc8892714ec557ac862639674cc3da85 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Sat, 29 Jul 2023 00:39:25 +0900 Subject: [PATCH 035/266] fix(roi_cluster_fusion): fix roi_cluster_fusion died bug (#4444) fix: fix roi_cluster_fusion died bug Signed-off-by: badai-nguyen --- .../src/roi_cluster_fusion/node.cpp | 57 ++++++++++--------- 1 file changed, 29 insertions(+), 28 deletions(-) diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index e0c346c3108a5..9180b18adeed8 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -191,38 +191,39 @@ void RoiClusterFusionNode::fuseOnSingleImage( max_iou = iou + iou_x + iou_y; } } - bool is_roi_label_known = feature_obj.object.classification.front().label != - autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; - bool is_roi_existence_prob_higher = - output_cluster_msg.feature_objects.at(index).object.existence_probability <= - feature_obj.object.existence_probability; - if (iou_threshold_ < max_iou && is_roi_existence_prob_higher && is_roi_label_known) { - output_cluster_msg.feature_objects.at(index).object.classification = - feature_obj.object.classification; - - // Update existence_probability for fused objects - if ( - output_cluster_msg.feature_objects.at(index).object.existence_probability < - min_roi_existence_prob_) { - output_cluster_msg.feature_objects.at(index).object.existence_probability = - min_roi_existence_prob_; + if (!output_cluster_msg.feature_objects.empty()) { + bool is_roi_label_known = feature_obj.object.classification.front().label != + autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; + bool is_roi_existence_prob_higher = + output_cluster_msg.feature_objects.at(index).object.existence_probability <= + feature_obj.object.existence_probability; + if (iou_threshold_ < max_iou && is_roi_existence_prob_higher && is_roi_label_known) { + output_cluster_msg.feature_objects.at(index).object.classification = + feature_obj.object.classification; + + // Update existence_probability for fused objects + if ( + output_cluster_msg.feature_objects.at(index).object.existence_probability < + min_roi_existence_prob_) { + output_cluster_msg.feature_objects.at(index).object.existence_probability = + min_roi_existence_prob_; + } } - } - // fuse with unknown roi - - if (unknown_iou_threshold_ < max_iou && is_roi_existence_prob_higher && !is_roi_label_known) { - output_cluster_msg.feature_objects.at(index).object.classification = - feature_obj.object.classification; - // Update existence_probability for fused objects - if ( - output_cluster_msg.feature_objects.at(index).object.existence_probability < - min_roi_existence_prob_) { - output_cluster_msg.feature_objects.at(index).object.existence_probability = - min_roi_existence_prob_; + // fuse with unknown roi + + if (unknown_iou_threshold_ < max_iou && is_roi_existence_prob_higher && !is_roi_label_known) { + output_cluster_msg.feature_objects.at(index).object.classification = + feature_obj.object.classification; + // Update existence_probability for fused objects + if ( + output_cluster_msg.feature_objects.at(index).object.existence_probability < + min_roi_existence_prob_) { + output_cluster_msg.feature_objects.at(index).object.existence_probability = + min_roi_existence_prob_; + } } } - debug_image_rois.push_back(feature_obj.feature.roi); } From 83ead419563ed2a988ab1888347189391cf8541c Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Sat, 29 Jul 2023 17:03:58 +0900 Subject: [PATCH 036/266] feat(intersection): extract occlusion contour as polygon (#4442) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 6 + .../config/intersection.param.yaml | 2 +- .../package.xml | 5 - .../src/debug.cpp | 8 ++ .../src/manager.cpp | 3 +- .../src/scene_intersection.cpp | 125 +++++++++--------- .../src/scene_intersection.hpp | 5 +- .../src/util_type.hpp | 1 + 8 files changed, 80 insertions(+), 75 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_intersection_module/CMakeLists.txt index 3e6d5bc81ff92..8ff78dac06716 100644 --- a/planning/behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/behavior_velocity_intersection_module/CMakeLists.txt @@ -5,6 +5,8 @@ find_package(autoware_cmake REQUIRED) autoware_package() pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +find_package(OpenCV REQUIRED) + ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp src/manager.cpp @@ -13,4 +15,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/util.cpp ) +target_link_libraries(${PROJECT_NAME} + ${OpenCV_LIBRARIES} +) + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index efe0efa3d7310..cbd4d4879753b 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -46,7 +46,7 @@ min_vehicle_brake_for_rss: -2.5 # [m/s^2] max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph denoise_kernel: 1.0 # [m] - pub_debug_grid: false + possible_object_bbox: [1.0, 2.0] # [m x m] enable_rtc: # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval intersection: true diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_intersection_module/package.xml index 25df9f2385d74..1d6067d4be322 100644 --- a/planning/behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_intersection_module/package.xml @@ -20,14 +20,9 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs behavior_velocity_planner_common - cv_bridge geometry_msgs - grid_map_cv - grid_map_ros interpolation lanelet2_extension - libboost-dev - libopencv-dev magic_enum motion_utils nav_msgs diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index dc5b2b8373f04..ae8eee39d6556 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -221,6 +221,14 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array, now); } + for (size_t j = 0; j < debug_data_.occlusion_polygons.size(); ++j) { + const auto & p = debug_data_.occlusion_polygons.at(j); + appendMarkerArray( + debug::createPolygonMarkerArray( + p, "occlusion_polygons", lane_id_ + j, now, 0.3, 0.0, 0.0, 1.0, 0.0, 0.0), + &debug_marker_array, now); + } + return debug_marker_array; } diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 8064ccbd33430..336087751d9aa 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -113,7 +113,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.occlusion.max_vehicle_velocity_for_rss = node.declare_parameter(ns + ".occlusion.max_vehicle_velocity_for_rss"); ip.occlusion.denoise_kernel = node.declare_parameter(ns + ".occlusion.denoise_kernel"); - ip.occlusion.pub_debug_grid = node.declare_parameter(ns + ".occlusion.pub_debug_grid"); + ip.occlusion.possible_object_bbox = + node.declare_parameter>(ns + ".occlusion.possible_object_bbox"); } void IntersectionModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 086e844cd5e81..d4db6e83861a2 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -12,26 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include -#include -#include -#include -#include - -#if __has_include() -#include -#else -#include -#endif -// #include -// #include #include "scene_intersection.hpp" + #include "util.hpp" #include #include #include +#include +#include +#include +#include #include #include @@ -93,10 +84,6 @@ IntersectionModule::IntersectionModule( planner_param_.collision_detection.state_transit_margin_time); before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time); before_creep_state_machine_.setState(StateMachine::State::STOP); - if (enable_occlusion_detection) { - occlusion_grid_pub_ = node_.create_publisher( - "~/debug/intersection/occlusion_grid", rclcpp::QoS(1).transient_local()); - } stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area); stuck_private_area_timeout_.setState(StateMachine::State::STOP); } @@ -1176,7 +1163,7 @@ bool IntersectionModule::isOcclusionCleared( } } for (const auto & poly : attention_area_cv_polygons) { - cv::fillPoly(attention_mask, poly, cv::Scalar(255), cv::LINE_AA); + cv::fillPoly(attention_mask, poly, cv::Scalar(255), cv::LINE_4); } // (1.1) // reset adjacent_lanelets area to 0 on attention_mask @@ -1201,8 +1188,8 @@ bool IntersectionModule::isOcclusionCleared( for (const auto & common_area : common_areas) { std::vector adjacent_lane_cv_polygon; for (const auto & p : common_area.outer()) { - const int idx_x = static_cast((p.x() - origin.x) / resolution); - const int idx_y = static_cast((p.y() - origin.y) / resolution); + const int idx_x = std::floor((p.x() - origin.x) / resolution); + const int idx_y = std::floor((p.y() - origin.y) / resolution); adjacent_lane_cv_polygon.emplace_back(idx_x, height - 1 - idx_y); } adjacent_lane_cv_polygons.push_back(adjacent_lane_cv_polygon); @@ -1231,7 +1218,7 @@ bool IntersectionModule::isOcclusionCleared( cv::bitwise_and(attention_mask, unknown_mask, occlusion_mask_raw); // (3.1) apply morphologyEx cv::Mat occlusion_mask; - const int morph_size = std::ceil(planner_param_.occlusion.denoise_kernel / resolution); + const int morph_size = static_cast(planner_param_.occlusion.denoise_kernel / resolution); cv::morphologyEx( occlusion_mask_raw, occlusion_mask, cv::MORPH_OPEN, cv::getStructuringElement(cv::MORPH_RECT, cv::Size(morph_size, morph_size))); @@ -1337,59 +1324,70 @@ bool IntersectionModule::isOcclusionCleared( } } - // clean-up and find nearest risk + const auto & possible_object_bbox = planner_param_.occlusion.possible_object_bbox; + const double possible_object_bbox_x = possible_object_bbox.at(0) / resolution; + const double possible_object_bbox_y = possible_object_bbox.at(1) / resolution; + const double possible_object_area = possible_object_bbox_x * possible_object_bbox_y; + std::vector> contours; + cv::findContours(occlusion_mask, contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE); + std::vector> valid_contours; + for (const auto & contour : contours) { + std::vector valid_contour; + for (const auto & p : contour) { + if (distance_grid.at(p.y, p.x) == undef_pixel) { + continue; + } + valid_contour.push_back(p); + } + if (valid_contour.size() <= 2) { + continue; + } + std::vector approx_contour; + cv::approxPolyDP( + valid_contour, approx_contour, + std::round(std::min(possible_object_bbox_x, possible_object_bbox_y) / std::sqrt(2.0)), true); + if (approx_contour.size() <= 1) continue; + // check area + const double poly_area = cv::contourArea(approx_contour); + if (poly_area < possible_object_area) continue; + + valid_contours.push_back(approx_contour); + geometry_msgs::msg::Polygon polygon_msg; + geometry_msgs::msg::Point32 point_msg; + for (const auto & p : approx_contour) { + const double glob_x = (p.x + 0.5) * resolution + origin.x; + const double glob_y = (height - 0.5 - p.y) * resolution + origin.y; + point_msg.x = glob_x; + point_msg.y = glob_y; + point_msg.z = origin.z; + polygon_msg.points.push_back(point_msg); + } + debug_data_.occlusion_polygons.push_back(polygon_msg); + } + const int min_cost_thr = dist2pixel(occlusion_dist_thr); int min_cost = undef_pixel - 1; - int max_cost = 0; - std::optional min_cost_projection_ind = std::nullopt; geometry_msgs::msg::Point nearest_occlusion_point; - for (int i = 0; i < width; ++i) { - for (int j = 0; j < height; ++j) { - const int pixel = static_cast(distance_grid.at(height - 1 - j, i)); - const bool occluded = (occlusion_mask.at(height - 1 - j, i) == 255); + for (const auto & occlusion_contour : valid_contours) { + for (const auto & p : occlusion_contour) { + const int pixel = static_cast(distance_grid.at(p.y, p.x)); + const bool occluded = (occlusion_mask.at(p.y, p.x) == 255); if (pixel == undef_pixel || !occluded) { - // ignore outside of cropped - // some cell maybe undef still - distance_grid.at(height - 1 - j, i) = 0; continue; } - if (max_cost < pixel) { - max_cost = pixel; - } - const int projection_ind = projection_ind_grid.at(height - 1 - j, i); if (pixel < min_cost) { - assert(projection_ind >= 0); min_cost = pixel; - min_cost_projection_ind = projection_ind; - nearest_occlusion_point.x = origin.x + i * resolution; - nearest_occlusion_point.y = origin.y + j * resolution; - nearest_occlusion_point.z = origin.z + distance_max * pixel / max_cost_pixel; + nearest_occlusion_point.x = origin.x + p.x * resolution; + nearest_occlusion_point.y = origin.y + (height - 1 - p.y) * resolution; + nearest_occlusion_point.z = origin.z; } } } - debug_data_.nearest_occlusion_point = nearest_occlusion_point; - - if (planner_param_.occlusion.pub_debug_grid) { - cv::Mat distance_grid_heatmap; - cv::applyColorMap(distance_grid, distance_grid_heatmap, cv::COLORMAP_JET); - grid_map::GridMap occlusion_grid({"elevation"}); - occlusion_grid.setFrameId("map"); - occlusion_grid.setGeometry( - grid_map::Length(width * resolution, height * resolution), resolution, - grid_map::Position(origin.x + width * resolution / 2, origin.y + height * resolution / 2)); - cv::rotate(distance_grid, distance_grid, cv::ROTATE_90_COUNTERCLOCKWISE); - cv::rotate(distance_grid_heatmap, distance_grid_heatmap, cv::ROTATE_90_COUNTERCLOCKWISE); - grid_map::GridMapCvConverter::addLayerFromImage( - distance_grid, "elevation", occlusion_grid, origin.z /* elevation for 0 */, - origin.z + distance_max /* elevation for 255 */); - grid_map::GridMapCvConverter::addColorLayerFromImage( - distance_grid_heatmap, "color", occlusion_grid); - occlusion_grid_pub_->publish(grid_map::GridMapRosConverter::toMessage(occlusion_grid)); - } - if (min_cost > min_cost_thr || !min_cost_projection_ind.has_value()) { + if (min_cost > min_cost_thr) { return true; } else { + debug_data_.nearest_occlusion_point = nearest_occlusion_point; return false; } } @@ -1418,9 +1416,8 @@ bool IntersectionModule::checkFrontVehicleDeceleration( // get the nearest centerpoint to object std::vector dist_obj_center_points; for (const auto & p : center_points) - dist_obj_center_points.push_back(tier4_autoware_utils::calcDistance2d(object_pose.position, p)); - const int obj_closest_centerpoint_idx = std::distance( - dist_obj_center_points.begin(), + dist_obj_center_points.push_back(tier4_autoware_utils::calcDistance2d(object_pose.position, +p)); const int obj_closest_centerpoint_idx = std::distance( dist_obj_center_points.begin(), std::min_element(dist_obj_center_points.begin(), dist_obj_center_points.end())); // find two center_points whose distances from `closest_centerpoint` cross stopping_distance double acc_dist_prev = 0.0, acc_dist = 0.0; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 893761e834f3a..950cd6006cbe4 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -20,13 +20,11 @@ #include #include #include -#include #include #include #include #include -#include #include #include @@ -108,7 +106,7 @@ class IntersectionModule : public SceneModuleInterface double min_vehicle_brake_for_rss; double max_vehicle_velocity_for_rss; double denoise_kernel; - bool pub_debug_grid; + std::vector possible_object_bbox; } occlusion; }; @@ -274,7 +272,6 @@ class IntersectionModule : public SceneModuleInterface */ util::DebugData debug_data_; - rclcpp::Publisher::SharedPtr occlusion_grid_pub_; }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 4a87b993dbe73..55e6308d7e67b 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -49,6 +49,7 @@ struct DebugData autoware_auto_perception_msgs::msg::PredictedObjects stuck_targets; std::optional nearest_occlusion_point = std::nullopt; std::optional nearest_occlusion_projection_point = std::nullopt; + std::vector occlusion_polygons; }; struct InterpolatedPathInfo From 8a139596de1ca20318cbb8d08a1a569e86988a90 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Sun, 30 Jul 2023 10:38:09 +0900 Subject: [PATCH 037/266] fix(compare_map_segmentation): change to using kinematic_state topic (#4448) Signed-off-by: badai-nguyen --- .../detection/pointcloud_map_filter.launch.py | 4 +-- .../compare_map_segmentation/CMakeLists.txt | 3 +-- perception/compare_map_segmentation/README.md | 11 ++++---- .../voxel_grid_map_loader.hpp | 13 +++------- .../compare_map_segmentation/package.xml | 3 +-- .../src/voxel_grid_map_loader.cpp | 26 +++---------------- .../launch/euclidean_cluster.launch.py | 2 +- ...xel_grid_based_euclidean_cluster.launch.py | 2 +- 8 files changed, 18 insertions(+), 46 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py index dc3e33faafb94..a5d8d2113d2db 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py @@ -65,7 +65,7 @@ def create_normal_pipeline(self): ("map", "/map/pointcloud_map"), ("output", LaunchConfiguration("output_topic")), ("map_loader_service", "/map/get_differential_pointcloud_map"), - ("pose_with_covariance", "/localization/pose_estimator/pose_with_covariance"), + ("kinematic_state", "/localization/kinematic_state"), ], parameters=[ { @@ -122,7 +122,7 @@ def create_down_sample_pipeline(self): ("map", "/map/pointcloud_map"), ("output", LaunchConfiguration("output_topic")), ("map_loader_service", "/map/get_differential_pointcloud_map"), - ("pose_with_covariance", "/localization/pose_estimator/pose_with_covariance"), + ("kinematic_state", "/localization/kinematic_state"), ], parameters=[ { diff --git a/perception/compare_map_segmentation/CMakeLists.txt b/perception/compare_map_segmentation/CMakeLists.txt index 2d65f75a098a3..4655cf4c2f73a 100644 --- a/perception/compare_map_segmentation/CMakeLists.txt +++ b/perception/compare_map_segmentation/CMakeLists.txt @@ -46,8 +46,7 @@ ament_target_dependencies(compare_map_segmentation sensor_msgs tier4_autoware_utils autoware_map_msgs - component_interface_specs - component_interface_utils + nav_msgs ) if(OPENMP_FOUND) diff --git a/perception/compare_map_segmentation/README.md b/perception/compare_map_segmentation/README.md index ad891b9ad6afa..0566b5af806db 100644 --- a/perception/compare_map_segmentation/README.md +++ b/perception/compare_map_segmentation/README.md @@ -61,12 +61,11 @@ This filter is a combination of the distance_based_compare_map_filter and voxel_ #### Input -| Name | Type | Description | -| ------------------------------------ | ----------------------------------------------- | -------------------------------------------------------------- | -| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points | -| `~/input/map` | `sensor_msgs::msg::PointCloud2` | map (in case static map loading) | -| `~/pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | current ego-vehicle pose (in case dynamic map loading) | -| `/localization/initialization_state` | `localization_interface::InitializationState` | Ego-vehicle pose initialization state (in dynamic map loading) | +| Name | Type | Description | +| ------------------------------- | ------------------------------- | ------------------------------------------------------ | +| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points | +| `~/input/map` | `sensor_msgs::msg::PointCloud2` | map (in case static map loading) | +| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | current ego-vehicle pose (in case dynamic map loading) | #### Output diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp index 9a9c0d1534a5e..8e3bb21cc4486 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp +++ b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp @@ -15,12 +15,11 @@ #ifndef COMPARE_MAP_SEGMENTATION__VOXEL_GRID_MAP_LOADER_HPP_ #define COMPARE_MAP_SEGMENTATION__VOXEL_GRID_MAP_LOADER_HPP_ -#include -#include #include #include #include +#include #include #include @@ -154,16 +153,11 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader }; typedef typename std::map VoxelGridDict; - using InitializationState = localization_interface::InitializationState; /** \brief Map to hold loaded map grid id and it's voxel filter */ VoxelGridDict current_voxel_grid_dict_; + rclcpp::Subscription::SharedPtr sub_kinematic_state_; - rclcpp::Subscription::SharedPtr - sub_estimated_pose_; - component_interface_utils::Subscription::SharedPtr - sub_pose_initializer_state_; - InitializationState::Message initialization_state_; std::optional current_position_ = std::nullopt; std::optional last_updated_position_ = std::nullopt; rclcpp::TimerBase::SharedPtr map_update_timer_; @@ -200,8 +194,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame, std::mutex * mutex, rclcpp::CallbackGroup::SharedPtr main_callback_group); - void onEstimatedPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose); - void onPoseInitializerCallback(const InitializationState::Message::ConstSharedPtr msg); + void onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr pose); void timer_callback(); bool should_update_map() const; diff --git a/perception/compare_map_segmentation/package.xml b/perception/compare_map_segmentation/package.xml index fc6806ddaa843..42fad723b5d57 100644 --- a/perception/compare_map_segmentation/package.xml +++ b/perception/compare_map_segmentation/package.xml @@ -18,10 +18,9 @@ autoware_cmake autoware_map_msgs - component_interface_specs - component_interface_utils grid_map_pcl grid_map_ros + nav_msgs pcl_conversions pointcloud_preprocessor rclcpp diff --git a/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp b/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp index 426dc8e706dc9..06bd89af38259 100644 --- a/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp +++ b/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp @@ -301,13 +301,8 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader( map_loader_radius_ = node->declare_parameter("map_loader_radius"); auto main_sub_opt = rclcpp::SubscriptionOptions(); main_sub_opt.callback_group = main_callback_group; - - const auto localization_node = component_interface_utils::NodeAdaptor(node); - localization_node.init_sub( - sub_pose_initializer_state_, this, &VoxelGridDynamicMapLoader::onPoseInitializerCallback); - - sub_estimated_pose_ = node->create_subscription( - "pose_with_covariance", rclcpp::QoS{1}, + sub_kinematic_state_ = node->create_subscription( + "kinematic_state", rclcpp::QoS{1}, std::bind(&VoxelGridDynamicMapLoader::onEstimatedPoseCallback, this, std::placeholders::_1), main_sub_opt); RCLCPP_INFO(logger_, "VoxelGridDynamicMapLoader initialized.\n"); @@ -327,18 +322,7 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader( node, node->get_clock(), period_ns, std::bind(&VoxelGridDynamicMapLoader::timer_callback, this), timer_callback_group_); } -void VoxelGridDynamicMapLoader::onPoseInitializerCallback( - const InitializationState::Message::ConstSharedPtr msg) -{ - initialization_state_.state = msg->state; - if (msg->state != InitializationState::Message::INITIALIZED) { - current_position_ = std::nullopt; - last_updated_position_ = std::nullopt; - RCLCPP_INFO(logger_, "Initializing pose... Reset the position of Vehicle"); - } -} -void VoxelGridDynamicMapLoader::onEstimatedPoseCallback( - geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg) +void VoxelGridDynamicMapLoader::onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg) { current_position_ = msg->pose.pose.position; } @@ -417,9 +401,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_map( } void VoxelGridDynamicMapLoader::timer_callback() { - if ( - current_position_ == std::nullopt || - initialization_state_.state != InitializationState::Message::INITIALIZED) { + if (current_position_ == std::nullopt) { return; } if (last_updated_position_ == std::nullopt) { diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index f4256422e6c8b..db86bbf80d250 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -57,7 +57,7 @@ def load_composable_node_param(param_path): ("map", LaunchConfiguration("input_map")), ("output", "compare_map_filtered/pointcloud"), ("map_loader_service", "/map/get_differential_pointcloud_map"), - ("pose_with_covariance", "/localization/pose_estimator/pose_with_covariance"), + ("kinematic_state", "/localization/kinematic_state"), ], parameters=[ { diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index a2c7c5966da62..82ce5605b67cd 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -47,7 +47,7 @@ def load_composable_node_param(param_path): ("map", LaunchConfiguration("input_map")), ("output", "map_filter/pointcloud"), ("map_loader_service", "/map/get_differential_pointcloud_map"), - ("pose_with_covariance", "/localization/pose_estimator/pose_with_covariance"), + ("kinematic_state", "/localization/kinematic_state"), ], parameters=[load_composable_node_param("compare_map_param_path")], ) From 86e0a0107f119b80874c8769e1480841a3958554 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 30 Jul 2023 13:21:50 +0900 Subject: [PATCH 038/266] fix(start_planner): fix path generation for separated lanes and extended loop lanes (#4418) * fix(start_planner): fix path generation for separated lanes and extended loop lanes Signed-off-by: kosuke55 * Add until goal lanes option Signed-off-by: kosuke55 * add commnets Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../behavior_path_planner/utils/utils.hpp | 2 +- .../goal_planner/goal_planner_module.cpp | 6 +- .../start_planner/start_planner_module.cpp | 9 ++- .../goal_planner/geometric_pull_over.cpp | 3 +- .../src/utils/goal_planner/goal_searcher.cpp | 4 +- .../utils/goal_planner/shift_pull_over.cpp | 5 +- .../start_planner/geometric_pull_out.cpp | 3 +- .../utils/start_planner/shift_pull_out.cpp | 4 +- .../src/utils/start_planner/util.cpp | 4 +- .../behavior_path_planner/src/utils/utils.cpp | 59 ++++++++++++++----- 10 files changed, 69 insertions(+), 30 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 07ec7c5db6605..d1a69fa0e6cce 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -383,7 +383,7 @@ lanelet::ConstLanelets getExtendedCurrentLanes( lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data, const double backward_length, - const double forward_length); + const double forward_length, const bool until_goal_lane); lanelet::ConstLanelets calcLaneAroundPose( const std::shared_ptr route_handler, const geometry_msgs::msg::Pose & pose, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6915b2be16819..61322025b46f2 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -153,7 +153,8 @@ void GoalPlannerModule::onTimer() // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length); + parameters_->forward_goal_search_length, + /*until_goal_lane*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; double min_start_arc_length = std::numeric_limits::max(); @@ -590,7 +591,8 @@ void GoalPlannerModule::setLanes() { status_.current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length); + parameters_->forward_goal_search_length, + /*until_goal_lane*/ false); status_.pull_over_lanes = goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_); status_.lanes = diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index bc3ce480476ee..fbc81d4a2e890 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -115,7 +115,8 @@ bool StartPlannerModule::isExecutionRequested() const const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max()); + planner_data_, backward_path_length, std::numeric_limits::max(), + /*until_goal_lane*/ true); const auto pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); auto lanes = current_lanes; @@ -326,7 +327,8 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max()); + planner_data_, backward_path_length, std::numeric_limits::max(), + /*until_goal_lane*/ true); const auto pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); @@ -562,7 +564,8 @@ void StartPlannerModule::updatePullOutStatus() const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_->max_back_distance; status_.current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max()); + planner_data_, backward_path_length, std::numeric_limits::max(), + /*until_goal_lane*/ true); status_.pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp index 24c6d98ed09e5..ca251e625a5b0 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp @@ -45,7 +45,8 @@ boost::optional GeometricPullOver::plan(const Pose & goal_pose) // prepare road nad shoulder lanes const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + /*until_goal_lane*/ false); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index 9123beca0d95c..a3bd96bddb3d7 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -54,7 +54,9 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose) const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); - auto lanes = utils::getExtendedCurrentLanes(planner_data_, backward_length, forward_length); + auto lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_length, forward_length, + /*until_goal_lane*/ false); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); const auto goal_arc_coords = diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp index 8bf20b212d51d..71ebed11cbd63 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp @@ -46,8 +46,9 @@ boost::optional ShiftPullOver::plan(const Pose & goal_pose) const double jerk_resolution = std::abs(max_jerk - min_jerk) / shift_sampling_num; // get road and shoulder lanes - const auto road_lanes = - utils::getExtendedCurrentLanes(planner_data_, backward_search_length, forward_search_length); + const auto road_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_search_length, forward_search_length, + /*until_goal_lane*/ false); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 9ab3101cdc4a5..5561411dfbf39 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -43,7 +43,8 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_.max_back_distance; const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max()); + planner_data_, backward_path_length, std::numeric_limits::max(), + /*until_goal_lane*/ true); const auto pull_out_lanes = getPullOutLanes(planner_data_, backward_path_length); auto lanes = road_lanes; for (const auto & pull_out_lane : pull_out_lanes) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index a34d9f536c682..4561062abfa73 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -53,8 +53,8 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) } const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max()); - + planner_data_, backward_path_length, std::numeric_limits::max(), + /*until_goal_lane*/ true); // find candidate paths auto pull_out_paths = calcPullOutPaths( *route_handler, road_lanes, start_pose, goal_pose, common_parameters, parameters_); diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 2a9ab676211fb..856385be8d970 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -114,6 +114,8 @@ lanelet::ConstLanelets getPullOutLanes( // pull out from road lane return utils::getExtendedCurrentLanes( - planner_data, backward_length, /*forward_length*/ std::numeric_limits::max()); + planner_data, backward_length, + /*forward_length*/ std::numeric_limits::max(), + /*until_goal_lane*/ true); } } // namespace behavior_path_planner::start_planner_utils diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 44b575e2cdf44..55beafa8a3ea1 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2864,7 +2864,14 @@ lanelet::ConstLanelets extendNextLane( // Add next lane const auto next_lanes = route_handler->getNextLanelets(extended_lanes.back()); if (!next_lanes.empty()) { - extended_lanes.push_back(next_lanes.front()); + // use the next lane in route if it exists + auto target_next_lane = next_lanes.front(); + for (const auto & next_lane : next_lanes) { + if (route_handler->isRouteLanelet(next_lane)) { + target_next_lane = next_lane; + } + } + extended_lanes.push_back(target_next_lane); } return extended_lanes; @@ -2878,9 +2885,15 @@ lanelet::ConstLanelets extendPrevLane( // Add previous lane const auto prev_lanes = route_handler->getPreviousLanelets(extended_lanes.front()); if (!prev_lanes.empty()) { - extended_lanes.insert(extended_lanes.begin(), prev_lanes.front()); + // use the previous lane in route if it exists + auto target_prev_lane = prev_lanes.front(); + for (const auto & prev_lane : prev_lanes) { + if (route_handler->isRouteLanelet(prev_lane)) { + target_prev_lane = prev_lane; + } + } + extended_lanes.insert(extended_lanes.begin(), target_prev_lane); } - return extended_lanes; } @@ -2895,26 +2908,24 @@ lanelet::ConstLanelets extendLanes( lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data, const double backward_length, - const double forward_length) + const double forward_length, const bool until_goal_lane) { auto lanes = getCurrentLanes(planner_data); if (lanes.empty()) return lanes; + const auto start_lane = lanes.front(); double forward_length_sum = 0.0; double backward_length_sum = 0.0; - const auto is_loop = [&](const auto & target_lane) { - auto it = std::find_if(lanes.begin(), lanes.end(), [&](const lanelet::ConstLanelet & lane) { - return lane.id() == target_lane.id(); - }); - - return it != lanes.end(); - }; - while (backward_length_sum < backward_length) { auto extended_lanes = extendPrevLane(planner_data->route_handler, lanes); - - if (extended_lanes.empty() || is_loop(extended_lanes.front())) { + if (extended_lanes.empty()) { + return lanes; + } + // loop check + // if current map lanes is looping and has a very large value for backward_length, + // the extending process will not finish. + if (extended_lanes.front().id() == start_lane.id()) { return lanes; } @@ -2927,9 +2938,25 @@ lanelet::ConstLanelets getExtendedCurrentLanes( } while (forward_length_sum < forward_length) { - auto extended_lanes = extendNextLane(planner_data->route_handler, lanes); + // stop extending if the goal lane is included + // if forward_length is a very large value, set it to true, + // as it may continue to extend lanes outside the route ahead of goal forever. + if (until_goal_lane) { + lanelet::ConstLanelet goal_lane; + planner_data->route_handler->getGoalLanelet(&goal_lane); + if (lanes.back().id() == goal_lane.id()) { + return lanes; + } + } - if (extended_lanes.empty() || is_loop(extended_lanes.back())) { + auto extended_lanes = extendNextLane(planner_data->route_handler, lanes); + if (extended_lanes.empty()) { + return lanes; + } + // loop check + // if current map lanes is looping and has a very large value for forward_length, + // the extending process will not finish. + if (extended_lanes.back().id() == start_lane.id()) { return lanes; } From 8a82fa92082972b0f447d93cf9f5325f187485e2 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 30 Jul 2023 13:22:05 +0900 Subject: [PATCH 039/266] fix(start_planner): remove shift pull out enough distance check (#4422) Signed-off-by: kosuke55 --- .../utils/start_planner/shift_pull_out.hpp | 4 --- .../utils/start_planner/shift_pull_out.cpp | 27 ------------------- 2 files changed, 31 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp index 7928938ac4d5b..2042593064c51 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp @@ -45,10 +45,6 @@ class ShiftPullOut : public PullOutPlannerBase const BehaviorPathPlannerParameters & common_parameter, const behavior_path_planner::StartPlannerParameters & parameter); - bool hasEnoughDistance( - const double pull_out_total_distance, const lanelet::ConstLanelets & current_lanes, - const Pose & current_pose, const bool isInGoalRouteSection, const Pose & goal_pose); - double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double target_after_arc_length, const double dr); diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index 4561062abfa73..ef6d55a7af4c6 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -216,14 +216,6 @@ std::vector ShiftPullOut::calcPullOutPaths( const double before_shifted_pull_out_distance = std::max(pull_out_distance, pull_out_distance_converted); - // check has enough distance - const bool is_in_goal_route_section = route_handler.isInGoalRouteSection(road_lanes.back()); - if (!hasEnoughDistance( - before_shifted_pull_out_distance, road_lanes, start_pose, is_in_goal_route_section, - goal_pose)) { - continue; - } - // if before_shifted_pull_out_distance is too short, shifting path fails, so add non shifted if (before_shifted_pull_out_distance < RESAMPLE_INTERVAL && !has_non_shifted_path) { candidate_paths.push_back(non_shifted_path); @@ -319,25 +311,6 @@ double ShiftPullOut::calcPullOutLongitudinalDistance( return min_pull_out_distance; } -bool ShiftPullOut::hasEnoughDistance( - const double pull_out_total_distance, const lanelet::ConstLanelets & road_lanes, - const Pose & current_pose, const bool is_in_goal_route_section, const Pose & goal_pose) -{ - // the goal is far so current_lanes do not include goal's lane - if (pull_out_total_distance > utils::getDistanceToEndOfLane(current_pose, road_lanes)) { - return false; - } - - // current_lanes include goal's lane - if ( - is_in_goal_route_section && - pull_out_total_distance > utils::getSignedDistance(current_pose, goal_pose, road_lanes)) { - return false; - } - - return true; -} - double ShiftPullOut::calcBeforeShiftedArcLength( const PathWithLaneId & path, const double target_after_arc_length, const double dr) { From 19bc571171f7e15881ca9c3bdea75edc40131841 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 31 Jul 2023 09:38:28 +0900 Subject: [PATCH 040/266] feat(dynamic_avoidance): calculate which side to avoid more accurately (#4451) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 8 +-- .../dynamic_avoidance_module.cpp | 49 +++++++++++++------ 2 files changed, 37 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index f8830212a8222..7f18c847af43e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -82,13 +82,13 @@ class DynamicAvoidanceModule : public SceneModuleInterface { DynamicAvoidanceObject( const PredictedObject & predicted_object, const double arg_vel, const double arg_lat_vel, - const bool arg_is_left, const double arg_time_to_collision) + const bool arg_is_collision_left, const double arg_time_to_collision) : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), shape(predicted_object.shape), vel(arg_vel), lat_vel(arg_lat_vel), - is_left(arg_is_left), + is_collision_left(arg_is_collision_left), time_to_collision(arg_time_to_collision) { for (const auto & path : predicted_object.kinematics.predicted_paths) { @@ -101,7 +101,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface autoware_auto_perception_msgs::msg::Shape shape; double vel; double lat_vel; - bool is_left; + bool is_collision_left; double time_to_collision; std::vector predicted_paths{}; }; @@ -162,7 +162,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; bool willObjectCutOut( - const double obj_tangent_vel, const double obj_normal_vel, const bool is_left) const; + const double obj_tangent_vel, const double obj_normal_vel, const bool is_collision_left) const; bool isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const; double calcTimeToCollision( diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index b1aa372c42ac5..185763172bbd4 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -262,7 +262,8 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() for (const auto & object : target_objects_) { const auto obstacle_poly = calcDynamicObstaclePolygon(object); if (obstacle_poly) { - obstacles_for_drivable_area.push_back({object.pose, obstacle_poly.value(), object.is_left}); + obstacles_for_drivable_area.push_back( + {object.pose, obstacle_poly.value(), object.is_collision_left}); appendObjectMarker(info_marker_, object.pose); appendExtractedPolygonMarker(debug_marker_, obstacle_poly.value()); @@ -396,16 +397,15 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() } // 6. calculate which side object exists against ego's path - // TODO(murooka) use obj_path.back() instead of obj_pose for the case where the object crosses - // the ego's path - const bool is_left = isLeft(prev_module_path->points, obj_path.path.back().position); + const bool is_object_left = isLeft(prev_module_path->points, obj_pose.position); const auto lat_lon_offset = getLateralLongitudinalOffset(prev_module_path->points, predicted_object); // 6. check if object will not cut in or cut out const bool will_object_cut_in = willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel, lat_lon_offset); - const bool will_object_cut_out = willObjectCutOut(obj_tangent_vel, obj_normal_vel, is_left); + const bool will_object_cut_out = + willObjectCutOut(obj_tangent_vel, obj_normal_vel, is_object_left); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -434,6 +434,13 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() continue; } + // calculate which side object will be against ego's path + const auto future_obj_pose = + object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); + const bool is_collision_left = future_obj_pose + ? isLeft(prev_module_path->points, future_obj_pose->position) + : is_object_left; + // 8. calculate alive counter for filtering objects const auto prev_target_object_candidate = DynamicAvoidanceObjectCandidate::getObjectFromUuid(prev_target_objects_candidate_, obj_uuid); @@ -445,7 +452,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() : 0; const auto target_object = DynamicAvoidanceObject( - predicted_object, obj_tangent_vel, obj_normal_vel, is_left, time_to_collision); + predicted_object, obj_tangent_vel, obj_normal_vel, is_collision_left, time_to_collision); const auto target_object_candidate = DynamicAvoidanceObjectCandidate{target_object, alive_counter}; output_objects_candidate.push_back(target_object_candidate); @@ -552,7 +559,7 @@ bool DynamicAvoidanceModule::willObjectCutIn( } bool DynamicAvoidanceModule::willObjectCutOut( - const double obj_tangent_vel, const double obj_normal_vel, const bool is_left) const + const double obj_tangent_vel, const double obj_normal_vel, const bool is_collision_left) const { // Ignore oncoming object if (obj_tangent_vel < 0) { @@ -560,7 +567,7 @@ bool DynamicAvoidanceModule::willObjectCutOut( } constexpr double object_lat_vel_thresh = 0.3; - if (is_left) { + if (is_collision_left) { if (object_lat_vel_thresh < obj_normal_vel) { return true; } @@ -689,8 +696,10 @@ std::optional DynamicAvoidanceModule::calcDynam } return getMinMaxValues(obj_lat_abs_offset_vec); }(); - const double min_obj_lat_offset = min_obj_lat_abs_offset * (object.is_left ? 1.0 : -1.0); - const double max_obj_lat_offset = max_obj_lat_abs_offset * (object.is_left ? 1.0 : -1.0); + const double min_obj_lat_offset = + min_obj_lat_abs_offset * (object.is_collision_left ? 1.0 : -1.0); + const double max_obj_lat_offset = + max_obj_lat_abs_offset * (object.is_collision_left ? 1.0 : -1.0); // calculate min/max longitudinal offset from object to path const auto obj_lon_offset = [&]() -> std::optional> { @@ -708,9 +717,15 @@ std::optional DynamicAvoidanceModule::calcDynam return std::nullopt; } - return std::make_pair( - raw_min_obj_lon_offset + object.vel * object.time_to_collision, - raw_max_obj_lon_offset + object.vel * object.time_to_collision); + if (object.vel < 0) { + return std::make_pair( + raw_min_obj_lon_offset + object.vel * object.time_to_collision, raw_max_obj_lon_offset); + } + + // NOTE: If time to collision is considered here, the ego is close to the object when starting + // avoidance. + // The ego should start avoidance before overtaking. + return std::make_pair(raw_min_obj_lon_offset, raw_max_obj_lon_offset); }(); if (!obj_lon_offset) { @@ -752,10 +767,11 @@ std::optional DynamicAvoidanceModule::calcDynam // calculate bound min and max lateral offset const double min_bound_lat_offset = [&]() { const double raw_min_bound_lat_offset = - min_obj_lat_offset - parameters_->lat_offset_from_obstacle * (object.is_left ? 1.0 : -1.0); + min_obj_lat_offset - + parameters_->lat_offset_from_obstacle * (object.is_collision_left ? 1.0 : -1.0); const double min_bound_lat_abs_offset_limit = planner_data_->parameters.vehicle_width / 2.0 - parameters_->max_lat_offset_to_avoid; - if (object.is_left) { + if (object.is_collision_left) { if (raw_min_bound_lat_offset < min_bound_lat_abs_offset_limit) { return min_bound_lat_abs_offset_limit; } @@ -767,7 +783,8 @@ std::optional DynamicAvoidanceModule::calcDynam return raw_min_bound_lat_offset; }(); const double max_bound_lat_offset = - max_obj_lat_offset + parameters_->lat_offset_from_obstacle * (object.is_left ? 1.0 : -1.0); + max_obj_lat_offset + + parameters_->lat_offset_from_obstacle * (object.is_collision_left ? 1.0 : -1.0); // filter min_bound_lat_offset const auto prev_min_bound_lat_offset = prev_objects_min_bound_lat_offset_.get(object.uuid); From da69d7ef87d852f1902ac280c93b4eab939bec07 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 31 Jul 2023 09:38:42 +0900 Subject: [PATCH 041/266] chore(dynamic_avoidance): revert debug marker's color (#4450) Revert "chore(dynamic_avoidance): change debug marker's color (#3926)" This reverts commit fc08b4f11770a6a2ac137ec8121c20f51179ca68. --- .../dynamic_avoidance/dynamic_avoidance_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 185763172bbd4..a90ded11d2dfe 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -56,7 +56,7 @@ void appendObjectMarker(MarkerArray & marker_array, const geometry_msgs::msg::Po "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "dynamic_objects_to_avoid", marker_array.markers.size(), visualization_msgs::msg::Marker::CUBE, tier4_autoware_utils::createMarkerScale(3.0, 1.0, 1.0), - tier4_autoware_utils::createMarkerColor(0.7, 0.15, 0.9, 0.8)); + tier4_autoware_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); marker.pose = obj_pose; marker_array.markers.push_back(marker); @@ -68,8 +68,8 @@ void appendExtractedPolygonMarker( auto marker = tier4_autoware_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "extracted_polygons", marker_array.markers.size(), visualization_msgs::msg::Marker::LINE_STRIP, - tier4_autoware_utils::createMarkerScale(0.1, 0.0, 0.0), - tier4_autoware_utils::createMarkerColor(0.7, 0.15, 0.9, 0.8)); + tier4_autoware_utils::createMarkerScale(0.05, 0.0, 0.0), + tier4_autoware_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); // NOTE: obj_poly.outer() has already duplicated points to close the polygon. for (size_t i = 0; i < obj_poly.outer().size(); ++i) { From 66e2df245212ebfc66432cd5794053f65a543f96 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 31 Jul 2023 12:12:16 +0900 Subject: [PATCH 042/266] ci: enable spell-check-partial for system (#4460) * ci: enable spell-check-partial for system Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .cspell-partial.json | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index ae92ec76f9546..3b1f918b7deb2 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -5,8 +5,7 @@ "**/launch/**", "**/perception/**", "**/planning/**", - "**/sensing/**", - "**/system/**" + "**/sensing/**" ], "ignoreRegExpList": [], "words": [] From bfe53147f576f4337bf82d97f82190f6ef329914 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 31 Jul 2023 13:32:21 +0900 Subject: [PATCH 043/266] ci: enable spell-check-partial for evaluator and launch (#4462) * ci: enable spell-check-partial for evaluator and launch Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .cspell-partial.json | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index 3b1f918b7deb2..ae52fee5614b0 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -1,12 +1,5 @@ { - "ignorePaths": [ - "**/control/**", - "**/evaluator/**", - "**/launch/**", - "**/perception/**", - "**/planning/**", - "**/sensing/**" - ], + "ignorePaths": ["**/control/**", "**/perception/**", "**/planning/**", "**/sensing/**"], "ignoreRegExpList": [], "words": [] } From 07308883c90518c1f58b44d2fb42d30fa90e50da Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 31 Jul 2023 16:59:58 +0900 Subject: [PATCH 044/266] feat(yabloc_monitor): add yabloc_monitor (#4395) * feat(yabloc_monitor): add yabloc_monitor Signed-off-by: kminoda * style(pre-commit): autofix * add readme Signed-off-by: kminoda * style(pre-commit): autofix * update config Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * remove unnecessary part Signed-off-by: kminoda * remove todo Signed-off-by: kminoda * fix typo Signed-off-by: kminoda * remove unnecessary part Signed-off-by: kminoda * update readme Signed-off-by: kminoda * shorten function Signed-off-by: kminoda * reflect chatgpt Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * cland-tidy Signed-off-by: kminoda * style(pre-commit): autofix * update variable name Signed-off-by: kminoda * fix if name Signed-off-by: kminoda * use nullopt (and moved yabloc monitor namespace Signed-off-by: kminoda * fix readme Signed-off-by: kminoda * style(pre-commit): autofix * add dependency Signed-off-by: kminoda * style(pre-commit): autofix * reflect comment Signed-off-by: kminoda * update comment Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_twist_estimator/yabloc.launch.xml | 6 +++ launch/tier4_localization_launch/package.xml | 1 + .../yabloc/yabloc_monitor/CMakeLists.txt | 18 +++++++ localization/yabloc/yabloc_monitor/README.md | 27 +++++++++++ .../config/yabloc_monitor.param.yaml | 3 ++ .../launch/yabloc_monitor.launch.xml | 8 ++++ .../yabloc/yabloc_monitor/package.xml | 25 ++++++++++ .../src/availability_module.cpp | 47 ++++++++++++++++++ .../src/availability_module.hpp | 43 +++++++++++++++++ .../src/yabloc_monitor_core.cpp | 48 +++++++++++++++++++ .../src/yabloc_monitor_core.hpp | 40 ++++++++++++++++ .../src/yabloc_monitor_node.cpp | 28 +++++++++++ 12 files changed, 294 insertions(+) create mode 100644 localization/yabloc/yabloc_monitor/CMakeLists.txt create mode 100644 localization/yabloc/yabloc_monitor/README.md create mode 100644 localization/yabloc/yabloc_monitor/config/yabloc_monitor.param.yaml create mode 100644 localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml create mode 100644 localization/yabloc/yabloc_monitor/package.xml create mode 100644 localization/yabloc/yabloc_monitor/src/availability_module.cpp create mode 100644 localization/yabloc/yabloc_monitor/src/availability_module.hpp create mode 100644 localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp create mode 100644 localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp create mode 100644 localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml index 447219085df7f..a9b0b93947054 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/yabloc.launch.xml @@ -53,5 +53,11 @@ + + + + + + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 93af4ee68a6f7..325ed86c4435c 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -26,6 +26,7 @@ topic_tools yabloc_common yabloc_image_processing + yabloc_monitor yabloc_particle_filter yabloc_pose_initializer diff --git a/localization/yabloc/yabloc_monitor/CMakeLists.txt b/localization/yabloc/yabloc_monitor/CMakeLists.txt new file mode 100644 index 0000000000000..aa1515661b2f6 --- /dev/null +++ b/localization/yabloc/yabloc_monitor/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.14) +project(yabloc_monitor) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(yabloc_monitor + src/yabloc_monitor_node.cpp + src/yabloc_monitor_core.cpp + src/availability_module.cpp +) +ament_target_dependencies(yabloc_monitor) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/yabloc/yabloc_monitor/README.md b/localization/yabloc/yabloc_monitor/README.md new file mode 100644 index 0000000000000..ed4cdc36b6ba0 --- /dev/null +++ b/localization/yabloc/yabloc_monitor/README.md @@ -0,0 +1,27 @@ +# yabloc_monitor + +YabLoc monitor is a node that monitors the status of the YabLoc localization system. It is a wrapper node that monitors the status of the YabLoc localization system and publishes the status as diagnostics. + +## Feature + +### Availability + +The node monitors the final output pose of YabLoc to verify the availability of YabLoc. + +### Others + +To be added, + +## Interfaces + +### Input + +| Name | Type | Description | +| --------------------- | --------------------------- | ------------------------------- | +| `~/input/yabloc_pose` | `geometry_msgs/PoseStamped` | The final output pose of YabLoc | + +### Output + +| Name | Type | Description | +| -------------- | --------------------------------- | ------------------- | +| `/diagnostics` | `diagnostic_msgs/DiagnosticArray` | Diagnostics outputs | diff --git a/localization/yabloc/yabloc_monitor/config/yabloc_monitor.param.yaml b/localization/yabloc/yabloc_monitor/config/yabloc_monitor.param.yaml new file mode 100644 index 0000000000000..b0a7ce9d9a6b8 --- /dev/null +++ b/localization/yabloc/yabloc_monitor/config/yabloc_monitor.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + availability/timestamp_tolerance: 1.0 diff --git a/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml b/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml new file mode 100644 index 0000000000000..cf9f73977d35d --- /dev/null +++ b/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml new file mode 100644 index 0000000000000..2c6c32bad9eb5 --- /dev/null +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -0,0 +1,25 @@ + + + + yabloc_monitor + 0.1.0 + YabLoc monitor package + Kento Yabuuchi + Koji Minoda + Apache License 2.0 + + ament_cmake_ros + autoware_cmake + + diagnostic_updater + geometry_msgs + rclcpp + + ament_cmake_gtest + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/localization/yabloc/yabloc_monitor/src/availability_module.cpp b/localization/yabloc/yabloc_monitor/src/availability_module.cpp new file mode 100644 index 0000000000000..5933b12d15016 --- /dev/null +++ b/localization/yabloc/yabloc_monitor/src/availability_module.cpp @@ -0,0 +1,47 @@ +// Copyright 2023 TIER IV +// +// 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 "availability_module.hpp" + +#include + +#include + +AvailabilityModule::AvailabilityModule(rclcpp::Node * node) +: clock_(node->get_clock()), + latest_yabloc_pose_stamp_(std::nullopt), + timestamp_threshold_(node->declare_parameter("availability/timestamp_tolerance")) +{ + sub_yabloc_pose_ = node->create_subscription( + "~/input/yabloc_pose", 10, + [this](const PoseStamped::ConstSharedPtr msg) { on_yabloc_pose(msg); }); +} + +bool AvailabilityModule::is_available() const +{ + if (!latest_yabloc_pose_stamp_.has_value()) { + return false; + } + + const auto now = clock_->now(); + + const auto diff_time = now - latest_yabloc_pose_stamp_.value(); + const auto diff_time_sec = diff_time.seconds(); + return diff_time_sec < timestamp_threshold_; +} + +void AvailabilityModule::on_yabloc_pose(const PoseStamped::ConstSharedPtr msg) +{ + latest_yabloc_pose_stamp_ = rclcpp::Time(msg->header.stamp); +} diff --git a/localization/yabloc/yabloc_monitor/src/availability_module.hpp b/localization/yabloc/yabloc_monitor/src/availability_module.hpp new file mode 100644 index 0000000000000..40d0ea335493c --- /dev/null +++ b/localization/yabloc/yabloc_monitor/src/availability_module.hpp @@ -0,0 +1,43 @@ +// Copyright 2023 TIER IV +// +// 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 AVAILABILITY_MODULE_HPP_ +#define AVAILABILITY_MODULE_HPP_ + +#include + +#include + +#include +#include + +class AvailabilityModule +{ +private: + using PoseStamped = geometry_msgs::msg::PoseStamped; + +public: + explicit AvailabilityModule(rclcpp::Node * node); + [[nodiscard]] bool is_available() const; + +private: + rclcpp::Subscription::SharedPtr sub_yabloc_pose_; + void on_yabloc_pose(PoseStamped::ConstSharedPtr msg); + + rclcpp::Clock::SharedPtr clock_; + std::optional latest_yabloc_pose_stamp_; + const double timestamp_threshold_; +}; + +#endif // AVAILABILITY_MODULE_HPP_ diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp new file mode 100644 index 0000000000000..876b86fd2bc9e --- /dev/null +++ b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp @@ -0,0 +1,48 @@ +// Copyright 2023 TIER IV +// +// 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 "yabloc_monitor_core.hpp" + +#include + +#include + +YabLocMonitor::YabLocMonitor() : Node("yabloc_monitor"), updater_(this) +{ + updater_.setHardwareID(get_name()); + updater_.add("yabloc_status", this, &YabLocMonitor::update_diagnostics); + + // Set timer + using std::chrono_literals::operator""ms; + timer_ = create_wall_timer(100ms, [this] { on_timer(); }); + // Evaluation modules + availability_module_ = std::make_unique(this); +} + +void YabLocMonitor::on_timer() +{ + updater_.force_update(); +} + +void YabLocMonitor::update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + bool is_available = availability_module_->is_available(); + stat.add("Availability", is_available ? "OK" : "NG"); + + if (is_available) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "OK"); + } else { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "NG"); + } +} diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp new file mode 100644 index 0000000000000..8b8b937da205b --- /dev/null +++ b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp @@ -0,0 +1,40 @@ +// Copyright 2023 TIER IV +// +// 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 YABLOC_MONITOR_CORE_HPP_ +#define YABLOC_MONITOR_CORE_HPP_ + +#include "availability_module.hpp" + +#include +#include + +#include + +class YabLocMonitor : public rclcpp::Node +{ +public: + YabLocMonitor(); + +private: + void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); + void on_timer(); + + diagnostic_updater::Updater updater_; + rclcpp::TimerBase::SharedPtr timer_; + + // Evaluation modules + std::unique_ptr availability_module_; +}; +#endif // YABLOC_MONITOR_CORE_HPP_ diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp new file mode 100644 index 0000000000000..9b58325c852ea --- /dev/null +++ b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp @@ -0,0 +1,28 @@ +// Copyright 2023 TIER IV +// +// 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 "yabloc_monitor_core.hpp" + +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::NodeOptions node_options; + auto node = std::make_shared(); + + rclcpp::spin(node); + + return 0; +} From 48870ea2184aee861ec8e6f7471f109d49f345c0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 31 Jul 2023 18:11:38 +0900 Subject: [PATCH 045/266] feat(goal_planner): add no_parking_area for goal search (#3467) * feat(behavior_path_planner): use no_parking_area for pull_over Signed-off-by: kosuke55 * support no_stopping_area Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../lanelet2_map_visualization_node.cpp | 9 ++++++++- .../utils/goal_planner/goal_searcher.hpp | 1 + .../src/utils/goal_planner/goal_searcher.cpp | 19 +++++++++++++++++++ 3 files changed, 28 insertions(+), 1 deletion(-) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index df845ca9bd252..53794fb93b7c6 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -125,13 +125,15 @@ void Lanelet2MapVisualizationNode::onMapBin( viz_lanelet_map, "no_obstacle_segmentation_area_for_run_out"); lanelet::ConstPolygons3d hatched_road_markings_area = lanelet::utils::query::getAllPolygonsByType(viz_lanelet_map, "hatched_road_markings"); + std::vector no_parking_reg_elems = + lanelet::utils::query::noParkingAreas(all_lanelets); std_msgs::msg::ColorRGBA cl_road, cl_shoulder, cl_cross, cl_partitions, cl_pedestrian_markings, cl_ll_borders, cl_shoulder_borders, cl_stoplines, cl_trafficlights, cl_detection_areas, cl_speed_bumps, cl_crosswalks, cl_parking_lots, cl_parking_spaces, cl_lanelet_id, cl_obstacle_polygons, cl_no_stopping_areas, cl_no_obstacle_segmentation_area, cl_no_obstacle_segmentation_area_for_run_out, cl_hatched_road_markings_area, - cl_hatched_road_markings_line; + cl_hatched_road_markings_line, cl_no_parking_areas; setColor(&cl_road, 0.27, 0.27, 0.27, 0.999); setColor(&cl_shoulder, 0.15, 0.15, 0.15, 0.999); setColor(&cl_cross, 0.27, 0.3, 0.27, 0.5); @@ -153,6 +155,7 @@ void Lanelet2MapVisualizationNode::onMapBin( setColor(&cl_no_obstacle_segmentation_area_for_run_out, 0.37, 0.7, 0.27, 0.5); setColor(&cl_hatched_road_markings_area, 0.3, 0.3, 0.3, 0.5); setColor(&cl_hatched_road_markings_line, 0.5, 0.5, 0.5, 0.999); + setColor(&cl_no_parking_areas, 0.42, 0.42, 0.42, 0.5); visualization_msgs::msg::MarkerArray map_marker_array; @@ -235,6 +238,10 @@ void Lanelet2MapVisualizationNode::onMapBin( lanelet::visualization::hatchedRoadMarkingsAreaAsMarkerArray( hatched_road_markings_area, cl_hatched_road_markings_area, cl_hatched_road_markings_line)); + insertMarkerArray( + &map_marker_array, + lanelet::visualization::noParkingAreasAsMarkerArray(no_parking_reg_elems, cl_no_parking_areas)); + pub_marker_->publish(map_marker_array); } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp index be6e1c0046449..d564dcaa19e29 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp @@ -44,6 +44,7 @@ class GoalSearcher : public GoalSearcherBase bool checkCollision(const Pose & pose) const; bool checkCollisionWithLongitudinalDistance( const Pose & ego_pose, const PredictedObjects & dynamic_objects) const; + BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index a3bd96bddb3d7..d6b30b0ee0f74 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -26,6 +26,7 @@ namespace behavior_path_planner { using lane_departure_checker::LaneDepartureChecker; +using lanelet::autoware::NoParkingArea; using lanelet::autoware::NoStoppingArea; using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::inverseTransformPose; @@ -104,6 +105,10 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose) const auto transformed_vehicle_footprint = transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(search_pose)); + if (isInAreas(transformed_vehicle_footprint, getNoParkingAreaPolygons(pull_over_lanes))) { + continue; + } + if (isInAreas(transformed_vehicle_footprint, getNoStoppingAreaPolygons(pull_over_lanes))) { continue; } @@ -276,6 +281,20 @@ void GoalSearcher::createAreaPolygons(std::vector original_search_poses) } } +BasicPolygons2d GoalSearcher::getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const +{ + BasicPolygons2d area_polygons{}; + for (const auto & ll : lanes) { + for (const auto & reg_elem : ll.regulatoryElementsAs()) { + for (const auto & area : reg_elem->noParkingAreas()) { + const auto & area_poly = lanelet::utils::to2D(area).basicPolygon(); + area_polygons.push_back(area_poly); + } + } + } + return area_polygons; +} + BasicPolygons2d GoalSearcher::getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const { BasicPolygons2d area_polygons{}; From 2212b003ad5efb7f0baba221c976d0c8801ad236 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 31 Jul 2023 19:35:35 +0900 Subject: [PATCH 046/266] chore(intersection): publish decision status string (#4456) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 31 +++++++++++++++++++ .../src/scene_intersection.hpp | 2 ++ 2 files changed, 33 insertions(+) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index d4db6e83861a2..b283a757dc8cb 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -86,6 +86,8 @@ IntersectionModule::IntersectionModule( before_creep_state_machine_.setState(StateMachine::State::STOP); stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area); stuck_private_area_timeout_.setState(StateMachine::State::STOP); + decision_state_pub_ = + node_.create_publisher("~/debug/intersection/decision_state", 1); } void IntersectionModule::initializeRTCStatus() @@ -648,6 +650,35 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // calculate the const auto decision_result = modifyPathVelocityDetail(path, stop_reason); + std::string decision_type = "intersection" + std::to_string(module_id_) + " : "; + if (std::get_if(&decision_result)) { + decision_type += "Indecisive"; + } + if (std::get_if(&decision_result)) { + decision_type += "StuckStop"; + } + if (std::get_if(&decision_result)) { + decision_type += "NonOccludedCollisionStop"; + } + if (std::get_if(&decision_result)) { + decision_type += "FirstWaitBeforeOcclusion"; + } + if (std::get_if(&decision_result)) { + decision_type += "PeekingTowardOcclusion"; + } + if (std::get_if(&decision_result)) { + decision_type += "OccludedCollisionStop"; + } + if (std::get_if(&decision_result)) { + decision_type += "Safe"; + } + if (std::get_if(&decision_result)) { + decision_type += "TrafficLightArrowSolidOn"; + } + std_msgs::msg::String decision_result_msg; + decision_result_msg.data = decision_type; + decision_state_pub_->publish(decision_result_msg); + prepareRTCStatus(decision_result, *path); const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 950cd6006cbe4..d4ef1442bb27a 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -25,6 +25,7 @@ #include #include +#include #include #include @@ -272,6 +273,7 @@ class IntersectionModule : public SceneModuleInterface */ util::DebugData debug_data_; + rclcpp::Publisher::SharedPtr decision_state_pub_; }; } // namespace behavior_velocity_planner From 862830d3e670b2962b7c7eaccb2f1266f5c5bc25 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 31 Jul 2023 19:01:52 +0300 Subject: [PATCH 047/266] chore(ci): use ec2 for build-and-test-differential (#4413) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../build-and-test-differential.yaml | 56 +++++++++++++++++-- 1 file changed, 52 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index e32dccda70b25..950141e8ae6da 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -13,10 +13,36 @@ jobs: with: label: run-build-and-test-differential - build-and-test-differential: + start-runner: + name: Start self-hosted EC2 runner needs: prevent-no-label-execution if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }} - runs-on: [self-hosted, linux, X64] + runs-on: ubuntu-latest + outputs: + label: ${{ steps.start-ec2-runner.outputs.label }} + ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} + steps: + - name: Configure AWS credentials + uses: aws-actions/configure-aws-credentials@v2 + with: + aws-access-key-id: ${{ secrets.EC2_ON_DEMAND_AWS_ACCESS_KEY_ID_COMMON }} + aws-secret-access-key: ${{ secrets.EC2_ON_DEMAND_AWS_SECRET_ACCESS_KEY_COMMON }} + aws-region: ${{ secrets.EC2_ON_DEMAND_AWS_REGION_COMMON }} + - name: Start EC2 runner + id: start-ec2-runner + uses: machulav/ec2-github-runner@v2 + with: + mode: start + github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN_MFC }} + ec2-image-id: ami-092a175a6ad1aad7a + ec2-instance-type: c6a.xlarge + subnet-id: subnet-070b3d46464230127 + security-group-id: sg-0cca5762919221f16 + runner-home-dir: /home/ubuntu/actions-runner + + build-and-test-differential: + needs: start-runner + runs-on: ${{ needs.start-runner.outputs.label }} container: ${{ matrix.container }}${{ matrix.container-suffix }} strategy: fail-fast: false @@ -70,9 +96,9 @@ jobs: flags: differential clang-tidy-differential: - runs-on: [self-hosted, linux, X64] - container: ghcr.io/autowarefoundation/autoware-universe:humble-latest-cuda needs: build-and-test-differential + runs-on: ${{ needs.start-runner.outputs.label }} + container: ghcr.io/autowarefoundation/autoware-universe:humble-latest-cuda steps: - name: Check out repository uses: actions/checkout@v3 @@ -103,3 +129,25 @@ jobs: target-files: ${{ steps.get-modified-files.outputs.all_changed_files }} clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy build-depends-repos: build_depends.repos + + stop-runner: + name: Stop self-hosted EC2 runner + needs: + - start-runner + - clang-tidy-differential + runs-on: ubuntu-latest + if: ${{ always() }} # required to stop the runner even if the error happened in the previous jobs + steps: + - name: Configure AWS credentials + uses: aws-actions/configure-aws-credentials@v2 + with: + aws-access-key-id: ${{ secrets.EC2_ON_DEMAND_AWS_ACCESS_KEY_ID_COMMON }} + aws-secret-access-key: ${{ secrets.EC2_ON_DEMAND_AWS_SECRET_ACCESS_KEY_COMMON }} + aws-region: ${{ secrets.EC2_ON_DEMAND_AWS_REGION_COMMON }} + - name: Stop EC2 runner + uses: machulav/ec2-github-runner@v2 + with: + mode: stop + github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN_MFC }} + label: ${{ needs.start-runner.outputs.label }} + ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} From ab0027f416f1e002f1037bac82c0e3f8e322d3ba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 31 Jul 2023 23:48:37 +0300 Subject: [PATCH 048/266] chore(ci): revert "use ec2 for build-and-test-differential (#4413)" (#4477) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../build-and-test-differential.yaml | 56 ++----------------- 1 file changed, 4 insertions(+), 52 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 950141e8ae6da..e32dccda70b25 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -13,36 +13,10 @@ jobs: with: label: run-build-and-test-differential - start-runner: - name: Start self-hosted EC2 runner + build-and-test-differential: needs: prevent-no-label-execution if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }} - runs-on: ubuntu-latest - outputs: - label: ${{ steps.start-ec2-runner.outputs.label }} - ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} - steps: - - name: Configure AWS credentials - uses: aws-actions/configure-aws-credentials@v2 - with: - aws-access-key-id: ${{ secrets.EC2_ON_DEMAND_AWS_ACCESS_KEY_ID_COMMON }} - aws-secret-access-key: ${{ secrets.EC2_ON_DEMAND_AWS_SECRET_ACCESS_KEY_COMMON }} - aws-region: ${{ secrets.EC2_ON_DEMAND_AWS_REGION_COMMON }} - - name: Start EC2 runner - id: start-ec2-runner - uses: machulav/ec2-github-runner@v2 - with: - mode: start - github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN_MFC }} - ec2-image-id: ami-092a175a6ad1aad7a - ec2-instance-type: c6a.xlarge - subnet-id: subnet-070b3d46464230127 - security-group-id: sg-0cca5762919221f16 - runner-home-dir: /home/ubuntu/actions-runner - - build-and-test-differential: - needs: start-runner - runs-on: ${{ needs.start-runner.outputs.label }} + runs-on: [self-hosted, linux, X64] container: ${{ matrix.container }}${{ matrix.container-suffix }} strategy: fail-fast: false @@ -96,9 +70,9 @@ jobs: flags: differential clang-tidy-differential: - needs: build-and-test-differential - runs-on: ${{ needs.start-runner.outputs.label }} + runs-on: [self-hosted, linux, X64] container: ghcr.io/autowarefoundation/autoware-universe:humble-latest-cuda + needs: build-and-test-differential steps: - name: Check out repository uses: actions/checkout@v3 @@ -129,25 +103,3 @@ jobs: target-files: ${{ steps.get-modified-files.outputs.all_changed_files }} clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy build-depends-repos: build_depends.repos - - stop-runner: - name: Stop self-hosted EC2 runner - needs: - - start-runner - - clang-tidy-differential - runs-on: ubuntu-latest - if: ${{ always() }} # required to stop the runner even if the error happened in the previous jobs - steps: - - name: Configure AWS credentials - uses: aws-actions/configure-aws-credentials@v2 - with: - aws-access-key-id: ${{ secrets.EC2_ON_DEMAND_AWS_ACCESS_KEY_ID_COMMON }} - aws-secret-access-key: ${{ secrets.EC2_ON_DEMAND_AWS_SECRET_ACCESS_KEY_COMMON }} - aws-region: ${{ secrets.EC2_ON_DEMAND_AWS_REGION_COMMON }} - - name: Stop EC2 runner - uses: machulav/ec2-github-runner@v2 - with: - mode: stop - github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN_MFC }} - label: ${{ needs.start-runner.outputs.label }} - ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} From d2a94d8e4704196406bbd8eac19ce10f13618f32 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 1 Aug 2023 07:54:58 +0900 Subject: [PATCH 049/266] fix(traffic_light_arbiter): clear perception msg when the stamp is over the tolerance (#4464) Signed-off-by: Tomohito Ando --- perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp index dfa01878bb81f..217430ee72d81 100644 --- a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -99,7 +99,7 @@ void TrafficLightArbiter::onExternalMsg(const TrafficSignalArray::ConstSharedPtr if ( (rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds() > perception_time_tolerance_) { - latest_external_msg_.signals.clear(); + latest_perception_msg_.signals.clear(); } arbitrateAndPublish(msg->stamp); From e35f14d92993ec73f4a870a68dd628f96199a93b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 10:13:00 +0900 Subject: [PATCH 050/266] feat(behavior_velocity_crosswalk_module): suppress sudden stop for stuck vehicle (#4449) * feat(behavior_velocity_crosswalk_module): suppress sudden stop for stuck vehicle Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 5 ++- .../src/manager.cpp | 3 ++ .../src/scene_crosswalk.cpp | 36 ++++++++++++++++--- .../src/scene_crosswalk.hpp | 3 ++ 4 files changed, 41 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 6ff7104bfa992..5fff846785353 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -4,8 +4,8 @@ common: show_processing_time: false # [-] whether to show processing time # param for input data - enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal + enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. # param for stop position stop_position: @@ -30,6 +30,9 @@ stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck max_stuck_vehicle_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] # param for pass judge logic pass_judge: diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index c774c8876c850..7f5c46f1cf91a 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -66,6 +66,9 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) node.declare_parameter(ns + ".stuck_vehicle.max_stuck_vehicle_lateral_offset"); cp.stuck_vehicle_attention_range = node.declare_parameter(ns + ".stuck_vehicle.stuck_vehicle_attention_range"); + cp.min_acc_for_stuck_vehicle = node.declare_parameter(ns + ".stuck_vehicle.min_acc"); + cp.max_jerk_for_stuck_vehicle = node.declare_parameter(ns + ".stuck_vehicle.max_jerk"); + cp.min_jerk_for_stuck_vehicle = node.declare_parameter(ns + ".stuck_vehicle.min_jerk"); // param for pass judge logic cp.ego_pass_first_margin = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 120f8ec8581be..9d0d0593a333e 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -30,6 +31,7 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; using motion_utils::calcArcLength; +using motion_utils::calcDecelDistWithJerkAndAccConstraints; using motion_utils::calcLateralOffset; using motion_utils::calcLongitudinalOffsetPoint; using motion_utils::calcLongitudinalOffsetPose; @@ -762,6 +764,8 @@ std::optional CrosswalkModule::checkStopForStuckVehicles( const std::vector & path_intersects, const std::optional & stop_pose) const { + const auto & p = planner_param_; + if (path_intersects.size() < 2 || !stop_pose) { return {}; } @@ -772,26 +776,48 @@ std::optional CrosswalkModule::checkStopForStuckVehicles( } const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; - if (planner_param_.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) { + if (p.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) { continue; } const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; const auto lateral_offset = calcLateralOffset(ego_path.points, obj_pos); - if (planner_param_.max_stuck_vehicle_lateral_offset < std::abs(lateral_offset)) { + if (p.max_stuck_vehicle_lateral_offset < std::abs(lateral_offset)) { continue; } const auto & ego_pos = planner_data_->current_odometry->pose.position; + const auto ego_vel = planner_data_->current_velocity->twist.linear.x; + const auto ego_acc = planner_data_->current_acceleration->accel.accel.linear.x; + const double near_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); - const double far_attention_range = - near_attention_range + planner_param_.stuck_vehicle_attention_range; + const double far_attention_range = near_attention_range + p.stuck_vehicle_attention_range; const auto dist_ego2obj = calcSignedArcLength(ego_path.points, ego_pos, obj_pos); if (near_attention_range < dist_ego2obj && dist_ego2obj < far_attention_range) { - return createStopFactor(*stop_pose, {obj_pos}); + // Plan STOP considering min_acc, max_jerk and min_jerk. + const auto min_feasible_dist_ego2stop = calcDecelDistWithJerkAndAccConstraints( + ego_vel, 0.0, ego_acc, p.min_acc_for_stuck_vehicle, p.max_jerk_for_stuck_vehicle, + p.min_jerk_for_stuck_vehicle); + if (!min_feasible_dist_ego2stop) { + continue; + } + + const double dist_ego2stop = + calcSignedArcLength(ego_path.points, ego_pos, stop_pose->position); + const double feasible_dist_ego2stop = std::max(*min_feasible_dist_ego2stop, dist_ego2stop); + const double dist_to_ego = + calcSignedArcLength(ego_path.points, ego_path.points.front().point.pose.position, ego_pos); + + const auto feasible_stop_pose = + calcLongitudinalOffsetPose(ego_path.points, 0, dist_to_ego + feasible_dist_ego2stop); + if (!feasible_stop_pose) { + continue; + } + + return createStopFactor(*feasible_stop_pose, {obj_pos}); } } diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 228be0d62ae29..b66b97dd6745f 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -76,6 +76,9 @@ class CrosswalkModule : public SceneModuleInterface double stuck_vehicle_velocity; double max_stuck_vehicle_lateral_offset; double stuck_vehicle_attention_range; + double min_acc_for_stuck_vehicle; + double max_jerk_for_stuck_vehicle; + double min_jerk_for_stuck_vehicle; // param for pass judge logic double ego_pass_first_margin; double ego_pass_later_margin; From 47c9a78151d4616df62eb19149811619043714d9 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 1 Aug 2023 10:36:22 +0900 Subject: [PATCH 051/266] docs(lane_change): update explanations for lane change safety check (#4474) Signed-off-by: yutaka --- ...ehavior_path_planner_lane_change_design.md | 9 +- .../image/lane_change/lane_objects.drawio.svg | 150 ++++++++++++++++++ 2 files changed, 158 insertions(+), 1 deletion(-) create mode 100644 planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md index ae49542b3970b..b793173285629 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md @@ -157,6 +157,12 @@ stop See [safety check utils explanation](../docs/behavior_path_planner_safety_check.md) +#### Objects selection and classification + +First, we divide the target objects into obstacles in the target lane, obstacles in the current lane, and obstacles in other lanes. Target lane indicates the lane that the ego vehicle is going to reach after the lane change and current lane mean the current lane where the ego vehicle is following before the lane change. Other lanes are lanes that do not belong to the target and current lanes. The following picture describes objects on each lane. Note that users can remove objects either on current and other lanes from safety check by changing the flag, which are `check_objects_on_current_lanes` and `check_objects_on_other_lanes`. + +![object lanes](../image/lane_change/lane_objects.drawio.svg) + ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. @@ -292,7 +298,8 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`. | `rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | | `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | | `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `use_predicted_path_outside_lanelet` | [-] | boolean | If true, include collision check for predicted path that is out of lanelet (freespace). | false | +| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | +| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | | `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | (\*1) the value must be negative. diff --git a/planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg new file mode 100644 index 0000000000000..768c50d034394 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg @@ -0,0 +1,150 @@ + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Current Lane + +
+
+
+
+ Current Lane +
+
+ + + + +
+
+
+ + Target Lane + +
+
+
+
+ Target Lane +
+
+ + + + +
+
+
+ + Other Lane + +
+
+
+
+ Other Lane +
+
+ +
+ + + + Text is not SVG - cannot display + + +
From 50a752b5ad9ead7e78ee76e71ee516b20bd1ae3f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 1 Aug 2023 10:37:38 +0900 Subject: [PATCH 052/266] feat(intersection_occlusion): ignore occlusion behind parked vehicles on the attention lane (#4466) --- .../config/intersection.param.yaml | 1 + .../src/manager.cpp | 2 + .../src/scene_intersection.cpp | 107 ++++++++++++++---- .../src/scene_intersection.hpp | 15 ++- 4 files changed, 100 insertions(+), 25 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index cbd4d4879753b..ce49163006d99 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -47,6 +47,7 @@ max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph denoise_kernel: 1.0 # [m] possible_object_bbox: [1.0, 2.0] # [m x m] + ignore_parked_vehicle_speed_threshold: 0.333 # == 1.2km/h enable_rtc: # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval intersection: true diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 336087751d9aa..75c282d117e97 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -115,6 +115,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.occlusion.denoise_kernel = node.declare_parameter(ns + ".occlusion.denoise_kernel"); ip.occlusion.possible_object_bbox = node.declare_parameter>(ns + ".occlusion.possible_object_bbox"); + ip.occlusion.ignore_parked_vehicle_speed_threshold = + node.declare_parameter(ns + ".occlusion.ignore_parked_vehicle_speed_threshold"); } void IntersectionModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index b283a757dc8cb..713df530b43d1 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -830,9 +830,10 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( ? 0.0 : (planner_param_.collision_detection.state_transit_margin_time - collision_state_machine_.getDuration()); + const auto target_objects = + filterTargetObjects(attention_lanelets, adjacent_lanelets, intersection_area); const bool has_collision = checkCollision( - *path, attention_lanelets, adjacent_lanelets, intersection_area, ego_lane_with_next_lane, - closest_idx, time_delay, tl_arrow_solid_on); + *path, target_objects, ego_lane_with_next_lane, closest_idx, time_delay, tl_arrow_solid_on); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, logger_.get_child("collision state_machine"), *clock_); @@ -853,12 +854,19 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const double occlusion_dist_thr = std::fabs( std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); + std::vector parked_attention_objects; + std::copy_if( + target_objects.objects.begin(), target_objects.objects.end(), + std::back_inserter(parked_attention_objects), + [thresh = planner_param_.occlusion.ignore_parked_vehicle_speed_threshold](const auto & object) { + return std::fabs(object.kinematics.initial_twist_with_covariance.twist.linear.x) <= thresh; + }); const bool is_occlusion_cleared = (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !tl_arrow_solid_on) ? isOcclusionCleared( *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, first_attention_area.value(), interpolated_path_info, - occlusion_attention_divisions_.value(), occlusion_dist_thr) + occlusion_attention_divisions_.value(), parked_attention_objects, occlusion_dist_thr) : true; // check safety @@ -940,13 +948,10 @@ bool IntersectionModule::checkStuckVehicle( return is_stuck; } -bool IntersectionModule::checkCollision( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, +autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterTargetObjects( const lanelet::ConstLanelets & attention_area_lanelets, const lanelet::ConstLanelets & adjacent_lanelets, - const std::optional & intersection_area, - const lanelet::ConstLanelets & ego_lane_with_next_lane, const int closest_idx, - const double time_delay, const bool tl_arrow_solid_on) + const std::optional & intersection_area) const { using lanelet::utils::getArcCoordinates; using lanelet::utils::getPolygonFromArcLength; @@ -993,6 +998,17 @@ bool IntersectionModule::checkCollision( target_objects.objects.push_back(object); } } + return target_objects; +} + +bool IntersectionModule::checkCollision( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const autoware_auto_perception_msgs::msg::PredictedObjects & objects, + const lanelet::ConstLanelets & ego_lane_with_next_lane, const int closest_idx, + const double time_delay, const bool tl_arrow_solid_on) +{ + using lanelet::utils::getArcCoordinates; + using lanelet::utils::getPolygonFromArcLength; // check collision between target_objects predicted path and ego lane // cut the predicted path at passing_time @@ -1001,6 +1017,7 @@ bool IntersectionModule::checkCollision( planner_param_.common.intersection_velocity, planner_param_.collision_detection.minimum_ego_predicted_velocity); const double passing_time = time_distance_array.back().first; + auto target_objects = objects; util::cutPredictPathWithDuration(&target_objects, clock_, passing_time); const auto closest_arc_coords = getArcCoordinates( @@ -1128,7 +1145,9 @@ bool IntersectionModule::isOcclusionCleared( const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, - const std::vector & lane_divisions, const double occlusion_dist_thr) + const std::vector & lane_divisions, + const std::vector & parked_attention_objects, + const double occlusion_dist_thr) { const auto & path_ip = interpolated_path_info.path; const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); @@ -1156,6 +1175,8 @@ bool IntersectionModule::isOcclusionCleared( cv::Mat unknown_mask(width, height, CV_8UC1, cv::Scalar(0)); // (1) prepare detection area mask + // attention: 255 + // non-attention: 0 Polygon2d grid_poly; grid_poly.outer().emplace_back(origin.x, origin.y); grid_poly.outer().emplace_back(origin.x + (width - 1) * resolution, origin.y); @@ -1194,7 +1215,7 @@ bool IntersectionModule::isOcclusionCleared( } } for (const auto & poly : attention_area_cv_polygons) { - cv::fillPoly(attention_mask, poly, cv::Scalar(255), cv::LINE_4); + cv::fillPoly(attention_mask, poly, cv::Scalar(255), cv::LINE_AA); } // (1.1) // reset adjacent_lanelets area to 0 on attention_mask @@ -1261,7 +1282,6 @@ bool IntersectionModule::isOcclusionCleared( const double distance_min = -distance_max; const int undef_pixel = 255; const int max_cost_pixel = 254; - auto dist2pixel = [=](const double dist) { return std::min( max_cost_pixel, @@ -1270,8 +1290,8 @@ bool IntersectionModule::isOcclusionCleared( auto pixel2dist = [=](const int pixel) { return pixel * 1.0 / max_cost_pixel * (distance_max - distance_min) + distance_min; }; - const int zero_dist_pixel = dist2pixel(0.0); + const int parked_vehicle_pixel = zero_dist_pixel - 1; // magic auto coord2index = [&](const double x, const double y) { const int idx_x = (x - origin.x) / resolution; @@ -1284,6 +1304,7 @@ bool IntersectionModule::isOcclusionCleared( cv::Mat distance_grid(width, height, CV_8UC1, cv::Scalar(undef_pixel)); cv::Mat projection_ind_grid(width, height, CV_32S, cv::Scalar(-1)); + // (4.1) fill zero_dist_pixel on the path const auto [lane_start, lane_end] = lane_attention_interval_ip; for (int i = static_cast(lane_end); i >= static_cast(lane_start); i--) { const auto & path_pos = path_ip.points.at(i).point.pose.position; @@ -1295,6 +1316,31 @@ bool IntersectionModule::isOcclusionCleared( projection_ind_grid.at(height - 1 - idx_y, idx_x) = i; } + // (4.2) fill parked_vehicle_pixel to parked_vehicles (both positive and negative) + for (const auto & parked_attention_object : parked_attention_objects) { + const auto obj_poly = tier4_autoware_utils::toPolygon2d(parked_attention_object); + std::vector common_areas; + bg::intersection(obj_poly, grid_poly, common_areas); + if (common_areas.empty()) continue; + for (size_t i = 0; i < common_areas.size(); ++i) { + common_areas[i].outer().push_back(common_areas[i].outer().front()); + bg::correct(common_areas[i]); + } + std::vector> parked_attention_object_area_cv_polygons; + for (const auto & common_area : common_areas) { + std::vector parked_attention_object_area_cv_polygon; + for (const auto & p : common_area.outer()) { + const int idx_x = static_cast((p.x() - origin.x) / resolution); + const int idx_y = static_cast((p.y() - origin.y) / resolution); + parked_attention_object_area_cv_polygon.emplace_back(idx_x, height - 1 - idx_y); + } + parked_attention_object_area_cv_polygons.push_back(parked_attention_object_area_cv_polygon); + } + for (const auto & poly : parked_attention_object_area_cv_polygons) { + cv::fillPoly(distance_grid, poly, cv::Scalar(parked_vehicle_pixel), cv::LINE_AA); + } + } + for (const auto & lane_division : lane_divisions) { const auto & divisions = lane_division.divisions; for (const auto & division : divisions) { @@ -1303,8 +1349,9 @@ bool IntersectionModule::isOcclusionCleared( int projection_ind = -1; std::optional> cost_prev_checkpoint = std::nullopt; // cost, x, y, projection_ind - for (const auto & point : division) { - const auto [valid, idx_x, idx_y] = coord2index(point.x(), point.y()); + for (auto point = division.begin(); point != division.end(); point++) { + const double x = point->x(), y = point->y(); + const auto [valid, idx_x, idx_y] = coord2index(x, y); // exited grid just now if (is_in_grid && !valid) break; @@ -1327,16 +1374,27 @@ bool IntersectionModule::isOcclusionCleared( zero_dist_cell_found = true; projection_ind = projection_ind_grid.at(height - 1 - idx_y, idx_x); assert(projection_ind >= 0); - cost_prev_checkpoint = std::make_optional>( - 0.0, point.x(), point.y(), projection_ind); + cost_prev_checkpoint = + std::make_optional>(0.0, x, y, projection_ind); continue; } + // hit positive parked vehicle + if (zero_dist_cell_found && pixel == parked_vehicle_pixel) { + while (point != division.end()) { + const double x = point->x(), y = point->y(); + const auto [valid, idx_x, idx_y] = coord2index(x, y); + if (valid) occlusion_mask.at(height - 1 - idx_y, idx_x) = 0; + point++; + } + break; + } + if (zero_dist_cell_found) { // finally traversed to defined cell (first half) const auto [prev_cost, prev_checkpoint_x, prev_checkpoint_y, prev_projection_ind] = cost_prev_checkpoint.value(); - const double dy = point.y() - prev_checkpoint_y, dx = point.x() - prev_checkpoint_x; + const double dy = y - prev_checkpoint_y, dx = x - prev_checkpoint_x; double new_dist = prev_cost + std::hypot(dy, dx); const int new_projection_ind = projection_ind_grid.at(height - 1 - idx_y, idx_x); const double cur_dist = pixel2dist(pixel); @@ -1349,7 +1407,7 @@ bool IntersectionModule::isOcclusionCleared( projection_ind_grid.at(height - 1 - idx_y, idx_x) = projection_ind; distance_grid.at(height - 1 - idx_y, idx_x) = dist2pixel(new_dist); cost_prev_checkpoint = std::make_optional>( - new_dist, point.x(), point.y(), projection_ind); + new_dist, x, y, projection_ind); } } } @@ -1360,7 +1418,7 @@ bool IntersectionModule::isOcclusionCleared( const double possible_object_bbox_y = possible_object_bbox.at(1) / resolution; const double possible_object_area = possible_object_bbox_x * possible_object_bbox_y; std::vector> contours; - cv::findContours(occlusion_mask, contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE); + cv::findContours(occlusion_mask, contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE); std::vector> valid_contours; for (const auto & contour : contours) { std::vector valid_contour; @@ -1377,11 +1435,18 @@ bool IntersectionModule::isOcclusionCleared( cv::approxPolyDP( valid_contour, approx_contour, std::round(std::min(possible_object_bbox_x, possible_object_bbox_y) / std::sqrt(2.0)), true); - if (approx_contour.size() <= 1) continue; + if (approx_contour.size() <= 2) continue; // check area const double poly_area = cv::contourArea(approx_contour); if (poly_area < possible_object_area) continue; - + // check bounding box size + const auto bbox = cv::minAreaRect(approx_contour); + if (const auto size = bbox.size; std::min(size.height, size.width) < + std::min(possible_object_bbox_x, possible_object_bbox_y) || + std::max(size.height, size.width) < + std::max(possible_object_bbox_x, possible_object_bbox_y)) { + continue; + } valid_contours.push_back(approx_contour); geometry_msgs::msg::Polygon polygon_msg; geometry_msgs::msg::Point32 point_msg; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index d4ef1442bb27a..5c6222b31bf54 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -108,6 +108,7 @@ class IntersectionModule : public SceneModuleInterface double max_vehicle_velocity_for_rss; double denoise_kernel; std::vector possible_object_bbox; + double ignore_parked_vehicle_speed_threshold; } occlusion; }; @@ -248,11 +249,14 @@ class IntersectionModule : public SceneModuleInterface const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const util::IntersectionStopLines & intersection_stop_lines); - bool checkCollision( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + autoware_auto_perception_msgs::msg::PredictedObjects filterTargetObjects( const lanelet::ConstLanelets & attention_area_lanelets, const lanelet::ConstLanelets & adjacent_lanelets, - const std::optional & intersection_area, + const std::optional & intersection_area) const; + + bool checkCollision( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const autoware_auto_perception_msgs::msg::PredictedObjects & target_objects, const lanelet::ConstLanelets & ego_lane_with_next_lane, const int closest_idx, const double time_delay, const bool tl_arrow_solid_on); @@ -262,7 +266,10 @@ class IntersectionModule : public SceneModuleInterface const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, - const std::vector & lane_divisions, const double occlusion_dist_thr); + const std::vector & lane_divisions, + const std::vector & + parked_attention_objects, + const double occlusion_dist_thr); /* bool IntersectionModule::checkFrontVehicleDeceleration( From 35295f4d2a95c76e29d307d0e232b323702b0be9 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 1 Aug 2023 11:06:19 +0900 Subject: [PATCH 053/266] fix(start_planner): fix drivable lanes (#4455) * fix(start_planner): fix drivable lanes Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../start_planner/start_planner_module.hpp | 6 +- .../start_planner/start_planner_module.cpp | 64 +++++++++++-------- 2 files changed, 41 insertions(+), 29 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index e17834326965d..2d7584e60c950 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -51,11 +51,7 @@ struct PullOutStatus size_t current_path_idx{0}; PlannerType planner_type{PlannerType::NONE}; PathWithLaneId backward_path{}; - lanelet::ConstLanelets current_lanes{}; lanelet::ConstLanelets pull_out_lanes{}; - std::vector lanes{}; - std::vector lane_follow_lane_ids{}; - std::vector pull_out_lane_ids{}; bool is_safe{false}; bool back_finished{false}; Pose pull_out_start_pose{}; @@ -139,6 +135,8 @@ class StartPlannerModule : public SceneModuleInterface const std::vector & start_pose_candidates, const Pose & goal_pose, const std::string search_priority); PathWithLaneId generateStopPath() const; + lanelet::ConstLanelets getPathLanes(const PathWithLaneId & path) const; + std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); static bool isOverlappedWithLane( const lanelet::ConstLanelet & candidate_lanelet, diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index fbc81d4a2e890..e64feacf6ba9d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -201,7 +201,7 @@ BehaviorModuleOutput StartPlannerModule::plan() } const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - path, status_.lanes, planner_data_->drivable_area_expansion_parameters); + path, generateDrivableLanes(path), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -330,11 +330,8 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() planner_data_, backward_path_length, std::numeric_limits::max(), /*until_goal_lane*/ true); - const auto pull_out_lanes = - start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); auto stop_path = status_.back_finished ? getCurrentPath() : status_.backward_path; - const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_out_lanes); + const auto drivable_lanes = generateDrivableLanes(stop_path); const auto & dp = planner_data_->drivable_area_expansion_parameters; const auto expanded_lanes = utils::expandLanelets( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, @@ -533,11 +530,39 @@ PathWithLaneId StartPlannerModule::generateStopPath() const // generate drivable area const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - path, status_.lanes, planner_data_->drivable_area_expansion_parameters); + path, generateDrivableLanes(path), planner_data_->drivable_area_expansion_parameters); return path; } +lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & path) const +{ + std::vector lane_ids; + for (const auto & p : path.points) { + for (const auto & id : p.lane_ids) { + if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) { + lane_ids.push_back(id); + } + } + } + + const auto & lanelet_layer = planner_data_->route_handler->getLaneletMapPtr()->laneletLayer; + + lanelet::ConstLanelets path_lanes; + path_lanes.reserve(lane_ids.size()); + for (const auto & id : lane_ids) { + path_lanes.push_back(lanelet_layer.get(id)); + } + + return path_lanes; +} + +std::vector StartPlannerModule::generateDrivableLanes( + const PathWithLaneId & path) const +{ + return utils::generateDrivableLanesWithShoulderLanes(getPathLanes(path), status_.pull_out_lanes); +} + void StartPlannerModule::updatePullOutStatus() { if (has_received_new_route_) { @@ -561,17 +586,10 @@ void StartPlannerModule::updatePullOutStatus() const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & goal_pose = planner_data_->route_handler->getGoalPose(); - const double backward_path_length = - planner_data_->parameters.backward_path_length + parameters_->max_back_distance; - status_.current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), - /*until_goal_lane*/ true); - status_.pull_out_lanes = - start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); - - // combine road and shoulder lanes - status_.lanes = - utils::generateDrivableLanesWithShoulderLanes(status_.current_lanes, status_.pull_out_lanes); + // save pull out lanes which is generated using current pose before starting pull out + // (before approval) + status_.pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); // search pull out start candidates backward std::vector start_pose_candidates = searchPullOutStartPoses(); @@ -583,10 +601,6 @@ void StartPlannerModule::updatePullOutStatus() *route_handler, status_.pull_out_lanes, current_pose, status_.pull_out_start_pose, parameters_->backward_velocity); } - - // Update status - status_.lane_follow_lane_ids = utils::getIds(status_.current_lanes); - status_.pull_out_lane_ids = utils::getIds(status_.pull_out_lanes); } std::vector StartPlannerModule::searchPullOutStartPoses() @@ -677,10 +691,10 @@ bool StartPlannerModule::hasFinishedPullOut() const const auto current_pose = planner_data_->self_odometry->pose.pose; // check that ego has passed pull out end point - const auto arclength_current = - lanelet::utils::getArcCoordinates(status_.current_lanes, current_pose); + const auto path_lanes = getPathLanes(getFullPath()); + const auto arclength_current = lanelet::utils::getArcCoordinates(path_lanes, current_pose); const auto arclength_pull_out_end = - lanelet::utils::getArcCoordinates(status_.current_lanes, status_.pull_out_path.end_pose); + lanelet::utils::getArcCoordinates(path_lanes, status_.pull_out_path.end_pose); // offset to not finish the module before engage constexpr double offset = 0.1; @@ -877,7 +891,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() output.path = std::make_shared(stop_path); DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = status_.lanes; + current_drivable_area_info.drivable_lanes = generateDrivableLanes(*output.path); output.drivable_area_info = utils::combineDrivableAreaInfo( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); From c2564ae33aa9be842b115c7414d984ac76f2b08b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 1 Aug 2023 11:29:13 +0900 Subject: [PATCH 054/266] disable pass judge decision while peeking (#4468) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 19 ++++++++++++++++++- .../src/scene_intersection.hpp | 1 + .../src/util.cpp | 4 ++++ 3 files changed, 23 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 713df530b43d1..dcfa3b0fce71f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -708,11 +708,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( lane_id_, associative_ids_, *path, planner_param_.common.path_interpolation_ds, logger_); if (!interpolated_path_info_opt) { RCLCPP_DEBUG(logger_, "splineInterpolate failed"); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } const auto & interpolated_path_info = interpolated_path_info_opt.value(); if (!interpolated_path_info.lane_id_interval) { RCLCPP_WARN(logger_, "Path has no interval on intersection lane %ld", lane_id_); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } @@ -733,6 +735,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto & conflicting_lanelets = intersection_lanelets_.value().conflicting(); const auto & first_conflicting_area = intersection_lanelets_.value().first_conflicting_area(); if (conflicting_lanelets.empty() || !first_conflicting_area) { + is_peeking_ = false; return IntersectionModule::Indecisive{}; } @@ -745,6 +748,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( planner_param_.common.stop_line_margin, planner_param_.occlusion.peeking_offset, path); if (!intersection_stop_lines_opt) { RCLCPP_DEBUG(logger_, "failed to generate intersection_stop_lines"); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } const auto & intersection_stop_lines = intersection_stop_lines_opt.value(); @@ -771,6 +775,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool timeout = (is_private_area_ && stuck_private_area_timeout_.getState() == StateMachine::State::GO); if (!timeout) { + is_peeking_ = false; return IntersectionModule::StuckStop{ stuck_stop_line_idx, !first_attention_area.has_value(), intersection_stop_lines}; } @@ -778,11 +783,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( if (!first_attention_area) { RCLCPP_DEBUG(logger_, "attention area is empty"); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } if (default_stop_line_idx == 0) { RCLCPP_DEBUG(logger_, "stop line index is 0"); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } @@ -796,7 +803,10 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const double vel = std::fabs(planner_data_->current_velocity->twist.linear.x); const bool keep_detection = (vel < planner_param_.collision_detection.keep_detection_vel_thr); // if ego is over the pass judge line and not stopped - if (is_over_default_stop_line && !is_over_pass_judge_line && keep_detection) { + if (is_peeking_) { + // do nothing + RCLCPP_DEBUG(logger_, "peeking now"); + } else if (is_over_default_stop_line && !is_over_pass_judge_line && keep_detection) { RCLCPP_DEBUG( logger_, "is_over_default_stop_line && !is_over_pass_judge_line && keep_detection"); // do nothing @@ -806,6 +816,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // activated_: current RTC approval is_permanent_go_ = true; RCLCPP_DEBUG(logger_, "over the pass judge line. no plan needed."); + is_peeking_ = false; return IntersectionModule::Indecisive{}; } @@ -841,6 +852,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( collision_state_machine_.getState() == StateMachine::State::STOP; if (tl_arrow_solid_on) { + is_peeking_ = false; return TrafficLightArrowSolidOn{has_collision, intersection_stop_lines}; } @@ -884,10 +896,12 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } if (before_creep_state_machine_.getState() == StateMachine::State::GO) { if (has_collision) { + is_peeking_ = true; return IntersectionModule::OccludedCollisionStop{ default_stop_line_idx, occlusion_peeking_stop_line_idx, is_occlusion_cleared, intersection_stop_lines}; } else { + is_peeking_ = true; return IntersectionModule::PeekingTowardOcclusion{ occlusion_peeking_stop_line_idx, is_occlusion_cleared, intersection_stop_lines}; } @@ -897,6 +911,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( before_creep_state_machine_.setStateWithMarginTime( StateMachine::State::GO, logger_.get_child("occlusion state_machine"), *clock_); } + is_peeking_ = true; return IntersectionModule::FirstWaitBeforeOcclusion{ default_stop_line_idx, occlusion_peeking_stop_line_idx, is_occlusion_cleared, intersection_stop_lines}; @@ -905,9 +920,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_over_default_stopLine = util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); const auto stop_line_idx = is_over_default_stopLine ? closest_idx : default_stop_line_idx; + is_peeking_ = false; return IntersectionModule::NonOccludedCollisionStop{stop_line_idx, intersection_stop_lines}; } + is_peeking_ = false; return IntersectionModule::Safe{intersection_stop_lines}; } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 5c6222b31bf54..a427c4930b6d5 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -210,6 +210,7 @@ class IntersectionModule : public SceneModuleInterface std::string turn_direction_; bool is_go_out_ = false; bool is_permanent_go_ = false; + bool is_peeking_ = false; // Parameter PlannerParam planner_param_; std::optional intersection_lanelets_; diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 13d8b10b8f76c..178df99ba7b02 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -315,6 +315,10 @@ std::optional generateIntersectionStopLines( intersection_stop_lines.default_stop_line) { intersection_stop_lines.occlusion_peeking_stop_line = intersection_stop_lines.default_stop_line; } + if ( + intersection_stop_lines.occlusion_peeking_stop_line > intersection_stop_lines.pass_judge_line) { + intersection_stop_lines.pass_judge_line = intersection_stop_lines.occlusion_peeking_stop_line; + } return intersection_stop_lines; } From e8051656dfdbba33e96154b0a9be4a25700fc6e4 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 1 Aug 2023 12:11:23 +0900 Subject: [PATCH 055/266] refactor(interface): remove redundant member variables (#4459) Signed-off-by: satoshi-ota --- .../scene_module/avoidance/avoidance_module.hpp | 6 +++--- .../scene_module/avoidance/manager.hpp | 2 -- .../dynamic_avoidance/dynamic_avoidance_module.hpp | 4 ++-- .../scene_module/dynamic_avoidance/manager.hpp | 1 - .../scene_module/goal_planner/goal_planner_module.hpp | 4 ++-- .../scene_module/goal_planner/manager.hpp | 2 -- .../scene_module/lane_change/interface.hpp | 2 +- .../scene_module/lane_change/manager.hpp | 2 -- .../scene_module/scene_module_interface.hpp | 3 +++ .../scene_module/side_shift/manager.hpp | 2 -- .../scene_module/side_shift/side_shift_module.hpp | 6 +++--- .../scene_module/start_planner/manager.hpp | 2 -- .../scene_module/start_planner/start_planner_module.hpp | 4 ++-- .../src/scene_module/lane_change/interface.cpp | 9 ++++----- .../src/scene_module/start_planner/manager.cpp | 7 ++++--- 15 files changed, 24 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index e4349c68cc0f5..0d574f8c31c02 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -49,7 +49,7 @@ class AvoidanceModule : public SceneModuleInterface public: AvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map > & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map); ModuleStatus updateState() override; CandidateOutput planCandidate() const override; @@ -62,9 +62,9 @@ class AvoidanceModule : public SceneModuleInterface void updateData() override; void acceptVisitor(const std::shared_ptr & visitor) const override; - void updateModuleParams(const std::shared_ptr & parameters) + void updateModuleParams(const std::any & parameters) override { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } std::shared_ptr get_debug_msg_array() const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp index e4421459e61fd..4aa7f9ef142c6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp @@ -44,8 +44,6 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface private: std::shared_ptr parameters_; - - std::vector> registered_modules_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 7f18c847af43e..6b18db98f156e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -129,9 +129,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map); - void updateModuleParams(const std::shared_ptr & parameters) + void updateModuleParams(const std::any & parameters) override { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp index d2b1deb36bd30..4e4a54af14b53 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp @@ -44,7 +44,6 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface private: std::shared_ptr parameters_; - std::vector> registered_modules_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index abad4b9f2959f..5263238d5c922 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -92,9 +92,9 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map); - void updateModuleParams(const std::shared_ptr & parameters) + void updateModuleParams(const std::any & parameters) override { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } BehaviorModuleOutput run() override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp index d836f73df22bc..b6960aba10846 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp @@ -42,8 +42,6 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface private: std::shared_ptr parameters_; - - std::vector> registered_modules_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index 34ded5c976e3b..c57e8f3b8b8b3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -87,7 +87,7 @@ class LaneChangeInterface : public SceneModuleInterface void acceptVisitor(const std::shared_ptr & visitor) const override; - void updateModuleParams(const std::shared_ptr & parameters); + void updateModuleParams(const std::any & parameters) override; void setData(const std::shared_ptr & data) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index 9dabd3d0004fb..af65245ce4e3f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -44,8 +44,6 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface protected: std::shared_ptr parameters_; - std::vector> registered_modules_; - Direction direction_; LaneChangeModuleType type_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 371169c86db4e..0c60c6b73afb4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -37,6 +37,7 @@ #include #include +#include #include #include #include @@ -88,6 +89,8 @@ class SceneModuleInterface virtual ~SceneModuleInterface() = default; + virtual void updateModuleParams(const std::any & parameters) = 0; + /** * @brief Return SUCCESS if plan is not needed or plan is successfully finished, * FAILURE if plan has failed, RUNNING if plan is on going. diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp index f35f497df0e4a..8a287e6920f33 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp @@ -43,8 +43,6 @@ class SideShiftModuleManager : public SceneModuleManagerInterface private: std::shared_ptr parameters_; - - std::vector> registered_modules_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index bc6f55008fa93..bdff915e15d5b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -43,7 +43,7 @@ class SideShiftModule : public SceneModuleInterface SideShiftModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map); bool isExecutionRequested() const override; bool isExecutionReady() const override; @@ -59,9 +59,9 @@ class SideShiftModule : public SceneModuleInterface void setParameters(const std::shared_ptr & parameters); - void updateModuleParams(const std::shared_ptr & parameters) + void updateModuleParams(const std::any & parameters) override { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } void acceptVisitor( diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp index 103e7dc375233..c86f9e415fdc7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp @@ -42,8 +42,6 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface private: std::shared_ptr parameters_; - - std::vector> registered_modules_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 2d7584e60c950..9d91cdbe3783e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -67,9 +67,9 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map); - void updateModuleParams(const std::shared_ptr & parameters) + void updateModuleParams(const std::any & parameters) override { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } BehaviorModuleOutput run() override; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 00b280af43677..14a568f5648ad 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -36,7 +36,7 @@ using utils::lane_change::assignToCandidate; LaneChangeInterface::LaneChangeInterface( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map > & rtc_interface_ptr_map, + const std::unordered_map> & rtc_interface_ptr_map, std::unique_ptr && module_type) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{std::move(parameters)}, @@ -278,10 +278,9 @@ CandidateOutput LaneChangeInterface::planCandidate() const return output; } -void LaneChangeInterface::updateModuleParams( - const std::shared_ptr & parameters) +void LaneChangeInterface::updateModuleParams(const std::any & parameters) { - parameters_ = parameters; + parameters_ = std::any_cast>(parameters); } void LaneChangeInterface::setData(const std::shared_ptr & data) @@ -507,7 +506,7 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, const std::shared_ptr & avoidance_by_lane_change_parameters, - const std::unordered_map > & rtc_interface_ptr_map) + const std::unordered_map> & rtc_interface_ptr_map) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, std::make_unique(parameters, avoidance_by_lane_change_parameters)} diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index d6104480f1cc3..881da2b52720a 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -100,10 +100,11 @@ void StartPlannerModuleManager::updateModuleParams( [[maybe_unused]] std::string ns = name_ + "."; std::for_each(registered_modules_.begin(), registered_modules_.end(), [&](const auto & m) { - m->updateModuleParams(p); - m->setInitialIsSimultaneousExecutableAsApprovedModule( + const auto start_planner_ptr = std::dynamic_pointer_cast(m); + start_planner_ptr->updateModuleParams(p); + start_planner_ptr->setInitialIsSimultaneousExecutableAsApprovedModule( enable_simultaneous_execution_as_approved_module_); - m->setInitialIsSimultaneousExecutableAsCandidateModule( + start_planner_ptr->setInitialIsSimultaneousExecutableAsCandidateModule( enable_simultaneous_execution_as_candidate_module_); }); } From e8c230a09594d6ccc785f0fb51c8521f079c0e8b Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Tue, 1 Aug 2023 12:13:30 +0900 Subject: [PATCH 056/266] chore: change TLR default model (#4476) * feat: change default model for traffic_light_fine_detector and classifier Signed-off-by: Shunsuke Miura * add maintainer to tlr packages Signed-off-by: Shunsuke Miura --------- Signed-off-by: Shunsuke Miura --- perception/traffic_light_arbiter/package.xml | 1 + .../launch/traffic_light_classifier.launch.xml | 9 ++++++--- .../launch/traffic_light_fine_detector.launch.xml | 4 ++-- perception/traffic_light_fine_detector/package.xml | 1 + perception/traffic_light_multi_camera_fusion/package.xml | 1 + perception/traffic_light_occlusion_predictor/package.xml | 1 + 6 files changed, 12 insertions(+), 5 deletions(-) diff --git a/perception/traffic_light_arbiter/package.xml b/perception/traffic_light_arbiter/package.xml index 7eb45f6c6b8cc..a95df132de3bd 100644 --- a/perception/traffic_light_arbiter/package.xml +++ b/perception/traffic_light_arbiter/package.xml @@ -5,6 +5,7 @@ 0.1.0 The traffic_light_arbiter package Kenzo Lobos-Tsunekawa + Shunsuke Miura Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml index e502aac8e2d35..d4794443d95d9 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -2,6 +2,9 @@ + + + @@ -16,9 +19,9 @@ - - - + + + diff --git a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml index 442aa3f45ea88..5ce7840c28fd6 100644 --- a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml +++ b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml @@ -1,6 +1,6 @@ - - + + diff --git a/perception/traffic_light_fine_detector/package.xml b/perception/traffic_light_fine_detector/package.xml index 960a90379279a..c54912e256c02 100644 --- a/perception/traffic_light_fine_detector/package.xml +++ b/perception/traffic_light_fine_detector/package.xml @@ -5,6 +5,7 @@ 0.1.0 The traffic_light_fine_detector package Mingyu Li + Shunsuke Miura Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_multi_camera_fusion/package.xml b/perception/traffic_light_multi_camera_fusion/package.xml index 6dd0bf89bd716..eb0858152e69e 100644 --- a/perception/traffic_light_multi_camera_fusion/package.xml +++ b/perception/traffic_light_multi_camera_fusion/package.xml @@ -5,6 +5,7 @@ 0.1.0 The traffic_light_multi_camera_fusion package Mingyu Li + Shunsuke Miura Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_occlusion_predictor/package.xml b/perception/traffic_light_occlusion_predictor/package.xml index 154b650669c8d..0ae390c90b9a9 100644 --- a/perception/traffic_light_occlusion_predictor/package.xml +++ b/perception/traffic_light_occlusion_predictor/package.xml @@ -5,6 +5,7 @@ 0.1.0 The traffic_light_occlusion_predictor package Mingyu Li + Shunsuke Miura Apache License 2.0 ament_cmake_auto From 2f282edb474aabb071746e4ed0f6ff2b0f3403db Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 1 Aug 2023 14:54:34 +0900 Subject: [PATCH 057/266] feat(avoidance): add parameter to configurate avoidance return point (#4467) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 1 + .../utils/avoidance/avoidance_module_data.hpp | 3 +++ .../src/scene_module/avoidance/avoidance_module.cpp | 13 +++++++------ .../src/scene_module/avoidance/manager.cpp | 1 + 4 files changed, 12 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 3b9165194a3bf..db2436f796dfe 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -160,6 +160,7 @@ # avoidance distance parameters longitudinal: prepare_time: 2.0 # [s] + remain_buffer_distance: 30.0 # [m] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index b590d452ae03e..2b1a9cf1b82d4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -225,6 +225,9 @@ struct AvoidanceParameters // nominal avoidance sped double nominal_avoidance_speed; + // module try to return original path to keep this distance from edge point of the path. + double remain_buffer_distance; + // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. double road_shoulder_safety_margin{1.0}; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 06ebd6e01b48b..45a26cfb29f48 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -996,9 +996,10 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length; // The end_margin also has the purpose of preventing the return path from NOT being // triggered at the end point. - const auto end_margin = 1.0; - const auto return_remaining_distance = - std::max(data.arclength_from_ego.back() - o.longitudinal - offset - end_margin, 0.0); + const auto return_remaining_distance = std::max( + data.arclength_from_ego.back() - o.longitudinal - offset - + parameters_->remain_buffer_distance, + 0.0); al_return.start_shift_length = feasible_shift_length.get(); al_return.end_shift_length = 0.0; @@ -1745,14 +1746,14 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) return; } - const auto remaining_distance = arclength_from_ego.back(); + const auto remaining_distance = arclength_from_ego.back() - parameters_->remain_buffer_distance; // If the avoidance point has already been set, the return shift must be set after the point. const auto last_sl_distance = avoidance_data_.arclength_from_ego.at(last_sl.end_idx); // check if there is enough distance for return. - if (last_sl_distance + 1.0 > remaining_distance) { // tmp: add some small number (+1.0) - DEBUG_PRINT("No enough distance for return."); + if (last_sl_distance > remaining_distance) { // tmp: add some small number (+1.0) + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 1000, "No enough distance for return."); return; } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 29b3535331547..ec2ede8373831 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -173,6 +173,7 @@ AvoidanceModuleManager::AvoidanceModuleManager( std::string ns = "avoidance.avoidance.longitudinal."; p.prepare_time = get_parameter(node, ns + "prepare_time"); p.min_prepare_distance = get_parameter(node, ns + "min_prepare_distance"); + p.remain_buffer_distance = get_parameter(node, ns + "remain_buffer_distance"); p.min_slow_down_speed = get_parameter(node, ns + "min_slow_down_speed"); p.buf_slow_down_speed = get_parameter(node, ns + "buf_slow_down_speed"); p.nominal_avoidance_speed = get_parameter(node, ns + "nominal_avoidance_speed"); From 8d6be6d4f56fdfbea119c32a887e1d0ad1e92190 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 18:42:55 +0900 Subject: [PATCH 058/266] feat(crosswalk): disable cancel yield at no traffic signals intersection (#4463) * feat(crosswalk): disable cancel yield at no traffic signals intersection Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/scene_crosswalk.cpp | 7 ++++++- .../src/scene_crosswalk.hpp | 10 ++++++---- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 9d0d0593a333e..d45004324e1b2 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -858,6 +858,10 @@ void CrosswalkModule::updateObjectState(const double dist_ego_to_stop) { const auto & objects_ptr = planner_data_->predicted_objects; + const auto traffic_lights_reg_elems = + crosswalk_.regulatoryElementsAs(); + const bool has_traffic_light = !traffic_lights_reg_elems.empty(); + // Check if ego is yielding const bool is_ego_yielding = [&]() { const auto has_reached_stop_point = dist_ego_to_stop < planner_param_.stop_position_threshold; @@ -872,7 +876,8 @@ void CrosswalkModule::updateObjectState(const double dist_ego_to_stop) const auto obj_uuid = toHexString(object.object_id); const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; object_info_manager_.update( - obj_uuid, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, planner_param_); + obj_uuid, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, has_traffic_light, + planner_param_); } object_info_manager_.finalize(); } diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index b66b97dd6745f..f3d174f1b9a9b 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -106,7 +106,7 @@ class CrosswalkModule : public SceneModuleInterface void updateState( const rclcpp::Time & now, const double obj_vel, const bool is_ego_yielding, - const PlannerParam & planner_param) + const bool has_traffic_light, const PlannerParam & planner_param) { const bool is_stopped = obj_vel < planner_param.stop_object_velocity; @@ -120,7 +120,9 @@ class CrosswalkModule : public SceneModuleInterface } const bool intent_to_cross = (now - *time_to_start_stopped).seconds() < planner_param.timeout_no_intention_to_walk; - if ((is_ego_yielding || planner_param.disable_stop_for_yield_cancel) && !intent_to_cross) { + if ( + (is_ego_yielding || (has_traffic_light && planner_param.disable_stop_for_yield_cancel)) && + !intent_to_cross) { state = State::FULLY_STOPPED; } else { // NOTE: Object may start moving @@ -137,7 +139,7 @@ class CrosswalkModule : public SceneModuleInterface void init() { current_uuids_.clear(); } void update( const std::string & uuid, const double obj_vel, const rclcpp::Time & now, - const bool is_ego_yielding, const PlannerParam & planner_param) + const bool is_ego_yielding, const bool has_traffic_light, const PlannerParam & planner_param) { // update current uuids current_uuids_.push_back(uuid); @@ -148,7 +150,7 @@ class CrosswalkModule : public SceneModuleInterface } // update object state - objects.at(uuid).updateState(now, obj_vel, is_ego_yielding, planner_param); + objects.at(uuid).updateState(now, obj_vel, is_ego_yielding, has_traffic_light, planner_param); } void finalize() { From cd9f5ce5c5fc827ceb9227e1e44503b524f60716 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 18:43:50 +0900 Subject: [PATCH 059/266] feat(crosswalk): add option to disable yield for new stopped object (#4465) * feat(crosswalk): disable cancel yield at no traffic signals intersection Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * feat(crosswalk): add option to disable yield for new stopped object Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 3 ++- .../src/manager.cpp | 2 ++ .../src/scene_crosswalk.hpp | 11 +++++++++-- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 5fff846785353..097b2c6c94aef 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -41,7 +41,8 @@ stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding - disable_stop_for_yield_cancel: false + disable_stop_for_yield_cancel: false # for the crosswalk where there is a traffic signal + disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal timeout_no_intention_to_walk: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 7f5c46f1cf91a..d287787006aff 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -80,6 +80,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) cp.min_object_velocity = node.declare_parameter(ns + ".pass_judge.min_object_velocity"); cp.disable_stop_for_yield_cancel = node.declare_parameter(ns + ".pass_judge.disable_stop_for_yield_cancel"); + cp.disable_yield_for_new_stopped_object = + node.declare_parameter(ns + ".pass_judge.disable_yield_for_new_stopped_object"); cp.timeout_no_intention_to_walk = node.declare_parameter(ns + ".pass_judge.timeout_no_intention_to_walk"); cp.timeout_ego_stop_for_yield = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index f3d174f1b9a9b..957fa9540f2f5 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -85,6 +85,7 @@ class CrosswalkModule : public SceneModuleInterface double stop_object_velocity; double min_object_velocity; bool disable_stop_for_yield_cancel; + bool disable_yield_for_new_stopped_object; double timeout_no_intention_to_walk; double timeout_ego_stop_for_yield; // param for input data @@ -101,7 +102,7 @@ class CrosswalkModule : public SceneModuleInterface { // NOTE: FULLY_STOPPED means stopped object which can be ignored. enum class State { STOPPED = 0, FULLY_STOPPED, OTHER }; - State state{State::OTHER}; + State state; std::optional time_to_start_stopped{std::nullopt}; void updateState( @@ -146,7 +147,13 @@ class CrosswalkModule : public SceneModuleInterface // add new object if (objects.count(uuid) == 0) { - objects.emplace(uuid, ObjectInfo{}); + if ( + has_traffic_light && planner_param.disable_stop_for_yield_cancel && + planner_param.disable_yield_for_new_stopped_object) { + objects.emplace(uuid, ObjectInfo{ObjectInfo::State::FULLY_STOPPED}); + } else { + objects.emplace(uuid, ObjectInfo{ObjectInfo::State::OTHER}); + } } // update object state From 92ffe6acde57d8f8235e33b6d3ce121a2e71d8d0 Mon Sep 17 00:00:00 2001 From: urasakikeisuke <79469739+urasakikeisuke@users.noreply.github.com> Date: Tue, 1 Aug 2023 20:13:00 +0900 Subject: [PATCH 060/266] fix(gyro_odometer): fix output_frame parameter name (#4485) --- localization/gyro_odometer/src/gyro_odometer_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 8ad9e77453db5..2412fd5d57602 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -102,7 +102,7 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer( GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options) : Node("gyro_odometer", options), - output_frame_(declare_parameter("base_link", "base_link")), + output_frame_(declare_parameter("output_frame", "base_link")), message_timeout_sec_(declare_parameter("message_timeout_sec", 0.2)), vehicle_twist_arrived_(false), imu_arrived_(false) From a5d0a7d33042ac4d0341d7cff3ecf69f7231bc08 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 20:16:37 +0900 Subject: [PATCH 061/266] fix(crosswalk): fix the doc of TTC-TTV graph (#4480) Signed-off-by: Takayuki Murooka --- .../docs/ttc-ttv.svg | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/docs/ttc-ttv.svg b/planning/behavior_velocity_crosswalk_module/docs/ttc-ttv.svg index 7bd11ecf2ee39..04a208eee4166 100644 --- a/planning/behavior_velocity_crosswalk_module/docs/ttc-ttv.svg +++ b/planning/behavior_velocity_crosswalk_module/docs/ttc-ttv.svg @@ -55,12 +55,12 @@
- TTV = TTC + ego_pass_later_margin + TTV = TTC + ego_pass_first_margin
- TTV = TTC + ego_pass_later_margin + TTV = TTC + ego_pass_first_margin
@@ -75,12 +75,12 @@
- TTC = TTV + ego_pass_first_margin + TTC = TTV + ego_pass_later_margin
- TTC = TTV + ego_pass_first_margin + TTC = TTV + ego_pass_later_margin
@@ -160,13 +160,13 @@
- ego_pass_later_margin + ego_pass_first_margin [s]
- ego_pass_later_margin [s] + ego_pass_first_margin [s]
@@ -181,13 +181,13 @@
- ego_pass_pass_margin + ego_pass_later_margin [s]
- ego_pass_pass_margin [s] + ego_pass_later_margin [s] From 90ddc1d7f9911de2c94441c429c75f5128165fe0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 20:16:51 +0900 Subject: [PATCH 062/266] fix(obstacle_avoidance_planner): fix the bug of inserting stop point (#4479) Signed-off-by: Takayuki Murooka --- planning/obstacle_avoidance_planner/src/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index a135ffdcfa4b7..da82fb14ea6d8 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -441,8 +441,8 @@ void ObstacleAvoidancePlanner::insertZeroVelocityOutsideDrivableArea( if (first_outside_idx) { debug_data_ptr_->stop_pose_by_drivable_area = optimized_traj_points.at(*first_outside_idx).pose; const auto stop_idx = [&]() { - const auto dist = tier4_autoware_utils::calcDistance2d( - optimized_traj_points.at(0), optimized_traj_points.at(*first_outside_idx)); + const auto dist = + motion_utils::calcSignedArcLength(optimized_traj_points, 0, *first_outside_idx); const auto dist_with_margin = dist - vehicle_stop_margin_outside_drivable_area_; const auto first_outside_idx_with_margin = motion_utils::insertTargetPoint(0, dist_with_margin, optimized_traj_points); From 9ea44d52c89ba44ea25cef2d441755477f3f4b7d Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 1 Aug 2023 20:29:22 +0900 Subject: [PATCH 063/266] chore(mpc_lateral_controller): fix typo (#4481) * chore(mpc_lateral_controller): fix typo Signed-off-by: kminoda * avoid using discretizing Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .../model_predictive_control_algorithm.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control/mpc_lateral_controller/model_predictive_control_algorithm.md b/control/mpc_lateral_controller/model_predictive_control_algorithm.md index 4568fb9882817..fa214abc9a564 100644 --- a/control/mpc_lateral_controller/model_predictive_control_algorithm.md +++ b/control/mpc_lateral_controller/model_predictive_control_algorithm.md @@ -125,7 +125,7 @@ Substituting equation (8) into equation (9) and tidying up the equation for $U$. $$ \begin{align} J(U) &= (H(Fx_{0}+GU+SW)-Y_{ref})^{T}Q(H(Fx_{0}+GU+SW)-Y_{ref})+(U-U_{ref})^{T}R(U-U_{ref}) \\ -& =U^{T}(G^{T}H^{T}QHG+R)U+2\left\{(H(Fx_{0}+SW)-Yref)^{T}QHG-U_{ref}^{T}R\right\}U +(\rm{constant}) \tag{10} +& =U^{T}(G^{T}H^{T}QHG+R)U+2\left\{(H(Fx_{0}+SW)-Y_{ref})^{T}QHG-U_{ref}^{T}R\right\}U +(\rm{constant}) \tag{10} \end{align} $$ @@ -182,7 +182,7 @@ Where $\kappa_{r}\left(s\right)$ is the curvature along the trajectory parametri There are three expressions in the update equations that are subject to linear approximation: the lateral deviation (or lateral coordinate) $y$, the heading angle (or the heading angle error) $\theta$, and the steering $\delta$. We can make a small angle assumption on the heading angle $\theta$. -In the path tracking problem, the curvature of the trajectory $\kappa_{r}$ is known in advance. At the lower speeds, the Ackermann formula approximates the reference steering angle $\theta_{r}$(this value corresponds to the $U_{ref}$ mentioned above). The Ackerman steering expression can be written as; +In the path tracking problem, the curvature of the trajectory $\kappa_{r}$ is known in advance. At the lower speeds, the Ackermann formula approximates the reference steering angle $\theta_{r}$(this value corresponds to the $U_{ref}$ mentioned above). The Ackermann steering expression can be written as; $$ \begin{align} @@ -344,7 +344,7 @@ $$ \end{align} $$ -Discretizing $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply both sides by dt the resulting constraint become linear and convex +We discretize $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply both sides by dt, and the resulting constraint become linear and convex $$ \begin{align} From 0901d3b4a5165cd008d5c9b5715c707044df9eb6 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 1 Aug 2023 21:29:48 +0900 Subject: [PATCH 064/266] refactor(traffic_light_arbiter): read parameters from config file (#4454) Signed-off-by: Tomohito Ando --- launch/tier4_perception_launch/launch/perception.launch.xml | 1 + perception/traffic_light_arbiter/CMakeLists.txt | 2 +- .../config/traffic_light_arbiter.param.yaml | 5 +++++ .../launch/traffic_light_arbiter.launch.xml | 2 ++ 4 files changed, 9 insertions(+), 1 deletion(-) create mode 100644 perception/traffic_light_arbiter/config/traffic_light_arbiter.param.yaml diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 204fb561b10ea..11630405a6336 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -22,6 +22,7 @@ + diff --git a/perception/traffic_light_arbiter/CMakeLists.txt b/perception/traffic_light_arbiter/CMakeLists.txt index ab7ba25fe3ad2..181c2bec867d1 100644 --- a/perception/traffic_light_arbiter/CMakeLists.txt +++ b/perception/traffic_light_arbiter/CMakeLists.txt @@ -12,4 +12,4 @@ rclcpp_components_register_nodes(${PROJECT_NAME} TrafficLightArbiter ) -ament_auto_package(INSTALL_TO_SHARE launch) +ament_auto_package(INSTALL_TO_SHARE launch config) diff --git a/perception/traffic_light_arbiter/config/traffic_light_arbiter.param.yaml b/perception/traffic_light_arbiter/config/traffic_light_arbiter.param.yaml new file mode 100644 index 0000000000000..5dc2b62eaa446 --- /dev/null +++ b/perception/traffic_light_arbiter/config/traffic_light_arbiter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + external_time_tolerance: 5.0 + perception_time_tolerance: 1.0 + external_priority: false diff --git a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml index f8c7b8a78fac6..eca4b8a61b5af 100644 --- a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml +++ b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml @@ -2,6 +2,7 @@ + @@ -10,6 +11,7 @@ + From a8595970a4e43f745ec66f179a5d5a2be62f53b9 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 1 Aug 2023 21:45:31 +0900 Subject: [PATCH 065/266] docs(topic_state_monitor): rename readme to README (#4225) Signed-off-by: Takamasa Horibe --- system/topic_state_monitor/{Readme.md => README.md} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename system/topic_state_monitor/{Readme.md => README.md} (100%) diff --git a/system/topic_state_monitor/Readme.md b/system/topic_state_monitor/README.md similarity index 100% rename from system/topic_state_monitor/Readme.md rename to system/topic_state_monitor/README.md From ec9a392a3385707bca3adcd9aa3050a73f188ee0 Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Tue, 1 Aug 2023 16:37:37 +0300 Subject: [PATCH 066/266] fix(pointcloud_preprocessor): fix launch error (#4431) * update launch file Signed-off-by: ismetatabay * style(pre-commit): autofix --------- Signed-off-by: ismetatabay Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../launch/preprocessor.launch.py | 65 ++++++++++--------- 1 file changed, 33 insertions(+), 32 deletions(-) diff --git a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py b/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py index cdff4bf0162a4..b2e245c5cbf4f 100644 --- a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py +++ b/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py @@ -15,41 +15,25 @@ import launch from launch.actions import DeclareLaunchArgument from launch.actions import LogInfo +from launch.actions import OpaqueFunction from launch.substitutions import LaunchConfiguration from launch.substitutions import PythonExpression from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode -def generate_launch_description(): +def launch_setup(context, *args, **kwargs): ns = "pointcloud_preprocessor" pkg = "pointcloud_preprocessor" - # declare launch arguments - input_points_raw_list_param = DeclareLaunchArgument( - "input_points_raw_list", - default_value="['/points_raw']", - description="Input pointcloud topic_name list as a string_array. " - "To subscribe multiple topics, write as: \"['/points_raw0', '/points_raw1', ...]\"", - ) - - output_points_raw_param = DeclareLaunchArgument( - "output_points_raw", default_value="/points_raw/cropbox/filtered" - ) - - tf_output_frame_param = DeclareLaunchArgument("tf_output_frame", default_value="base_link") - - # set concat filter as a component - separate_concatenate_node_and_timesync_node_str = DeclareLaunchArgument( - "separate_concatenate_node_and_timesync_node", - default_value="false", - description="Set True to separate concatenate node and timesync node. which will cause to larger memory usage.", - ) - separate_concatenate_node_and_timesync_node = ( - separate_concatenate_node_and_timesync_node_str.lower() == "true" + separate_concatenate_node_and_timesync_node = LaunchConfiguration( + "separate_concatenate_node_and_timesync_node" + ).perform(context) + is_separate_concatenate_node_and_timesync_node = ( + separate_concatenate_node_and_timesync_node.lower() == "true" ) - if not separate_concatenate_node_and_timesync_node: + if not is_separate_concatenate_node_and_timesync_node: sync_and_concat_component = ComposableNode( package=pkg, plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", @@ -150,13 +134,30 @@ def generate_launch_description(): ] ) ) + return [container, log_info] - return launch.LaunchDescription( - [ - input_points_raw_list_param, - output_points_raw_param, - tf_output_frame_param, - container, - log_info, - ] + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None, description=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append( + DeclareLaunchArgument(name, default_value=default_value, description=description) + ) + + add_launch_arg( + "input_points_raw_list", + ["/points_raw"], + "Input pointcloud topic_name list as a string_array. " + "To subscribe multiple topics, write as: \"['/points_raw0', '/points_raw1', ...]\"", ) + add_launch_arg("output_points_raw", "/points_raw/cropbox/filtered") + add_launch_arg("tf_output_frame", "base_link") + add_launch_arg( + "separate_concatenate_node_and_timesync_node", + "true", + "Set True to separate concatenate node and timesync node. which will cause to larger memory usage.", + ) + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) From 9a73f2c53670ea262d3b3acbc921e86ca8e0d652 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 2 Aug 2023 01:45:00 +0900 Subject: [PATCH 067/266] fix(goal_planner): plan path even if ego is on the original goal (#4472) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 2 +- .../goal_planner/goal_planner_module.cpp | 15 +++++++++------ 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 5263238d5c922..6789d70a7065b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -194,7 +194,7 @@ class GoalPlannerModule : public SceneModuleInterface std::deque & odometry_buffer, const double time); bool hasFinishedCurrentPath(); bool hasFinishedGoalPlanner(); - bool isOnGoal() const; + bool isOnModifiedGoal() const; double calcModuleRequestLength() const; void resetStatus(); bool needPathUpdate(const double path_update_duration) const; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 61322025b46f2..dd555af17d182 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1085,17 +1085,20 @@ bool GoalPlannerModule::hasFinishedCurrentPath() return is_near_target && isStopped(); } -bool GoalPlannerModule::isOnGoal() const +bool GoalPlannerModule::isOnModifiedGoal() const { + if (!modified_goal_pose_) { + return false; + } + const Pose current_pose = planner_data_->self_odometry->pose.pose; - const Pose goal_pose = modified_goal_pose_ ? modified_goal_pose_->goal_pose - : planner_data_->route_handler->getGoalPose(); - return calcDistance2d(current_pose, goal_pose) < parameters_->th_arrived_distance; + return calcDistance2d(current_pose, modified_goal_pose_->goal_pose) < + parameters_->th_arrived_distance; } bool GoalPlannerModule::hasFinishedGoalPlanner() { - return isOnGoal() && isStopped(); + return isOnModifiedGoal() && isStopped(); } TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const @@ -1516,7 +1519,7 @@ bool GoalPlannerModule::checkOriginalGoalIsInShoulder() const bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const { - return !isOnGoal() && hasEnoughTimePassedSincePathUpdate(path_update_duration); + return !isOnModifiedGoal() && hasEnoughTimePassedSincePathUpdate(path_update_duration); } bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const From f78ee7d1e4e39b0507d8991394271f375f0c52e8 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 2 Aug 2023 06:56:30 +0900 Subject: [PATCH 068/266] feat(out_of_lane): add param for the min confidence of a predicted path (#4217) Signed-off-by: Maxime CLEMENT --- .../behavior_velocity_out_of_lane_module/README.md | 11 ++++++----- .../config/out_of_lane.param.yaml | 1 + .../src/decisions.cpp | 10 ++++++---- .../src/decisions.hpp | 10 ++++++---- .../src/manager.cpp | 2 ++ .../src/types.hpp | 1 + 6 files changed, 22 insertions(+), 13 deletions(-) diff --git a/planning/behavior_velocity_out_of_lane_module/README.md b/planning/behavior_velocity_out_of_lane_module/README.md index a3089cbc1fde3..da46055460a99 100644 --- a/planning/behavior_velocity_out_of_lane_module/README.md +++ b/planning/behavior_velocity_out_of_lane_module/README.md @@ -101,7 +101,7 @@ at its current velocity or at half the velocity of the path points, whichever is ###### Dynamic objects Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted path of the dynamic object is used. +If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. #### 5. Path update @@ -138,10 +138,11 @@ Moreover, parameter `action.distance_buffer` adds an extra distance between the | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| --------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] consider objects with an estimated time to collision bellow this value while on the overlap | -| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | +| Parameter /objects | Type | Description | +| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] consider objects with an estimated time to collision bellow this value while on the overlap | +| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | | Parameter /overlap | Type | Description | | ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | diff --git a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml index c501599b4ae1c..dd4c1c610261c 100644 --- a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -16,6 +16,7 @@ minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored use_predicted_paths: true # if true, use the predicted paths to estimate future positions. # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. + predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp index a164a03a9aa43..0fdd153b17530 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp @@ -42,7 +42,7 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx) std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const rclcpp::Logger & logger) + const double min_confidence, const rclcpp::Logger & logger) { const auto max_deviation = object.shape.dimensions.y * 2.0; @@ -50,6 +50,7 @@ std::optional> object_time_to_range( auto worst_exit_time = std::optional(); for (const auto & predicted_path : object.kinematics.predicted_paths) { + if (predicted_path.confidence < min_confidence) continue; const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); const auto enter_point = geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); @@ -274,9 +275,10 @@ bool should_not_enter( continue; // skip objects with velocity bellow a threshold } // skip objects that are already on the interval - const auto enter_exit_time = params.objects_use_predicted_paths - ? object_time_to_range(object, range, logger) - : object_time_to_range(object, range, inputs, logger); + const auto enter_exit_time = + params.objects_use_predicted_paths + ? object_time_to_range(object, range, params.objects_min_confidence, logger) + : object_time_to_range(object, range, inputs, logger); if (!enter_exit_time) { RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); continue; // skip objects that are not driving towards the overlapping range diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp index 6af03bc53ea3c..da183133e7728 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp @@ -56,22 +56,24 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx); /// but may not exist (e.g,, predicted path ends before reaching the end of the range) /// @param [in] object dynamic object /// @param [in] range overlapping range +/// @param [in] min_confidence minimum confidence to consider a predicted path +/// @param [in] logger ros logger /// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in /// the opposite direction, time at enter > time at exit std::optional> object_time_to_range( - const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range); + const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, + const double min_confidence, const rclcpp::Logger & logger); /// @brief use the lanelet map to estimate the times when an object will reach the enter and exit /// points of an overlapping range /// @param [in] object dynamic object /// @param [in] range overlapping range /// @param [in] lanelets objects to consider -/// @param [in] route_handler route handler used to estimate the path of the dynamic object +/// @param [in] logger ros logger /// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in /// the opposite direction, time at enter > time at exit. std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const lanelet::ConstLanelets & lanelets, - const std::shared_ptr & route_handler); + const DecisionInputs & inputs, const rclcpp::Logger & logger); /// @brief decide whether an object is coming in the range at the same time as ego /// @details the condition depends on the mode (threshold, intervals, ttc) /// @param [in] range_times times when ego and the object enter/exit the range diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp index 1eccd8773cc92..22fb29110466a 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp @@ -44,6 +44,8 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node) pp.objects_min_vel = node.declare_parameter(ns + ".objects.minimum_velocity"); pp.objects_use_predicted_paths = node.declare_parameter(ns + ".objects.use_predicted_paths"); + pp.objects_min_confidence = + node.declare_parameter(ns + ".objects.predicted_path_min_confidence"); pp.overlap_min_dist = node.declare_parameter(ns + ".overlap.minimum_distance"); pp.overlap_extra_length = node.declare_parameter(ns + ".overlap.extra_length"); diff --git a/planning/behavior_velocity_out_of_lane_module/src/types.hpp b/planning/behavior_velocity_out_of_lane_module/src/types.hpp index e4ba8fbfead81..85266d779f34e 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/types.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/types.hpp @@ -45,6 +45,7 @@ struct PlannerParam bool objects_use_predicted_paths; // # whether to use the objects' predicted paths double objects_min_vel; // # [m/s] objects lower than this velocity will be ignored + double objects_min_confidence; // # minimum confidence to consider a predicted path double overlap_extra_length; // [m] extra length to add around an overlap range double overlap_min_dist; // [m] min distance inside another lane to consider an overlap From 62fcd11727e20eabda9cd4ea331d7b0c2a042925 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 2 Aug 2023 08:41:54 +0900 Subject: [PATCH 069/266] fix(start_planner): fix extending lanes in lane change case (#4491) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/utils.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 55beafa8a3ea1..5a2f450f0eb0d 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2938,13 +2938,11 @@ lanelet::ConstLanelets getExtendedCurrentLanes( } while (forward_length_sum < forward_length) { - // stop extending if the goal lane is included + // stop extending when the goal route section is reached // if forward_length is a very large value, set it to true, // as it may continue to extend lanes outside the route ahead of goal forever. if (until_goal_lane) { - lanelet::ConstLanelet goal_lane; - planner_data->route_handler->getGoalLanelet(&goal_lane); - if (lanes.back().id() == goal_lane.id()) { + if (planner_data->route_handler->isInGoalRouteSection(lanes.back())) { return lanes; } } From 07acbd7357c2ff7ea6b6971df711cc42b3074cd2 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 2 Aug 2023 09:12:58 +0900 Subject: [PATCH 070/266] ci: enable spell-check-partial for control (#4483) Signed-off-by: kminoda --- .cspell-partial.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index ae52fee5614b0..e7b32ed3ae53f 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -1,5 +1,5 @@ { - "ignorePaths": ["**/control/**", "**/perception/**", "**/planning/**", "**/sensing/**"], + "ignorePaths": ["**/perception/**", "**/planning/**", "**/sensing/**"], "ignoreRegExpList": [], "words": [] } From 0becdc64eeb56143190227be8c290a313f30bba3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 2 Aug 2023 09:36:40 +0900 Subject: [PATCH 071/266] feat(crosswalk): suppress chattering of GO/STOP decision (#4471) * feat(crosswalk): organize the code Signed-off-by: Takayuki Murooka * suppress chattering Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 2 + .../src/manager.cpp | 4 + .../src/scene_crosswalk.cpp | 122 ++++++++---------- .../src/scene_crosswalk.hpp | 97 ++++++++++---- 4 files changed, 135 insertions(+), 90 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 097b2c6c94aef..11184eedf4aaf 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -37,7 +37,9 @@ # param for pass judge logic pass_judge: ego_pass_first_margin: 6.0 # [s] time margin for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering ego_pass_later_margin: 10.0 # [s] time margin for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) + ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index d287787006aff..400c3333412f5 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -73,8 +73,12 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) // param for pass judge logic cp.ego_pass_first_margin = node.declare_parameter(ns + ".pass_judge.ego_pass_first_margin"); + cp.ego_pass_first_additional_margin = + node.declare_parameter(ns + ".pass_judge.ego_pass_first_additional_margin"); cp.ego_pass_later_margin = node.declare_parameter(ns + ".pass_judge.ego_pass_later_margin"); + cp.ego_pass_later_additional_margin = + node.declare_parameter(ns + ".pass_judge.ego_pass_later_additional_margin"); cp.stop_object_velocity = node.declare_parameter(ns + ".pass_judge.stop_object_velocity_threshold"); cp.min_object_velocity = node.declare_parameter(ns + ".pass_judge.min_object_velocity"); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index d45004324e1b2..1265c13ab1871 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -297,7 +297,6 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const std::optional & default_stop_pose) { const auto & ego_pos = planner_data_->current_odometry->pose.position; - const auto & objects_ptr = planner_data_->predicted_objects; const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line->first) + p_stop_line->second; @@ -309,45 +308,30 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const auto attention_area = getAttentionArea(sparse_resample_path, crosswalk_attention_range); // Update object state - updateObjectState(dist_ego_to_stop); + updateObjectState( + dist_ego_to_stop, sparse_resample_path, crosswalk_attention_range, attention_area); // Check pedestrian for stop // NOTE: first stop point and its minimum distance from ego to stop std::optional> nearest_stop_info; std::vector stop_factor_points; - const auto ignore_crosswalk = debug_data_.ignore_crosswalk = isRedSignalForPedestrians(); - for (const auto & object : objects_ptr->objects) { - const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; - const auto obj_uuid = toHexString(object.object_id); - - if (!isCrosswalkUserType(object)) { - continue; - } - - if (ignore_crosswalk) { - continue; - } - - // NOTE: Collision points are calculated on each predicted path - const auto collision_point = - getCollisionPoints(sparse_resample_path, object, attention_area, crosswalk_attention_range); - - for (const auto & cp : collision_point) { - const auto collision_state = - getCollisionState(obj_uuid, cp.time_to_collision, cp.time_to_vehicle); - debug_data_.collision_points.push_back(std::make_pair(cp, collision_state)); - + for (const auto & object : object_info_manager_.getObject()) { + const auto & collision_point = object.collision_point; + if (collision_point) { + const auto & collision_state = object.collision_state; if (collision_state != CollisionState::YIELD) { continue; } - stop_factor_points.push_back(obj_pos); + stop_factor_points.push_back(object.position); const auto dist_ego2cp = - calcSignedArcLength(sparse_resample_path.points, ego_pos, cp.collision_point) - + calcSignedArcLength( + sparse_resample_path.points, ego_pos, collision_point->collision_point) - planner_param_.stop_distance_from_object; if (!nearest_stop_info || dist_ego2cp - base_link2front < nearest_stop_info->second) { - nearest_stop_info = std::make_pair(cp.collision_point, dist_ego2cp - base_link2front); + nearest_stop_info = + std::make_pair(collision_point->collision_point, dist_ego2cp - base_link2front); } } } @@ -560,9 +544,9 @@ std::pair CrosswalkModule::clampAttentionRangeByNeighborCrosswal return std::make_pair(clamped_near_attention_range, clamped_far_attention_range); } -std::vector CrosswalkModule::getCollisionPoints( - const PathWithLaneId & ego_path, const PredictedObject & object, const Polygon2d & attention_area, - const std::pair & crosswalk_attention_range) +std::optional CrosswalkModule::getCollisionPoint( + const PathWithLaneId & ego_path, const PredictedObject & object, + const std::pair & crosswalk_attention_range, const Polygon2d & attention_area) { stop_watch_.tic(__func__); @@ -576,6 +560,8 @@ std::vector CrosswalkModule::getCollisionPoints( const auto obj_polygon = createObjectPolygon(object.shape.dimensions.x, object.shape.dimensions.y); + double minimum_stop_dist = std::numeric_limits::max(); + std::optional nearest_collision_point{std::nullopt}; for (const auto & obj_path : object.kinematics.predicted_paths) { for (size_t i = 0; i < obj_path.path.size() - 1; ++i) { const auto & p_obj_front = obj_path.path.at(i); @@ -588,26 +574,26 @@ std::vector CrosswalkModule::getCollisionPoints( continue; } - // Calculate nearest collision point - double minimum_stop_dist = std::numeric_limits::max(); - geometry_msgs::msg::Point nearest_collision_point{}; + // Calculate nearest collision point among collisions with a predicted path + double local_minimum_stop_dist = std::numeric_limits::max(); + geometry_msgs::msg::Point local_nearest_collision_point{}; for (const auto & p : tmp_intersection) { const auto cp = createPoint(p.x(), p.y(), ego_pos.z); const auto dist_ego2cp = calcSignedArcLength(ego_path.points, ego_pos, cp); - if (dist_ego2cp < minimum_stop_dist) { - minimum_stop_dist = dist_ego2cp; - nearest_collision_point = cp; + if (dist_ego2cp < local_minimum_stop_dist) { + local_minimum_stop_dist = dist_ego2cp; + local_nearest_collision_point = cp; } } const auto dist_ego2cp = - calcSignedArcLength(ego_path.points, ego_pos, nearest_collision_point); + calcSignedArcLength(ego_path.points, ego_pos, local_nearest_collision_point); constexpr double eps = 1e-3; const auto dist_obj2cp = calcArcLength(obj_path.path) < eps ? 0.0 - : calcSignedArcLength(obj_path.path, size_t(0), nearest_collision_point); + : calcSignedArcLength(obj_path.path, size_t(0), local_nearest_collision_point); if ( dist_ego2cp < crosswalk_attention_range.first || @@ -615,10 +601,13 @@ std::vector CrosswalkModule::getCollisionPoints( continue; } - ret.push_back( - createCollisionPoint(nearest_collision_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel)); - - debug_data_.obj_polygons.push_back(toGeometryPointVector(obj_one_step_polygon, ego_pos.z)); + // Calculate nearest collision point among predicted paths + if (dist_ego2cp < minimum_stop_dist) { + minimum_stop_dist = dist_ego2cp; + nearest_collision_point = createCollisionPoint( + local_nearest_collision_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel); + debug_data_.obj_polygons.push_back(toGeometryPointVector(obj_one_step_polygon, ego_pos.z)); + } break; } @@ -628,7 +617,7 @@ std::vector CrosswalkModule::getCollisionPoints( logger_, planner_param_.show_processing_time, "%s : %f ms", __func__, stop_watch_.toc(__func__, true)); - return ret; + return nearest_collision_point; } CollisionPoint CrosswalkModule::createCollisionPoint( @@ -653,25 +642,6 @@ CollisionPoint CrosswalkModule::createCollisionPoint( return collision_point; } -CollisionState CrosswalkModule::getCollisionState( - const std::string & obj_uuid, const double ttc, const double ttv) const -{ - // First, check if the object can be ignored - const auto obj_state = object_info_manager_.getState(obj_uuid); - if (obj_state == ObjectInfo::State::FULLY_STOPPED) { - return CollisionState::IGNORE; - } - - // Compare time to collision and vehicle - if (ttc + planner_param_.ego_pass_first_margin < ttv) { - return CollisionState::EGO_PASS_FIRST; - } - if (ttv + planner_param_.ego_pass_later_margin < ttc) { - return CollisionState::EGO_PASS_LATER; - } - return CollisionState::YIELD; -} - void CrosswalkModule::applySafetySlowDownSpeed( PathWithLaneId & output, const std::vector & path_intersects) { @@ -854,7 +824,9 @@ std::optional CrosswalkModule::getNearestStopFactor( return {}; } -void CrosswalkModule::updateObjectState(const double dist_ego_to_stop) +void CrosswalkModule::updateObjectState( + const double dist_ego_to_stop, const PathWithLaneId & sparse_resample_path, + const std::pair & crosswalk_attention_range, const Polygon2d & attention_area) { const auto & objects_ptr = planner_data_->predicted_objects; @@ -870,14 +842,34 @@ void CrosswalkModule::updateObjectState(const double dist_ego_to_stop) has_reached_stop_point; }(); + const auto ignore_crosswalk = isRedSignalForPedestrians(); + debug_data_.ignore_crosswalk = ignore_crosswalk; + // Update object state object_info_manager_.init(); for (const auto & object : objects_ptr->objects) { const auto obj_uuid = toHexString(object.object_id); + const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; + + // calculate collision point and state + if (!isCrosswalkUserType(object)) { + continue; + } + if (ignore_crosswalk) { + continue; + } + + const auto collision_point = + getCollisionPoint(sparse_resample_path, object, crosswalk_attention_range, attention_area); object_info_manager_.update( - obj_uuid, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, has_traffic_light, - planner_param_); + obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, + has_traffic_light, collision_point, planner_param_); + + if (collision_point) { + const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); + debug_data_.collision_points.push_back(std::make_pair(*collision_point, collision_state)); + } } object_info_manager_.finalize(); } diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 957fa9540f2f5..df396b987da58 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -81,7 +81,9 @@ class CrosswalkModule : public SceneModuleInterface double min_jerk_for_stuck_vehicle; // param for pass judge logic double ego_pass_first_margin; + double ego_pass_first_additional_margin; double ego_pass_later_margin; + double ego_pass_later_additional_margin; double stop_object_velocity; double min_object_velocity; bool disable_stop_for_yield_cancel; @@ -100,19 +102,22 @@ class CrosswalkModule : public SceneModuleInterface struct ObjectInfo { - // NOTE: FULLY_STOPPED means stopped object which can be ignored. - enum class State { STOPPED = 0, FULLY_STOPPED, OTHER }; - State state; + CollisionState collision_state{}; std::optional time_to_start_stopped{std::nullopt}; - void updateState( - const rclcpp::Time & now, const double obj_vel, const bool is_ego_yielding, - const bool has_traffic_light, const PlannerParam & planner_param) + geometry_msgs::msg::Point position{}; + std::optional collision_point{}; + + void transitState( + const rclcpp::Time & now, const double vel, const bool is_ego_yielding, + const bool has_traffic_light, const std::optional & collision_point, + const PlannerParam & planner_param) { - const bool is_stopped = obj_vel < planner_param.stop_object_velocity; + const bool is_stopped = vel < planner_param.stop_object_velocity; + // Check if the object can be ignored if (is_stopped) { - if (state == State::FULLY_STOPPED) { + if (collision_state == CollisionState::IGNORE) { return; } @@ -124,14 +129,41 @@ class CrosswalkModule : public SceneModuleInterface if ( (is_ego_yielding || (has_traffic_light && planner_param.disable_stop_for_yield_cancel)) && !intent_to_cross) { - state = State::FULLY_STOPPED; - } else { - // NOTE: Object may start moving - state = State::STOPPED; + collision_state = CollisionState::IGNORE; + return; } } else { time_to_start_stopped = std::nullopt; - state = State::OTHER; + } + + // Compare time to collision and vehicle + if (collision_point) { + // Check if ego will pass first + const double ego_pass_first_additional_margin = + collision_state == CollisionState::EGO_PASS_FIRST + ? 0.0 + : planner_param.ego_pass_first_additional_margin; + if ( + collision_point->time_to_collision + planner_param.ego_pass_first_margin + + ego_pass_first_additional_margin < + collision_point->time_to_vehicle) { + collision_state = CollisionState::EGO_PASS_FIRST; + return; + } + // Check if ego will pass later + const double ego_pass_later_additional_margin = + collision_state == CollisionState::EGO_PASS_LATER + ? 0.0 + : planner_param.ego_pass_later_additional_margin; + if ( + collision_point->time_to_vehicle + planner_param.ego_pass_later_margin + + ego_pass_later_additional_margin < + collision_point->time_to_collision) { + collision_state = CollisionState::EGO_PASS_LATER; + return; + } + collision_state = CollisionState::YIELD; + return; } } }; @@ -139,8 +171,9 @@ class CrosswalkModule : public SceneModuleInterface { void init() { current_uuids_.clear(); } void update( - const std::string & uuid, const double obj_vel, const rclcpp::Time & now, - const bool is_ego_yielding, const bool has_traffic_light, const PlannerParam & planner_param) + const std::string & uuid, const geometry_msgs::msg::Point & position, const double vel, + const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light, + const std::optional & collision_point, const PlannerParam & planner_param) { // update current uuids current_uuids_.push_back(uuid); @@ -150,14 +183,17 @@ class CrosswalkModule : public SceneModuleInterface if ( has_traffic_light && planner_param.disable_stop_for_yield_cancel && planner_param.disable_yield_for_new_stopped_object) { - objects.emplace(uuid, ObjectInfo{ObjectInfo::State::FULLY_STOPPED}); + objects.emplace(uuid, ObjectInfo{CollisionState::IGNORE}); } else { - objects.emplace(uuid, ObjectInfo{ObjectInfo::State::OTHER}); + objects.emplace(uuid, ObjectInfo{CollisionState::YIELD}); } } // update object state - objects.at(uuid).updateState(now, obj_vel, is_ego_yielding, has_traffic_light, planner_param); + objects.at(uuid).transitState( + now, vel, is_ego_yielding, has_traffic_light, collision_point, planner_param); + objects.at(uuid).collision_point = collision_point; + objects.at(uuid).position = position; } void finalize() { @@ -174,7 +210,19 @@ class CrosswalkModule : public SceneModuleInterface objects.erase(obsolete_uuid); } } - ObjectInfo::State getState(const std::string & uuid) const { return objects.at(uuid).state; } + + std::vector getObject() const + { + std::vector object_info_vec; + for (auto object : objects) { + object_info_vec.push_back(object.second); + } + return object_info_vec; + } + CollisionState getCollisionState(const std::string & uuid) const + { + return objects.at(uuid).collision_state; + } std::unordered_map objects; std::vector current_uuids_; @@ -210,9 +258,9 @@ class CrosswalkModule : public SceneModuleInterface const std::vector & path_intersects, const std::optional & stop_pose) const; - std::vector getCollisionPoints( + std::optional getCollisionPoint( const PathWithLaneId & ego_path, const PredictedObject & object, - const Polygon2d & attention_area, const std::pair & crosswalk_attention_range); + const std::pair & crosswalk_attention_range, const Polygon2d & attention_area); std::optional getNearestStopFactor( const PathWithLaneId & ego_path, @@ -243,9 +291,6 @@ class CrosswalkModule : public SceneModuleInterface const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel, const geometry_msgs::msg::Vector3 & obj_vel) const; - CollisionState getCollisionState( - const std::string & obj_uuid, const double ttc, const double ttv) const; - float calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const; @@ -257,7 +302,9 @@ class CrosswalkModule : public SceneModuleInterface const PathWithLaneId & ego_path, const std::vector & objects, const std::vector & path_intersects) const; - void updateObjectState(const double dist_ego_to_stop); + void updateObjectState( + const double dist_ego_to_stop, const PathWithLaneId & sparse_resample_path, + const std::pair & crosswalk_attention_range, const Polygon2d & attention_area); bool isRedSignalForPedestrians() const; From d16b8875bea884fb840a9296cc4e5365f3f00bcf Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 2 Aug 2023 10:58:41 +0900 Subject: [PATCH 072/266] fix(behavior_path_planner): search duplicated lane id with remove_if (#4271) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/src/utils/utils.cpp | 29 ++++++++++--------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 5a2f450f0eb0d..452277d50f60f 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1268,18 +1268,17 @@ boost::optional getOverlappedLaneletId(const std::vector std::vector cutOverlappedLanes( PathWithLaneId & path, const std::vector & lanes) { - const auto overlapped_lanelet_id = getOverlappedLaneletId(lanes); - if (!overlapped_lanelet_id) { + const auto overlapped_lanelet_idx = getOverlappedLaneletId(lanes); + if (!overlapped_lanelet_idx) { return lanes; } - const std::vector shorten_lanes{ - lanes.begin(), lanes.begin() + *overlapped_lanelet_id}; + std::vector shorten_lanes{lanes.begin(), lanes.begin() + *overlapped_lanelet_idx}; const auto shorten_lanelets = utils::transformToLanelets(shorten_lanes); // create removed lanelets std::vector removed_lane_ids; - for (size_t i = *overlapped_lanelet_id; i < lanes.size(); ++i) { + for (size_t i = *overlapped_lanelet_idx; i < lanes.size(); ++i) { const auto target_lanelets = utils::transformToLanelets(lanes.at(i)); for (const auto & target_lanelet : target_lanelets) { // if target lane is inside of the shorten lanelets, we do not remove it @@ -1290,18 +1289,22 @@ std::vector cutOverlappedLanes( } } - for (size_t i = 0; i < path.points.size(); ++i) { - const auto & lane_ids = path.points.at(i).lane_ids; + const auto is_same_lane_id = [&removed_lane_ids](const auto & point) { + const auto & lane_ids = point.lane_ids; for (const auto & lane_id : lane_ids) { - if ( - std::find(removed_lane_ids.begin(), removed_lane_ids.end(), lane_id) != - removed_lane_ids.end()) { - path.points.erase(path.points.begin() + i, path.points.end()); - return shorten_lanes; + const auto is_same_id = [&lane_id](const auto id) { return lane_id == id; }; + + if (std::any_of(removed_lane_ids.begin(), removed_lane_ids.end(), is_same_id)) { + return true; } } - } + return false; + }; + + const auto points_with_overlapped_id = + std::remove_if(path.points.begin(), path.points.end(), is_same_lane_id); + path.points.erase(points_with_overlapped_id, path.points.end()); return shorten_lanes; } From 592a6b21f426cfc651f451a074595193298b2bec Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 2 Aug 2023 11:36:25 +0900 Subject: [PATCH 073/266] feat(crosswalk): add pass judge line (#4492) * feat(crosswalk): add pass judge line Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 1 + .../behavior_velocity_crosswalk_module/src/manager.cpp | 2 ++ .../src/scene_crosswalk.cpp | 10 ++++++++++ .../src/scene_crosswalk.hpp | 1 + 4 files changed, 14 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 11184eedf4aaf..b0e198be68ef6 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -40,6 +40,7 @@ ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering ego_pass_later_margin: 10.0 # [s] time margin for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering + max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 400c3333412f5..72cc1970fb192 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -79,6 +79,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) node.declare_parameter(ns + ".pass_judge.ego_pass_later_margin"); cp.ego_pass_later_additional_margin = node.declare_parameter(ns + ".pass_judge.ego_pass_later_additional_margin"); + cp.max_offset_to_crosswalk_for_yield = + node.declare_parameter(ns + ".pass_judge.max_offset_to_crosswalk_for_yield"); cp.stop_object_velocity = node.declare_parameter(ns + ".pass_judge.stop_object_velocity_threshold"); cp.min_object_velocity = node.declare_parameter(ns + ".pass_judge.min_object_velocity"); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 1265c13ab1871..fd3b0d76107cb 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -311,6 +311,16 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( updateObjectState( dist_ego_to_stop, sparse_resample_path, crosswalk_attention_range, attention_area); + // Check if ego moves forward enough to ignore yield. + if (!path_intersects.empty()) { + const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const double dist_ego2crosswalk = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); + if (dist_ego2crosswalk - base_link2front < planner_param_.max_offset_to_crosswalk_for_yield) { + return {}; + } + } + // Check pedestrian for stop // NOTE: first stop point and its minimum distance from ego to stop std::optional> nearest_stop_info; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index df396b987da58..9562ae2520fd6 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -84,6 +84,7 @@ class CrosswalkModule : public SceneModuleInterface double ego_pass_first_additional_margin; double ego_pass_later_margin; double ego_pass_later_additional_margin; + double max_offset_to_crosswalk_for_yield; double stop_object_velocity; double min_object_velocity; bool disable_stop_for_yield_cancel; From 7e893e8618ded1a9a5df7322c1d2b7bf1aeab5eb Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Wed, 2 Aug 2023 11:53:20 +0900 Subject: [PATCH 074/266] refactor(lane_change): create new helper functions to clean code (#4495) --- .../utils/lane_change/utils.hpp | 8 ++++++-- .../src/scene_module/lane_change/normal.cpp | 14 +++----------- .../src/utils/lane_change/utils.cpp | 19 +++++++++++++++++-- 3 files changed, 26 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index 26163bcfd8058..e885313be3e81 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -76,8 +76,8 @@ std::vector replaceWithSortedIds( const std::vector> & sorted_lane_ids); std::vector> getSortedLaneIds( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const double rough_shift_length); + const RouteHandler & route_handler, const Pose & current_pose, + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes); PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWithLaneId & path2); @@ -90,6 +90,10 @@ lanelet::ConstLanelets getTargetNeighborLanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const LaneChangeModuleType & type); +lanelet::BasicPolygon2d getTargetNeighborLanesPolygon( + const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, + const LaneChangeModuleType & type); + bool isPathInLanelets( const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 7ce71a342de2b..360d12a753625 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -679,21 +679,13 @@ bool NormalLaneChange::getLaneChangePaths( const auto dist_to_end_of_current_lanes = utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); - const auto arc_position_from_target = - lanelet::utils::getArcCoordinates(target_lanes, getEgoPose()); - const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes); - const auto sorted_lane_ids = utils::lane_change::getSortedLaneIds( - route_handler, current_lanes, target_lanes, arc_position_from_target.distance); - - const auto target_neighbor_lanelets = - utils::lane_change::getTargetNeighborLanes(route_handler, current_lanes, type_); + const auto sorted_lane_ids = + utils::lane_change::getSortedLaneIds(route_handler, getEgoPose(), current_lanes, target_lanes); - const auto target_neighbor_preferred_lane_poly = lanelet::utils::getPolygonFromArcLength( - target_neighbor_lanelets, 0, std::numeric_limits::max()); const auto target_neighbor_preferred_lane_poly_2d = - lanelet::utils::to2D(target_neighbor_preferred_lane_poly).basicPolygon(); + utils::lane_change::getTargetNeighborLanesPolygon(route_handler, current_lanes, type_); const auto target_objects = getTargetObjects(current_lanes, target_lanes); diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 90f108267055a..21bd524d8af02 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -203,6 +203,18 @@ lanelet::ConstLanelets getTargetNeighborLanes( return neighbor_lanes; } +lanelet::BasicPolygon2d getTargetNeighborLanesPolygon( + const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, + const LaneChangeModuleType & type) +{ + const auto target_neighbor_lanelets = + utils::lane_change::getTargetNeighborLanes(route_handler, current_lanes, type); + const auto target_neighbor_preferred_lane_poly = lanelet::utils::getPolygonFromArcLength( + target_neighbor_lanelets, 0, std::numeric_limits::max()); + + return lanelet::utils::to2D(target_neighbor_preferred_lane_poly).basicPolygon(); +} + bool isPathInLanelets( const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) @@ -640,9 +652,12 @@ std::string getStrDirection(const std::string & name, const Direction direction) } std::vector> getSortedLaneIds( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const double rough_shift_length) + const RouteHandler & route_handler, const Pose & current_pose, + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) { + const auto rough_shift_length = + lanelet::utils::getArcCoordinates(target_lanes, current_pose).distance; + std::vector> sorted_lane_ids{}; sorted_lane_ids.reserve(target_lanes.size()); const auto get_sorted_lane_ids = [&](const lanelet::ConstLanelet & target_lane) { From 9db024effa5b9cd77a19e7500bd9a410d68125e8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 2 Aug 2023 14:19:50 +0900 Subject: [PATCH 075/266] feat(crosswalk): gradable pass margin (#4494) * feat(crosswalk): gradable pass margin Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 6 ++-- .../src/manager.cpp | 12 ++++--- .../src/scene_crosswalk.hpp | 35 ++++++++++++++++--- 3 files changed, 43 insertions(+), 10 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index b0e198be68ef6..4b0a1ffc4317b 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -36,9 +36,11 @@ # param for pass judge logic pass_judge: - ego_pass_first_margin: 6.0 # [s] time margin for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_first_margin_x: [0.0] # [[s]] time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_first_margin_y: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering - ego_pass_later_margin: 10.0 # [s] time margin for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) + ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) + ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 72cc1970fb192..992d1c48eb9f4 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -71,12 +71,16 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) cp.min_jerk_for_stuck_vehicle = node.declare_parameter(ns + ".stuck_vehicle.min_jerk"); // param for pass judge logic - cp.ego_pass_first_margin = - node.declare_parameter(ns + ".pass_judge.ego_pass_first_margin"); + cp.ego_pass_first_margin_x = + node.declare_parameter>(ns + ".pass_judge.ego_pass_first_margin_x"); + cp.ego_pass_first_margin_y = + node.declare_parameter>(ns + ".pass_judge.ego_pass_first_margin_y"); cp.ego_pass_first_additional_margin = node.declare_parameter(ns + ".pass_judge.ego_pass_first_additional_margin"); - cp.ego_pass_later_margin = - node.declare_parameter(ns + ".pass_judge.ego_pass_later_margin"); + cp.ego_pass_later_margin_x = + node.declare_parameter>(ns + ".pass_judge.ego_pass_later_margin_x"); + cp.ego_pass_later_margin_y = + node.declare_parameter>(ns + ".pass_judge.ego_pass_later_margin_y"); cp.ego_pass_later_additional_margin = node.declare_parameter(ns + ".pass_judge.ego_pass_later_additional_margin"); cp.max_offset_to_crosswalk_for_yield = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 9562ae2520fd6..7ac00ab880be8 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -56,6 +56,24 @@ using tier4_api_msgs::msg::CrosswalkStatus; using tier4_autoware_utils::Polygon2d; using tier4_autoware_utils::StopWatch; +namespace +{ +double interpolateEgoPassMargin( + const std::vector & x_vec, const std::vector & y_vec, const double target_x) +{ + for (size_t i = 0; i < x_vec.size(); ++i) { + if (target_x < x_vec.at(i)) { + if (i == 0) { + return y_vec.at(i); + } + const double ratio = (target_x - x_vec.at(i - 1)) / (x_vec.at(i) - x_vec.at(i - 1)); + return y_vec.at(i - 1) + ratio * (y_vec.at(i) - y_vec.at(i - 1)); + } + } + return y_vec.back(); +} +} // namespace + class CrosswalkModule : public SceneModuleInterface { public: @@ -80,9 +98,11 @@ class CrosswalkModule : public SceneModuleInterface double max_jerk_for_stuck_vehicle; double min_jerk_for_stuck_vehicle; // param for pass judge logic - double ego_pass_first_margin; + std::vector ego_pass_first_margin_x; + std::vector ego_pass_first_margin_y; double ego_pass_first_additional_margin; - double ego_pass_later_margin; + std::vector ego_pass_later_margin_x; + std::vector ego_pass_later_margin_y; double ego_pass_later_additional_margin; double max_offset_to_crosswalk_for_yield; double stop_object_velocity; @@ -144,20 +164,27 @@ class CrosswalkModule : public SceneModuleInterface collision_state == CollisionState::EGO_PASS_FIRST ? 0.0 : planner_param.ego_pass_first_additional_margin; + const double ego_pass_first_margin = interpolateEgoPassMargin( + planner_param.ego_pass_first_margin_x, planner_param.ego_pass_first_margin_y, + collision_point->time_to_collision); if ( - collision_point->time_to_collision + planner_param.ego_pass_first_margin + + collision_point->time_to_collision + ego_pass_first_margin + ego_pass_first_additional_margin < collision_point->time_to_vehicle) { collision_state = CollisionState::EGO_PASS_FIRST; return; } + // Check if ego will pass later const double ego_pass_later_additional_margin = collision_state == CollisionState::EGO_PASS_LATER ? 0.0 : planner_param.ego_pass_later_additional_margin; + const double ego_pass_later_margin = interpolateEgoPassMargin( + planner_param.ego_pass_later_margin_x, planner_param.ego_pass_later_margin_y, + collision_point->time_to_vehicle); if ( - collision_point->time_to_vehicle + planner_param.ego_pass_later_margin + + collision_point->time_to_vehicle + ego_pass_later_margin + ego_pass_later_additional_margin < collision_point->time_to_collision) { collision_state = CollisionState::EGO_PASS_LATER; From 2f20151cb63e58927a2f748c11d95346c7319e8c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 2 Aug 2023 14:23:49 +0900 Subject: [PATCH 076/266] chore(tier4_planning_launch): enable to abort lane change from a parameter file (#4469) Signed-off-by: Fumiya Watanabe --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index fc1fac04b9415..fc1b55ee52eac 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -102,9 +102,6 @@ def launch_setup(context, *args, **kwargs): behavior_path_planner_param, vehicle_param, { - "lane_change.cancel.enable_on_lane_changing_phase": LaunchConfiguration( - "use_experimental_lane_change_function" - ), "lane_change.enable_collision_check_at_prepare_phase": LaunchConfiguration( "use_experimental_lane_change_function" ), From 9c4a042d733e91622407beea5e02c63fb76c4998 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 2 Aug 2023 14:25:45 +0900 Subject: [PATCH 077/266] fix(start_planner): execute when curent pose is close to route start pose not receiving new route (#4453) Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.hpp | 1 - .../start_planner/start_planner_module.cpp | 26 +++++++++++-------- .../include/route_handler/route_handler.hpp | 1 + planning/route_handler/src/route_handler.cpp | 9 +++++++ 4 files changed, 25 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 9d91cdbe3783e..0a44db1055cac 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -118,7 +118,6 @@ class StartPlannerModule : public SceneModuleInterface std::unique_ptr last_route_received_time_; std::unique_ptr last_pull_out_start_update_time_; std::unique_ptr last_approved_pose_; - mutable bool has_received_new_route_{false}; std::shared_ptr getCurrentPlanner() const; PathWithLaneId getFullPath() const; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index e64feacf6ba9d..51106847ed651 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -78,27 +78,27 @@ void StartPlannerModule::processOnExit() bool StartPlannerModule::isExecutionRequested() const { + // Execute when current pose is near route start pose + const Pose & start_pose = planner_data_->route_handler->getStartPose(); + const Pose & current_pose = planner_data_->self_odometry->pose.pose; + if ( + tier4_autoware_utils::calcDistance2d(start_pose.position, current_pose.position) > + parameters_->th_arrived_distance) { + return false; + } + // Check if ego arrives at goal const Pose & goal_pose = planner_data_->route_handler->getGoalPose(); - const Pose & current_pose = planner_data_->self_odometry->pose.pose; if ( tier4_autoware_utils::calcDistance2d(goal_pose.position, current_pose.position) < parameters_->th_arrived_distance) { return false; } - has_received_new_route_ = - !planner_data_->prev_route_id || - *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); - if (current_state_ == ModuleStatus::RUNNING) { return true; } - if (!has_received_new_route_) { - return false; - } - const bool is_stopped = utils::l2Norm(planner_data_->self_odometry->twist.twist.linear) < parameters_->th_stopped_velocity; if (!is_stopped) { @@ -565,13 +565,17 @@ std::vector StartPlannerModule::generateDrivableLanes( void StartPlannerModule::updatePullOutStatus() { - if (has_received_new_route_) { + const bool has_received_new_route = + !planner_data_->prev_route_id || + *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); + + if (has_received_new_route) { status_ = PullOutStatus(); } // skip updating if enough time has not passed for preventing chattering between back and // start_planner - if (!has_received_new_route_ && !last_pull_out_start_update_time_ && !status_.back_finished) { + if (!has_received_new_route && !last_pull_out_start_update_time_ && !status_.back_finished) { if (!last_pull_out_start_update_time_) { last_pull_out_start_update_time_ = std::make_unique(clock_->now()); } diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index c60c0e431108e..3c3ddbc1acaf2 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -96,6 +96,7 @@ class RouteHandler // for goal bool isInGoalRouteSection(const lanelet::ConstLanelet & lanelet) const; Pose getGoalPose() const; + Pose getStartPose() const; lanelet::Id getGoalLaneId() const; bool getGoalLanelet(lanelet::ConstLanelet * goal_lanelet) const; std::vector getLanesBeforePose( diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 3027ca0b96560..358c44a295a29 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -418,6 +418,15 @@ lanelet::ConstLanelets RouteHandler::getRouteLanelets() const return route_lanelets_; } +Pose RouteHandler::getStartPose() const +{ + if (!route_ptr_) { + RCLCPP_WARN(logger_, "[Route Handler] getStartPose: Route has not been set yet"); + Pose(); + } + return route_ptr_->start_pose; +} + Pose RouteHandler::getGoalPose() const { if (!route_ptr_) { From eec3cb83a7ebcc332729d93af8f6287fa5b7877b Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 2 Aug 2023 16:44:23 +0900 Subject: [PATCH 078/266] chore: add maintainer in localization and map packages (#4501) Signed-off-by: kminoda --- localization/ekf_localizer/package.xml | 1 + localization/gyro_odometer/package.xml | 1 + localization/initial_pose_button_panel/package.xml | 1 + localization/localization_error_monitor/package.xml | 1 + localization/ndt_scan_matcher/package.xml | 1 + localization/pose2twist/package.xml | 1 + localization/pose_initializer/package.xml | 1 + localization/stop_filter/package.xml | 1 + localization/twist2accel/package.xml | 1 + localization/yabloc/yabloc_common/package.xml | 1 + localization/yabloc/yabloc_image_processing/package.xml | 1 + localization/yabloc/yabloc_monitor/package.xml | 1 + localization/yabloc/yabloc_particle_filter/package.xml | 1 + localization/yabloc/yabloc_pose_initializer/package.xml | 1 + map/map_height_fitter/package.xml | 1 + map/map_loader/package.xml | 1 + 16 files changed, 16 insertions(+) diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index 8e837920f6d6a..5bc9c5e42712d 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -8,6 +8,7 @@ Koji Minoda Yamato Ando Takeshi Ishita + Masahiro Sakamoto Apache License 2.0 Takamasa Horibe diff --git a/localization/gyro_odometer/package.xml b/localization/gyro_odometer/package.xml index 26781513ff2f7..cbcaadebddc2e 100644 --- a/localization/gyro_odometer/package.xml +++ b/localization/gyro_odometer/package.xml @@ -5,6 +5,7 @@ 0.1.0 The gyro_odometer package as a ROS 2 node Yamato Ando + Masahiro Sakamoto Apache License 2.0 Yamato Ando diff --git a/localization/initial_pose_button_panel/package.xml b/localization/initial_pose_button_panel/package.xml index 2db87fe645fb1..f0b4d41bc4f51 100644 --- a/localization/initial_pose_button_panel/package.xml +++ b/localization/initial_pose_button_panel/package.xml @@ -5,6 +5,7 @@ 0.1.0 The initial_pose_button_panel package Yamato ANDO + Masahiro Sakamoto Apache License 2.0 Yamato ANDO diff --git a/localization/localization_error_monitor/package.xml b/localization/localization_error_monitor/package.xml index 4c563f0b30ab1..23e71f2a844cd 100644 --- a/localization/localization_error_monitor/package.xml +++ b/localization/localization_error_monitor/package.xml @@ -5,6 +5,7 @@ 0.1.0 ros node for monitoring localization error Yamato Ando + Masahiro Sakamoto Apache License 2.0 Taichi Higashide diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index 17db6b17d4a45..92c690a708492 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -7,6 +7,7 @@ Yamato Ando Kento Yabuuchi Koji Minoda + Masahiro Sakamoto Apache License 2.0 Yamato Ando diff --git a/localization/pose2twist/package.xml b/localization/pose2twist/package.xml index ed044bd285909..83bce5a718334 100644 --- a/localization/pose2twist/package.xml +++ b/localization/pose2twist/package.xml @@ -5,6 +5,7 @@ 0.1.0 The pose2twist package Yamato Ando + Masahiro Sakamoto Apache License 2.0 Yamato Ando diff --git a/localization/pose_initializer/package.xml b/localization/pose_initializer/package.xml index cb519c49e6335..f8333d89fa8ac 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/pose_initializer/package.xml @@ -6,6 +6,7 @@ The pose_initializer package Yamato Ando Takagi, Isamu + Masahiro Sakamoto Apache License 2.0 Yamato Ando Takagi, Isamu diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index b0beeb4758951..b17809aaa9948 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -6,6 +6,7 @@ The stop filter package Koji Minoda Yamato Ando + Masahiro Sakamoto Apache License 2.0 Koji Minoda diff --git a/localization/twist2accel/package.xml b/localization/twist2accel/package.xml index dc54311b3a1db..c44cd9d144566 100644 --- a/localization/twist2accel/package.xml +++ b/localization/twist2accel/package.xml @@ -6,6 +6,7 @@ The acceleration estimation package Koji Minoda Yamato Ando + Masahiro Sakamoto Apache License 2.0 Koji Minoda diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index d56b111df45d3..1c3ba4de307f6 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -4,6 +4,7 @@ 0.1.0 YabLoc common library Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_image_processing/package.xml b/localization/yabloc/yabloc_image_processing/package.xml index 92d8210be85a3..961ce574f7c7a 100644 --- a/localization/yabloc/yabloc_image_processing/package.xml +++ b/localization/yabloc/yabloc_image_processing/package.xml @@ -5,6 +5,7 @@ 0.0.0 YabLoc image processing package Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index 2c6c32bad9eb5..8c92c3c6a4303 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -6,6 +6,7 @@ YabLoc monitor package Kento Yabuuchi Koji Minoda + Masahiro Sakamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index 7a70b8ad6a8fb..6d11b12d9c922 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -5,6 +5,7 @@ 0.1.0 YabLoc particle filter package Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 9adfc2a85f663..f6e8aa83bafc7 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -4,6 +4,7 @@ 0.0.0 The pose initializer Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake_ros diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index b288da6aca2cb..8f6ccf969c9a4 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -6,6 +6,7 @@ The map_height_fitter package Takagi, Isamu Yamato Ando + Masahiro Sakamoto Apache License 2.0 Takagi, Isamu diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index e9ed6af24edd9..93b00cd412147 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -7,6 +7,7 @@ Ryohsuke Mitsudome Ryu Yamamoto Koji Minoda + Masahiro Sakamoto Apache License 2.0 From d3865449fb2acabcd10430de0cdd62d9b7ccf6ed Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Wed, 2 Aug 2023 08:07:41 +0000 Subject: [PATCH 079/266] chore: update CODEOWNERS (#4478) Signed-off-by: GitHub Co-authored-by: kminoda --- .github/CODEOWNERS | 39 ++++++++++++++++++++------------------- 1 file changed, 20 insertions(+), 19 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 10b1309eac2ea..59e8a6f80832e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -79,21 +79,22 @@ launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp -localization/ekf_localizer/** koji.minoda@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp -localization/gyro_odometer/** yamato.ando@tier4.jp -localization/initial_pose_button_panel/** yamato.ando@tier4.jp -localization/localization_error_monitor/** yamato.ando@tier4.jp -localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp yamato.ando@tier4.jp -localization/pose2twist/** yamato.ando@tier4.jp -localization/pose_initializer/** isamu.takagi@tier4.jp yamato.ando@tier4.jp -localization/stop_filter/** koji.minoda@tier4.jp yamato.ando@tier4.jp -localization/twist2accel/** koji.minoda@tier4.jp yamato.ando@tier4.jp -localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp -localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp -localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp -localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp -map/map_height_fitter/** isamu.takagi@tier4.jp yamato.ando@tier4.jp -map/map_loader/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp +localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp +localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/initial_pose_button_panel/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/localization_error_monitor/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/pose2twist/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/pose_initializer/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/stop_filter/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/twist2accel/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp +localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp +localization/yabloc/yabloc_monitor/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp +localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp +localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp +map/map_height_fitter/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +map/map_loader/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp map/map_tf_generator/** azumi.suzuki@tier4.jp map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp perception/bytetrack/** manato.hirabayashi@tier4.jp @@ -130,12 +131,12 @@ perception/simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4. perception/tensorrt_classifier/** mingyu.li@tier4.jp perception/tensorrt_yolo/** daisuke.nishimatsu@tier4.jp perception/tensorrt_yolox/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp -perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp +perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp -perception/traffic_light_fine_detector/** mingyu.li@tier4.jp +perception/traffic_light_fine_detector/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp -perception/traffic_light_multi_camera_fusion/** mingyu.li@tier4.jp -perception/traffic_light_occlusion_predictor/** mingyu.li@tier4.jp +perception/traffic_light_multi_camera_fusion/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp +perception/traffic_light_occlusion_predictor/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp From 6768a29c1f0cc7b9738f2b66225c690d4842972c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 2 Aug 2023 18:05:57 +0900 Subject: [PATCH 080/266] fix(behavior_path_planner): insert stop point for multiple lane change (#4493) * fix(behavior_path_planner): fix for multiple lane change Signed-off-by: Fumiya Watanabe * fix(behavior_path_planner): fix Signed-off-by: Fumiya Watanabe * fix(behavior_path_planner): remove comments and debug message Signed-off-by: Fumiya Watanabe * fix(behavior_path_planner): fix conditions Signed-off-by: Fumiya Watanabe * fix(behavior_path_planner): fix distance calculation Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../scene_module/lane_change/base_class.hpp | 6 +- .../scene_module/lane_change/normal.hpp | 2 +- .../scene_module/lane_change/interface.cpp | 4 +- .../src/scene_module/lane_change/normal.cpp | 55 +++++++++++++++---- 4 files changed, 52 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp index 133998b493567..6ca06ff21c4a9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp @@ -137,7 +137,11 @@ class LaneChangeBase virtual void updateSpecialData() {} - virtual void insertStopPoint([[maybe_unused]] PathWithLaneId & path) {} + virtual void insertStopPoint( + [[maybe_unused]] const lanelet::ConstLanelets & lanelets, + [[maybe_unused]] PathWithLaneId & path) + { + } const LaneChangeStatus & getLaneChangeStatus() const { return status_; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index bebda4eb7f353..9a937e0cfca49 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -62,7 +62,7 @@ class NormalLaneChange : public LaneChangeBase void extendOutputDrivableArea(BehaviorModuleOutput & output) override; - void insertStopPoint(PathWithLaneId & path) override; + void insertStopPoint(const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) override; PathWithLaneId getReferencePath() const override; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 14a568f5648ad..b6258d8fba597 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -220,6 +220,7 @@ BehaviorModuleOutput LaneChangeInterface::plan() auto output = module_type_->generateOutput(); path_reference_ = output.reference_path; *prev_approved_path_ = *getPreviousModuleOutput().path; + module_type_->insertStopPoint(module_type_->getLaneChangeStatus().target_lanes, *output.path); updateSteeringFactorPtr(output); clearWaitingApproval(); @@ -230,7 +231,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { *prev_approved_path_ = *getPreviousModuleOutput().path; - module_type_->insertStopPoint(*prev_approved_path_); + module_type_->insertStopPoint( + module_type_->getLaneChangeStatus().current_lanes, *prev_approved_path_); BehaviorModuleOutput out; out.path = std::make_shared(*prev_approved_path_); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 360d12a753625..cd344a40e3d8c 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -164,17 +164,38 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) utils::combineDrivableAreaInfo(current_drivable_area_info, prev_drivable_area_info_); } -void NormalLaneChange::insertStopPoint(PathWithLaneId & path) +void NormalLaneChange::insertStopPoint( + const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) { - const auto shift_intervals = getRouteHandler()->getLateralIntervalsToPreferredLane( - status_.lane_change_path.info.current_lanes.back()); + if (lanelets.empty()) { + return; + } + + const auto & route_handler = getRouteHandler(); + + if (route_handler->getNumLaneToPreferredLane(lanelets.back()) == 0) { + return; + } + + const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back()); const double lane_change_buffer = utils::calcMinimumLaneChangeLength(getCommonParam(), shift_intervals, 0.0); - constexpr double stop_point_buffer{1.0}; - const auto stopping_distance = std::max( - motion_utils::calcArcLength(path.points) - lane_change_buffer - stop_point_buffer, 0.0); - const auto stop_point = utils::insertStopPoint(stopping_distance, path); + // If lanelets.back() is in goal route section, get distance to goal. + // Otherwise, get distance to end of lane. + double distance_to_terminal = 0.0; + if (route_handler->isInGoalRouteSection(lanelets.back())) { + const auto goal = route_handler->getGoalPose(); + distance_to_terminal = utils::getSignedDistance(path.points.front().point.pose, goal, lanelets); + } else { + distance_to_terminal = utils::getDistanceToEndOfLane(path.points.front().point.pose, lanelets); + } + + const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; + if (stopping_distance > 0.0) { + const auto stop_point = utils::insertStopPoint(stopping_distance, path); + } } PathWithLaneId NormalLaneChange::getReferencePath() const @@ -348,11 +369,16 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( bool NormalLaneChange::hasFinishedLaneChange() const { const auto & current_pose = getEgoPose(); - const auto & lane_change_path = status_.lane_change_path.path; const auto & lane_change_end = status_.lane_change_path.info.shift_line.end; - const double dist_to_lane_change_end = motion_utils::calcSignedArcLength( - lane_change_path.points, current_pose.position, lane_change_end.position); - const double finish_judge_buffer = planner_data_->parameters.lane_change_finish_judge_buffer; + const double dist_to_lane_change_end = utils::getSignedDistance( + current_pose, lane_change_end, status_.lane_change_path.info.target_lanes); + double finish_judge_buffer = planner_data_->parameters.lane_change_finish_judge_buffer; + + // If ego velocity is low, relax finish judge buffer + const double ego_velocity = getEgoVelocity(); + if (std::abs(ego_velocity) < 1.0) { + finish_judge_buffer = 0.0; + } const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0; if (!reach_lane_change_end) { @@ -650,6 +676,7 @@ bool NormalLaneChange::getLaneChangePaths( std::max(common_parameters.min_acc, lane_change_parameters_->min_longitudinal_acc); const auto max_longitudinal_acc = std::min(common_parameters.max_acc, lane_change_parameters_->max_longitudinal_acc); + const auto finish_judge_buffer = common_parameters.lane_change_finish_judge_buffer; // get velocity const auto current_velocity = getEgoTwist().linear.x; @@ -764,8 +791,12 @@ bool NormalLaneChange::getLaneChangePaths( lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose).length; const double s_goal = lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose()).length; + const auto num = + std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); + const double backward_buffer = + num == 0 ? 0.0 : common_parameters.backward_length_buffer_for_end_of_lane; if ( - s_start + lane_changing_length + common_parameters.lane_change_finish_judge_buffer + + s_start + lane_changing_length + finish_judge_buffer + backward_buffer + next_lane_change_buffer > s_goal) { RCLCPP_DEBUG(logger_, "length of lane changing path is longer than length to goal!!"); From 37c80ad7f5a9fd9a9129ad96c889cb3d975853e4 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 3 Aug 2023 08:41:32 +0900 Subject: [PATCH 081/266] fix(object_merger): preserve unknown objects close to known objects (#4499) * fix(object_merger): separate GIoU Signed-off-by: badai-nguyen * fix: update GIoU threshold Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- perception/object_merger/README.md | 2 +- .../object_merger/config/overlapped_judge.param.yaml | 3 +++ .../include/object_association_merger/node.hpp | 2 +- .../launch/object_association_merger.launch.xml | 2 +- .../object_merger/src/object_association_merger/node.cpp | 7 +++++-- 5 files changed, 11 insertions(+), 5 deletions(-) diff --git a/perception/object_merger/README.md b/perception/object_merger/README.md index 62a95ada62b09..18bf12fa8cdb8 100644 --- a/perception/object_merger/README.md +++ b/perception/object_merger/README.md @@ -34,7 +34,7 @@ The successive shortest path algorithm is used to solve the data association pro | `max_rad_matrix` | double | Maximum angle table for data association | | `base_link_frame_id` | double | association frame | | `distance_threshold_list` | `std::vector` | Distance threshold for each class used in judging overlap. The class order depends on [ObjectClassification](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/ObjectClassification.idl). | -| `generalized_iou_threshold` | double | Generalized IoU threshold | +| `generalized_iou_threshold` | `std::vector` | Generalized IoU threshold for each class | ## Tips diff --git a/perception/object_merger/config/overlapped_judge.param.yaml b/perception/object_merger/config/overlapped_judge.param.yaml index 94882fae4f282..0410b77390187 100644 --- a/perception/object_merger/config/overlapped_judge.param.yaml +++ b/perception/object_merger/config/overlapped_judge.param.yaml @@ -3,3 +3,6 @@ distance_threshold_list: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN [9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] #UNKNOWN + + generalized_iou_threshold: + [-0.1, -0.1, -0.1, -0.6, -0.6, -0.1, -0.1, -0.1] diff --git a/perception/object_merger/include/object_association_merger/node.hpp b/perception/object_merger/include/object_association_merger/node.hpp index 704f7859f6672..1e5b9fad9c9ca 100644 --- a/perception/object_merger/include/object_association_merger/node.hpp +++ b/perception/object_merger/include/object_association_merger/node.hpp @@ -76,7 +76,7 @@ class ObjectAssociationMergerNode : public rclcpp::Node { double precision_threshold; double recall_threshold; - double generalized_iou_threshold; + std::map generalized_iou_threshold; std::map distance_threshold_map; } overlapped_judge_param_; }; diff --git a/perception/object_merger/launch/object_association_merger.launch.xml b/perception/object_merger/launch/object_association_merger.launch.xml index 1b89693b0f9f7..3418f7d5a5e61 100644 --- a/perception/object_merger/launch/object_association_merger.launch.xml +++ b/perception/object_merger/launch/object_association_merger.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/perception/object_merger/src/object_association_merger/node.cpp b/perception/object_merger/src/object_association_merger/node.cpp index 17397b782892b..4f600ce8a4948 100644 --- a/perception/object_merger/src/object_association_merger/node.cpp +++ b/perception/object_merger/src/object_association_merger/node.cpp @@ -35,8 +35,11 @@ bool isUnknownObjectOverlapped( const autoware_auto_perception_msgs::msg::DetectedObject & unknown_object, const autoware_auto_perception_msgs::msg::DetectedObject & known_object, const double precision_threshold, const double recall_threshold, - std::map distance_threshold_map, const double generalized_iou_threshold) + std::map distance_threshold_map, + const std::map generalized_iou_threshold_map) { + const double generalized_iou_threshold = generalized_iou_threshold_map.at( + object_recognition_utils::getHighestProbLabel(known_object.classification)); const double distance_threshold = distance_threshold_map.at( object_recognition_utils::getHighestProbLabel(known_object.classification)); const double sq_distance_threshold = std::pow(distance_threshold, 2.0); @@ -95,7 +98,7 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio overlapped_judge_param_.recall_threshold = declare_parameter("recall_threshold_to_judge_overlapped", 0.5); overlapped_judge_param_.generalized_iou_threshold = - declare_parameter("generalized_iou_threshold"); + convertListToClassMap(declare_parameter>("generalized_iou_threshold")); // get distance_threshold_map from distance_threshold_list /** TODO(Shin-kyoto): From 5f15fd37725ff219559d30e2c48bcdafb20d3599 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 3 Aug 2023 11:10:53 +0900 Subject: [PATCH 082/266] perf(planner_manger): remove lifo limitation (#4458) * feat(route_handler): add function to get closest preferred lanelet Signed-off-by: satoshi-ota * perf(planner_manager): remove module immediately once its status is success Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner/planner_manager.hpp | 36 +++-------- .../src/planner_manager.cpp | 59 ++++--------------- .../include/route_handler/route_handler.hpp | 2 + planning/route_handler/src/route_handler.cpp | 7 +++ 4 files changed, 30 insertions(+), 74 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 8820ef70c37bf..6ca2ecf638da6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -348,41 +348,21 @@ class PlannerManager candidate_module_ptrs_.clear(); } - /** - * @brief stop and remove not RUNNING modules in candidate_module_ptrs_. - */ - void clearNotRunningCandidateModules() - { - const auto it = std::remove_if( - candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), [this](auto & m) { - if (m->getCurrentStatus() != ModuleStatus::RUNNING) { - deleteExpiredModules(m); - return true; - } - return false; - }); - candidate_module_ptrs_.erase(it, candidate_module_ptrs_.end()); - } - - /** - * @brief check if there is any RUNNING module in candidate_module_ptrs_. - */ - bool hasAnyRunningCandidateModule() - { - return std::any_of(candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), [](auto & m) { - return m->getCurrentStatus() == ModuleStatus::RUNNING; - }); - } - /** * @brief get current root lanelet. the lanelet is used for reference path generation. * @param planner data. * @return root lanelet. */ - lanelet::ConstLanelet updateRootLanelet(const std::shared_ptr & data) const + lanelet::ConstLanelet updateRootLanelet( + const std::shared_ptr & data, bool success_lane_change = false) const { lanelet::ConstLanelet ret{}; - data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret); + if (success_lane_change) { + data->route_handler->getClosestPreferredLaneletWithinRoute( + data->self_odometry->pose.pose, &ret); + } else { + data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret); + } RCLCPP_DEBUG(logger_, "update start lanelet. id:%ld", ret.id()); return ret; } diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index a3309968dd62c..08af698683c32 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -439,8 +439,6 @@ std::pair PlannerManager::runRequestModule BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr & data) { - const bool has_any_running_candidate_module = hasAnyRunningCandidateModule(); - std::unordered_map results; BehaviorModuleOutput output = getReferencePath(data); results.emplace("root", output); @@ -514,59 +512,28 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrgetCurrentStatus() != ModuleStatus::SUCCESS; }); - - // convert reverse iterator -> iterator - const auto success_itr = std::prev(not_success_itr).base() - 1; - /** - * there is no succeeded module. return. + * remove success module immediately. if lane change module has succeeded, update root lanelet. */ - if (success_itr == approved_module_ptrs_.end()) { - return approved_modules_output; - } - - const auto lane_change_itr = std::find_if( - success_itr, approved_module_ptrs_.end(), - [](const auto & m) { return m->name().find("lane_change") != std::string::npos; }); - - /** - * remove success modules according to Last In First Out(LIFO) policy. when the next module is in - * ModuleStatus::RUNNING, the previous module keeps running even if it is in - * ModuleStatus::SUCCESS. - */ - if (lane_change_itr == approved_module_ptrs_.end() && !has_any_running_candidate_module) { - std::for_each(success_itr, approved_module_ptrs_.end(), [this](auto & m) { - debug_info_.emplace_back(m, Action::DELETE, "From Approved"); - deleteExpiredModules(m); - }); + { + const auto success_module_itr = std::partition( + approved_module_ptrs_.begin(), approved_module_ptrs_.end(), + [](const auto & m) { return m->getCurrentStatus() != ModuleStatus::SUCCESS; }); - approved_module_ptrs_.erase(success_itr, approved_module_ptrs_.end()); - clearNotRunningCandidateModules(); + const auto success_lane_change = std::any_of( + success_module_itr, approved_module_ptrs_.end(), + [](const auto & m) { return m->name().find("lane_change") != std::string::npos; }); - return approved_modules_output; - } + if (success_lane_change) { + root_lanelet_ = updateRootLanelet(data, true); + } - /** - * as an exception, when there is lane change module is in succeeded modules, it doesn't remove - * any modules if module whose status is NOT ModuleStatus::SUCCESS exists. this is because the - * root lanelet is updated at the moment of lane change module's unregistering, and that causes - * change First In module's input. - */ - if (not_success_itr == approved_module_ptrs_.rend() && !has_any_running_candidate_module) { - std::for_each(success_itr, approved_module_ptrs_.end(), [this](auto & m) { + std::for_each(success_module_itr, approved_module_ptrs_.end(), [&](auto & m) { debug_info_.emplace_back(m, Action::DELETE, "From Approved"); deleteExpiredModules(m); }); - approved_module_ptrs_.erase(success_itr, approved_module_ptrs_.end()); - clearNotRunningCandidateModules(); - - root_lanelet_ = updateRootLanelet(data); - - return approved_modules_output; + approved_module_ptrs_.erase(success_module_itr, approved_module_ptrs_.end()); } return approved_modules_output; diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 3c3ddbc1acaf2..b298d69949610 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -301,6 +301,8 @@ class RouteHandler bool getClosestLaneletWithinRoute( const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const; + bool getClosestPreferredLaneletWithinRoute( + const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const; bool getClosestLaneletWithConstrainsWithinRoute( const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet, const double dist_threshold, const double yaw_threshold) const; diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 358c44a295a29..33d44851e73f1 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -788,6 +788,13 @@ bool RouteHandler::getClosestLaneletWithinRoute( return lanelet::utils::query::getClosestLanelet(route_lanelets_, search_pose, closest_lanelet); } +bool RouteHandler::getClosestPreferredLaneletWithinRoute( + const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const +{ + return lanelet::utils::query::getClosestLanelet( + preferred_lanelets_, search_pose, closest_lanelet); +} + bool RouteHandler::getClosestLaneletWithConstrainsWithinRoute( const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet, const double dist_threshold, const double yaw_threshold) const From 73726bdaea33ccef3b833b27889b5c63a1256cc1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 3 Aug 2023 12:16:20 +0900 Subject: [PATCH 083/266] refactor(interface): use `weak_ptr` or `unique_ptr` instead of `shared_ptr` (#4452) refactor(interface): use weak pointer Signed-off-by: satoshi-ota --- .../behavior_path_planner/planner_manager.hpp | 11 +- .../scene_module/avoidance/manager.hpp | 4 +- .../dynamic_avoidance/manager.hpp | 4 +- .../scene_module/goal_planner/manager.hpp | 4 +- .../scene_module/lane_change/manager.hpp | 4 +- .../scene_module_manager_interface.hpp | 167 ++++++++++-------- .../scene_module/side_shift/manager.hpp | 4 +- .../scene_module/start_planner/manager.hpp | 4 +- .../src/behavior_path_planner_node.cpp | 35 ++-- .../src/planner_manager.cpp | 56 +++--- .../src/scene_module/avoidance/manager.cpp | 4 +- .../dynamic_avoidance/manager.cpp | 4 +- .../src/scene_module/goal_planner/manager.cpp | 4 +- .../src/scene_module/lane_change/manager.cpp | 14 +- .../src/scene_module/side_shift/manager.cpp | 4 +- .../scene_module/start_planner/manager.cpp | 18 +- 16 files changed, 192 insertions(+), 149 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 6ca2ecf638da6..02e5452cc2103 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -105,9 +105,9 @@ class PlannerManager */ void registerSceneModuleManager(const SceneModuleManagerPtr & manager_ptr) { - RCLCPP_INFO(logger_, "register %s module", manager_ptr->getModuleName().c_str()); + RCLCPP_INFO(logger_, "register %s module", manager_ptr->name().c_str()); manager_ptrs_.push_back(manager_ptr); - processing_time_.emplace(manager_ptr->getModuleName(), 0.0); + processing_time_.emplace(manager_ptr->name(), 0.0); } /** @@ -301,8 +301,9 @@ class PlannerManager */ void deleteExpiredModules(SceneModulePtr & module_ptr) const { - const auto manager = getManager(module_ptr); - manager->deleteModules(module_ptr); + module_ptr->onExit(); + module_ptr->publishRTCStatus(); + module_ptr.reset(); } /** @@ -376,7 +377,7 @@ class PlannerManager { const auto itr = std::find_if( manager_ptrs_.begin(), manager_ptrs_.end(), - [&module_ptr](const auto & m) { return m->getModuleName() == module_ptr->name(); }); + [&module_ptr](const auto & m) { return m->name() == module_ptr->name(); }); if (itr == manager_ptrs_.end()) { throw std::domain_error("unknown manager name."); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp index 4aa7f9ef142c6..9d89138f7cdfe 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp @@ -35,9 +35,9 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface AvoidanceModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override + std::unique_ptr createNewSceneModuleInstance() override { - return std::make_shared(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp index 4e4a54af14b53..10a0d055a5a77 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp @@ -34,9 +34,9 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface DynamicAvoidanceModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override + std::unique_ptr createNewSceneModuleInstance() override { - return std::make_shared( + return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_); } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp index b6960aba10846..592a578f7fc72 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp @@ -33,9 +33,9 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface GoalPlannerModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override + std::unique_ptr createNewSceneModuleInstance() override { - return std::make_shared(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index af65245ce4e3f..cf618b755b094 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -37,7 +37,7 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, const Direction direction, const LaneChangeModuleType type); - std::shared_ptr createNewSceneModuleInstance() override; + std::unique_ptr createNewSceneModuleInstance() override; void updateModuleParams(const std::vector & parameters) override; @@ -55,7 +55,7 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager AvoidanceByLaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override; + std::unique_ptr createNewSceneModuleInstance() override; // void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp index 0c6ec17e94a6a..ee5d539b3415d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp @@ -38,6 +38,7 @@ using motion_utils::createStopVirtualWallMarker; using tier4_autoware_utils::toHexString; using unique_identifier_msgs::msg::UUID; using SceneModulePtr = std::shared_ptr; +using SceneModuleObserver = std::weak_ptr; class SceneModuleManagerInterface { @@ -73,56 +74,50 @@ class SceneModuleManagerInterface virtual ~SceneModuleManagerInterface() = default; - SceneModulePtr getNewModule() + void updateIdleModuleInstance() { - if (idling_module_ptr_ != nullptr) { - idling_module_ptr_->onEntry(); - return idling_module_ptr_; + if (idle_module_ptr_) { + idle_module_ptr_->onEntry(); + return; } - idling_module_ptr_ = createNewSceneModuleInstance(); - return idling_module_ptr_; + idle_module_ptr_ = createNewSceneModuleInstance(); } - bool isExecutionRequested( - const SceneModulePtr & module_ptr, const BehaviorModuleOutput & previous_module_output) const + bool isExecutionRequested(const BehaviorModuleOutput & previous_module_output) const { - module_ptr->setData(planner_data_); - module_ptr->setPreviousModuleOutput(previous_module_output); - module_ptr->updateData(); + idle_module_ptr_->setData(planner_data_); + idle_module_ptr_->setPreviousModuleOutput(previous_module_output); + idle_module_ptr_->updateData(); - return module_ptr->isExecutionRequested(); + return idle_module_ptr_->isExecutionRequested(); } void registerNewModule( - const SceneModulePtr & module_ptr, const BehaviorModuleOutput & previous_module_output) + const SceneModuleObserver & observer, const BehaviorModuleOutput & previous_module_output) { - module_ptr->setIsSimultaneousExecutableAsApprovedModule( + if (observer.expired()) { + return; + } + + observer.lock()->setIsSimultaneousExecutableAsApprovedModule( enable_simultaneous_execution_as_approved_module_); - module_ptr->setIsSimultaneousExecutableAsCandidateModule( + observer.lock()->setIsSimultaneousExecutableAsCandidateModule( enable_simultaneous_execution_as_candidate_module_); - module_ptr->setData(planner_data_); - module_ptr->setPreviousModuleOutput(previous_module_output); - module_ptr->onEntry(); + observer.lock()->setData(planner_data_); + observer.lock()->setPreviousModuleOutput(previous_module_output); + observer.lock()->onEntry(); - registered_modules_.push_back(module_ptr); + observers_.push_back(observer); } - void deleteModules(SceneModulePtr & module_ptr) + void updateObserver() { - module_ptr->onExit(); - module_ptr->publishRTCStatus(); - - const auto itr = std::find(registered_modules_.begin(), registered_modules_.end(), module_ptr); - - if (itr != registered_modules_.end()) { - registered_modules_.erase(itr); - } + const auto itr = std::remove_if( + observers_.begin(), observers_.end(), + [](const auto & observer) { return observer.expired(); }); - module_ptr.reset(); - idling_module_ptr_.reset(); - - pub_debug_marker_->publish(MarkerArray{}); + observers_.erase(itr, observers_.end()); } void publishVirtualWall() const @@ -134,32 +129,36 @@ class SceneModuleManagerInterface const auto marker_offset = std::numeric_limits::max(); uint32_t marker_id = marker_offset; - for (const auto & m : registered_modules_) { - const auto opt_stop_pose = m->getStopPose(); + for (const auto & m : observers_) { + if (m.expired()) { + continue; + } + + const auto opt_stop_pose = m.lock()->getStopPose(); if (!!opt_stop_pose) { const auto virtual_wall = createStopVirtualWallMarker( - opt_stop_pose.get(), m->name(), rclcpp::Clock().now(), marker_id); + opt_stop_pose.get(), m.lock()->name(), rclcpp::Clock().now(), marker_id); appendMarkerArray(virtual_wall, &markers); } - const auto opt_slow_pose = m->getSlowPose(); + const auto opt_slow_pose = m.lock()->getSlowPose(); if (!!opt_slow_pose) { const auto virtual_wall = createSlowDownVirtualWallMarker( - opt_slow_pose.get(), m->name(), rclcpp::Clock().now(), marker_id); + opt_slow_pose.get(), m.lock()->name(), rclcpp::Clock().now(), marker_id); appendMarkerArray(virtual_wall, &markers); } - const auto opt_dead_pose = m->getDeadPose(); + const auto opt_dead_pose = m.lock()->getDeadPose(); if (!!opt_dead_pose) { const auto virtual_wall = createDeadLineVirtualWallMarker( - opt_dead_pose.get(), m->name(), rclcpp::Clock().now(), marker_id); + opt_dead_pose.get(), m.lock()->name(), rclcpp::Clock().now(), marker_id); appendMarkerArray(virtual_wall, &markers); } - const auto module_specific_wall = m->getModuleVirtualWall(); + const auto module_specific_wall = m.lock()->getModuleVirtualWall(); appendMarkerArray(module_specific_wall, &markers); - m->resetWallPoses(); + m.lock()->resetWallPoses(); } pub_virtual_wall_->publish(markers); @@ -176,18 +175,22 @@ class SceneModuleManagerInterface const auto marker_offset = std::numeric_limits::max(); uint32_t marker_id = marker_offset; - for (const auto & m : registered_modules_) { - for (auto & marker : m->getInfoMarkers().markers) { + for (const auto & m : observers_) { + if (m.expired()) { + continue; + } + + for (auto & marker : m.lock()->getInfoMarkers().markers) { marker.id += marker_id; info_markers.markers.push_back(marker); } - for (auto & marker : m->getDebugMarkers().markers) { + for (auto & marker : m.lock()->getDebugMarkers().markers) { marker.id += marker_id; debug_markers.markers.push_back(marker); } - for (auto & marker : m->getDrivableLanesMarkers().markers) { + for (auto & marker : m.lock()->getDrivableLanesMarkers().markers) { marker.id += marker_id; drivable_lanes_markers.markers.push_back(marker); } @@ -195,10 +198,10 @@ class SceneModuleManagerInterface marker_id += marker_offset; } - if (registered_modules_.empty() && idling_module_ptr_ != nullptr) { - appendMarkerArray(idling_module_ptr_->getInfoMarkers(), &info_markers); - appendMarkerArray(idling_module_ptr_->getDebugMarkers(), &debug_markers); - appendMarkerArray(idling_module_ptr_->getDrivableLanesMarkers(), &drivable_lanes_markers); + if (observers_.empty() && idle_module_ptr_ != nullptr) { + appendMarkerArray(idle_module_ptr_->getInfoMarkers(), &info_markers); + appendMarkerArray(idle_module_ptr_->getDebugMarkers(), &debug_markers); + appendMarkerArray(idle_module_ptr_->getDrivableLanesMarkers(), &drivable_lanes_markers); } pub_info_marker_->publish(info_markers); @@ -208,50 +211,62 @@ class SceneModuleManagerInterface bool exist(const SceneModulePtr & module_ptr) const { - return std::find(registered_modules_.begin(), registered_modules_.end(), module_ptr) != - registered_modules_.end(); + return std::any_of(observers_.begin(), observers_.end(), [&](const auto & observer) { + return !observer.expired() && observer.lock() == module_ptr; + }); } - bool canLaunchNewModule() const { return registered_modules_.size() < max_module_num_; } + bool canLaunchNewModule() const { return observers_.size() < max_module_num_; } bool isSimultaneousExecutableAsApprovedModule() const { - if (registered_modules_.empty()) { + if (observers_.empty()) { return enable_simultaneous_execution_as_approved_module_; } - return std::all_of( - registered_modules_.begin(), registered_modules_.end(), [](const SceneModulePtr & module) { - return module->isSimultaneousExecutableAsApprovedModule(); - }); + const auto checker = [this](const SceneModuleObserver & observer) { + if (observer.expired()) { + return enable_simultaneous_execution_as_approved_module_; + } + return observer.lock()->isSimultaneousExecutableAsApprovedModule(); + }; + + return std::all_of(observers_.begin(), observers_.end(), checker); } bool isSimultaneousExecutableAsCandidateModule() const { - if (registered_modules_.empty()) { + if (observers_.empty()) { return enable_simultaneous_execution_as_candidate_module_; } - return std::all_of( - registered_modules_.begin(), registered_modules_.end(), [](const SceneModulePtr & module) { - return module->isSimultaneousExecutableAsCandidateModule(); - }); + const auto checker = [this](const SceneModuleObserver & observer) { + if (observer.expired()) { + return enable_simultaneous_execution_as_candidate_module_; + } + return observer.lock()->isSimultaneousExecutableAsCandidateModule(); + }; + + return std::all_of(observers_.begin(), observers_.end(), checker); } void setData(const std::shared_ptr & planner_data) { planner_data_ = planner_data; } void reset() { - std::for_each(registered_modules_.begin(), registered_modules_.end(), [](const auto & m) { - m->onExit(); - m->publishRTCStatus(); + std::for_each(observers_.begin(), observers_.end(), [](const auto & observer) { + if (!observer.expired()) { + observer.lock()->onExit(); + observer.lock()->publishRTCStatus(); + } }); - registered_modules_.clear(); - if (idling_module_ptr_ != nullptr) { - idling_module_ptr_->onExit(); - idling_module_ptr_->publishRTCStatus(); - idling_module_ptr_.reset(); + observers_.clear(); + + if (idle_module_ptr_ != nullptr) { + idle_module_ptr_->onExit(); + idle_module_ptr_->publishRTCStatus(); + idle_module_ptr_.reset(); } pub_debug_marker_->publish(MarkerArray{}); @@ -259,14 +274,16 @@ class SceneModuleManagerInterface size_t getPriority() const { return priority_; } - std::string getModuleName() const { return name_; } + std::string name() const { return name_; } + + std::vector getSceneModuleObservers() { return observers_; } - std::vector getSceneModules() { return registered_modules_; } + std::shared_ptr getIdleModule() { return std::move(idle_module_ptr_); } virtual void updateModuleParams(const std::vector & parameters) = 0; protected: - virtual std::shared_ptr createNewSceneModuleInstance() = 0; + virtual std::unique_ptr createNewSceneModuleInstance() = 0; rclcpp::Node * node_; @@ -286,9 +303,9 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; - std::vector registered_modules_; + std::vector observers_; - SceneModulePtr idling_module_ptr_; + std::unique_ptr idle_module_ptr_; std::unordered_map> rtc_interface_ptr_map_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp index 8a287e6920f33..b74be38c0faf9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp @@ -34,9 +34,9 @@ class SideShiftModuleManager : public SceneModuleManagerInterface SideShiftModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override + std::unique_ptr createNewSceneModuleInstance() override { - return std::make_shared(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp index c86f9e415fdc7..9822e799b8ccf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp @@ -33,9 +33,9 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface StartPlannerModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); - std::shared_ptr createNewSceneModuleInstance() override + std::unique_ptr createNewSceneModuleInstance() override { - return std::make_shared(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 29f1ee762abdf..6037daef13abe 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -131,7 +131,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod planner_manager_ = std::make_shared(*this, p.verbose); const auto register_and_create_publisher = [&](const auto & manager) { - const auto & module_name = manager->getModuleName(); + const auto & module_name = manager->name(); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( module_name, create_publisher(path_candidate_name_space + module_name, 1)); @@ -779,27 +779,31 @@ void BehaviorPathPlannerNode::publishPathCandidate( const std::shared_ptr & planner_data) { for (auto & manager : managers) { - if (path_candidate_publishers_.count(manager->getModuleName()) == 0) { + if (path_candidate_publishers_.count(manager->name()) == 0) { continue; } - if (manager->getSceneModules().empty()) { - path_candidate_publishers_.at(manager->getModuleName()) + if (manager->getSceneModuleObservers().empty()) { + path_candidate_publishers_.at(manager->name()) ->publish(convertToPath(nullptr, false, planner_data)); continue; } - for (auto & module : manager->getSceneModules()) { - const auto & status = module->getCurrentStatus(); + for (auto & observer : manager->getSceneModuleObservers()) { + if (observer.expired()) { + continue; + } + const auto & status = observer.lock()->getCurrentStatus(); const auto candidate_path = std::invoke([&]() { if (status == ModuleStatus::SUCCESS || status == ModuleStatus::FAILURE) { // clear candidate path if the module is finished return convertToPath(nullptr, false, planner_data); } - return convertToPath(module->getPathCandidate(), module->isExecutionReady(), planner_data); + return convertToPath( + observer.lock()->getPathCandidate(), observer.lock()->isExecutionReady(), planner_data); }); - path_candidate_publishers_.at(module->name())->publish(candidate_path); + path_candidate_publishers_.at(observer.lock()->name())->publish(candidate_path); } } } @@ -809,19 +813,22 @@ void BehaviorPathPlannerNode::publishPathReference( const std::shared_ptr & planner_data) { for (auto & manager : managers) { - if (path_reference_publishers_.count(manager->getModuleName()) == 0) { + if (path_reference_publishers_.count(manager->name()) == 0) { continue; } - if (manager->getSceneModules().empty()) { - path_reference_publishers_.at(manager->getModuleName()) + if (manager->getSceneModuleObservers().empty()) { + path_reference_publishers_.at(manager->name()) ->publish(convertToPath(nullptr, false, planner_data)); continue; } - for (auto & module : manager->getSceneModules()) { - path_reference_publishers_.at(module->name()) - ->publish(convertToPath(module->getPathReference(), true, planner_data)); + for (auto & observer : manager->getSceneModuleObservers()) { + if (observer.expired()) { + continue; + } + path_reference_publishers_.at(observer.lock()->name()) + ->publish(convertToPath(observer.lock()->getPathReference(), true, planner_data)); } } } diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 08af698683c32..4b5d36c56f268 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -209,14 +209,14 @@ std::vector PlannerManager::getRequestModules( }; for (const auto & manager_ptr : manager_ptrs_) { - stop_watch_.tic(manager_ptr->getModuleName()); + stop_watch_.tic(manager_ptr->name()); /** * don't launch candidate module if approved modules already exist. */ if (!approved_module_ptrs_.empty()) { if (!manager_ptr->isSimultaneousExecutableAsApprovedModule()) { - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); continue; } } @@ -225,21 +225,20 @@ std::vector PlannerManager::getRequestModules( * launch new candidate module. */ { - const auto name = manager_ptr->getModuleName(); + const auto name = manager_ptr->name(); const auto find_same_name_module = [&name](const auto & m) { return m->name() == name; }; const auto itr = std::find_if( candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), find_same_name_module); if (itr == candidate_module_ptrs_.end()) { if (manager_ptr->canLaunchNewModule()) { - const auto new_module_ptr = manager_ptr->getNewModule(); - - if (manager_ptr->isExecutionRequested(new_module_ptr, previous_module_output)) { - request_modules.emplace_back(new_module_ptr); + manager_ptr->updateIdleModuleInstance(); + if (manager_ptr->isExecutionRequested(previous_module_output)) { + request_modules.emplace_back(manager_ptr->getIdleModule()); } } - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); continue; } } @@ -249,7 +248,7 @@ std::vector PlannerManager::getRequestModules( * candidate. if locked, break this loop. */ { - const auto name = manager_ptr->getModuleName(); + const auto name = manager_ptr->name(); const auto find_block_module = [&name](const auto & m) { return m->name() == name && m->isLockedNewModuleLaunch(); }; @@ -259,7 +258,7 @@ std::vector PlannerManager::getRequestModules( if (itr != candidate_module_ptrs_.end()) { request_modules.clear(); request_modules.emplace_back(*itr); - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); break; } } @@ -268,14 +267,14 @@ std::vector PlannerManager::getRequestModules( * module already exist. keep using it as candidate. */ { - const auto name = manager_ptr->getModuleName(); + const auto name = manager_ptr->name(); const auto find_launched_module = [&name](const auto & m) { return m->name() == name; }; const auto itr = std::find_if( candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), find_launched_module); if (itr != candidate_module_ptrs_.end()) { request_modules.emplace_back(*itr); - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); continue; } } @@ -285,20 +284,20 @@ std::vector PlannerManager::getRequestModules( */ { if (!manager_ptr->canLaunchNewModule()) { - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); continue; } - const auto new_module_ptr = manager_ptr->getNewModule(); - if (!manager_ptr->isExecutionRequested(new_module_ptr, previous_module_output)) { - toc(manager_ptr->getModuleName()); + manager_ptr->updateIdleModuleInstance(); + if (!manager_ptr->isExecutionRequested(previous_module_output)) { + toc(manager_ptr->name()); continue; } - request_modules.emplace_back(new_module_ptr); + request_modules.emplace_back(manager_ptr->getIdleModule()); } - toc(manager_ptr->getModuleName()); + toc(manager_ptr->name()); } return request_modules; @@ -366,7 +365,8 @@ std::pair PlannerManager::runRequestModule const auto & manager_ptr = getManager(module_ptr); if (!manager_ptr->exist(module_ptr)) { - manager_ptr->registerNewModule(module_ptr, previous_module_output); + manager_ptr->registerNewModule( + std::weak_ptr(module_ptr), previous_module_output); } results.emplace(module_ptr->name(), run(module_ptr, data, previous_module_output)); @@ -393,6 +393,9 @@ std::pair PlannerManager::runRequestModule executable_modules.erase( std::remove_if(executable_modules.begin(), executable_modules.end(), remove_expired_modules), executable_modules.end()); + + std::for_each( + manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); }); } /** @@ -470,6 +473,8 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrupdateObserver(); }); debug_info_.emplace_back(*itr, Action::MOVE, "Back To Waiting Approval"); } @@ -490,6 +495,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrupdateObserver(); }); + if (itr != approved_module_ptrs_.end()) { clearCandidateModules(); } @@ -534,6 +542,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrupdateObserver(); }); } return approved_modules_output; @@ -568,6 +579,9 @@ void PlannerManager::updateCandidateModules( std::remove_if( candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), candidate_to_remove), candidate_module_ptrs_.end()); + + std::for_each( + manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); }); } /** @@ -666,8 +680,8 @@ void PlannerManager::print() const string_stream << "-----------------------------------------------------------\n"; string_stream << "registered modules: "; for (const auto & m : manager_ptrs_) { - string_stream << "[" << m->getModuleName() << "]"; - max_string_num = std::max(max_string_num, m->getModuleName().length()); + string_stream << "[" << m->name() << "]"; + max_string_num = std::max(max_string_num, m->name().length()); } string_stream << "\n"; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index ec2ede8373831..13b3344dc7c39 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -366,8 +366,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorsharp_shift_filter_threshold); } - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { - m->updateModuleParams(p); + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { + if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 27b467b3c9a74..8cf80f3289e9c 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -171,8 +171,8 @@ void DynamicAvoidanceModuleManager::updateModuleParams( p->end_duration_to_avoid_oncoming_object); } - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { - m->updateModuleParams(p); + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { + if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index caa75927f4062..bfa1487f05411 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -246,8 +246,8 @@ void GoalPlannerModuleManager::updateModuleParams( [[maybe_unused]] std::string ns = name_ + "."; - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { - m->updateModuleParams(p); + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { + if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 18c669a207095..7c12579bf34f5 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -133,14 +133,14 @@ LaneChangeModuleManager::LaneChangeModuleManager( parameters_ = std::make_shared(p); } -std::shared_ptr LaneChangeModuleManager::createNewSceneModuleInstance() +std::unique_ptr LaneChangeModuleManager::createNewSceneModuleInstance() { if (type_ == LaneChangeModuleType::NORMAL) { - return std::make_shared( + return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } - return std::make_shared( + return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, std::make_unique(parameters_, direction_)); } @@ -155,8 +155,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector( parameters, ns + "finish_judge_lateral_threshold", p->finish_judge_lateral_threshold); - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { - m->updateModuleParams(p); + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { + if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } @@ -271,10 +271,10 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( avoidance_parameters_ = std::make_shared(p); } -std::shared_ptr +std::unique_ptr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { - return std::make_shared( + return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_); } diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp index 5c92d7ced6036..5a039a98f2e52 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp @@ -51,8 +51,8 @@ void SideShiftModuleManager::updateModuleParams( [[maybe_unused]] std::string ns = "side_shift."; // updateParam(parameters, ns + ..., ...); - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { - m->updateModuleParams(p); + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { + if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index 881da2b52720a..3b6801a7b0309 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -99,13 +99,17 @@ void StartPlannerModuleManager::updateModuleParams( [[maybe_unused]] std::string ns = name_ + "."; - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&](const auto & m) { - const auto start_planner_ptr = std::dynamic_pointer_cast(m); - start_planner_ptr->updateModuleParams(p); - start_planner_ptr->setInitialIsSimultaneousExecutableAsApprovedModule( - enable_simultaneous_execution_as_approved_module_); - start_planner_ptr->setInitialIsSimultaneousExecutableAsCandidateModule( - enable_simultaneous_execution_as_candidate_module_); + std::for_each(observers_.begin(), observers_.end(), [&](const auto & observer) { + if (!observer.expired()) { + const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); + if (start_planner_ptr) { + start_planner_ptr->updateModuleParams(p); + start_planner_ptr->setInitialIsSimultaneousExecutableAsApprovedModule( + enable_simultaneous_execution_as_approved_module_); + start_planner_ptr->setInitialIsSimultaneousExecutableAsCandidateModule( + enable_simultaneous_execution_as_candidate_module_); + } + } }); } } // namespace behavior_path_planner From d6351fc73a2745d66dadded05fca081fd09d0377 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 3 Aug 2023 12:59:56 +0900 Subject: [PATCH 084/266] feat(lane_change): improve lane change sampled acceleration (#4488) * feat(lane_change): improve lane change sampled acceleration Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../scene_module/lane_change/normal.hpp | 4 + .../utils/lane_change/utils.hpp | 10 ++- .../src/scene_module/lane_change/normal.cpp | 80 ++++++++++++++----- .../src/utils/lane_change/utils.cpp | 59 +++++++++++--- 4 files changed, 119 insertions(+), 34 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 9a937e0cfca49..a6a6d12a5642b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -104,6 +104,10 @@ class NormalLaneChange : public LaneChangeBase int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const override; + std::vector sampleLongitudinalAccValues( + const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes) const; + double calcPrepareDuration( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index e885313be3e81..dc8298720239c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -57,8 +57,16 @@ using tier4_autoware_utils::Polygon2d; double calcLaneChangeResampleInterval( const double lane_changing_length, const double lane_changing_velocity); +double calcMaximumLaneChangeLength( + const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const std::vector & shift_intervals, const double max_acc); + +double calcMinimumAcceleration( + const double current_velocity, const double min_longitudinal_acc, + const BehaviorPathPlannerParameters & params); + double calcMaximumAcceleration( - const PathWithLaneId & path, const Pose & current_pose, const double current_velocity, + const double current_velocity, const double current_max_velocity, const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params); double calcLaneChangingAcceleration( diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index cd344a40e3d8c..c684ffa10bdc6 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -497,6 +497,62 @@ int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) return std::abs(getRouteHandler()->getNumLaneToPreferredLane(lane, get_opposite_direction)); } +std::vector NormalLaneChange::sampleLongitudinalAccValues( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const +{ + if (prev_module_path_.points.empty()) { + return {}; + } + + const auto & common_parameters = planner_data_->parameters; + const auto & route_handler = *getRouteHandler(); + const auto current_pose = getEgoPose(); + const auto current_velocity = getEgoVelocity(); + + const auto longitudinal_acc_sampling_num = lane_change_parameters_->longitudinal_acc_sampling_num; + const auto vehicle_min_acc = + std::max(common_parameters.min_acc, lane_change_parameters_->min_longitudinal_acc); + const auto vehicle_max_acc = + std::min(common_parameters.max_acc, lane_change_parameters_->max_longitudinal_acc); + const double nearest_dist_threshold = common_parameters.ego_nearest_dist_threshold; + const double nearest_yaw_threshold = common_parameters.ego_nearest_yaw_threshold; + + const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prev_module_path_.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); + const double & max_path_velocity = + prev_module_path_.points.at(current_seg_idx).point.longitudinal_velocity_mps; + + // calculate minimum and maximum acceleration + const auto min_acc = utils::lane_change::calcMinimumAcceleration( + current_velocity, vehicle_min_acc, common_parameters); + const auto max_acc = utils::lane_change::calcMaximumAcceleration( + current_velocity, max_path_velocity, vehicle_max_acc, common_parameters); + + // if max acc is not positive, then we do the normal sampling + if (max_acc <= 0.0) { + return utils::lane_change::getAccelerationValues( + min_acc, max_acc, longitudinal_acc_sampling_num); + } + + // calculate maximum lane change length + const double max_lane_change_length = utils::lane_change::calcMaximumLaneChangeLength( + current_velocity, common_parameters, + route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()), max_acc); + + // if maximum lane change length is less than length to goal or the end of target lanes, only + // sample max acc + if (route_handler.isInGoalRouteSection(target_lanes.back())) { + const auto goal_pose = route_handler.getGoalPose(); + if (max_lane_change_length < utils::getSignedDistance(current_pose, goal_pose, target_lanes)) { + return {max_acc}; + } + } else if (max_lane_change_length < utils::getDistanceToEndOfLane(current_pose, target_lanes)) { + return {max_acc}; + } + + return utils::lane_change::getAccelerationValues(min_acc, max_acc, longitudinal_acc_sampling_num); +} + double NormalLaneChange::calcPrepareDuration( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { @@ -670,31 +726,14 @@ bool NormalLaneChange::getLaneChangePaths( const auto backward_path_length = common_parameters.backward_path_length; const auto forward_path_length = common_parameters.forward_path_length; const auto minimum_lane_changing_velocity = common_parameters.minimum_lane_changing_velocity; - const auto longitudinal_acc_sampling_num = lane_change_parameters_->longitudinal_acc_sampling_num; const auto lateral_acc_sampling_num = lane_change_parameters_->lateral_acc_sampling_num; - const auto min_longitudinal_acc = - std::max(common_parameters.min_acc, lane_change_parameters_->min_longitudinal_acc); - const auto max_longitudinal_acc = - std::min(common_parameters.max_acc, lane_change_parameters_->max_longitudinal_acc); - const auto finish_judge_buffer = common_parameters.lane_change_finish_judge_buffer; // get velocity - const auto current_velocity = getEgoTwist().linear.x; - - // compute maximum longitudinal deceleration and acceleration - const auto maximum_deceleration = std::invoke([&minimum_lane_changing_velocity, ¤t_velocity, - &min_longitudinal_acc, &common_parameters]() { - const double min_a = (minimum_lane_changing_velocity - current_velocity) / - common_parameters.lane_change_prepare_duration; - return std::clamp( - min_a, -std::abs(min_longitudinal_acc), -std::numeric_limits::epsilon()); - }); - const auto maximum_acceleration = utils::lane_change::calcMaximumAcceleration( - prev_module_path_, getEgoPose(), current_velocity, max_longitudinal_acc, common_parameters); + const auto current_velocity = getEgoVelocity(); // get sampling acceleration values - const auto longitudinal_acc_sampling_values = utils::lane_change::getAccelerationValues( - maximum_deceleration, maximum_acceleration, longitudinal_acc_sampling_num); + const auto longitudinal_acc_sampling_values = + sampleLongitudinalAccValues(current_lanes, target_lanes); const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); @@ -795,6 +834,7 @@ bool NormalLaneChange::getLaneChangePaths( std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); const double backward_buffer = num == 0 ? 0.0 : common_parameters.backward_length_buffer_for_end_of_lane; + const double finish_judge_buffer = common_parameters.lane_change_finish_judge_buffer; if ( s_start + lane_changing_length + finish_judge_buffer + backward_buffer + next_lane_change_buffer > diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 21bd524d8af02..b3688fdb1310e 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -61,24 +61,57 @@ double calcLaneChangeResampleInterval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } -double calcMaximumAcceleration( - const PathWithLaneId & path, const Pose & current_pose, const double current_velocity, - const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params) +double calcMaximumLaneChangeLength( + const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const std::vector & shift_intervals, const double max_acc) { - if (path.points.empty()) { - return max_longitudinal_acc; + if (shift_intervals.empty()) { + return 0.0; } - const double & nearest_dist_threshold = params.ego_nearest_dist_threshold; - const double & nearest_yaw_threshold = params.ego_nearest_yaw_threshold; + const double & finish_judge_buffer = common_param.lane_change_finish_judge_buffer; + const double & lateral_jerk = common_param.lane_changing_lateral_jerk; + const double & t_prepare = common_param.lane_change_prepare_duration; + + double vel = current_velocity; + double accumulated_length = 0.0; + for (const auto & shift_interval : shift_intervals) { + // prepare section + const double prepare_length = vel * t_prepare + 0.5 * max_acc * t_prepare * t_prepare; + vel = vel + max_acc * t_prepare; + + // lane changing section + const auto lat_acc = common_param.lane_change_lat_acc_map.find(vel); + const double t_lane_changing = + PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, lat_acc.second); + const double lane_changing_length = + vel * t_lane_changing + 0.5 * max_acc * t_lane_changing * t_lane_changing; + + accumulated_length += prepare_length + lane_changing_length + finish_judge_buffer; + vel = vel + max_acc * t_lane_changing; + } + accumulated_length += + common_param.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); - const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); - const double & max_path_velocity = - path.points.at(current_seg_idx).point.longitudinal_velocity_mps; - const double & prepare_duration = params.lane_change_prepare_duration; + return accumulated_length; +} - const double acc = (max_path_velocity - current_velocity) / prepare_duration; +double calcMinimumAcceleration( + const double current_velocity, const double min_longitudinal_acc, + const BehaviorPathPlannerParameters & params) +{ + const double min_lane_changing_velocity = params.minimum_lane_changing_velocity; + const double prepare_duration = params.lane_change_prepare_duration; + const double acc = (min_lane_changing_velocity - current_velocity) / prepare_duration; + return std::clamp(acc, -std::abs(min_longitudinal_acc), -std::numeric_limits::epsilon()); +} + +double calcMaximumAcceleration( + const double current_velocity, const double current_max_velocity, + const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params) +{ + const double prepare_duration = params.lane_change_prepare_duration; + const double acc = (current_max_velocity - current_velocity) / prepare_duration; return std::clamp(acc, 0.0, max_longitudinal_acc); } From 24870d960dce896519282d045d971e7c6a4af862 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 3 Aug 2023 16:36:32 +0900 Subject: [PATCH 085/266] feat(out_of_lane): ignore dynamic objects located in irrelevent lanelets (#4473) Signed-off-by: Maxime CLEMENT --- .../src/decisions.cpp | 30 ++++++++++++++++--- .../src/decisions.hpp | 9 ++++-- 2 files changed, 32 insertions(+), 7 deletions(-) diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp index 0fdd153b17530..163c8632e40c7 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp @@ -40,10 +40,31 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx) return dist / v; } +bool object_is_incoming( + const lanelet::BasicPoint2d & object_position, + const std::shared_ptr route_handler, + const lanelet::ConstLanelet & lane) +{ + const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); + if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; + for (const auto & lls : lanelets) + for (const auto & ll : lls) + if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; + return false; +} + std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const double min_confidence, const rclcpp::Logger & logger) + const std::shared_ptr route_handler, const double min_confidence, + const rclcpp::Logger & logger) { + // skip the dynamic object if it is not in a lane preceding the overlapped lane + // lane changes are intentionally not considered + const auto object_point = lanelet::BasicPoint2d( + object.kinematics.initial_pose_with_covariance.pose.position.x, + object.kinematics.initial_pose_with_covariance.pose.position.y); + if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; + const auto max_deviation = object.shape.dimensions.y * 2.0; auto worst_enter_time = std::optional(); @@ -244,7 +265,7 @@ bool ttc_condition( return collision_during_overlap || ttc_is_bellow_threshold; } -bool object_is_incoming( +bool will_collide_on_range( const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) { RCLCPP_DEBUG( @@ -277,7 +298,8 @@ bool should_not_enter( // skip objects that are already on the interval const auto enter_exit_time = params.objects_use_predicted_paths - ? object_time_to_range(object, range, params.objects_min_confidence, logger) + ? object_time_to_range( + object, range, inputs.route_handler, params.objects_min_confidence, logger) : object_time_to_range(object, range, inputs, logger); if (!enter_exit_time) { RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); @@ -286,7 +308,7 @@ bool should_not_enter( range_times.object.enter_time = enter_exit_time->first; range_times.object.exit_time = enter_exit_time->second; - if (object_is_incoming(range_times, params, logger)) return true; + if (will_collide_on_range(range_times, params, logger)) return true; } return false; } diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp index da183133e7728..bf6bf81e506cf 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp @@ -56,18 +56,21 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx); /// but may not exist (e.g,, predicted path ends before reaching the end of the range) /// @param [in] object dynamic object /// @param [in] range overlapping range +/// @param [in] route_handler route handler used to estimate the path of the dynamic object /// @param [in] min_confidence minimum confidence to consider a predicted path /// @param [in] logger ros logger /// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in /// the opposite direction, time at enter > time at exit std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const double min_confidence, const rclcpp::Logger & logger); + const std::shared_ptr route_handler, const double min_confidence, + const rclcpp::Logger & logger); /// @brief use the lanelet map to estimate the times when an object will reach the enter and exit /// points of an overlapping range /// @param [in] object dynamic object /// @param [in] range overlapping range -/// @param [in] lanelets objects to consider +/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route +/// handler, lanelets) /// @param [in] logger ros logger /// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in /// the opposite direction, time at enter > time at exit. @@ -79,7 +82,7 @@ std::optional> object_time_to_range( /// @param [in] range_times times when ego and the object enter/exit the range /// @param [in] params parameters /// @param [in] logger ros logger -bool object_is_incoming( +bool will_collide_on_range( const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); /// @brief check whether we should avoid entering the given range /// @param [in] range the range to check From 1f873b05b30114522ef0e834b242ba5e76addb72 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 3 Aug 2023 16:41:29 +0900 Subject: [PATCH 086/266] feat(tier4_state_rviz_plugin): add init by gnss button (#4392) Signed-off-by: Takagi, Isamu --- .../src/autoware_state_panel.cpp | 12 ++++++++++++ .../src/autoware_state_panel.hpp | 6 ++++++ 2 files changed, 18 insertions(+) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 8f4e56c84164e..aa1dcfcd1651d 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -166,6 +166,10 @@ QGroupBox * AutowareStatePanel::makeLocalizationGroup() localization_label_ptr_->setStyleSheet("border:1px solid black;"); grid->addWidget(localization_label_ptr_, 0, 0); + init_by_gnss_button_ptr_ = new QPushButton("Init by GNSS"); + connect(init_by_gnss_button_ptr_, SIGNAL(clicked()), SLOT(onClickInitByGnss())); + grid->addWidget(init_by_gnss_button_ptr_, 1, 0); + group->setLayout(grid); return group; } @@ -249,6 +253,9 @@ void AutowareStatePanel::onInitialize() "/api/localization/initialization_state", rclcpp::QoS{1}.transient_local(), std::bind(&AutowareStatePanel::onLocalization, this, _1)); + client_init_by_gnss_ = + raw_node_->create_client("/api/localization/initialize"); + // Motion sub_motion_ = raw_node_->create_subscription( "/api/motion/state", rclcpp::QoS{1}.transient_local(), @@ -587,6 +594,11 @@ void AutowareStatePanel::onClickClearRoute() callServiceWithoutResponse(client_clear_route_); } +void AutowareStatePanel::onClickInitByGnss() +{ + callServiceWithoutResponse(client_init_by_gnss_); +} + void AutowareStatePanel::onClickAcceptStart() { callServiceWithoutResponse(client_accept_start_); diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 3a9bd6a542401..eba3e4eacd275 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include #include @@ -51,6 +52,7 @@ class AutowareStatePanel : public rviz_common::Panel using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; using LocalizationInitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState; + using InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization; using MotionState = autoware_adapi_v1_msgs::msg::MotionState; using AcceptStart = autoware_adapi_v1_msgs::srv::AcceptStart; using MRMState = autoware_adapi_v1_msgs::msg::MrmState; @@ -69,6 +71,7 @@ public Q_SLOTS: // NOLINT for Qt void onClickAutowareControl(); void onClickDirectControl(); void onClickClearRoute(); + void onClickInitByGnss(); void onClickAcceptStart(); void onClickVelocityLimit(); void onClickEmergencyButton(); @@ -130,7 +133,10 @@ public Q_SLOTS: // NOLINT for Qt // Localization QLabel * localization_label_ptr_{nullptr}; + QPushButton * init_by_gnss_button_ptr_{nullptr}; + rclcpp::Subscription::SharedPtr sub_localization_; + rclcpp::Client::SharedPtr client_init_by_gnss_; void onLocalization(const LocalizationInitializationState::ConstSharedPtr msg); From 1e55eff715bcfceeee6a2f44b96e782d4c7c50ac Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 3 Aug 2023 23:17:36 +0900 Subject: [PATCH 087/266] fix(behavior_path_planner): drivable area front nearest segment index (#4489) Signed-off-by: Takayuki Murooka --- .../behavior_path_planner/src/utils/utils.cpp | 27 +++++++++++-------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 452277d50f60f..4b6deaac42d1b 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -81,28 +81,33 @@ template size_t findNearestSegmentIndexFromLateralDistance( const std::vector & points, const geometry_msgs::msg::Point & target_point) { - size_t closest_idx = motion_utils::findNearestSegmentIndex(points, target_point); - double min_lateral_dist = - std::fabs(motion_utils::calcLateralOffset(points, target_point, closest_idx)); - + std::optional closest_idx{std::nullopt}; + double min_lateral_dist = std::numeric_limits::max(); for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) { const double lon_dist = motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); const double segment_length = tier4_autoware_utils::calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); - if (lon_dist < 0.0 || segment_length < lon_dist) { - continue; - } - - const double lat_dist = - std::fabs(motion_utils::calcLateralOffset(points, target_point, seg_idx)); + const double lat_dist = [&]() { + if (lon_dist < 0.0) { + return tier4_autoware_utils::calcDistance2d(points.at(seg_idx), target_point); + } + if (segment_length < lon_dist) { + return tier4_autoware_utils::calcDistance2d(points.at(seg_idx + 1), target_point); + } + return std::abs(motion_utils::calcLateralOffset(points, target_point, seg_idx)); + }(); if (lat_dist < min_lateral_dist) { closest_idx = seg_idx; min_lateral_dist = lat_dist; } } - return closest_idx; + if (closest_idx) { + return *closest_idx; + } + + return motion_utils::findNearestSegmentIndex(points, target_point); } bool checkHasSameLane( From 5542693b6e37b8de6a2710cb9cc3ecfaace4cc3a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 3 Aug 2023 23:17:57 +0900 Subject: [PATCH 088/266] fix(obstacle_avoidance_planner): stop point insertion in looped path (#4486) Signed-off-by: Takayuki Murooka --- planning/obstacle_avoidance_planner/src/node.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index da82fb14ea6d8..d40d271112814 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -389,11 +389,18 @@ void ObstacleAvoidancePlanner::applyInputVelocity( const auto stop_idx = motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); if (stop_idx) { const auto input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.get()).pose; - const size_t stop_seg_idx = trajectory_utils::findEgoSegmentIndex( - output_traj_points, input_stop_pose, ego_nearest_param_); + // NOTE: motion_utils::findNearestSegmentIndex is used instead of + // trajectory_utils::findEgoSegmentIndex + // for the case where input_traj_points is much longer than output_traj_points, and the + // former has a stop point but the latter will not have. + const auto stop_seg_idx = motion_utils::findNearestSegmentIndex( + output_traj_points, input_stop_pose, ego_nearest_param_.dist_threshold, + ego_nearest_param_.yaw_threshold); // calculate and insert stop pose on output trajectory - trajectory_utils::insertStopPoint(output_traj_points, input_stop_pose, stop_seg_idx); + if (stop_seg_idx) { + trajectory_utils::insertStopPoint(output_traj_points, input_stop_pose, *stop_seg_idx); + } } time_keeper_ptr_->toc(__func__, " "); From 476d17d3e08a04aed439309fee5aa3eb2df05857 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 3 Aug 2023 23:24:08 +0900 Subject: [PATCH 089/266] feat(behavior_path_planner): change straight turn signal condition (#4507) --- .../src/turn_signal_decider.cpp | 31 ++++++++++--------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 78ea16dbc3c05..fa661aef06681 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -260,21 +260,24 @@ boost::optional TurnSignalDecider::getIntersectionTurnSignalInfo continue; } - if ( - (lane_attribute == "right" || lane_attribute == "left" || lane_attribute == "straight") && - dist_to_front_point < search_distance) { - // update map if necessary - if (desired_start_point_map_.find(lane_id) == desired_start_point_map_.end()) { - desired_start_point_map_.emplace(lane_id, current_pose); + constexpr double stop_velocity_threshold = 0.1; + if (dist_to_front_point < search_distance) { + if ( + lane_attribute == "right" || lane_attribute == "left" || + (lane_attribute == "straight" && current_vel < stop_velocity_threshold)) { + // update map if necessary + if (desired_start_point_map_.find(lane_id) == desired_start_point_map_.end()) { + desired_start_point_map_.emplace(lane_id, current_pose); + } + + TurnSignalInfo turn_signal_info{}; + turn_signal_info.desired_start_point = desired_start_point_map_.at(lane_id); + turn_signal_info.required_start_point = lane_front_pose; + turn_signal_info.required_end_point = get_required_end_point(combined_lane.centerline3d()); + turn_signal_info.desired_end_point = lane_back_pose; + turn_signal_info.turn_signal.command = signal_map.at(lane_attribute); + signal_queue.push(turn_signal_info); } - - TurnSignalInfo turn_signal_info{}; - turn_signal_info.desired_start_point = desired_start_point_map_.at(lane_id); - turn_signal_info.required_start_point = lane_front_pose; - turn_signal_info.required_end_point = get_required_end_point(combined_lane.centerline3d()); - turn_signal_info.desired_end_point = lane_back_pose; - turn_signal_info.turn_signal.command = signal_map.at(lane_attribute); - signal_queue.push(turn_signal_info); } } From 36991bcbf78cede44710fec6ff65073a9e0a257e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 4 Aug 2023 01:56:33 +0900 Subject: [PATCH 090/266] fix(start_planner): invalid lane id access (#4511) Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 51106847ed651..23232f9b26681 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -551,7 +551,9 @@ lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & p lanelet::ConstLanelets path_lanes; path_lanes.reserve(lane_ids.size()); for (const auto & id : lane_ids) { - path_lanes.push_back(lanelet_layer.get(id)); + if (id != lanelet::InvalId) { + path_lanes.push_back(lanelet_layer.get(id)); + } } return path_lanes; @@ -573,6 +575,11 @@ void StartPlannerModule::updatePullOutStatus() status_ = PullOutStatus(); } + // save pull out lanes which is generated using current pose before starting pull out + // (before approval) + status_.pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + // skip updating if enough time has not passed for preventing chattering between back and // start_planner if (!has_received_new_route && !last_pull_out_start_update_time_ && !status_.back_finished) { @@ -590,11 +597,6 @@ void StartPlannerModule::updatePullOutStatus() const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & goal_pose = planner_data_->route_handler->getGoalPose(); - // save pull out lanes which is generated using current pose before starting pull out - // (before approval) - status_.pull_out_lanes = start_planner_utils::getPullOutLanes( - planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // search pull out start candidates backward std::vector start_pose_candidates = searchPullOutStartPoses(); planWithPriority(start_pose_candidates, goal_pose, parameters_->search_priority); From 48e10b593a6b87cd352eebc56efd26fae7e9b056 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 4 Aug 2023 01:57:09 +0900 Subject: [PATCH 091/266] feat(start_planner): ignore objects out of pull out lanes for start pose search (#4513) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 23232f9b26681..ae1f9b24b886d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -623,6 +623,10 @@ std::vector StartPlannerModule::searchPullOutStartPoses() status_.pull_out_lanes, arc_position_pose.length - check_distance, arc_position_pose.length + check_distance); + // filter pull out lanes objects + const auto [pull_out_lane_objects, others] = + utils::separateObjectsByLanelets(*planner_data_->dynamic_object, status_.pull_out_lanes); + // lateral shift to current_pose const double distance_from_center_line = arc_position_pose.distance; for (auto & p : backward_shoulder_path.points) { @@ -665,7 +669,7 @@ std::vector StartPlannerModule::searchPullOutStartPoses() } if (utils::checkCollisionBetweenFootprintAndObjects( - local_vehicle_footprint, *backed_pose, *(planner_data_->dynamic_object), + local_vehicle_footprint, *backed_pose, pull_out_lane_objects, parameters_->collision_check_margin)) { break; // poses behind this has a collision, so break. } From 408f4eee66d027fa853d69fd8ac5c66eb18b788c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 4 Aug 2023 10:17:16 +0900 Subject: [PATCH 092/266] chore(start_planner): rename shoulder lane variables (#4512) chore(start_planner): rename variables Signed-off-by: kosuke55 --- .../scene_module/start_planner/start_planner_module.cpp | 7 +++---- .../src/utils/start_planner/geometric_pull_out.cpp | 2 +- .../src/utils/start_planner/shift_pull_out.cpp | 2 +- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index ae1f9b24b886d..c035834fb18da 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -517,10 +517,9 @@ PathWithLaneId StartPlannerModule::generateStopPath() const PathPointWithLaneId p{}; p.point.pose = pose; p.point.longitudinal_velocity_mps = 0.0; - lanelet::Lanelet closest_shoulder_lanelet; - lanelet::utils::query::getClosestLanelet( - status_.pull_out_lanes, pose, &closest_shoulder_lanelet); - p.lane_ids.push_back(closest_shoulder_lanelet.id()); + lanelet::Lanelet closest_lanelet; + lanelet::utils::query::getClosestLanelet(status_.pull_out_lanes, pose, &closest_lanelet); + p.lane_ids.push_back(closest_lanelet.id()); return p; }; diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 5561411dfbf39..4744651d802d7 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -39,7 +39,7 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p { PullOutPath output; - // combine road lane and shoulder lane + // combine road lane and pull out lane const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_.max_back_distance; const auto road_lanes = utils::getExtendedCurrentLanes( diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index ef6d55a7af4c6..106d01f01848b 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -62,7 +62,7 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) return boost::none; } - // extract objects in shoulder lane for collision check + // extract objects in pull out lane for collision check const auto [pull_out_lane_objects, others] = utils::separateObjectsByLanelets(*dynamic_objects, pull_out_lanes); From b487784734abbfad1b59cbc0f88afe06eb8fdded Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 4 Aug 2023 11:52:06 +0900 Subject: [PATCH 093/266] refactor(utils): remove unnecessary drivable area generation (#4291) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/utils/utils.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 4b6deaac42d1b..3c8e7850985d5 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2785,10 +2785,6 @@ BehaviorModuleOutput getReferencePath( shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); - // for old architecture - generateDrivableArea( - reference_path, expanded_lanes, false, false, p.vehicle_length, planner_data); - BehaviorModuleOutput output; output.path = std::make_shared(reference_path); output.reference_path = std::make_shared(reference_path); From cd09c426cb1cbb2c80d7ab56e7408930b71c5438 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 4 Aug 2023 14:33:55 +0900 Subject: [PATCH 094/266] feat(start_planner): use stop objects in pull out lanes for collision check (#4514) Signed-off-by: kosuke55 --- .../config/start_planner/start_planner.param.yaml | 1 + .../utils/start_planner/start_planner_parameters.hpp | 1 + .../src/scene_module/start_planner/manager.cpp | 1 + .../start_planner/start_planner_module.cpp | 6 ++++-- .../src/utils/start_planner/geometric_pull_out.cpp | 10 +++++++--- .../src/utils/start_planner/shift_pull_out.cpp | 6 ++++-- 6 files changed, 18 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 5ae5c99ff8224..60f292744025d 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -6,6 +6,7 @@ th_stopped_time: 1.0 collision_check_margin: 1.0 collision_check_distance_from_end: 1.0 + th_moving_object_velocity: 1.0 # shift pull out enable_shift_pull_out: true check_shift_path_lane_departure: false diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 8c21d065ef852..9abad1a2fbec6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -33,6 +33,7 @@ struct StartPlannerParameters double length_ratio_for_turn_signal_deactivation_near_intersection; double collision_check_margin; double collision_check_distance_from_end; + double th_moving_object_velocity; // shift pull out bool enable_shift_pull_out; bool check_shift_path_lane_departure; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index 3b6801a7b0309..bba0ffc99294a 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -42,6 +42,7 @@ StartPlannerModuleManager::StartPlannerModuleManager( p.collision_check_margin = node->declare_parameter(ns + "collision_check_margin"); p.collision_check_distance_from_end = node->declare_parameter(ns + "collision_check_distance_from_end"); + p.th_moving_object_velocity = node->declare_parameter(ns + "th_moving_object_velocity"); // shift pull out p.enable_shift_pull_out = node->declare_parameter(ns + "enable_shift_pull_out"); p.check_shift_path_lane_departure = diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index c035834fb18da..18e7c006e7ae4 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -622,9 +622,11 @@ std::vector StartPlannerModule::searchPullOutStartPoses() status_.pull_out_lanes, arc_position_pose.length - check_distance, arc_position_pose.length + check_distance); - // filter pull out lanes objects + // filter pull out lanes stop objects const auto [pull_out_lane_objects, others] = utils::separateObjectsByLanelets(*planner_data_->dynamic_object, status_.pull_out_lanes); + const auto pull_out_lane_stop_objects = + utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_->th_moving_object_velocity); // lateral shift to current_pose const double distance_from_center_line = arc_position_pose.distance; @@ -668,7 +670,7 @@ std::vector StartPlannerModule::searchPullOutStartPoses() } if (utils::checkCollisionBetweenFootprintAndObjects( - local_vehicle_footprint, *backed_pose, pull_out_lane_objects, + local_vehicle_footprint, *backed_pose, pull_out_lane_stop_objects, parameters_->collision_check_margin)) { break; // poses behind this has a collision, so break. } diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 4744651d802d7..2af34740b133b 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -66,12 +66,16 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p return {}; } - // collision check with objects in shoulder lanes + // collision check with stop objects in pull out lanes const auto arc_path = planner_.getArcPath(); - const auto [shoulder_lane_objects, others] = + const auto [pull_out_lane_objects, others] = utils::separateObjectsByLanelets(*(planner_data_->dynamic_object), pull_out_lanes); + const auto pull_out_lane_stop_objects = + utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_.th_moving_object_velocity); + if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, arc_path, shoulder_lane_objects, parameters_.collision_check_margin)) { + vehicle_footprint_, arc_path, pull_out_lane_stop_objects, + parameters_.collision_check_margin)) { return {}; } diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index 106d01f01848b..bd8d80884e08d 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -62,9 +62,11 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) return boost::none; } - // extract objects in pull out lane for collision check + // extract stop objects in pull out lane for collision check const auto [pull_out_lane_objects, others] = utils::separateObjectsByLanelets(*dynamic_objects, pull_out_lanes); + const auto pull_out_lane_stop_objects = + utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_.th_moving_object_velocity); // get safe path for (auto & pull_out_path : pull_out_paths) { @@ -109,7 +111,7 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) // check collision if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, path_start_to_end, pull_out_lane_objects, + vehicle_footprint_, path_start_to_end, pull_out_lane_stop_objects, parameters_.collision_check_margin)) { continue; } From 74d4e7548978face5985c190a4977758a411150f Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 4 Aug 2023 15:51:44 +0900 Subject: [PATCH 095/266] fix(behavior_path_planner): fix turn signal for lane change abort (#4520) Signed-off-by: Fumiya Watanabe --- .../src/scene_module/lane_change/normal.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index c684ffa10bdc6..3d2bb44ad8bc0 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -125,6 +125,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() if (isAbortState()) { output.reference_path = std::make_shared(prev_module_reference_path_); + output.turn_signal_info = prev_turn_signal_info_; return output; } From 7ebe65faa058fceed9ab481bd7438facb31410a9 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 4 Aug 2023 18:12:53 +0900 Subject: [PATCH 096/266] feat(workflow): run gpt review from forked pr (#4515) * feat(workflow): run gpt review from forked pr Signed-off-by: Yukihito Saito * only run when the label is added Signed-off-by: Yukihito Saito --------- Signed-off-by: Yukihito Saito --- .github/workflows/openai-pr-reviewer.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.github/workflows/openai-pr-reviewer.yaml b/.github/workflows/openai-pr-reviewer.yaml index ecd8d85769a95..0ba732b580204 100644 --- a/.github/workflows/openai-pr-reviewer.yaml +++ b/.github/workflows/openai-pr-reviewer.yaml @@ -5,10 +5,8 @@ permissions: pull-requests: write on: - pull_request: + pull_request_target: types: - - opened - - synchronize - labeled pull_request_review_comment: types: [created] From e39c9282e259bab7f2342a736019ce07a9076377 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Fri, 4 Aug 2023 17:36:41 +0800 Subject: [PATCH 097/266] feat(tier4_vehicle_rviz_plugin): add acceleration visualization plugin to RViz (#4506) * feat: add acceleration visualization plugin to RVIZ Signed-off-by: Owen-Liuyuxuan * feat: add RVIZ plugin for acceleration; remove limit text; debugging: property_label_scale_ not responding Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix Signed-off-by: Owen-Liuyuxuan * fix typo in acceleration Signed-off-by: Owen-Liuyuxuan * fix a bug in keeping using abs(accel) to compute meter angle; delete text of acceleration meter, and delte the parameter of property_label_value Signed-off-by: Owen-Liuyuxuan * feat: separate the setting of max/min emergency threshold; update max/min acceration; set threshold for reconfiguring emergency speed Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix --------- Signed-off-by: Owen-Liuyuxuan Co-authored-by: Owen-Liuyuxuan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../tier4_vehicle_rviz_plugin/CMakeLists.txt | 2 + common/tier4_vehicle_rviz_plugin/README.md | 17 +- .../icons/classes/AccelerationMeter.png | Bin 0 -> 18815 bytes .../plugins/plugin_description.xml | 4 + .../src/tools/acceleration_meter.cpp | 247 ++++++++++++++++++ .../src/tools/acceleration_meter.hpp | 96 +++++++ 6 files changed, 365 insertions(+), 1 deletion(-) create mode 100644 common/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png create mode 100644 common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp create mode 100644 common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp diff --git a/common/tier4_vehicle_rviz_plugin/CMakeLists.txt b/common/tier4_vehicle_rviz_plugin/CMakeLists.txt index 184fe34fd8e96..de535d3dace05 100644 --- a/common/tier4_vehicle_rviz_plugin/CMakeLists.txt +++ b/common/tier4_vehicle_rviz_plugin/CMakeLists.txt @@ -17,6 +17,7 @@ set(HEADERS src/tools/steering_angle.hpp src/tools/jsk_overlay_utils.hpp src/tools/velocity_history.hpp + src/tools/acceleration_meter.hpp ) ## Declare a C++ library @@ -26,6 +27,7 @@ ament_auto_add_library(tier4_vehicle_rviz_plugin SHARED src/tools/steering_angle.cpp src/tools/jsk_overlay_utils.cpp src/tools/velocity_history.cpp + src/tools/acceleration_meter.cpp ${HEADERS} ) diff --git a/common/tier4_vehicle_rviz_plugin/README.md b/common/tier4_vehicle_rviz_plugin/README.md index ffbefeb1d7652..09576ac327bec 100644 --- a/common/tier4_vehicle_rviz_plugin/README.md +++ b/common/tier4_vehicle_rviz_plugin/README.md @@ -5,7 +5,7 @@ Note that jsk_overlay_utils.cpp and jsk_overlay_utils.hpp are BSD license. ## Purpose -This plugin provides a visual and easy-to-understand display of vehicle speed, turn signal and steering status. +This plugin provides a visual and easy-to-understand display of vehicle speed, turn signal, steering status and acceleration. ## Inputs / Outputs @@ -16,6 +16,7 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t | `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | The topic is vehicle twist | | `/control/turn_signal_cmd` | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport` | The topic is status of turn signal | | `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | The topic is status of steering | +| `/localization/acceleration` | `geometry_msgs::msg::AccelWithCovarianceStamped` | The topic is the acceleration | ## Parameter @@ -64,6 +65,20 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t | `property_velocity_color_` | QColor | Qt::black | Color of velocity history | | `property_vel_max_` | float | 3.0 | Color Border Vel Max [m/s] | +#### AccelerationMeter + +| Name | Type | Default Value | Description | +| ----------------------------------- | ------ | -------------------- | ------------------------------------------------ | +| `property_normal_text_color_` | QColor | QColor(25, 255, 240) | Normal text color | +| `property_emergency_text_color_` | QColor | QColor(255, 80, 80) | Emergency acceleration color | +| `property_left_` | int | 896 | Left of the plotter window [px] | +| `property_top_` | int | 128 | Top of the plotter window [px] | +| `property_length_` | int | 256 | Height of the plotter window [px] | +| `property_value_height_offset_` | int | 0 | Height offset of the plotter window [px] | +| `property_value_scale_` | float | 1 / 6.667 | Value text scale | +| `property_emergency_threshold_max_` | float | 1.0 | Max acceleration threshold for emergency [m/s^2] | +| `property_emergency_threshold_min_` | float | -2.5 | Min acceleration threshold for emergency [m/s^2] | + ## Assumptions / Known limits TBD. diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png b/common/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml b/common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml index 35431a17d5937..65f7414831f8f 100644 --- a/common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml +++ b/common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml @@ -15,4 +15,8 @@ type="rviz_plugins::VelocityHistoryDisplay" base_class_type="rviz_common::Display"> + + diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp new file mode 100644 index 0000000000000..3b3810a782a91 --- /dev/null +++ b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp @@ -0,0 +1,247 @@ +// Copyright 2023 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 "acceleration_meter.hpp" + +#include +#include + +#include + +#include +namespace rviz_plugins +{ +AccelerationMeterDisplay::AccelerationMeterDisplay() +{ + const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL)); + + constexpr float hight_4k = 2160.0; + const float scale = static_cast(screen_info->height) / hight_4k; + const auto left = static_cast(std::round(896 * scale)); + const auto top = static_cast(std::round(128 * scale)); + const auto length = static_cast(std::round(256 * scale)); + + property_normal_text_color_ = new rviz_common::properties::ColorProperty( + "Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this); + property_emergency_text_color_ = new rviz_common::properties::ColorProperty( + "Emergency Color", QColor(255, 80, 80), "emergency text color", this, + SLOT(updateVisualization()), this); + property_left_ = new rviz_common::properties::IntProperty( + "Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this); + property_left_->setMin(0); + property_top_ = new rviz_common::properties::IntProperty( + "Top", top, "Top of the plotter window", this, SLOT(updateVisualization())); + property_top_->setMin(0); + + property_length_ = new rviz_common::properties::IntProperty( + "Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this); + property_length_->setMin(10); + property_value_height_offset_ = new rviz_common::properties::IntProperty( + "Value height offset", 0, "Height offset of the plotter window", this, + SLOT(updateVisualization())); + property_emergency_threshold_max_ = new rviz_common::properties::FloatProperty( + "Max Emergency Threshold", 1.0, "Max emergency threshold for acceleration", this, + SLOT(updateVisualization()), this); + property_emergency_threshold_max_->setMin(0.01); + property_emergency_threshold_min_ = new rviz_common::properties::FloatProperty( + "Min Emergency Threshold", -2.5, "Min emergency threshold for acceleration", this, + SLOT(updateVisualization()), this); + property_emergency_threshold_min_->setMax(-0.01); + property_value_scale_ = new rviz_common::properties::FloatProperty( + "Value Scale", 1.0 / 6.667, "Value scale", this, SLOT(updateVisualization()), this); + property_value_scale_->setMin(0.01); +} + +AccelerationMeterDisplay::~AccelerationMeterDisplay() +{ + if (initialized()) { + overlay_->hide(); + } +} + +void AccelerationMeterDisplay::onInitialize() +{ + RTDClass::onInitialize(); + static int count = 0; + rviz_common::UniformStringStream ss; + ss << "AccelerationMeterDisplayObject" << count++; + overlay_.reset(new jsk_rviz_plugins::OverlayObject(ss.str())); + + overlay_->show(); + + overlay_->updateTextureSize(property_length_->getInt(), property_length_->getInt()); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); +} + +void AccelerationMeterDisplay::onEnable() +{ + subscribe(); + overlay_->show(); +} + +void AccelerationMeterDisplay::onDisable() +{ + unsubscribe(); + reset(); + overlay_->hide(); +} + +void AccelerationMeterDisplay::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; + (void)ros_dt; + + double acceleration_x = 0; + { + std::lock_guard message_lock(mutex_); + if (last_msg_ptr_) { + acceleration_x = last_msg_ptr_->accel.accel.linear.x; + } + } + + QColor background_color; + background_color.setAlpha(0); + jsk_rviz_plugins::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(background_color); + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + const int w = overlay_->getTextureWidth() - line_width_; + const int h = overlay_->getTextureHeight() - line_width_; + + // meter + QColor white_color(Qt::white); + white_color.setAlpha(255); + const float acceleration_ratio = std::min( + std::max(acceleration_x - meter_min_acceleration_, 0.0) / + (meter_max_acceleration_ - meter_min_acceleration_), + 1.0); + const float theta = + (acceleration_ratio * (meter_max_angle_ - meter_min_angle_)) + meter_min_angle_ + M_PI_2; + + painter.setPen(QPen(white_color, hand_width_, Qt::SolidLine)); + painter.drawLine( + w * 0.5, h * 0.5, + (w * 0.5) + + (static_cast(w) * 0.5 - (static_cast(hand_width_) * 0.5)) * std::cos(theta), + (h * 0.5) + + (static_cast(h) * 0.5 - (static_cast(hand_width_) * 0.5)) * std::sin(theta)); + + painter.setPen(QPen(white_color, line_width_, Qt::SolidLine)); + painter.drawLine(min_range_line_.x0, min_range_line_.y0, min_range_line_.x1, min_range_line_.y1); + painter.drawLine(max_range_line_.x0, max_range_line_.y0, max_range_line_.x1, max_range_line_.y1); + painter.drawArc( + outer_arc_.x0, outer_arc_.y0, outer_arc_.x1, outer_arc_.y1, outer_arc_.start_angle * 16, + outer_arc_.end_angle * 16); + painter.drawArc( + inner_arc_.x0, inner_arc_.y0, inner_arc_.x1, inner_arc_.y1, inner_arc_.start_angle * 16, + inner_arc_.end_angle * 16); + + // text + QColor text_color; + if ( + (acceleration_x > property_emergency_threshold_max_->getFloat()) || + (acceleration_x < + property_emergency_threshold_min_ + ->getFloat())) { // Write in Red if acceleration is over emergency threshold. + text_color = property_emergency_text_color_->getColor(); + } else { + text_color = property_normal_text_color_->getColor(); + } + text_color.setAlpha(255); + painter.setPen(QPen(text_color, static_cast(2), Qt::SolidLine)); + QFont font = painter.font(); + font.setPixelSize( + std::max(static_cast(static_cast(w) * property_value_scale_->getFloat()), 1)); + font.setBold(true); + painter.setFont(font); + std::ostringstream acceleration_ss; + // Write acceleration in m/s^2 for debugging usage. + acceleration_ss << std::fixed << std::setprecision(2) << acceleration_x << "m/s^2"; + painter.drawText( + 0, std::min(property_value_height_offset_->getInt(), h - 1), w, + std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignCenter | Qt::AlignVCenter, + acceleration_ss.str().c_str()); + + painter.end(); + updateVisualization(); +} + +void AccelerationMeterDisplay::processMessage( + const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg_ptr) +{ + if (!isEnabled()) { + return; + } + + { + std::lock_guard message_lock(mutex_); + last_msg_ptr_ = msg_ptr; + } + + queueRender(); +} + +void AccelerationMeterDisplay::updateVisualization() +{ + // Transferred from ConsoleMeter for unified design + overlay_->updateTextureSize(property_length_->getInt(), property_length_->getInt()); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); + const float min_range_theta = meter_max_angle_ + M_PI_2; + const float max_range_theta = meter_min_angle_ + M_PI_2; + const int w = overlay_->getTextureWidth() - line_width_; + const int h = overlay_->getTextureHeight() - line_width_; + + min_range_line_.x0 = + (w / 2.0) + line_width_ / 2.0 + (static_cast(w) / 8.0) * std::cos(min_range_theta); + min_range_line_.y0 = + (h / 2.0) + line_width_ / 2.0 + (static_cast(h) / 8.0) * std::sin(min_range_theta); + min_range_line_.x1 = + (w / 2.0) + line_width_ / 2.0 + + (static_cast(w) / 2.0 - (line_width_ / 2.0)) * std::cos(min_range_theta); + min_range_line_.y1 = + (h / 2.0) + line_width_ / 2.0 + + (static_cast(h) / 2.0 - (line_width_ / 2.0)) * std::sin(min_range_theta); + max_range_line_.x0 = + (w / 2.0) + line_width_ / 2.0 + (static_cast(w) / 8.0) * std::cos(max_range_theta); + max_range_line_.y0 = + (h / 2.0) + line_width_ / 2.0 + (static_cast(h) / 8.0) * std::sin(max_range_theta); + max_range_line_.x1 = + (w * 0.5) + line_width_ * 0.5 + + (static_cast(w) / 2.0 - (line_width_ * 0.5)) * std::cos(max_range_theta); + max_range_line_.y1 = + (h * 0.5) + line_width_ * 0.5 + + (static_cast(h) / 2.0 - (line_width_ * 0.5)) * std::sin(max_range_theta); + inner_arc_.x0 = line_width_ / 2.0; + inner_arc_.y0 = line_width_ / 2.0; + inner_arc_.x1 = w; + inner_arc_.y1 = h; + inner_arc_.start_angle = tier4_autoware_utils::rad2deg(min_range_theta - M_PI); + inner_arc_.end_angle = tier4_autoware_utils::rad2deg(max_range_theta - min_range_theta); + outer_arc_.x0 = w * 3 / 8; + outer_arc_.y0 = h * 3 / 8; + outer_arc_.x1 = w / 4; + outer_arc_.y1 = h / 4; + outer_arc_.start_angle = tier4_autoware_utils::rad2deg(min_range_theta - M_PI); + outer_arc_.end_angle = tier4_autoware_utils::rad2deg(max_range_theta - min_range_theta); +} + +} // namespace rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::AccelerationMeterDisplay, rviz_common::Display) diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp new file mode 100644 index 0000000000000..371480eccdbce --- /dev/null +++ b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp @@ -0,0 +1,96 @@ +// Copyright 2023 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 TOOLS__ACCELERATION_METER_HPP_ +#define TOOLS__ACCELERATION_METER_HPP_ + +#include +#include + +#ifndef Q_MOC_RUN +#include "jsk_overlay_utils.hpp" + +#include +#include +#include +#include +#include + +#include +#endif + +namespace rviz_plugins +{ +class AccelerationMeterDisplay +: public rviz_common::RosTopicDisplay +{ + Q_OBJECT + +public: + AccelerationMeterDisplay(); + ~AccelerationMeterDisplay() override; + + void onInitialize() override; + void onDisable() override; + void onEnable() override; + +private Q_SLOTS: + void updateVisualization(); + +protected: + void update(float wall_dt, float ros_dt) override; + void processMessage( + const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg_ptr) override; + jsk_rviz_plugins::OverlayObject::Ptr overlay_; + rviz_common::properties::ColorProperty * property_normal_text_color_; + rviz_common::properties::ColorProperty * property_emergency_text_color_; + rviz_common::properties::IntProperty * property_left_; + rviz_common::properties::IntProperty * property_top_; + rviz_common::properties::IntProperty * property_length_; + rviz_common::properties::IntProperty * property_value_height_offset_; + rviz_common::properties::FloatProperty * property_value_scale_; + rviz_common::properties::FloatProperty * property_emergency_threshold_max_; + rviz_common::properties::FloatProperty * property_emergency_threshold_min_; + // QImage hud_; + +private: + static constexpr float meter_min_acceleration_ = -10.0f; + static constexpr float meter_max_acceleration_ = 10.0f; + static constexpr float meter_min_angle_ = tier4_autoware_utils::deg2rad(40.f); + static constexpr float meter_max_angle_ = tier4_autoware_utils::deg2rad(320.f); + static constexpr int line_width_ = 2; + static constexpr int hand_width_ = 4; + struct Line // for drawLine + { + int x0, y0; + int x1, y1; + }; + Line min_range_line_; + Line max_range_line_; + struct Arc // for drawArc + { + int x0, y0; + int x1, y1; + float start_angle, end_angle; + }; + Arc inner_arc_; + Arc outer_arc_; + + std::mutex mutex_; + geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr last_msg_ptr_; +}; + +} // namespace rviz_plugins + +#endif // TOOLS__ACCELERATION_METER_HPP_ From 4811435ef1ae80a0ec47dc66a6295ffde645f0ae Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 5 Aug 2023 10:51:27 +0900 Subject: [PATCH 098/266] feat(dynamic_avoidance): memorize previous object information (#4433) * feat(dynamic_avoidance): refactor previous info access Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 166 ++++++---- .../dynamic_avoidance_module.cpp | 307 +++++++++--------- .../dynamic_avoidance/manager.cpp | 5 + 3 files changed, 278 insertions(+), 200 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 6b18db98f156e..71cfddaa24d56 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -35,6 +35,12 @@ namespace behavior_path_planner { +struct MinMaxValue +{ + double min_value; + double max_value; +}; + struct DynamicAvoidanceParameters { // common @@ -51,6 +57,7 @@ struct DynamicAvoidanceParameters bool avoid_pedestrian{false}; double min_obstacle_vel{0.0}; int successive_num_to_entry_dynamic_avoidance_condition{0}; + int successive_num_to_exit_dynamic_avoidance_condition{0}; double min_obj_lat_offset_to_ego_path{0.0}; double max_obj_lat_offset_to_ego_path{0.0}; @@ -82,14 +89,17 @@ class DynamicAvoidanceModule : public SceneModuleInterface { DynamicAvoidanceObject( const PredictedObject & predicted_object, const double arg_vel, const double arg_lat_vel, - const bool arg_is_collision_left, const double arg_time_to_collision) + const bool arg_is_collision_left, const double arg_time_to_collision, + const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid) : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), shape(predicted_object.shape), vel(arg_vel), lat_vel(arg_lat_vel), is_collision_left(arg_is_collision_left), - time_to_collision(arg_time_to_collision) + time_to_collision(arg_time_to_collision), + lon_offset_to_avoid(arg_lon_offset_to_avoid), + lat_offset_to_avoid(arg_lat_offset_to_avoid) { for (const auto & path : predicted_object.kinematics.predicted_paths) { predicted_paths.push_back(path); @@ -103,25 +113,103 @@ class DynamicAvoidanceModule : public SceneModuleInterface double lat_vel; bool is_collision_left; double time_to_collision; + MinMaxValue lon_offset_to_avoid; + MinMaxValue lat_offset_to_avoid; std::vector predicted_paths{}; }; - struct DynamicAvoidanceObjectCandidate + + struct TargetObjectsManager { - DynamicAvoidanceObject object; - int alive_counter; + TargetObjectsManager(const int arg_max_count, const int arg_min_count) + : max_count_(arg_max_count), min_count_(arg_min_count) + { + } + int max_count_; + int min_count_; + + void initialize() { current_uuids_.clear(); } + void updateObject(const std::string & uuid, const DynamicAvoidanceObject & object) + { + // add/update object + if (object_map_.count(uuid) != 0) { + object_map_.at(uuid) = object; + } else { + object_map_.emplace(uuid, object); + } + + // increase counter + if (counter_map_.count(uuid) != 0) { + counter_map_.at(uuid) = std::min(max_count_ + 1, std::max(1, counter_map_.at(uuid) + 1)); + } else { + counter_map_.emplace(uuid, 1); + } + + // memorize uuid + current_uuids_.push_back(uuid); + } - static std::optional getObjectFromUuid( - const std::vector & objects, const std::string & target_uuid) + void finalize() { - const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) { - return object.object.uuid == target_uuid; - }); + // decrease counter for not updated uuids + std::vector not_updated_uuids; + for (const auto & object : object_map_) { + if ( + std::find(current_uuids_.begin(), current_uuids_.end(), object.first) == + current_uuids_.end()) { + not_updated_uuids.push_back(object.first); + } + } + for (const auto & uuid : not_updated_uuids) { + if (counter_map_.count(uuid) != 0) { + counter_map_.at(uuid) = std::max(min_count_ - 1, std::min(-1, counter_map_.at(uuid) - 1)); + } else { + counter_map_.emplace(uuid, -1); + } + } - if (itr == objects.end()) { + // remove objects whose counter is lower than threshold + std::vector obsolete_uuids; + for (const auto & counter : counter_map_) { + if (counter.second < min_count_) { + obsolete_uuids.push_back(counter.first); + } + } + for (const auto & obsolete_uuid : obsolete_uuids) { + counter_map_.erase(obsolete_uuid); + object_map_.erase(obsolete_uuid); + } + } + std::vector getValidObjects() const + { + std::vector objects; + for (const auto & object : object_map_) { + if (counter_map_.count(object.first) != 0) { + if (max_count_ <= counter_map_.at(object.first)) { + objects.push_back(object.second); + } + } + } + return objects; + } + std::optional getValidObject(const std::string & uuid) const + { + // add/update object + if (counter_map_.count(uuid) == 0) { + return std::nullopt; + } + if (counter_map_.at(uuid) < max_count_) { return std::nullopt; } - return *itr; + if (object_map_.count(uuid) == 0) { + return std::nullopt; + } + return object_map_.at(uuid); } + + std::vector current_uuids_; + // NOTE: positive is for meeting entrying condition, and negative is for exiting. + std::unordered_map counter_map_; + std::unordered_map object_map_; }; DynamicAvoidanceModule( @@ -157,7 +245,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface }; bool isLabelTargetObstacle(const uint8_t label) const; - std::vector calcTargetObjectsCandidate(); + void updateTargetObjects(); + std::optional> calcPathForObjectPolygon() const; bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; @@ -172,58 +261,25 @@ class DynamicAvoidanceModule : public SceneModuleInterface const std::vector & ego_path, const PredictedPath & obj_path) const; LatLonOffset getLateralLongitudinalOffset( const std::vector & ego_path, const PredictedObject & object) const; + MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( + const std::vector & path_points_for_object_polygon, + const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, + const double time_to_collision) const; + MinMaxValue calcMinMaxLateralOffsetToAvoid( + const std::vector & path_points_for_object_polygon, + const Polygon2d & obj_points, const bool is_collision_left, + const std::optional & prev_object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; std::optional calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; - std::vector - prev_target_objects_candidate_; std::vector target_objects_; // std::vector prev_target_objects_; std::shared_ptr parameters_; - struct ObjectsVariable - { - void resetCurrentUuids() { current_uuids_.clear(); } - void addCurrentUuid(const std::string & uuid) { current_uuids_.push_back(uuid); } - void removeCounterUnlessUpdated() - { - std::vector obsolete_uuids; - for (const auto & key_and_value : variable_) { - if ( - std::find(current_uuids_.begin(), current_uuids_.end(), key_and_value.first) == - current_uuids_.end()) { - obsolete_uuids.push_back(key_and_value.first); - } - } - - for (const auto & obsolete_uuid : obsolete_uuids) { - variable_.erase(obsolete_uuid); - } - } - - std::optional get(const std::string & uuid) const - { - if (variable_.count(uuid) != 0) { - return variable_.at(uuid); - } - return std::nullopt; - } - void update(const std::string & uuid, const double new_variable) - { - if (variable_.count(uuid) != 0) { - variable_.at(uuid) = new_variable; - } else { - variable_.emplace(uuid, new_variable); - } - } - - std::unordered_map variable_; - std::vector current_uuids_; - }; - mutable ObjectsVariable prev_objects_min_bound_lat_offset_; + TargetObjectsManager target_objects_manager_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index a90ded11d2dfe..689f68616d32d 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -41,13 +41,13 @@ geometry_msgs::msg::Point toGeometryPoint(const tier4_autoware_utils::Point2d & return geom_obj_point; } -std::pair getMinMaxValues(const std::vector & vec) +MinMaxValue getMinMaxValues(const std::vector & vec) { const size_t min_idx = std::distance(vec.begin(), std::min_element(vec.begin(), vec.end())); const size_t max_idx = std::distance(vec.begin(), std::max_element(vec.begin(), vec.end())); - return std::make_pair(vec.at(min_idx), vec.at(max_idx)); + return MinMaxValue{vec.at(min_idx), vec.at(max_idx)}; } void appendObjectMarker(MarkerArray & marker_array, const geometry_msgs::msg::Pose & obj_pose) @@ -187,7 +187,11 @@ DynamicAvoidanceModule::DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{std::move(parameters)} +: SceneModuleInterface{name, node, rtc_interface_ptr_map}, + parameters_{std::move(parameters)}, + target_objects_manager_{TargetObjectsManager( + parameters_->successive_num_to_entry_dynamic_avoidance_condition, + parameters_->successive_num_to_exit_dynamic_avoidance_condition)} { } @@ -223,18 +227,10 @@ bool DynamicAvoidanceModule::isExecutionReady() const void DynamicAvoidanceModule::updateData() { - // calculate target objects candidate - const auto target_objects_candidate = calcTargetObjectsCandidate(); + // calculate target objects + updateTargetObjects(); - // calculate target objects considering flickering suppress - target_objects_.clear(); - for (const auto & target_object_candidate : target_objects_candidate) { - if ( - parameters_->successive_num_to_entry_dynamic_avoidance_condition <= - target_object_candidate.alive_counter) { - target_objects_.push_back(target_object_candidate.object); - } - } + target_objects_ = target_objects_manager_.getValidObjects(); } ModuleStatus DynamicAvoidanceModule::updateState() @@ -258,7 +254,6 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() // create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; - prev_objects_min_bound_lat_offset_.resetCurrentUuids(); for (const auto & object : target_objects_) { const auto obstacle_poly = calcDynamicObstaclePolygon(object); if (obstacle_poly) { @@ -267,11 +262,8 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() appendObjectMarker(info_marker_, object.pose); appendExtractedPolygonMarker(debug_marker_, obstacle_poly.value()); - - prev_objects_min_bound_lat_offset_.addCurrentUuid(object.uuid); } } - prev_objects_min_bound_lat_offset_.removeCounterUnlessUpdated(); BehaviorModuleOutput output; output.path = prev_module_path; @@ -326,14 +318,17 @@ bool DynamicAvoidanceModule::isLabelTargetObstacle(const uint8_t label) const return false; } -std::vector -DynamicAvoidanceModule::calcTargetObjectsCandidate() +void DynamicAvoidanceModule::updateTargetObjects() { const auto prev_module_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; - // convert predicted objects to dynamic avoidance objects - std::vector output_objects_candidate; + const auto path_points_for_object_polygon = calcPathForObjectPolygon(); + if (!path_points_for_object_polygon) { + return; + } + + target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { const auto obj_uuid = tier4_autoware_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; @@ -342,6 +337,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() predicted_object.kinematics.predicted_paths.begin(), predicted_object.kinematics.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const auto prev_object = target_objects_manager_.getValidObject(obj_uuid); // 1. check label const bool is_label_target_obstacle = @@ -401,7 +397,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const auto lat_lon_offset = getLateralLongitudinalOffset(prev_module_path->points, predicted_object); - // 6. check if object will not cut in or cut out + // 7. check if object will not cut in or cut out const bool will_object_cut_in = willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel, lat_lon_offset); const bool will_object_cut_out = @@ -419,7 +415,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() continue; } - // 7. check if time to collision + // 8. check if time to collision const double time_to_collision = calcTimeToCollision(prev_module_path->points, obj_pose, obj_tangent_vel); if ( @@ -433,33 +429,60 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() obj_uuid.c_str()); continue; } + if (time_to_collision < -parameters_->duration_to_hold_avoidance_overtaking_object) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision is a small negative " + "value.", + obj_uuid.c_str()); + continue; + } - // calculate which side object will be against ego's path + // 9. calculate which side object will be against ego's path const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); const bool is_collision_left = future_obj_pose ? isLeft(prev_module_path->points, future_obj_pose->position) : is_object_left; - // 8. calculate alive counter for filtering objects - const auto prev_target_object_candidate = - DynamicAvoidanceObjectCandidate::getObjectFromUuid(prev_target_objects_candidate_, obj_uuid); - const int alive_counter = - prev_target_object_candidate - ? std::min( - parameters_->successive_num_to_entry_dynamic_avoidance_condition, - prev_target_object_candidate->alive_counter + 1) - : 0; + // 10. calculate longitudinal and lateral offset to avoid + const auto obj_points = tier4_autoware_utils::toPolygon2d(obj_pose, predicted_object.shape); + const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( + *path_points_for_object_polygon, obj_pose, obj_points, obj_tangent_vel, time_to_collision); + const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( + *path_points_for_object_polygon, obj_points, is_collision_left, prev_object); const auto target_object = DynamicAvoidanceObject( - predicted_object, obj_tangent_vel, obj_normal_vel, is_collision_left, time_to_collision); - const auto target_object_candidate = - DynamicAvoidanceObjectCandidate{target_object, alive_counter}; - output_objects_candidate.push_back(target_object_candidate); + predicted_object, obj_tangent_vel, obj_normal_vel, is_collision_left, time_to_collision, + lon_offset_to_avoid, lat_offset_to_avoid); + + target_objects_manager_.updateObject(obj_uuid, target_object); } + target_objects_manager_.finalize(); +} - prev_target_objects_candidate_ = output_objects_candidate; - return output_objects_candidate; +std::optional> DynamicAvoidanceModule::calcPathForObjectPolygon() + const +{ + const auto & ego_pose = getEgoPose(); + const auto & rh = planner_data_->route_handler; + + // get path with backward margin + lanelet::ConstLanelet current_lane; + if (!rh->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { + RCLCPP_ERROR( + rclcpp::get_logger("behavior_path_planner").get_child("dynamic_avoidance"), + "failed to find closest lanelet within route!!!"); + return std::nullopt; + } + + constexpr double forward_length = 100.0; + const double backward_length = 50.0; + const auto current_lanes = + rh->getLaneletSequence(current_lane, ego_pose, backward_length, forward_length); + const auto path = utils::getCenterLinePath( + *rh, current_lanes, ego_pose, backward_length, forward_length, planner_data_->parameters); + return path.points; } [[maybe_unused]] std::optional> @@ -650,128 +673,85 @@ DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudi const auto obj_lon_min_max_offset = getMinMaxValues(obj_lon_offset_vec); return LatLonOffset{ - obj_seg_idx, obj_lat_min_max_offset.second, obj_lat_min_max_offset.first, - obj_lon_min_max_offset.second, obj_lon_min_max_offset.first}; + obj_seg_idx, obj_lat_min_max_offset.max_value, obj_lat_min_max_offset.min_value, + obj_lon_min_max_offset.max_value, obj_lon_min_max_offset.min_value}; } -// NOTE: object does not have const only to update min_bound_lat_offset. -std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( - const DynamicAvoidanceObject & object) const +MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( + const std::vector & path_points_for_object_polygon, + const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, + const double time_to_collision) const { - const auto ego_pose = getEgoPose(); - const auto & rh = planner_data_->route_handler; - - // get path with backward margin - lanelet::ConstLanelet current_lane; - if (!rh->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("dynamic_avoidance"), - "failed to find closest lanelet within route!!!"); - return std::nullopt; - } - - auto path_with_backward_margin = [&]() { - constexpr double forward_length = 100.0; - const double backward_length = 50.0; - const auto current_lanes = - rh->getLaneletSequence(current_lane, ego_pose, backward_length, forward_length); - return utils::getCenterLinePath( - *rh, current_lanes, ego_pose, backward_length, forward_length, planner_data_->parameters); - }(); - const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(path_with_backward_margin.points, object.pose.position); - const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); - - // calculate min/max lateral offset from object to path - const auto [min_obj_lat_abs_offset, max_obj_lat_abs_offset] = [&]() { - std::vector obj_lat_abs_offset_vec; - for (size_t i = 0; i < obj_points.outer().size(); ++i) { - const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); - const size_t obj_point_seg_idx = - motion_utils::findNearestSegmentIndex(path_with_backward_margin.points, geom_obj_point); - const double obj_point_lat_offset = motion_utils::calcLateralOffset( - path_with_backward_margin.points, geom_obj_point, obj_point_seg_idx); - obj_lat_abs_offset_vec.push_back(std::abs(obj_point_lat_offset)); - } - return getMinMaxValues(obj_lat_abs_offset_vec); - }(); - const double min_obj_lat_offset = - min_obj_lat_abs_offset * (object.is_collision_left ? 1.0 : -1.0); - const double max_obj_lat_offset = - max_obj_lat_abs_offset * (object.is_collision_left ? 1.0 : -1.0); + motion_utils::findNearestSegmentIndex(path_points_for_object_polygon, obj_pose.position); // calculate min/max longitudinal offset from object to path - const auto obj_lon_offset = [&]() -> std::optional> { + const auto obj_lon_offset = [&]() { std::vector obj_lon_offset_vec; for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const double lon_offset = motion_utils::calcLongitudinalOffsetToSegment( - path_with_backward_margin.points, obj_seg_idx, geom_obj_point); + path_points_for_object_polygon, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } - const auto [raw_min_obj_lon_offset, raw_max_obj_lon_offset] = - getMinMaxValues(obj_lon_offset_vec); - if (object.time_to_collision < -parameters_->duration_to_hold_avoidance_overtaking_object) { - return std::nullopt; - } + const auto raw_obj_lon_offset = getMinMaxValues(obj_lon_offset_vec); - if (object.vel < 0) { - return std::make_pair( - raw_min_obj_lon_offset + object.vel * object.time_to_collision, raw_max_obj_lon_offset); + if (obj_vel < 0) { + return MinMaxValue{ + raw_obj_lon_offset.min_value + obj_vel * time_to_collision, raw_obj_lon_offset.max_value}; } // NOTE: If time to collision is considered here, the ego is close to the object when starting // avoidance. // The ego should start avoidance before overtaking. - return std::make_pair(raw_min_obj_lon_offset, raw_max_obj_lon_offset); + return raw_obj_lon_offset; }(); - if (!obj_lon_offset) { - return std::nullopt; - } - const double min_obj_lon_offset = obj_lon_offset->first; - const double max_obj_lon_offset = obj_lon_offset->second; - // calculate bound start and end index - const bool is_object_overtaking = (0.0 <= object.vel); - // TODO(murooka) use getEgoSpeed() instead of object.vel + const bool is_object_overtaking = (0.0 <= obj_vel); + // TODO(murooka) use getEgoSpeed() instead of obj_vel const double start_length_to_avoid = - std::abs(object.vel) * (is_object_overtaking - ? parameters_->start_duration_to_avoid_overtaking_object - : parameters_->start_duration_to_avoid_oncoming_object); + std::abs(obj_vel) * (is_object_overtaking + ? parameters_->start_duration_to_avoid_overtaking_object + : parameters_->start_duration_to_avoid_oncoming_object); const double end_length_to_avoid = - std::abs(object.vel) * (is_object_overtaking - ? parameters_->end_duration_to_avoid_overtaking_object - : parameters_->end_duration_to_avoid_oncoming_object); - const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( - obj_seg_idx, min_obj_lon_offset - start_length_to_avoid, path_with_backward_margin.points); - const size_t updated_obj_seg_idx = - (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 - : obj_seg_idx; - const auto lon_bound_end_idx_opt = motion_utils::insertTargetPoint( - updated_obj_seg_idx, max_obj_lon_offset + end_length_to_avoid, - path_with_backward_margin.points); + std::abs(obj_vel) * (is_object_overtaking ? parameters_->end_duration_to_avoid_overtaking_object + : parameters_->end_duration_to_avoid_oncoming_object); - if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { - // NOTE: The obstacle is longitudinally out of the ego's trajectory. - return std::nullopt; - } - const size_t lon_bound_start_idx = - lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); - const size_t lon_bound_end_idx = - lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() - : static_cast(path_with_backward_margin.points.size() - 1); + return MinMaxValue{ + obj_lon_offset.min_value - start_length_to_avoid, + obj_lon_offset.max_value + end_length_to_avoid}; +} + +MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( + const std::vector & path_points_for_object_polygon, + const Polygon2d & obj_points, const bool is_collision_left, + const std::optional & prev_object) const +{ + // calculate min/max lateral offset from object to path + const auto obj_lat_abs_offset = [&]() { + std::vector obj_lat_abs_offset_vec; + for (size_t i = 0; i < obj_points.outer().size(); ++i) { + const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); + const size_t obj_point_seg_idx = + motion_utils::findNearestSegmentIndex(path_points_for_object_polygon, geom_obj_point); + const double obj_point_lat_offset = motion_utils::calcLateralOffset( + path_points_for_object_polygon, geom_obj_point, obj_point_seg_idx); + obj_lat_abs_offset_vec.push_back(std::abs(obj_point_lat_offset)); + } + return getMinMaxValues(obj_lat_abs_offset_vec); + }(); + const double min_obj_lat_offset = obj_lat_abs_offset.min_value * (is_collision_left ? 1.0 : -1.0); + const double max_obj_lat_offset = obj_lat_abs_offset.max_value * (is_collision_left ? 1.0 : -1.0); // calculate bound min and max lateral offset const double min_bound_lat_offset = [&]() { const double raw_min_bound_lat_offset = - min_obj_lat_offset - - parameters_->lat_offset_from_obstacle * (object.is_collision_left ? 1.0 : -1.0); + min_obj_lat_offset - parameters_->lat_offset_from_obstacle * (is_collision_left ? 1.0 : -1.0); const double min_bound_lat_abs_offset_limit = planner_data_->parameters.vehicle_width / 2.0 - parameters_->max_lat_offset_to_avoid; - if (object.is_collision_left) { + if (is_collision_left) { if (raw_min_bound_lat_offset < min_bound_lat_abs_offset_limit) { return min_bound_lat_abs_offset_limit; } @@ -783,29 +763,66 @@ std::optional DynamicAvoidanceModule::calcDynam return raw_min_bound_lat_offset; }(); const double max_bound_lat_offset = - max_obj_lat_offset + - parameters_->lat_offset_from_obstacle * (object.is_collision_left ? 1.0 : -1.0); + max_obj_lat_offset + parameters_->lat_offset_from_obstacle * (is_collision_left ? 1.0 : -1.0); // filter min_bound_lat_offset - const auto prev_min_bound_lat_offset = prev_objects_min_bound_lat_offset_.get(object.uuid); + const auto prev_min_lat_avoid_to_offset = [&]() -> std::optional { + if (!prev_object) { + return std::nullopt; + } + return prev_object->lat_offset_to_avoid.min_value; + }(); const double filtered_min_bound_lat_offset = - prev_min_bound_lat_offset - ? signal_processing::lowpassFilter(min_bound_lat_offset, *prev_min_bound_lat_offset, 0.3) + prev_min_lat_avoid_to_offset + ? signal_processing::lowpassFilter(min_bound_lat_offset, *prev_min_lat_avoid_to_offset, 0.3) : min_bound_lat_offset; - prev_objects_min_bound_lat_offset_.update(object.uuid, filtered_min_bound_lat_offset); + + return MinMaxValue{filtered_min_bound_lat_offset, max_bound_lat_offset}; +} + +// NOTE: object does not have const only to update min_bound_lat_offset. +std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( + const DynamicAvoidanceObject & object) const +{ + auto path_points_for_object_polygon = calcPathForObjectPolygon(); + if (!path_points_for_object_polygon) { + return std::nullopt; + } + + const size_t obj_seg_idx = + motion_utils::findNearestSegmentIndex(*path_points_for_object_polygon, object.pose.position); + const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); + + const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( + obj_seg_idx, object.lon_offset_to_avoid.min_value, *path_points_for_object_polygon); + const size_t updated_obj_seg_idx = + (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 + : obj_seg_idx; + const auto lon_bound_end_idx_opt = motion_utils::insertTargetPoint( + updated_obj_seg_idx, object.lon_offset_to_avoid.max_value, *path_points_for_object_polygon); + + if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { + // NOTE: The obstacle is longitudinally out of the ego's trajectory. + return std::nullopt; + } + const size_t lon_bound_start_idx = + lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); + const size_t lon_bound_end_idx = + lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() + : static_cast(path_points_for_object_polygon->size() - 1); // create inner/outer bound points std::vector obj_inner_bound_points; std::vector obj_outer_bound_points; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { - obj_inner_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - path_with_backward_margin.points.at(i).point.pose, 0.0, filtered_min_bound_lat_offset, 0.0) - .position); - obj_outer_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - path_with_backward_margin.points.at(i).point.pose, 0.0, max_bound_lat_offset, 0.0) - .position); + obj_inner_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + path_points_for_object_polygon->at(i).point.pose, 0.0, + object.lat_offset_to_avoid.min_value, 0.0) + .position); + obj_outer_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + path_points_for_object_polygon->at(i).point.pose, 0.0, + object.lat_offset_to_avoid.max_value, 0.0) + .position); } // create obj_polygon from inner/outer bound points diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 8cf80f3289e9c..328639513af05 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -47,6 +47,8 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.min_obstacle_vel = node->declare_parameter(ns + "min_obstacle_vel"); p.successive_num_to_entry_dynamic_avoidance_condition = node->declare_parameter(ns + "successive_num_to_entry_dynamic_avoidance_condition"); + p.successive_num_to_exit_dynamic_avoidance_condition = + node->declare_parameter(ns + "successive_num_to_exit_dynamic_avoidance_condition"); p.min_obj_lat_offset_to_ego_path = node->declare_parameter(ns + "min_obj_lat_offset_to_ego_path"); @@ -120,6 +122,9 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "successive_num_to_entry_dynamic_avoidance_condition", p->successive_num_to_entry_dynamic_avoidance_condition); + updateParam( + parameters, ns + "successive_num_to_exit_dynamic_avoidance_condition", + p->successive_num_to_exit_dynamic_avoidance_condition); updateParam( parameters, ns + "min_obj_lat_offset_to_ego_path", p->min_obj_lat_offset_to_ego_path); From 9e0cfa81440de4160e94015330144118834173e0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 6 Aug 2023 00:07:18 +0900 Subject: [PATCH 099/266] feat(goal_planner): publish stop reason (#4530) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 1 - .../goal_planner/goal_planner_module.cpp | 17 +++++++---------- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 6789d70a7065b..aa25a16c94c4f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -80,7 +80,6 @@ struct PUllOverStatus bool prev_is_safe{false}; bool has_decided_velocity{false}; bool has_requested_approval{false}; - std::optional stop_pose{}; bool is_ready{false}; }; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index dd555af17d182..ebfe162d6188c 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -604,7 +604,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) if (status_.is_safe) { // clear stop pose when the path is safe and activated if (isActivated()) { - status_.stop_pose.reset(); + resetWallPoses(); } // keep stop if not enough time passed, @@ -819,6 +819,8 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() printParkingPositionError(); } + setStopReason(StopReason::GOAL_PLANNER, status_.pull_over_path->getFullPath()); + return output; } @@ -873,6 +875,8 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( {status_.pull_over_path->start_pose, modified_goal_pose_->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); + setStopReason(StopReason::GOAL_PLANNER, status_.pull_over_path->getFullPath()); + return out; } @@ -954,7 +958,7 @@ PathWithLaneId GoalPlannerModule::generateStopPath() // slow down for turn signal, insert stop point to stop_pose decelerateForTurnSignal(stop_pose, reference_path); - status_.stop_pose = stop_pose; + stop_pose_ = stop_pose; // slow down before the search area. if (search_start_offset_pose) { @@ -998,7 +1002,7 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const auto stop_idx = motion_utils::insertStopPoint(current_pose, *min_stop_distance, stop_path.points); if (stop_idx) { - status_.stop_pose = stop_path.points.at(*stop_idx).point.pose; + stop_pose_ = stop_path.points.at(*stop_idx).point.pose; } return stop_path; @@ -1476,13 +1480,6 @@ void GoalPlannerModule::setDebugData() add(createPoseMarkerArray( debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); } - - // Visualize stop pose - if (status_.stop_pose) { - add(createStopVirtualWallMarker( - *status_.stop_pose, "pull_over", clock_->now(), 0, - planner_data_->parameters.base_link2front)); - } } void GoalPlannerModule::printParkingPositionError() const From 1e700edff40aaf85f50be4048292da56f05c211c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 6 Aug 2023 00:07:38 +0900 Subject: [PATCH 100/266] fix(goal_planner): goal planner sudden decel (#4529) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index ebfe162d6188c..ec3efbdeb7bbb 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -915,6 +915,7 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const auto & route_handler = planner_data_->route_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & common_parameters = planner_data_->parameters; + const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; if (status_.current_lanes.empty()) { @@ -952,7 +953,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath() // if stop pose is closer than min_stop_distance, stop as soon as possible const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, stop_pose); const auto min_stop_distance = calcFeasibleDecelDistance(0.0); - if (min_stop_distance && ego_to_stop_distance + stop_distance_buffer_ < *min_stop_distance) { + const double eps_vel = 0.01; + const bool is_stopped = std::abs(current_vel) < eps_vel; + const double buffer = is_stopped ? stop_distance_buffer_ : 0.0; + if (min_stop_distance && ego_to_stop_distance + buffer < *min_stop_distance) { return generateFeasibleStopPath(); } @@ -1175,13 +1179,12 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c // distance to restart should be less than decide_path_distance. // otherwise, the goal would change immediately after departure. const bool is_separated_path = status_.pull_over_path->partial_paths.size() > 1; - constexpr double eps_vel = 0.01; const double distance_to_start = calcSignedArcLength( pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position); const double distance_to_restart = parameters_->decide_path_distance / 2; - if ( - is_separated_path && std::abs(current_vel) < eps_vel && - distance_to_start < distance_to_restart) { + const double eps_vel = 0.01; + const bool is_stopped = std::abs(current_vel) < eps_vel; + if (is_separated_path && is_stopped && distance_to_start < distance_to_restart) { return false; } @@ -1190,7 +1193,11 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c return false; } - if (distance_to_start + stop_distance_buffer_ < *current_to_stop_distance) { + // If the stop line is subtly exceeded, it is assumed that there is not enough distance to the + // starting point of parking, so to prevent this, once the vehicle has stopped, it also has a + // stop_distance_buffer to allow for the amount exceeded. + const double buffer = is_stopped ? stop_distance_buffer_ : 0.0; + if (distance_to_start + buffer < *current_to_stop_distance) { return false; } From 43e8e1697f3db919c0ab6b6b09f3ae6aa8be9039 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 6 Aug 2023 00:26:42 +0900 Subject: [PATCH 101/266] fix(start_plannere): do not request when modifed route is received (#4528) Signed-off-by: kosuke55 --- .../include/route_handler/route_handler.hpp | 4 ++++ planning/route_handler/src/route_handler.cpp | 9 +++++++++ 2 files changed, 13 insertions(+) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index b298d69949610..e17895a2f5018 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -97,6 +97,7 @@ class RouteHandler bool isInGoalRouteSection(const lanelet::ConstLanelet & lanelet) const; Pose getGoalPose() const; Pose getStartPose() const; + Pose getOriginalStartPose() const; lanelet::Id getGoalLaneId() const; bool getGoalLanelet(lanelet::ConstLanelet * goal_lanelet) const; std::vector getLanesBeforePose( @@ -375,6 +376,9 @@ class RouteHandler bool is_map_msg_ready_{false}; bool is_handler_ready_{false}; + // save original(not modified) route start pose for start planer execution + Pose original_start_pose_; + // non-const methods void setLaneletsFromRouteMsg(); diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 33d44851e73f1..4f50070ca64bb 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -173,6 +173,10 @@ bool RouteHandler::isRouteLooped(const RouteSections & route_sections) void RouteHandler::setRoute(const LaneletRoute & route_msg) { if (!isRouteLooped(route_msg.segments)) { + // if get not modified route but new route, reset original start pose + if (!route_ptr_ || route_ptr_->uuid != route_msg.uuid) { + original_start_pose_ = route_msg.start_pose; + } route_ptr_ = std::make_shared(route_msg); is_handler_ready_ = false; setLaneletsFromRouteMsg(); @@ -427,6 +431,11 @@ Pose RouteHandler::getStartPose() const return route_ptr_->start_pose; } +Pose RouteHandler::getOriginalStartPose() const +{ + return original_start_pose_; +} + Pose RouteHandler::getGoalPose() const { if (!route_ptr_) { From d5b849fbb9ec5d7099983081e82072cfe530c24e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 6 Aug 2023 03:04:24 +0900 Subject: [PATCH 102/266] chore(route_handler): add takayuki5168 to route handler code owner (#4531) Signed-off-by: kosuke55 --- planning/route_handler/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/route_handler/package.xml b/planning/route_handler/package.xml index fc38d02845796..ef2051d1b244a 100644 --- a/planning/route_handler/package.xml +++ b/planning/route_handler/package.xml @@ -8,6 +8,7 @@ Zulfaqar Azmi Yutaka Shimizu Kosuke Takeuchi + Takayuki Murooka Apache License 2.0 Fumiya Watanabe From 21ff4bdd2ce6ff67c1141f510f2c0260a7c79453 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 5 Aug 2023 18:29:23 +0000 Subject: [PATCH 103/266] chore: update CODEOWNERS (#4533) Signed-off-by: GitHub Co-authored-by: kosuke55 --- .github/CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 59e8a6f80832e..1c0587f1ac1d5 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -170,7 +170,7 @@ planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp planning/planning_validator/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp -planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp +planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp planning/rtc_auto_mode_manager/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp From 0fa8b57ce72355a0acee784afd5f3fbe2a5baeed Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Sun, 6 Aug 2023 15:50:17 +0900 Subject: [PATCH 104/266] chore(tier4_simulator_launch): launch camera and V2X fusion module in simple planning simulator (#4522) Signed-off-by: Tomohito Ando --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 6f83ca0793798..aef1e45f517b1 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -16,7 +16,8 @@ - + + From 404a3b1020d8e4703174898d30ffefdaa76aaaa7 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 7 Aug 2023 02:28:46 +0900 Subject: [PATCH 105/266] feat(lane_change): remove unused parameters (#4534) --- .../config/lane_change/lane_change.param.yaml | 1 - .../include/behavior_path_planner/parameters.hpp | 1 - .../behavior_path_planner/src/behavior_path_planner_node.cpp | 2 -- 3 files changed, 4 deletions(-) diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml index 8fabe8daa85b2..745fd3877fec6 100644 --- a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml +++ b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml @@ -8,7 +8,6 @@ lane_change_finish_judge_buffer: 2.0 # [m] lane_changing_lateral_jerk: 0.5 # [m/s3] - lateral_acc_switching_velocity: 4.0 #[m/s] minimum_lane_changing_velocity: 2.78 # [m/s] prediction_time_resolution: 0.5 # [s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 1fdf4e020d71f..e7d017477b177 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -100,7 +100,6 @@ struct BehaviorPathPlannerParameters // lane change parameters double lane_changing_lateral_jerk{0.5}; - double lateral_acc_switching_velocity{0.4}; double minimum_lane_changing_velocity{5.6}; double lane_change_prepare_duration{4.0}; double lane_change_finish_judge_buffer{3.0}; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 6037daef13abe..869de6cb4d103 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -337,8 +337,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() declare_parameter("lane_change.backward_length_buffer_for_end_of_lane"); p.lane_changing_lateral_jerk = declare_parameter("lane_change.lane_changing_lateral_jerk"); - p.lateral_acc_switching_velocity = - declare_parameter("lane_change.lateral_acc_switching_velocity"); p.lane_change_prepare_duration = declare_parameter("lane_change.prepare_duration"); p.minimum_lane_changing_velocity = declare_parameter("lane_change.minimum_lane_changing_velocity"); From 5dfa9d2a588665020561e706865774bcedf8cc4e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 7 Aug 2023 10:35:52 +0900 Subject: [PATCH 106/266] feat(dynamic_avoidance): precise cut-out decision (#4527) * feat(dynamic_avoidance): precise cut-out decision Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 47 ++++-- .../dynamic_avoidance_module.cpp | 158 ++++++++++++------ .../dynamic_avoidance/manager.cpp | 11 ++ 3 files changed, 154 insertions(+), 62 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 71cfddaa24d56..ab00bba507ee0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -64,6 +64,8 @@ struct DynamicAvoidanceParameters double min_time_to_start_cut_in{0.0}; double min_lon_offset_ego_to_cut_in_object{0.0}; + double max_time_from_outside_ego_path_for_cut_out{0.0}; + double min_cut_out_object_lat_vel{0.0}; double max_front_object_angle{0.0}; double min_crossing_object_vel{0.0}; double max_crossing_object_angle{0.0}; @@ -89,17 +91,15 @@ class DynamicAvoidanceModule : public SceneModuleInterface { DynamicAvoidanceObject( const PredictedObject & predicted_object, const double arg_vel, const double arg_lat_vel, - const bool arg_is_collision_left, const double arg_time_to_collision, - const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid) + const bool arg_is_object_on_ego_path, + const std::optional & arg_latest_time_inside_ego_path) : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), shape(predicted_object.shape), vel(arg_vel), lat_vel(arg_lat_vel), - is_collision_left(arg_is_collision_left), - time_to_collision(arg_time_to_collision), - lon_offset_to_avoid(arg_lon_offset_to_avoid), - lat_offset_to_avoid(arg_lat_offset_to_avoid) + is_object_on_ego_path(arg_is_object_on_ego_path), + latest_time_inside_ego_path(arg_latest_time_inside_ego_path) { for (const auto & path : predicted_object.kinematics.predicted_paths) { predicted_paths.push_back(path); @@ -111,11 +111,24 @@ class DynamicAvoidanceModule : public SceneModuleInterface autoware_auto_perception_msgs::msg::Shape shape; double vel; double lat_vel; - bool is_collision_left; - double time_to_collision; + bool is_object_on_ego_path; + std::optional latest_time_inside_ego_path{std::nullopt}; + std::vector predicted_paths{}; + MinMaxValue lon_offset_to_avoid; MinMaxValue lat_offset_to_avoid; - std::vector predicted_paths{}; + bool is_collision_left; + bool should_be_avoided{false}; + + void update( + const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, + const bool arg_is_collision_left, const bool arg_should_be_avoided) + { + lon_offset_to_avoid = arg_lon_offset_to_avoid; + lat_offset_to_avoid = arg_lat_offset_to_avoid; + is_collision_left = arg_is_collision_left; + should_be_avoided = arg_should_be_avoided; + } }; struct TargetObjectsManager @@ -205,6 +218,16 @@ class DynamicAvoidanceModule : public SceneModuleInterface } return object_map_.at(uuid); } + void updateObject( + const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, + const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, + const bool should_be_avoided) + { + if (object_map_.count(uuid) != 0) { + object_map_.at(uuid).update( + lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided); + } + } std::vector current_uuids_; // NOTE: positive is for meeting entrying condition, and negative is for exiting. @@ -251,7 +274,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; bool willObjectCutOut( - const double obj_tangent_vel, const double obj_normal_vel, const bool is_collision_left) const; + const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, + const std::optional & prev_object) const; bool isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const; double calcTimeToCollision( @@ -260,7 +284,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional> calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const; LatLonOffset getLateralLongitudinalOffset( - const std::vector & ego_path, const PredictedObject & object) const; + const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( const std::vector & path_points_for_object_polygon, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 689f68616d32d..04b4f1782ad51 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -181,6 +181,20 @@ bool isLeft( } return false; } + +template +std::optional getObstacleFromUuid( + const std::vector & obstacles, const std::string & target_uuid) +{ + const auto itr = std::find_if(obstacles.begin(), obstacles.end(), [&](const auto & obstacle) { + return obstacle.uuid == target_uuid; + }); + + if (itr == obstacles.end()) { + return std::nullopt; + } + return *itr; +} } // namespace DynamicAvoidanceModule::DynamicAvoidanceModule( @@ -230,7 +244,13 @@ void DynamicAvoidanceModule::updateData() // calculate target objects updateTargetObjects(); - target_objects_ = target_objects_manager_.getValidObjects(); + const auto target_objects_candidate = target_objects_manager_.getValidObjects(); + target_objects_.clear(); + for (const auto & target_object_candidate : target_objects_candidate) { + if (target_object_candidate.should_be_avoided) { + target_objects_.push_back(target_object_candidate); + } + } } ModuleStatus DynamicAvoidanceModule::updateState() @@ -328,32 +348,31 @@ void DynamicAvoidanceModule::updateTargetObjects() return; } + const auto prev_objects = target_objects_manager_.getValidObjects(); + + // 1. Rough filtering of target objects target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { const auto obj_uuid = tier4_autoware_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; const double obj_vel = predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; - const auto obj_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; }); - const auto prev_object = target_objects_manager_.getValidObject(obj_uuid); + const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); - // 1. check label + // 1.a. check label const bool is_label_target_obstacle = isLabelTargetObstacle(predicted_object.classification.front().label); if (!is_label_target_obstacle) { continue; } - // 2. check if velocity is large enough + // 1.b. check if velocity is large enough const auto [obj_tangent_vel, obj_normal_vel] = projectObstacleVelocityToTrajectory(prev_module_path->points, predicted_object); if (std::abs(obj_tangent_vel) < parameters_->min_obstacle_vel) { continue; } - // 3. check if object is not crossing ego's path + // 1.c. check if object is not crossing ego's path const double obj_angle = calcDiffAngleAgainstPath(prev_module_path->points, obj_pose); const bool is_obstacle_crossing_path = parameters_->max_crossing_object_angle < std::abs(obj_angle) && @@ -368,46 +387,80 @@ void DynamicAvoidanceModule::updateTargetObjects() continue; } - // 4. check if object is not to be followed by ego + // 1.e. check if object lateral offset to ego's path is small enough const double obj_dist_to_path = calcDistanceToPath(prev_module_path->points, obj_pose.position); + const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); + if (is_object_far_from_path) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since lateral offset is large.", obj_uuid.c_str()); + continue; + } + + // 1.f. calculate the object is on ego's path or not const bool is_object_on_ego_path = obj_dist_to_path < planner_data_->parameters.vehicle_width / 2.0 + parameters_->min_obj_lat_offset_to_ego_path; + + // 1.g. calculate latest time inside ego's path + const auto latest_time_inside_ego_path = [&]() -> std::optional { + if (!prev_object || !prev_object->latest_time_inside_ego_path) { + if (is_object_on_ego_path) { + return clock_->now(); + } + return std::nullopt; + } + if (is_object_on_ego_path) { + return clock_->now(); + } + return *prev_object->latest_time_inside_ego_path; + }(); + + const auto target_object = DynamicAvoidanceObject( + predicted_object, obj_tangent_vel, obj_normal_vel, is_object_on_ego_path, + latest_time_inside_ego_path); + target_objects_manager_.updateObject(obj_uuid, target_object); + } + target_objects_manager_.finalize(); + + // 2. Precise filtering of target objects and check if they should be avoided + for (const auto & object : target_objects_manager_.getValidObjects()) { + const auto obj_uuid = object.uuid; + const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); + const auto obj_path = *std::max_element( + object.predicted_paths.begin(), object.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + + // 2.a. check if object is not to be followed by ego + const double obj_angle = calcDiffAngleAgainstPath(prev_module_path->points, object.pose); const bool is_object_aligned_to_path = std::abs(obj_angle) < parameters_->max_front_object_angle || M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); - if (is_object_on_ego_path && is_object_aligned_to_path) { + if (object.is_object_on_ego_path && is_object_aligned_to_path) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, "[DynamicAvoidance] Ignore obstacle (%s) since it is to be followed.", obj_uuid.c_str()); continue; } - // 5. check if object lateral offset to ego's path is large enough - const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); - if (is_object_far_from_path) { - RCLCPP_INFO_EXPRESSION( - getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since lateral offset is large.", obj_uuid.c_str()); - continue; - } - - // 6. calculate which side object exists against ego's path - const bool is_object_left = isLeft(prev_module_path->points, obj_pose.position); + // 2.b. calculate which side object exists against ego's path + const bool is_object_left = isLeft(prev_module_path->points, object.pose.position); const auto lat_lon_offset = - getLateralLongitudinalOffset(prev_module_path->points, predicted_object); + getLateralLongitudinalOffset(prev_module_path->points, object.pose, object.shape); - // 7. check if object will not cut in or cut out + // 2.c. check if object will not cut in const bool will_object_cut_in = - willObjectCutIn(prev_module_path->points, obj_path, obj_tangent_vel, lat_lon_offset); - const bool will_object_cut_out = - willObjectCutOut(obj_tangent_vel, obj_normal_vel, is_object_left); + willObjectCutIn(prev_module_path->points, obj_path, object.vel, lat_lon_offset); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, "[DynamicAvoidance] Ignore obstacle (%s) since it will cut in.", obj_uuid.c_str()); continue; } + + // 2.d. check if object will not cut out + const bool will_object_cut_out = + willObjectCutOut(object.vel, object.lat_vel, is_object_left, prev_object); if (will_object_cut_out) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -415,14 +468,13 @@ void DynamicAvoidanceModule::updateTargetObjects() continue; } - // 8. check if time to collision + // 2.e. check if time to collision const double time_to_collision = - calcTimeToCollision(prev_module_path->points, obj_pose, obj_tangent_vel); + calcTimeToCollision(prev_module_path->points, object.pose, object.vel); if ( - (0 <= obj_tangent_vel && + (0 <= object.vel && parameters_->max_time_to_collision_overtaking_object < time_to_collision) || - (obj_tangent_vel <= 0 && - parameters_->max_time_to_collision_oncoming_object < time_to_collision)) { + (object.vel <= 0 && parameters_->max_time_to_collision_oncoming_object < time_to_collision)) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, "[DynamicAvoidance] Ignore obstacle (%s) since time to collision is large.", @@ -438,27 +490,24 @@ void DynamicAvoidanceModule::updateTargetObjects() continue; } - // 9. calculate which side object will be against ego's path + // 2.f. calculate which side object will be against ego's path const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); const bool is_collision_left = future_obj_pose ? isLeft(prev_module_path->points, future_obj_pose->position) : is_object_left; - // 10. calculate longitudinal and lateral offset to avoid - const auto obj_points = tier4_autoware_utils::toPolygon2d(obj_pose, predicted_object.shape); + // 2.g. calculate longitudinal and lateral offset to avoid + const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - *path_points_for_object_polygon, obj_pose, obj_points, obj_tangent_vel, time_to_collision); + *path_points_for_object_polygon, object.pose, obj_points, object.vel, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( *path_points_for_object_polygon, obj_points, is_collision_left, prev_object); - const auto target_object = DynamicAvoidanceObject( - predicted_object, obj_tangent_vel, obj_normal_vel, is_collision_left, time_to_collision, - lon_offset_to_avoid, lat_offset_to_avoid); - - target_objects_manager_.updateObject(obj_uuid, target_object); + const bool should_be_avoided = true; + target_objects_manager_.updateObject( + obj_uuid, lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided); } - target_objects_manager_.finalize(); } std::optional> DynamicAvoidanceModule::calcPathForObjectPolygon() @@ -582,20 +631,28 @@ bool DynamicAvoidanceModule::willObjectCutIn( } bool DynamicAvoidanceModule::willObjectCutOut( - const double obj_tangent_vel, const double obj_normal_vel, const bool is_collision_left) const + const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, + const std::optional & prev_object) const { // Ignore oncoming object if (obj_tangent_vel < 0) { return false; } - constexpr double object_lat_vel_thresh = 0.3; - if (is_collision_left) { - if (object_lat_vel_thresh < obj_normal_vel) { + if (prev_object && prev_object->latest_time_inside_ego_path) { + if ( + parameters_->max_time_from_outside_ego_path_for_cut_out < + (clock_->now() - *prev_object->latest_time_inside_ego_path).seconds()) { + return false; + } + } + + if (is_object_left) { + if (parameters_->min_cut_out_object_lat_vel < obj_normal_vel) { return true; } } else { - if (obj_normal_vel < -object_lat_vel_thresh) { + if (obj_normal_vel < -parameters_->min_cut_out_object_lat_vel) { return true; } } @@ -643,12 +700,11 @@ std::pair DynamicAvoidanceModule } DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudinalOffset( - const std::vector & ego_path, const PredictedObject & object) const + const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { - const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; - const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); - const auto obj_points = tier4_autoware_utils::toPolygon2d(obj_pose, object.shape); + const auto obj_points = tier4_autoware_utils::toPolygon2d(obj_pose, obj_shape); // TODO(murooka) calculation is not so accurate. std::vector obj_lat_offset_vec; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 328639513af05..87525068c8c34 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -60,6 +60,11 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.min_lon_offset_ego_to_cut_in_object = node->declare_parameter(ns + "cut_in_object.min_lon_offset_ego_to_object"); + p.max_time_from_outside_ego_path_for_cut_out = + node->declare_parameter(ns + "cut_out_object.max_time_from_outside_ego_path"); + p.min_cut_out_object_lat_vel = + node->declare_parameter(ns + "cut_out_object.min_object_lat_vel"); + p.max_front_object_angle = node->declare_parameter(ns + "front_object.max_object_angle"); @@ -137,6 +142,12 @@ void DynamicAvoidanceModuleManager::updateModuleParams( parameters, ns + "cut_in_object.min_lon_offset_ego_to_object", p->min_lon_offset_ego_to_cut_in_object); + updateParam( + parameters, ns + "cut_out_object.max_time_from_outside_ego_path", + p->max_time_from_outside_ego_path_for_cut_out); + updateParam( + parameters, ns + "cut_out_object.min_object_lat_vel", p->min_cut_out_object_lat_vel); + updateParam( parameters, ns + "front_object.max_object_angle", p->max_front_object_angle); From 95e008645ed0ffb2c77a8c641c9584e008c97208 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 7 Aug 2023 10:36:11 +0900 Subject: [PATCH 107/266] fix(behavior_path_planner): avoid infinity loop of polygons concatenation (#4535) * fix(behavior_path_planner): avoid infinity loop of polygons concatenation Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../behavior_path_planner/src/utils/utils.cpp | 81 +++++++++++++++---- 1 file changed, 66 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 3c8e7850985d5..088dd736e9d49 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -118,6 +118,12 @@ bool checkHasSameLane( const auto has_same = [&](const auto & ll) { return ll.id() == target_lane.id(); }; return std::find_if(lanelets.begin(), lanelets.end(), has_same) != lanelets.end(); } + +bool isSamePoint(const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2) +{ + constexpr double epsilon = 1e-3; + return std::abs(point1.x - point2.x) < epsilon && std::abs(point1.y - point2.y) < epsilon; +} } // namespace namespace behavior_path_planner::utils @@ -288,43 +294,88 @@ std::vector convertToGeometryPoints( return points; } +// NOTE: See the PR's figure. https://github.com/autowarefoundation/autoware.universe/pull/2880 std::vector concatenateTwoPolygons( const std::vector & front_polygon, const std::vector & back_polygon) { + const auto make_unique_polygon = [&](const auto & polygon) { + std::vector unique_polygon; + for (const auto & point : polygon) { + if (!unique_polygon.empty() && isSamePoint(unique_polygon.back().point, point.point)) { + continue; + } + unique_polygon.push_back(point); + } + return unique_polygon; + }; + const auto unique_front_polygon = make_unique_polygon(front_polygon); + const auto unique_back_polygon = make_unique_polygon(back_polygon); + // At first, the front polygon is the outside polygon bool is_front_polygon_outside = true; - size_t outside_idx = 0; + size_t before_outside_idx = 0; const auto get_out_poly = [&]() { - return is_front_polygon_outside ? front_polygon : back_polygon; + return is_front_polygon_outside ? unique_front_polygon : unique_back_polygon; }; const auto get_in_poly = [&]() { - return is_front_polygon_outside ? back_polygon : front_polygon; + return is_front_polygon_outside ? unique_back_polygon : unique_front_polygon; }; + // NOTE: Polygon points is assumed to be clock-wise. std::vector concatenated_polygon; - while (rclcpp::ok()) { - concatenated_polygon.push_back(get_out_poly().at(outside_idx)); - if (outside_idx == get_out_poly().size() - 1) { + // NOTE: Maximum number of loop is set to avoid infinity loop calculation just in case. + const size_t max_loop_num = (unique_front_polygon.size() + unique_back_polygon.size()) * 2; + for (size_t loop_idx = 0; loop_idx < max_loop_num; ++loop_idx) { + concatenated_polygon.push_back(get_out_poly().at(before_outside_idx)); + if (before_outside_idx == get_out_poly().size() - 1) { break; } - const size_t curr_idx = outside_idx; - const size_t next_idx = outside_idx + 1; + const size_t curr_idx = before_outside_idx; + const size_t next_idx = before_outside_idx + 1; + // NOTE: Two polygons may have two intersection points. Therefore the closest intersection + // point is used. + std::optional closest_idx = std::nullopt; + double min_dist_to_intersection = std::numeric_limits::max(); + PolygonPoint closest_intersect_point; for (size_t i = 0; i < get_in_poly().size() - 1; ++i) { const auto intersection = tier4_autoware_utils::intersect( get_out_poly().at(curr_idx).point, get_out_poly().at(next_idx).point, get_in_poly().at(i).point, get_in_poly().at(i + 1).point); - if (intersection) { - const auto intersect_point = PolygonPoint{*intersection, 0, 0.0, 0.0}; - concatenated_polygon.push_back(intersect_point); + if (!intersection) { + continue; + } + if ( + isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i).point) || + isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i + 1).point) || + isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i).point) || + isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i + 1).point)) { + // NOTE: If the segments shares one point, the while loop will not end. + continue; + } - is_front_polygon_outside = !is_front_polygon_outside; - outside_idx = i; - break; + const auto intersect_point = PolygonPoint{*intersection, 0, 0.0, 0.0}; + const double dist_to_intersection = + tier4_autoware_utils::calcDistance2d(get_out_poly().at(curr_idx).point, *intersection); + if (dist_to_intersection < min_dist_to_intersection) { + closest_idx = i; + min_dist_to_intersection = dist_to_intersection; + closest_intersect_point = intersect_point; } } - outside_idx += 1; + + if (closest_idx) { + before_outside_idx = *closest_idx; + concatenated_polygon.push_back(closest_intersect_point); + is_front_polygon_outside = !is_front_polygon_outside; + } + + before_outside_idx += 1; + + if (loop_idx == max_loop_num - 1) { + return front_polygon; + } } return concatenated_polygon; From c889d94b36f7b02bc371eb3f4ddc4d461d692433 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 7 Aug 2023 11:43:13 +0900 Subject: [PATCH 108/266] chore(ci): ignore perception/bytetrack/lib in spell-check-partial (#4517) * chore(ci): ignore perception/bytetrack/lib in spell-check-partial * style(pre-commit): autofix --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .cspell-partial.json | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index e7b32ed3ae53f..a3c4ca455d444 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -1,5 +1,10 @@ { - "ignorePaths": ["**/perception/**", "**/planning/**", "**/sensing/**"], + "ignorePaths": [ + "**/perception/**", + "**/planning/**", + "**/sensing/**", + "perception/bytetrack/lib/**" + ], "ignoreRegExpList": [], "words": [] } From 4a9a97d8bb9fd16df9ecbac7da5fd0b9fc4055c5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 7 Aug 2023 15:48:37 +0900 Subject: [PATCH 109/266] refactor(interface): rebuild state transition (#4518) * refactor(bpp): remove redundant header file Signed-off-by: satoshi-ota * refactor(bpp): move some interface function from public to protected Signed-off-by: satoshi-ota * refactor(interface): add new state and interface Signed-off-by: satoshi-ota * refactor(avoidance): support new state transition Signed-off-by: satoshi-ota * refactor(modules): support new interface Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner/module_status.hpp | 29 -- .../avoidance/avoidance_module.hpp | 14 +- .../dynamic_avoidance_module.hpp | 32 +- .../goal_planner/goal_planner_module.hpp | 12 +- .../scene_module/lane_change/interface.hpp | 28 +- .../scene_module/scene_module_interface.hpp | 306 ++++++++++++------ .../side_shift/side_shift_module.hpp | 27 +- .../start_planner/start_planner_module.hpp | 13 +- .../avoidance/avoidance_module.cpp | 159 ++++----- .../scene_module/lane_change/interface.cpp | 1 - 10 files changed, 392 insertions(+), 229 deletions(-) delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp diff --git a/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp b/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp deleted file mode 100644 index f6a7a10b21db1..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2023 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 BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ -#define BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ - -namespace behavior_path_planner -{ -enum class ModuleStatus { - IDLE = 0, - RUNNING = 1, - SUCCESS = 2, - FAILURE = 3, - // SKIPPED = 4, -}; -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 0d574f8c31c02..b6cc840a560f0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -51,7 +51,6 @@ class AvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map); - ModuleStatus updateState() override; CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; @@ -69,6 +68,12 @@ class AvoidanceModule : public SceneModuleInterface std::shared_ptr get_debug_msg_array() const; private: + bool canTransitSuccessState() override; + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return true; } + /** * @brief update RTC status for candidate shift line. * @param candidate path. @@ -177,6 +182,11 @@ class AvoidanceModule : public SceneModuleInterface */ void initRTCStatus(); + /** + * @brief update RTC status. + */ + void updateRTCData(); + // ego state check /** @@ -425,7 +435,7 @@ class AvoidanceModule : public SceneModuleInterface * @brief add new shift line to path shifter if the RTC status is activated. * @param new shift lines. */ - void addShiftLineIfApproved(const AvoidLineArray & point); + void updatePathShifter(const AvoidLineArray & point); /** * @brief add new shift line to path shifter. diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index ab00bba507ee0..bb9200514b848 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -230,7 +230,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface } std::vector current_uuids_; - // NOTE: positive is for meeting entrying condition, and negative is for exiting. + // NOTE: positive is for meeting entry condition, and negative is for exiting. std::unordered_map counter_map_; std::unordered_map object_map_; }; @@ -245,12 +245,32 @@ class DynamicAvoidanceModule : public SceneModuleInterface parameters_ = std::any_cast>(parameters); } + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override + { + updateData(); + + if (!isWaitingApproval()) { + return plan(); + } + + // module is waiting approval. Check it. + if (isActivated()) { + RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); + return plan(); + } else { + RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); + return planWaitingApproval(); + } + } + bool isExecutionRequested() const override; bool isExecutionReady() const override; - ModuleStatus updateState() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; - CandidateOutput planCandidate() const override; BehaviorModuleOutput planWaitingApproval() override; + CandidateOutput planCandidate() const override; void updateData() override; void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override @@ -267,6 +287,12 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double min_lon_offset; }; + bool canTransitSuccessState() override { return false; } + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return false; } + bool isLabelTargetObstacle(const uint8_t label) const; void updateTargetObjects(); std::optional> calcPathForObjectPolygon() const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index aa25a16c94c4f..2bf589a122087 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -96,10 +96,12 @@ class GoalPlannerModule : public SceneModuleInterface parameters_ = std::any_cast>(parameters); } - BehaviorModuleOutput run() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; - ModuleStatus updateState() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; void processOnEntry() override; @@ -114,6 +116,12 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; }; private: + bool canTransitSuccessState() override { return false; } + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return false; } + PUllOverStatus status_; std::shared_ptr parameters_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index c57e8f3b8b8b3..b7f84987e0499 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -73,7 +73,8 @@ class LaneChangeInterface : public SceneModuleInterface bool isExecutionReady() const override; - ModuleStatus updateState() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; void updateData() override; @@ -96,11 +97,36 @@ class LaneChangeInterface : public SceneModuleInterface TurnSignalInfo getCurrentTurnSignalInfo( const PathWithLaneId & path, const TurnSignalInfo & original_turn_signal_info); + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override + { + updateData(); + + if (!isWaitingApproval()) { + return plan(); + } + + // module is waiting approval. Check it. + if (isActivated()) { + RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); + return plan(); + } else { + RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); + return planWaitingApproval(); + } + } + protected: std::shared_ptr parameters_; std::unique_ptr module_type_; + bool canTransitSuccessState() override { return false; } + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return false; } + void resetPathIfAbort(); void resetLaneChangeModule(); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 0c60c6b73afb4..9f53defac2827 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -16,12 +16,12 @@ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_INTERFACE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/module_status.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/utils.hpp" #include #include +#include #include #include #include @@ -66,6 +66,14 @@ using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; using PlanResult = PathWithLaneId::SharedPtr; +enum class ModuleStatus { + IDLE = 0, + RUNNING = 1, + WAITING_APPROVAL = 2, + SUCCESS = 3, + FAILURE = 4, +}; + class SceneModuleInterface { public: @@ -75,9 +83,6 @@ class SceneModuleInterface : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, - is_waiting_approval_{false}, - is_locked_new_module_launch_{false}, - current_state_{ModuleStatus::IDLE}, rtc_interface_ptr_map_(rtc_interface_ptr_map), steering_factor_interface_ptr_( std::make_unique(&node, utils::convertToSnakeCase(name))) @@ -91,17 +96,22 @@ class SceneModuleInterface virtual void updateModuleParams(const std::any & parameters) = 0; - /** - * @brief Return SUCCESS if plan is not needed or plan is successfully finished, - * FAILURE if plan has failed, RUNNING if plan is on going. - * These condition is to be implemented in each modules. - */ - virtual ModuleStatus updateState() = 0; + virtual void acceptVisitor(const std::shared_ptr & visitor) const = 0; /** * @brief Set the current_state_ based on updateState output. */ - virtual void updateCurrentState() { current_state_ = updateState(); } + virtual void updateCurrentState() + { + const auto print = [this](const auto & from, const auto & to) { + RCLCPP_DEBUG( + getLogger(), "[%s] Transit from %s to %s.", name_.c_str(), from.data(), to.data()); + }; + + const auto & from = current_state_; + current_state_ = updateState(); + print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_)); + } /** * @brief Return true if the module has request for execution (not necessarily feasible) @@ -113,36 +123,6 @@ class SceneModuleInterface */ virtual bool isExecutionReady() const = 0; - /** - * @brief Calculate path. This function is called with the plan is approved. - */ - virtual BehaviorModuleOutput plan() = 0; - - /** - * @brief Calculate path under waiting_approval condition. - * The default implementation is just to return the reference path. - */ - virtual BehaviorModuleOutput planWaitingApproval() - { - BehaviorModuleOutput out; - out.path = utils::generateCenterLinePath(planner_data_); - const auto candidate = planCandidate(); - path_candidate_ = std::make_shared(candidate.path_candidate); - - // for new architecture - const auto lanes = utils::getLaneletsFromPath(*out.path, planner_data_->route_handler); - const auto drivable_lanes = utils::generateDrivableLanes(lanes); - out.drivable_area_info.drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, drivable_lanes, planner_data_->drivable_area_expansion_parameters); - - return out; - } - - /** - * @brief Get candidate path. This information is used for external judgement. - */ - virtual CandidateOutput planCandidate() const = 0; - /** * @brief update data for planning. Note that the call of this function does not mean * that the module executed. It should only updates the data necessary for @@ -157,19 +137,7 @@ class SceneModuleInterface virtual BehaviorModuleOutput run() { updateData(); - - if (!isWaitingApproval()) { - return plan(); - } - - // module is waiting approval. Check it. - if (isActivated()) { - RCLCPP_DEBUG(logger_, "Was waiting approval, and now approved. Do plan()."); - return plan(); - } else { - RCLCPP_DEBUG(logger_, "keep waiting approval... Do planCandidate()."); - return planWaitingApproval(); - } + return isWaitingApproval() ? planWaitingApproval() : plan(); } /** @@ -179,15 +147,11 @@ class SceneModuleInterface { RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); - current_state_ = ModuleStatus::IDLE; - stop_reason_ = StopReason(); processOnEntry(); } - virtual void processOnEntry() {} - /** * @brief Called when the module exit from RUNNING. */ @@ -195,7 +159,6 @@ class SceneModuleInterface { RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); - current_state_ = ModuleStatus::SUCCESS; clearWaitingApproval(); removeRTCStatus(); unlockNewModuleLaunch(); @@ -206,8 +169,6 @@ class SceneModuleInterface processOnExit(); } - virtual void processOnExit() {} - /** * @brief Publish status if the module is requested to run */ @@ -220,24 +181,6 @@ class SceneModuleInterface } } - /** - * @brief Return true if the activation command is received from the RTC interface. - * If no RTC interface is registered, return true. - */ - bool isActivated() - { - if (rtc_interface_ptr_map_.empty()) { - return true; - } - - for (auto itr = rtc_interface_ptr_map_.begin(); itr != rtc_interface_ptr_map_.end(); ++itr) { - if (itr->second->isRegistered(uuid_map_.at(itr->first))) { - return itr->second->isActivated(uuid_map_.at(itr->first)); - } - } - return false; - } - void publishSteeringFactor() { if (!steering_factor_interface_ptr_) { @@ -277,14 +220,13 @@ class SceneModuleInterface */ virtual void setData(const std::shared_ptr & data) { planner_data_ = data; } - bool isWaitingApproval() const { return is_waiting_approval_; } + bool isWaitingApproval() const + { + return is_waiting_approval_ || current_state_ == ModuleStatus::WAITING_APPROVAL; + } bool isLockedNewModuleLaunch() const { return is_locked_new_module_launch_; } - void resetPathCandidate() { path_candidate_.reset(); } - - void resetPathReference() { path_reference_.reset(); } - PlanResult getPathCandidate() const { return path_candidate_; } PlanResult getPathReference() const { return path_reference_; } @@ -301,8 +243,6 @@ class SceneModuleInterface StopReason getStopReason() const { return stop_reason_; } - virtual void acceptVisitor(const std::shared_ptr & visitor) const = 0; - std::string name() const { return name_; } boost::optional getStopPose() const @@ -342,12 +282,6 @@ class SceneModuleInterface dead_pose_ = boost::none; } - void setDrivableLanes(const std::vector & drivable_lanes) - { - drivable_lanes_marker_ = - marker_utils::createDrivableLanesMarkerArray(drivable_lanes, "drivable_lanes"); - } - rclcpp::Logger getLogger() const { return logger_; } void setIsSimultaneousExecutableAsApprovedModule(const bool enable) @@ -371,13 +305,109 @@ class SceneModuleInterface } private: + bool existRegisteredRequest() const + { + return std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), + [&](const auto & rtc) { return rtc.second->isRegistered(uuid_map_.at(rtc.first)); }); + } + + bool existApprovedRequest() const + { + return std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { + return rtc.second->isRegistered(uuid_map_.at(rtc.first)) && + rtc.second->isActivated(uuid_map_.at(rtc.first)); + }); + } + + bool existNotApprovedRequest() const + { + return std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { + return rtc.second->isRegistered(uuid_map_.at(rtc.first)) && + !rtc.second->isActivated(uuid_map_.at(rtc.first)); + }); + } + + bool canTransitWaitingApprovalState() const + { + if (!existRegisteredRequest()) { + return false; + } + return existNotApprovedRequest(); + } + + bool canTransitWaitingApprovalToRunningState() const + { + if (!existRegisteredRequest()) { + return true; + } + return existApprovedRequest(); + } + std::string name_; rclcpp::Logger logger_; BehaviorModuleOutput previous_module_output_; + StopReason stop_reason_; + + bool is_simultaneously_executable_as_approved_module_{false}; + + bool is_simultaneously_executable_as_candidate_module_{false}; + + bool is_locked_new_module_launch_{false}; + protected: + /** + * @brief State transition condition ANY -> SUCCESS + */ + virtual bool canTransitSuccessState() = 0; + + /** + * @brief State transition condition ANY -> FAILURE + */ + virtual bool canTransitFailureState() = 0; + + /** + * @brief State transition condition IDLE -> RUNNING + */ + virtual bool canTransitIdleToRunningState() = 0; + + /** + * @brief Get candidate path. This information is used for external judgement. + */ + virtual CandidateOutput planCandidate() const = 0; + + /** + * @brief Calculate path. This function is called with the plan is approved. + */ + virtual BehaviorModuleOutput plan() = 0; + + /** + * @brief Calculate path under waiting_approval condition. + * The default implementation is just to return the reference path. + */ + virtual BehaviorModuleOutput planWaitingApproval() + { + path_candidate_ = std::make_shared(planCandidate().path_candidate); + path_reference_ = getPreviousModuleOutput().reference_path; + + return getPreviousModuleOutput(); + } + + /** + * @brief Module unique entry process. + */ + virtual void processOnEntry() {} + + /** + * @brief Module unique exit process. + */ + virtual void processOnExit() {} + virtual void updateRTCStatus(const double start_distance, const double finish_distance) { for (auto itr = rtc_interface_ptr_map_.begin(); itr != rtc_interface_ptr_map_.end(); ++itr) { @@ -389,6 +419,80 @@ class SceneModuleInterface } } + /** + * @brief Return SUCCESS if plan is not needed or plan is successfully finished, + * FAILURE if plan has failed, RUNNING if plan is on going. + * These condition is to be implemented in each modules. + */ + virtual ModuleStatus updateState() + { + if (current_state_ == ModuleStatus::IDLE) { + if (canTransitIdleToRunningState()) { + return ModuleStatus::RUNNING; + } + + return ModuleStatus::IDLE; + } + + if (current_state_ == ModuleStatus::RUNNING) { + if (canTransitSuccessState()) { + return ModuleStatus::SUCCESS; + } + + if (canTransitFailureState()) { + return ModuleStatus::FAILURE; + } + + if (canTransitWaitingApprovalState()) { + return ModuleStatus::WAITING_APPROVAL; + } + + return ModuleStatus::RUNNING; + } + + if (current_state_ == ModuleStatus::WAITING_APPROVAL) { + if (canTransitSuccessState()) { + return ModuleStatus::SUCCESS; + } + + if (canTransitFailureState()) { + return ModuleStatus::FAILURE; + } + + if (canTransitWaitingApprovalToRunningState()) { + return ModuleStatus::RUNNING; + } + + return ModuleStatus::WAITING_APPROVAL; + } + + if (current_state_ == ModuleStatus::SUCCESS) { + return ModuleStatus::SUCCESS; + } + + if (current_state_ == ModuleStatus::FAILURE) { + return ModuleStatus::FAILURE; + } + + return ModuleStatus::IDLE; + } + + /** + * @brief Return true if the activation command is received from the RTC interface. + * If no RTC interface is registered, return true. + */ + bool isActivated() + { + if (rtc_interface_ptr_map_.empty()) { + return true; + } + + if (!existRegisteredRequest()) { + return false; + } + return existApprovedRequest(); + } + void removeRTCStatus() { for (auto itr = rtc_interface_ptr_map_.begin(); itr != rtc_interface_ptr_map_.end(); ++itr) { @@ -415,6 +519,12 @@ class SceneModuleInterface stop_reason_.stop_factors.push_back(stop_factor); } + void setDrivableLanes(const std::vector & drivable_lanes) + { + drivable_lanes_marker_ = + marker_utils::createDrivableLanesMarkerArray(drivable_lanes, "drivable_lanes"); + } + BehaviorModuleOutput getPreviousModuleOutput() const { return previous_module_output_; } void lockNewModuleLaunch() { is_locked_new_module_launch_ = true; } @@ -425,6 +535,10 @@ class SceneModuleInterface void clearWaitingApproval() { is_waiting_approval_ = false; } + void resetPathCandidate() { path_candidate_.reset(); } + + void resetPathReference() { path_reference_.reset(); } + geometry_msgs::msg::Point getEgoPosition() const { return planner_data_->self_odometry->pose.pose.position; @@ -442,15 +556,11 @@ class SceneModuleInterface return std::abs(planner_data_->self_odometry->twist.twist.linear.x); } - bool is_simultaneously_executable_as_approved_module_{false}; - bool is_simultaneously_executable_as_candidate_module_{false}; - rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; - bool is_waiting_approval_; - bool is_locked_new_module_launch_; + bool is_waiting_approval_{false}; std::unordered_map uuid_map_; @@ -459,8 +569,6 @@ class SceneModuleInterface ModuleStatus current_state_{ModuleStatus::IDLE}; - StopReason stop_reason_; - std::unordered_map> rtc_interface_ptr_map_; std::unique_ptr steering_factor_interface_ptr_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index bdff915e15d5b..7c04cab5c081f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -49,7 +49,8 @@ class SideShiftModule : public SceneModuleInterface bool isExecutionReady() const override; bool isReadyForNextRequest( const double & min_request_time_sec, bool override_requests = false) const noexcept; - ModuleStatus updateState() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; void updateData() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; @@ -69,7 +70,31 @@ class SideShiftModule : public SceneModuleInterface { } + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override + { + updateData(); + + if (!isWaitingApproval()) { + return plan(); + } + + // module is waiting approval. Check it. + if (isActivated()) { + RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); + return plan(); + } else { + RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); + return planWaitingApproval(); + } + } + private: + bool canTransitSuccessState() override { return false; } + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return false; } rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; void initVariables(); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 0a44db1055cac..1405e3cd1f10e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -72,14 +72,17 @@ class StartPlannerModule : public SceneModuleInterface parameters_ = std::any_cast>(parameters); } - BehaviorModuleOutput run() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; - ModuleStatus updateState() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; + void processOnExit() override; void setParameters(const std::shared_ptr & parameters) @@ -107,6 +110,12 @@ class StartPlannerModule : public SceneModuleInterface }; private: + bool canTransitSuccessState() override { return false; } + + bool canTransitFailureState() override { return false; } + + bool canTransitIdleToRunningState() override { return false; } + std::shared_ptr parameters_; vehicle_info_util::VehicleInfo vehicle_info_; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 45a26cfb29f48..6dff21d26dee7 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -110,10 +110,6 @@ bool AvoidanceModule::isExecutionRequested() const { DEBUG_PRINT("AVOIDANCE isExecutionRequested"); - if (current_state_ == ModuleStatus::RUNNING) { - return true; - } - // Check ego is in preferred lane updateInfoMarker(avoidance_data_); updateDebugMarker(avoidance_data_, path_shifter_, debug_data_); @@ -136,7 +132,7 @@ bool AvoidanceModule::isExecutionReady() const return avoidance_data_.safe; } -ModuleStatus AvoidanceModule::updateState() +bool AvoidanceModule::canTransitSuccessState() { const auto & data = avoidance_data_; const auto is_plan_running = isAvoidancePlanRunning(); @@ -144,7 +140,7 @@ ModuleStatus AvoidanceModule::updateState() if (!isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "previous module lane is updated."); - return ModuleStatus::SUCCESS; + return true; } const auto idx = planner_data_->findEgoIndex(data.reference_path.points); @@ -157,29 +153,26 @@ ModuleStatus AvoidanceModule::updateState() calcDistance2d(getEgoPose(), getPose(data.reference_path.points.back())) > THRESHOLD && arrived_path_end_) { RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "reach path end point. exit avoidance module."); - return ModuleStatus::SUCCESS; + return true; } DEBUG_PRINT( "is_plan_running = %d, has_avoidance_target = %d", is_plan_running, has_avoidance_target); if (!is_plan_running && !has_avoidance_target) { - return ModuleStatus::SUCCESS; + return true; } if ( !has_avoidance_target && parameters_->enable_update_path_when_object_is_gone && !isAvoidanceManeuverRunning()) { // if dynamic objects are removed on path, change current state to reset path - return ModuleStatus::SUCCESS; + return true; } helper_.setPreviousDrivingLanes(data.current_lanelets); - if (is_plan_running || current_state_ == ModuleStatus::RUNNING) { - return ModuleStatus::RUNNING; - } - return ModuleStatus::IDLE; + return false; } bool AvoidanceModule::isAvoidancePlanRunning() const @@ -2109,35 +2102,7 @@ BehaviorModuleOutput AvoidanceModule::plan() resetPathCandidate(); resetPathReference(); - /** - * Has new shift point? - * Yes -> Is it approved? - * Yes -> add the shift point. - * No -> set approval_handler to WAIT_APPROVAL state. - * No -> waiting approval? - * Yes -> clear WAIT_APPROVAL state. - * No -> do nothing. - */ - if (!data.safe_new_sl.empty()) { - debug_data_.new_shift_lines = data.safe_new_sl; - DEBUG_PRINT("new_shift_lines size = %lu", data.safe_new_sl.size()); - printShiftLines(data.safe_new_sl, "new_shift_lines"); - - const auto sl = helper_.getMainShiftLine(data.safe_new_sl); - if (helper_.getRelativeShiftToPath(sl) > 0.0) { - removePreviousRTCStatusRight(); - } else if (helper_.getRelativeShiftToPath(sl) < 0.0) { - removePreviousRTCStatusLeft(); - } else { - RCLCPP_WARN_STREAM(getLogger(), "Direction is UNKNOWN"); - } - if (!parameters_->disable_path_update) { - addShiftLineIfApproved(data.safe_new_sl); - } - } else if (isWaitingApproval()) { - clearWaitingApproval(); - removeCandidateRTCStatus(); - } + updatePathShifter(data.safe_new_sl); // generate path with shift points that have been inserted. ShiftedPath linear_shift_path = utils::avoidance::toShiftedPath(data.reference_path); @@ -2200,7 +2165,7 @@ BehaviorModuleOutput AvoidanceModule::plan() generateExtendedDrivableArea(output); setDrivableLanes(output.drivable_area_info.drivable_lanes); - updateRegisteredRTCStatus(spline_shift_path.path); + // updateRegisteredRTCStatus(spline_shift_path.path); return output; } @@ -2249,71 +2214,53 @@ CandidateOutput AvoidanceModule::planCandidate() const BehaviorModuleOutput AvoidanceModule::planWaitingApproval() { - const auto & data = avoidance_data_; - - // we can execute the plan() since it handles the approval appropriately. BehaviorModuleOutput out = plan(); if (path_shifter_.getShiftLines().empty()) { out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; } - const auto all_unavoidable = std::all_of( - data.target_objects.begin(), data.target_objects.end(), - [](const auto & o) { return !o.is_avoidable; }); - - const auto candidate = planCandidate(); - if (!data.safe_new_sl.empty()) { - updateCandidateRTCStatus(candidate); - waitApproval(); - } else if (path_shifter_.getShiftLines().empty()) { - waitApproval(); - } else if (all_unavoidable) { - waitApproval(); - } else { - clearWaitingApproval(); - removeCandidateRTCStatus(); - } - - path_candidate_ = std::make_shared(candidate.path_candidate); + path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; return out; } -void AvoidanceModule::addShiftLineIfApproved(const AvoidLineArray & shift_lines) +void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) { - if (isActivated()) { - DEBUG_PRINT("We want to add this shift point, and approved. ADD SHIFT POINT!"); - const size_t prev_size = path_shifter_.getShiftLinesSize(); - addNewShiftLines(path_shifter_, shift_lines); + if (parameters_->disable_path_update) { + return; + } - current_raw_shift_lines_ = avoidance_data_.unapproved_raw_sl; + if (shift_lines.empty()) { + return; + } - // register original points for consistency - registerRawShiftLines(shift_lines); + if (!isActivated()) { + return; + } - const auto sl = helper_.getMainShiftLine(shift_lines); - const auto sl_front = shift_lines.front(); - const auto sl_back = shift_lines.back(); + addNewShiftLines(path_shifter_, shift_lines); - if (helper_.getRelativeShiftToPath(sl) > 0.0) { - left_shift_array_.push_back({uuid_map_.at("left"), sl_front.start, sl_back.end}); - } else if (helper_.getRelativeShiftToPath(sl) < 0.0) { - right_shift_array_.push_back({uuid_map_.at("right"), sl_front.start, sl_back.end}); - } + current_raw_shift_lines_ = avoidance_data_.unapproved_raw_sl; - uuid_map_.at("left") = generateUUID(); - uuid_map_.at("right") = generateUUID(); - candidate_uuid_ = generateUUID(); + registerRawShiftLines(shift_lines); - lockNewModuleLaunch(); + const auto sl = helper_.getMainShiftLine(shift_lines); + const auto sl_front = shift_lines.front(); + const auto sl_back = shift_lines.back(); - DEBUG_PRINT("shift_line size: %lu -> %lu", prev_size, path_shifter_.getShiftLinesSize()); - } else { - DEBUG_PRINT("We want to add this shift point, but NOT approved. waiting..."); - waitApproval(); + if (helper_.getRelativeShiftToPath(sl) > 0.0) { + left_shift_array_.push_back({uuid_map_.at("left"), sl_front.start, sl_back.end}); + } else if (helper_.getRelativeShiftToPath(sl) < 0.0) { + right_shift_array_.push_back({uuid_map_.at("right"), sl_front.start, sl_back.end}); } + + uuid_map_.at("left") = generateUUID(); + uuid_map_.at("right") = generateUUID(); + candidate_uuid_ = generateUUID(); + + lockNewModuleLaunch(); } /** @@ -2535,12 +2482,13 @@ void AvoidanceModule::updateData() fillShiftLine(avoidance_data_, debug_data_); fillEgoStatus(avoidance_data_, debug_data_); fillDebugData(avoidance_data_, debug_data_); + + updateRTCData(); } void AvoidanceModule::processOnEntry() { initVariables(); - waitApproval(); } void AvoidanceModule::processOnExit() @@ -2576,6 +2524,39 @@ void AvoidanceModule::initRTCStatus() candidate_uuid_ = generateUUID(); } +void AvoidanceModule::updateRTCData() +{ + const auto & data = avoidance_data_; + + updateRegisteredRTCStatus(helper_.getPreviousSplineShiftPath().path); + + if (data.safe_new_sl.empty()) { + removeCandidateRTCStatus(); + return; + } + + const auto shift_line = helper_.getMainShiftLine(data.safe_new_sl); + if (helper_.getRelativeShiftToPath(shift_line) > 0.0) { + removePreviousRTCStatusRight(); + } else if (helper_.getRelativeShiftToPath(shift_line) < 0.0) { + removePreviousRTCStatusLeft(); + } else { + RCLCPP_WARN_STREAM(getLogger(), "Direction is UNKNOWN"); + } + + CandidateOutput output; + + const auto sl_front = data.safe_new_sl.front(); + const auto sl_back = data.safe_new_sl.back(); + + output.path_candidate = data.candidate_path.path; + output.lateral_shift = helper_.getRelativeShiftToPath(shift_line); + output.start_distance_to_path_change = sl_front.start_longitudinal; + output.finish_distance_to_path_change = sl_back.end_longitudinal; + + updateCandidateRTCStatus(output); +} + TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) const { const auto shift_lines = path_shifter_.getShiftLines(); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index b6258d8fba597..baa9fd0a7e3f5 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -15,7 +15,6 @@ #include "behavior_path_planner/scene_module/lane_change/interface.hpp" #include "behavior_path_planner/marker_utils/lane_change/debug.hpp" -#include "behavior_path_planner/module_status.hpp" #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/lane_change/utils.hpp" From 2f44d6d63ab4963d908a1fe6c48f3cd4c4a31b03 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 7 Aug 2023 17:14:26 +0900 Subject: [PATCH 110/266] feat(localization): add a new localization package `ar_tag_based_localizer` (#4347) * Added ar_tag_based_localizer Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Added include Signed-off-by: Shintaro Sakoda * Fixed typo Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Added comment Signed-off-by: Shintaro Sakoda * Updated license statements Signed-off-by: Shintaro Sakoda * Updated default topic names Signed-off-by: Shintaro Sakoda * Replaced "_2_" to "_to_" Signed-off-by: Shintaro Sakoda * Fixed tf_listener_ shared_ptr to unique_ptr Signed-off-by: Shintaro Sakoda * Removed unused get_transform Signed-off-by: Shintaro Sakoda * Fixed alt text Signed-off-by: Shintaro Sakoda * Fixed topic name Signed-off-by: Shintaro SAKODA * Fixed default topic name of tag_tf_caster Signed-off-by: Shintaro SAKODA * Fixed AR Tag Based Localizer to work independently Signed-off-by: Shintaro SAKODA * Added principle Signed-off-by: Shintaro Sakoda * Fixed how to launch Signed-off-by: Shintaro Sakoda * Added link to sample data Signed-off-by: Shintaro Sakoda * Added sample_result.png Signed-off-by: Shintaro Sakoda * Update localization/ar_tag_based_localizer/README.md Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Update localization/ar_tag_based_localizer/README.md Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Fixed LaneLet2 to Lanelet2 Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Update localization/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * style(pre-commit): autofix * Update localization/ar_tag_based_localizer/config/tag_tf_caster.param.yaml Signed-off-by: Shintaro Sakoda Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Added unit to range parameter Signed-off-by: Shintaro Sakoda * Removed std::pow Signed-off-by: Shintaro Sakoda * Removed marker_size_ != -1 Signed-off-by: Shintaro Sakoda * Fixed maintainer Signed-off-by: Shintaro Sakoda * Added ar_tag_based_localizer to tier4_localization_launch/package.xml Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed legend of node_diagram Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Renamed range to distance_threshold Signed-off-by: Shintaro Sakoda * Fixed topic names in README.md Signed-off-by: Shintaro Sakoda * Fixed parameter input Signed-off-by: Shintaro Sakoda * Removed right_to_left_ Signed-off-by: Shintaro Sakoda * Added namespace ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * Updated inputs/outputs Signed-off-by: Shintaro Sakoda * Fixed covariance Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Added principle of tag_tf_caster Signed-off-by: Shintaro Sakoda * Removed ament_lint_auto Signed-off-by: Shintaro Sakoda * Fixed launch name Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro SAKODA Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../ar_tag_based_localizer.launch.xml | 22 ++ .../pose_twist_estimator.launch.xml | 23 ++ launch/tier4_localization_launch/package.xml | 1 + .../ar_tag_based_localizer/CMakeLists.txt | 47 +++ localization/ar_tag_based_localizer/README.md | 154 ++++++++++ .../config/ar_tag_based_localizer.param.yaml | 26 ++ .../config/tag_tf_caster.param.yaml | 4 + .../doc_image/ar_tag_image.png | Bin 0 -> 833751 bytes .../lanelet2_data_structure.drawio.svg | 156 ++++++++++ .../doc_image/node_diagram.drawio.svg | 86 ++++++ .../doc_image/principle.png | Bin 0 -> 1479008 bytes .../doc_image/sample_result.png | Bin 0 -> 45098 bytes .../ar_tag_based_localizer_core.hpp | 103 +++++++ .../tag_tf_caster_core.hpp | 49 ++++ .../include/ar_tag_based_localizer/utils.hpp | 66 +++++ .../launch/ar_tag_based_localizer.launch.xml | 21 ++ .../launch/tag_tf_caster.launch.xml | 12 + .../ar_tag_based_localizer/package.xml | 30 ++ .../src/ar_tag_based_localizer_core.cpp | 272 ++++++++++++++++++ .../src/ar_tag_based_localizer_node.cpp | 54 ++++ .../src/tag_tf_caster_core.cpp | 125 ++++++++ .../src/tag_tf_caster_node.cpp | 22 ++ .../ar_tag_based_localizer/src/utils.cpp | 116 ++++++++ 23 files changed, 1389 insertions(+) create mode 100644 launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml create mode 100644 localization/ar_tag_based_localizer/CMakeLists.txt create mode 100644 localization/ar_tag_based_localizer/README.md create mode 100644 localization/ar_tag_based_localizer/config/ar_tag_based_localizer.param.yaml create mode 100644 localization/ar_tag_based_localizer/config/tag_tf_caster.param.yaml create mode 100644 localization/ar_tag_based_localizer/doc_image/ar_tag_image.png create mode 100644 localization/ar_tag_based_localizer/doc_image/lanelet2_data_structure.drawio.svg create mode 100644 localization/ar_tag_based_localizer/doc_image/node_diagram.drawio.svg create mode 100644 localization/ar_tag_based_localizer/doc_image/principle.png create mode 100644 localization/ar_tag_based_localizer/doc_image/sample_result.png create mode 100644 localization/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp create mode 100644 localization/ar_tag_based_localizer/include/ar_tag_based_localizer/tag_tf_caster_core.hpp create mode 100644 localization/ar_tag_based_localizer/include/ar_tag_based_localizer/utils.hpp create mode 100644 localization/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml create mode 100644 localization/ar_tag_based_localizer/launch/tag_tf_caster.launch.xml create mode 100644 localization/ar_tag_based_localizer/package.xml create mode 100644 localization/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp create mode 100644 localization/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp create mode 100644 localization/ar_tag_based_localizer/src/tag_tf_caster_core.cpp create mode 100644 localization/ar_tag_based_localizer/src/tag_tf_caster_node.cpp create mode 100644 localization/ar_tag_based_localizer/src/utils.cpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml new file mode 100644 index 0000000000000..4de9aec81bb38 --- /dev/null +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml index 0cbda728b7fdc..abbb15c797d19 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml @@ -112,4 +112,27 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 325ed86c4435c..f00752d1c14fc 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -14,6 +14,7 @@ ament_cmake_auto autoware_cmake + ar_tag_based_localizer automatic_pose_initializer eagleye_fix2pose eagleye_gnss_converter diff --git a/localization/ar_tag_based_localizer/CMakeLists.txt b/localization/ar_tag_based_localizer/CMakeLists.txt new file mode 100644 index 0000000000000..89337b9bb966c --- /dev/null +++ b/localization/ar_tag_based_localizer/CMakeLists.txt @@ -0,0 +1,47 @@ +cmake_minimum_required(VERSION 3.14) +project(ar_tag_based_localizer) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +find_package(OpenCV REQUIRED) + +# +# ar_tag_based_localizer +# +ament_auto_add_executable(ar_tag_based_localizer + src/ar_tag_based_localizer_node.cpp + src/ar_tag_based_localizer_core.cpp + src/utils.cpp +) +target_include_directories(ar_tag_based_localizer + SYSTEM PUBLIC + ${OpenCV_INCLUDE_DIRS} +) +target_link_libraries(ar_tag_based_localizer ${OpenCV_LIBRARIES}) + +# +# tag_tf_caster +# +ament_auto_add_executable(tag_tf_caster + src/tag_tf_caster_node.cpp + src/tag_tf_caster_core.cpp +) +target_include_directories(tag_tf_caster + SYSTEM PUBLIC + ${OpenCV_INCLUDE_DIRS} +) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/ar_tag_based_localizer/README.md b/localization/ar_tag_based_localizer/README.md new file mode 100644 index 0000000000000..e471378773cbb --- /dev/null +++ b/localization/ar_tag_based_localizer/README.md @@ -0,0 +1,154 @@ +# AR Tag Based Localizer + +**ArTagBasedLocalizer** is a vision-based localization package. + + + +This package uses [the ArUco library](https://index.ros.org/p/aruco/) to detect AR-Tags from camera images and calculates and publishes the pose of the ego vehicle based on these detections. +The positions and orientations of the AR-Tags are assumed to be written in the Lanelet2 format. + +This package includes two nodes. + +- `ar_tag_based_localizer` : A node that detects AR-Tags from camera images and publishes the pose of the ego vehicle. +- `tag_tf_caster` : A node that publishes the pose of the AR-Tags applied in Lanelet2 as `tf_static`. + +## Inputs / Outputs + +### `ar_tag_based_localizer` node + +#### Input + +| Name | Type | Description | +| :-------------------- | :----------------------------- | :----------- | +| `~/input/image` | `sensor_msgs::msg::Image` | Camera Image | +| `~/input/camera_info` | `sensor_msgs::msg::CameraInfo` | Camera Info | + +#### Output + +| Name | Type | Description | +| :------------------------------ | :---------------------------------------------- | :---------------------------------------------------------------------------------------- | +| `~/output/pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated Pose | +| `~/debug/result` | `sensor_msgs::msg::Image` | [debug topic] Image in which marker detection results are superimposed on the input image | +| `tf` | `geometry_msgs::msg::TransformStamped` | [debug topic] TF from camera to detected tag | + +### `tag_tf_caster` node + +#### Input + +| Name | Type | Description | +| :--------------------- | :------------------------------------------- | :--------------- | +| `~/input/lanelet2_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Data of lanelet2 | + +#### Output + +| Name | Type | Description | +| :---------- | :------------------------------------- | :----------------- | +| `tf_static` | `geometry_msgs::msg::TransformStamped` | TF from map to tag | + +## How to launch + +When launching Autoware, specify `artag` for `pose_source`. + +```bash +ros2 launch autoware_launch ... \ + pose_source:=artag \ + ... +``` + +[Sample rosbag and map](https://drive.google.com/file/d/1wiCQjyjRnYbb0dg8G6mRecdSGh8tv3zR/view) + +This dataset contains issues such as missing IMU data, and overall the accuracy is low. Even when running AR tag-based self-localization, significant difference from the true trajectory can be observed. + +The image below shows the trajectory when the sample is executed and plotted. + +![sample_result](./doc_image/sample_result.png) + +The pull request video below should also be helpful. + + + +## Architecture + +![node diagram](./doc_image/node_diagram.drawio.svg) + +## Principle + +### `ar_tag_based_localizer` node + +![principle](./doc_image/principle.png) + +### `tag_tf_caster` node + +The definitions of the tags written to the map are introduced in the next section. See `Map Specifications`. + +The `tag_tf_caster` node publishes the TF from the map to the tag. + +- Translation : The center of the four vertices of the tag +- Rotation : Let the vertex numbers be 1, 2, 3, 4 counterclockwise as shown in the next section. Direction is defined as the cross product of the vector from 1 to 2 and the vector from 2 to 3. + +Users can define tags as Lanelet2 4-vertex polygons. +In this case, it is possible to define an arrangement in which the four vertices cannot be considered to be on the same plane. The direction of the tag in that case is difficult to calculate. +So, if the 4 vertices are considered as forming a tetrahedron and its volume exceeds the `volume_threshold` parameter, the tag will not publish tf_static. + +## Map specifications + +For this package to function correctly, the pose of the AR-Tags must be specified in the Lanelet2 map format that Autoware can interpret. + +The four vertices of AR-Tag are defined counterclockwise. + +The order of the four vertices is defined as follows. In the coordinate system of AR-Tag, + +- the x-axis is parallel to the vector from the first vertex to the second vertex +- the y-axis is parallel to the vector from the second vertex to the third vertex + +![lanelet2 data structure](./doc_image/lanelet2_data_structure.drawio.svg) + +### example of `lanelet2_map.osm` + +The values provided below are placeholders. +Ensure to input the correct coordinates corresponding to the actual location where the AR-Tag is placed, such as `lat`, `lon`, `mgrs_code`, `local_x`, `local_y`. + +```xml +... + + + + + + + + + + + + + + + + + + + + + + + + + + +... + + + + + + + + + + + + +... + +``` diff --git a/localization/ar_tag_based_localizer/config/ar_tag_based_localizer.param.yaml b/localization/ar_tag_based_localizer/config/ar_tag_based_localizer.param.yaml new file mode 100644 index 0000000000000..385e86498c58c --- /dev/null +++ b/localization/ar_tag_based_localizer/config/ar_tag_based_localizer.param.yaml @@ -0,0 +1,26 @@ +/**: + ros__parameters: + # marker_size + marker_size: 0.6 + + # target_tag_ids + target_tag_ids: ['0','4','5'] + + # covariance + covariance: [0.1, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + # Detect AR-Tags within this range and publish the pose of ego vehicle + distance_threshold: 6.0 # [m] + + # Camera frame id + camera_frame: "camera" + + # Detector parameters + # See https://github.com/pal-robotics/aruco_ros/blob/7787a6794d30c248bc546d1582e65dd47bc40c12/aruco/include/aruco/markerdetector.h#L106-L126 + detection_mode: "DM_NORMAL" # select from [DM_NORMAL, DM_FAST, DM_VIDEO_FAST] + min_marker_size: 0.02 diff --git a/localization/ar_tag_based_localizer/config/tag_tf_caster.param.yaml b/localization/ar_tag_based_localizer/config/tag_tf_caster.param.yaml new file mode 100644 index 0000000000000..2fe2869038e82 --- /dev/null +++ b/localization/ar_tag_based_localizer/config/tag_tf_caster.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + # Tags with a volume greater than this value will not cast their pose + volume_threshold: 1e-5 # [m^3] diff --git a/localization/ar_tag_based_localizer/doc_image/ar_tag_image.png b/localization/ar_tag_based_localizer/doc_image/ar_tag_image.png new file mode 100644 index 0000000000000000000000000000000000000000..9d2aa204ba24ef9843587632fdd6bc3abc310be4 GIT binary patch literal 833751 zcmV)+K#0GIP)i^&AZeJG=OF=Yz{?fD4AL^jpqM?>$}sRf-l;Nz7AbnkG)CnbR?oCM9Q(3IZS?0?vbT_HS$xR0Rsu3bnsh z`|Q#00VnoU1+AdPUTd{iv^}Lg`{Vp?`4dm~Cw|i&uDvI6_Eb9$=OK7|?VqVa1xkUG z?Nzm%udHKnerT|sgR<_=1qcyhfH**m-p1cK#0iL_s-hJ{1m_*jIlNawbi^o#Q$*|_ zR1>)r@?6NN{|=nk0F>;=S;?u8vND|@B^%QaAOweqqt=Sn3Mz=eAR}YkFt`n(j#`AA z3)3_+oo1jgj*)S*;o@@7umAin_z(Z_Kk`5R^Qs@UPy|sS_{e6nWwYBbjw5jhgy3+_BWma7#1UM? zi-!tn&fL!rJfst+GV$T=6aV!4zvaLF-GAnr@BV?q{1G=~F0MyzUTnE~w&7~O;bIpV zqQ{9+Y9g1JQZvpALktXKB=`ZUpd}zW65NOu&vcxaPl<}4&QqN*i;~q5H+x>b_<|QN zzGO38P?Ip93iBy({BXJ1MdU^c<+%=3BltAdzGOgUT~ozV(S|Ez96e>`xasxc=qfSuV205;_8NR z9B|tUE-x>U&4zdH-t&j=-g0<&V0-n9U;N^i{KfzDzw&2)_DgQAKV!4maLJY!0y`b? z&M{^iGdWeJd1g9HOs9!bGU6OuR5qIpekVBZNx>r`lwpGclPW1Cj(H;G%skz5nodk7 zd%gemkNjW%<-hP>|I>fs-Mb$UNq7;eWafD$r4zLlgaSZ}$}kQ*zuIthb;<5>WV;<1 zcAjC3ph8NSJZDNSs1v+%I2UZKsHc=dnU&+=#KYah{p|w}w*AYq7seDQNA^8MLbXUCkaz_pPk{ zTfE?hz-GH)d$Hl-V$bE}j{Sa590r`&+(Mxgp=2dZHkSs!v+rL#<6?isI9{>YY}jl! z48w?X4uGP?{O5e+_25!Y~f(b{lrP zo!PYzh|c4^Bl_;QSk{ngA=N^zm6Q!<)oeIPE96p`CmZh}Y-QTdgct#j@Xbt4taj`?HL)0S`oC>}Qk}IhsN^O7*Ma6)#B9y9B z>f(E}86Z(x>)L@fvaX4?=4-7e=1ZOT%lB2=`tAU?Z$bqTx8hp`DdrDd?S@ngZ`cpa zj{${>BG7Pwla3E;F4bC5Ep}X5S1YQH^T&cI+Edi6WTF{xCpPb-fqZQ^s6TWe6)UZP zX4{~7alXEC`4ch+QLR!voKs(nnk|F(g z#o1>fZ47NJZFaQlA=1tdYAwt65b)yKxpwE)?PjyZX3Zas|8o6B7XQYwjYn@RquVCp z*)`~&_Rm?)v%j%mskRk6G+B<}Pe0mtEuMQlwNNwU1hY>#XU;E%nczbszz)SON-2eu z@&Y1rG4fl>dO+@s^qn7UA4hR*=gvNNV$=GZbe;{-|G!6{!H=%elYc+i!PEWelizx0 z2D1YkfYOM(o_$~YwU#G;_rp?qo|E76^X|v3RZ(Y`%!v`6Ze|2&iwuxTt%Z~dh^Yj9 z5!GtfCnpmS%8~QpmX(oHmwD6z5>3P<3LKir^3pl%h;2ffruB z{)}Jz>KDBF{59K)3!cAz&C6f?ocQdTlfwHCx7>cZ$Gbob1DoBR&p-bPA2yVBy!W>U zf(C{V83@D>@k2Ba79t@;ocC0;0UvPcn&4tiRGp(XgO^Js<0$G-^>{ZBWFQdn8ekT3 z&CH`Cr)c2cNh5V0k&4y^4r?XlLaCXol@OF#l#(1y6GN;xBDrR=CUOB4M;7InXAY-K zl}~*7_`tW{y+ey*IwnqsnbTqB@bQ-0x9^eT%+H^{=2w6ID}M8#fbsJ z)y^%3&qSXNX3Hwb^kuBw<_O+-Vu+06$Y!%)+>ChVDYcp{%f2}>VOB-7;zaRn|G_x} z_tL41sBC$o!}hc%u&@2AiCcdb9gH` zi0m&f`SRyq@rytE1sD5kocCymhzN%%L#pJ%iMt;^^6|$z=DP!Bc9e$$Kl|B<-FC+< zTS5qIbwHdW&W@ZjdMZrwOg?2&o=GJmK;9<2_mm-nz!U;8Mr5}m#9(4wt;}U&o@eIc zfz#>8@$Q!UhkHJJ`yJnX_bpRNgmFMiF(8=^Bb)&30E^iEy`(rL5Px zR;XPhm6ZVN86HptFW@qixsph2{g|y0H33hHGy$fVk(LeyrL7fgPF9;E>ZE~2+p*Tt z#-WkCs<^gZymvSs7V=wBv&!V5MMDUPci5(zBK^dnRykw&BIYNg6JVSFChF1% zZFvlMo!a$N15>I>&bfW3tqZktsJJu#WFS|yl1ruJY&g*?~g9Gz*3feEM|DAKtv->#x7&kAFOpb7^y2kXmfMNM7a_zWF{cBxZ6h;AR8b zGPlXx2(EaXx@IF4S7Q?vf?X#KL`-OAt$Ma(8t2Y6^Am{h?dxGG3cBA&oN zj|z2rWOJ&K-!r0XtI#d}PaDQ8k-H!GQF(jM)*7N)#khxGOQ3NP!c4kh|ET&f+IBL z%QtUf^SY2zWttNyDLK(1M`r+`pO>x?-~~YV^}EstSL@Z10Mf9LbBz9eo2{IFrSzvL7G@7}%V>)-#5yHEGLdiI*nUVYB) za>qDa@cj8}N~!qh5f?ceXR=dd^bDIw95!uEn&KA?FBo=?*|9A$~ji#T%v!2^mHN5E67BTW;hxghfi!IM&9J}GEm zj5~&~#o^Gbw}uYdIm{{3J7 zdtSeKWxz?5;vLn&?ZZ9aeD?=_|NDR9&70rz!@F-|bNc-?y2KFf8j^*Trlg!iZAOVmYHkk8Mj^Oa|H<&Y2^05sRcnERqo{@~goB zTW*o%+PCQp5OzQzKH$7XH$UBe;^VD>+0s^TQOCpm17%K7m3*4`P~P#+`R|xM-txoi zAJ}cSggWA!XX~~mVjK%;PUKT!nrBif7G2W}z&y@)@0epkM3{pTqKAz|W=8SmE2f#_ z;lOk_ay*@w4@Vvz9+)5QI2}*aY~WcnqneRga8$h0Gso9QG*PRgl!;nAr36ZGlwxzM z6pO~pd8QU^WXbHK=0+ehzSx@C` z0k`iecrmzdz}MJv)ru!DZX++Az2e35myBW81db7KEi**XQkbTRQVKpe@WMP#JUra- zaJaWID|T>k7`VQ^=CjW}=VJdkMm2T>9~rU{VxKSVSmw$+&6I-)mJV&UV?wne!A@{W znIC`rfR7t)KYZf${g2G^j1wj2M4e|;9llTSqJ$X8C|ZT2WxbYwwqSrr#XE^4LW~4A5@MhhIGrY@bdQSS6$S~2Gct}#3jlui!zC}qZ z&Sjhr7HP&Akt&bZrgNBRSxsmy#iH?j9uzS_(glxi#IgG|ZS%5=lp%P=xM3W(#5f>6 zHVhHjU0$-gydrFONQk&-xG0WWhRu#JjHq)I2WmzhA)uH5M$3RK&Cob?7A*zPik5;j zKWXcrf&N8oUeg{shO})et_4gMQrQ5nb0)O+NB6h25tJ?>^}jlypql+a)iU>Fy`U~LPN3Syj|ie2UMVIPh&I}O7I9le zN^Rq8?;8(t3z2din`E=owbmu7Ep$%MvTaoD{Gb`;M*7$z8`2X6xKyGnaF0 zWI8kq;5)&GCO*|>quTmevKStp<3bE+SyR=5N3N4;>EEeszlM!_=FdVl)cgl(#J`^x zXIO8UUyC2Ltj_c3t)3fWr60ggzVk?k!LBE5ezEL}N9$E}yPXEs$oVlx$H> zmsG`>#LF zap=E6eEUG1|E7~gY2d_rOO*-1)5Y@AJt}A5rtj?cESlgguH^1a(Uwy&;<_Z-v+IRQ&JlwzI_uu@1|MvG^Q;Tx5f5v`)!S(JMsj{TE zRaFD2rwM9BtF*}P&AMm_%Uc)fx>}n8YK~eP`OK>1T3Y(6vfJ+Y>dRkpak(J` z$LZ~Xx!hB-IeJqhe6z`lcnCO3Q}9p6BU4Hy2%QqAW2R=u5H@T#dv==(Hqp|=bFLPJ zm=mE?LV@|=f&2T3c`oLdi=w$u=fXB@cz$!q7hn907q4F8htblw=8Oa(OX0h>Z}^*k z{CmFsr@!UX?Hg)+Aovs8jW7(J5Y)0Os;S9F1}v#moX3epMj!6(C?8Lx1Zj56Q{vN) zcYOcHH+*{dK&q1|l--c1k;~-ir~&QjZZc^if(`w|G;^tAU|~)GxM7SpUB| zBkI|))F%suzQ&t_@eUVScEKQ)#y1Ed23)jpt}fd+ltvO7@wDM}O*l2sF-5LK+uhmat3Ot%*Vv(cw(9?C3()- zqVK`LKpG~*Im$5G_FMX7@!1G|RZ`C6DUs%xJSB3;Xtr_ns+Iz)P*bL+L`gH6(%H2F zTuamSMht5MLn$YG3UI8<^Na|joJmt=PBSGNVbapXKBw*d|@v!2?GpcAOyh$Gq$CH>Qd?wp%V3$2Itg> zMkm1?kT;UPq-xWMB#(hYPcgJKQ%h$KEpOZWwt>4&5(Nm(F9g_$w{u*4z?wE`ktYMg zX2UZ%rA43+XCS3$S?oB-Qa-T)LutfxwKtY|mXYt8k~yV<)`|~Gh!K}6 zo9VX8)U@DvF3B4qGnwS8O(0 zf^I-zlq+`I9sBJK!!QtK3kZk11MlCz=f}Hulv1n|z&XTEM(SK6944hVpn;@`xg0r8;9|ms5s?5A?6~pvcO$?~ zZC!Y5txGdFqGpXm#KtW&|0pyv-O_PIY#R*-inH}YBU{=)yfk1c?e{Fc9sC)2>6c-N z{HmoN8=1AaqFAN|ElAPwNmn1HO3|LWY-6qnzOBbn3Z;026JZuBB4ydY_`EhDI9skokD zic(t|`uUhhi`eNBRkMG0gk)t4w%s+oyko^CtTZ8FnO~2NYyE{2X9U0dHqIZq*zt}{ z%^$Y!pQXIpTwAfAh{;UUYGf2F1r{v*#|FFYrYR`e(quK;qI_~F3mMi1zR#n*J(}1T z=R&Y#8N;7Od^@nTvYyA}_X%-bMvOo4ou>!dg`X#%>lwlBDcd0kF$RVhaiOuuoLg<) zda?eked=hhA!Zo|h1K#)`bn&obfb8)iu)G z0Yuwo={0?=c9uu$#f)Z8iL}q;@pqiI>s2W!ljdwhrTQ}>+nkgWJgtt}JE99lPP^@D zB)T+*yRO-;eRtwcQ*N8#ZA_=1x;FdbniB0=nlp>t^N90!AMq0CsXw(8LPZrtB(*XpEKcTA3V)cV1=a$NBDafL}sk9D{5>(My znNF2F8}ZF)M$@X8I}dJH?U+=dR3k!e5|GN2R(EJNu#)py&(z6ICz7VL8Ha&kfyz;z6XxrJV>7_9jvsqDOSrHz4@}9NQ|+GfDIHj65(4Kv1G+bAm^F+a6-kz(RrSiXrdD#DV$Q`{&3(hO@ut-RS_S_ zMVRxEk_%xzk>*65Z0=LmTE|){Q#k?A7yAo_U{NF&EgL7N z#M`%T_`84kd)~hJo>Q)mh$zkgqt}dcLWmo#_BVX_)t7wnvoE;0cu9-{qrYYxMmGM! zfNa^2QsUEx2flyvhU*XSI316qI+=J^K2gc29Bq#Iw#uYMgjplDRkcN%Y|Ok^jj+{w zdRvd#BPB5Uo%J)Aj^vz7Sfu+8iw>9EjW(c_p2_4|KO7TDt<-9DQ5BpKwRxUVJ#aiu zRJGLIipR%+!!dFHFmZ8t%P?+neuIPoCnL^}#IPmAO{|+-XNCpZCK070eXrv4Wswk*hXBm*`b!wEX^<0 z1!QC8e65#FC)Vm3hBd=NJlO?Ya=utiyW zj}fEUEI7Bn+cRqV*mh3h`u-Y;stp_TROfRpVAz}{j@fp5s>90VU$PSWO7KaZYsxlMM@{HgtX9ypI{EUH81~l=I6EPIO6Y1=QdUQ@Tn}Nn`2D@5X83G>%jcc2os(ZZ z`>sCz-Jc}8=igiB=n6_W`>Y>xfA)Ii4tzUNKL^0=yXQ4wPp;8p(t9?TkAQMp_^w5T zhas}vZrN_P#1N@e>f9P!8T4oi%4!sgHu0jRcGa`}I>(Zh-lM-cuTNDwRU>*BP?xYO zO0_ofy`H3YkR@t0TQ&2;yYKkF|8pYxft+n31{c|Fc5JqL#6?_Iay|0>w}0g2^H-)s zkGq8ckK=}m-G*ViH}GAQ&_G6Qu(KN&EsA)n!CF##&c4&%apDLewt3!DIU*rCQkjTh zhgMITDyKu@)M|3a=nx6Gp_3y^8&9cnc$oS0;lT0XL`iCnR)^M*BQRd?c(!@Ts~4{c zaX_^-JQB~{{R1&Y+(D=p5W7sI|RIaiTtHBhyb#hD0}Le}SC<9jxTnltDGxYW{W^m+=vTYlqO z(*Tv)(!N?#5LHm$RAXC+wHOIXv!&)%Ev@;MrLl{+258Np`qmi3OCz2=`mBYbxhee0 zqRyQgG+44HtSua7}zvSlT8JC;q)<`a15aU2_8^A=+hrKQ6cdO3)_~8S8{4n!yI8c&-VD$$S2=0DyqFxH>3m!$Pm2XJ(l$>!1a!$zP z@TC&6f<#g`&G zNCSB1V2$M*dma0d9@^H8YY|LS_>J_&*5qv^wPz`OjdU(xO`+6P=`Y!`KM?alRkOW! zMu3+HMF`8F^oU7LiIirG=+|CFh2R(2uPA>Qm(>AtWl z{22I)(G*>GwivCXqL5QDp(a`RP-*M;{F-*sTykZeGsoiz5oaYPzBS7W5$7FwF5KNd zAQBnecBwzkxiX!=`v3(}Dx6L;hlc}mol%sOtrk|C;({Yq6Xg=hAx-!^5m8DJn2xy9 z9cfN*5Sy!$iGPC_2@j+7vPdO0QeieVlt9tSvzO1fyt(9hw`afKvu!n>J$vHQ#|MNh zzkmA{EgwJ!Tx(8cWUQqM`$F)Z7)Qo&%gyz3zWCxRK6~|NY{m^Aax#(ZFkKKK60Fn*4u(gEsmUQrHX4JiZSCBv~fgV(OA*g)=gWJM&3Y6 zBBz2dp$fTT8BBOw7`gp);KL7}7{)yzY(NHtfRn+*ldvOrivX*5#05km*8J4gfe+Rf zCHjE0^{1_Kn~~p!5#nHeuaO=f+>&L1vef?@sc_9F8F_TU<3q#;k2*^;C;GJ^WD^Cv zIHL17r>jkCeoI?zr-+S}c#n#uc)Ql01%c`;LRMWP>CMNwj)e{AS!>poT?#3#K(V(D1)B9%8k&y{_5Te_gP7_xXYl8b0aegllxPHJ*}{ z2={+A{B{`Ca{WZ!@HeXk8zX?ImN$=jA;5 zHhQ*HZ}8Q}(axbe%%3{z-Ydd;zY^fZ$+t)O>G-UJ3o9A@6W{A3c&U@>MDhGs&d6h* zv}fnAM1CI;-+znz{%gm1PJYk+UYcQ?9b-Kw^$MCTEiR>sNVdu28b~g>bbjuU*A;v{ zITTrU{dl0-u8I*)--tu#U51Bd$Q+cEsWnkGHIQy;QcD!AtjFI4g{2;?pHCydr5M;v z$&S4fZxM^=g&1%W0C%PsS(M_j=Aj_PY8VPU+8_-0W|-dG?|KpQbd5H#OY{OQUIN-yNhWK&@0M)+EO*RVj}qg*HVn1S1pP z`E_n-YHD_is8vsz;dID6+)mtYj)VZ-ZwNjDLM=kgj*^5rdzc4CwPqF}jtp+gChoYt zxaPCV&vyrAkK4}Jw zHV>>8O;ph)f;i`KTJY*A+G6`!7V=X{fxL=DP6Rjfj_RJJYqOeDv>!F+RBMY2l_eTi zwOTVGIEy~7O+ic)Y9wY+*G4S^(b>yj|;e@89sZfAhEe;rof{{(%}!c<<5B>J0si zpop{PVnVN_ZRE5h@;u>k{gRQowB^9rn)%4ofCCxyB+AYXcef^kNF8uqo;?v*3i&wR>>JB1-HUb&_eE_ zJ5ZfP1(U0I-!ltrP2d7?*bsee z+Q-^CM~DM12Ii9Zbbre%7GYLDq7~dRGEXylbmWrp$-rv~h3q17@T8oW(u}I&Lu4EV zE`}Xf`ztn|y=1rDakIU&@~Q-<(}}w~tJBvqqh(<5H(XtQPINoO2}y3Po4z+;Onf%m zN?<-_K7RPb?d?4`*O@q26tt9rueo8YKvfuq4HvI2ad?i0BX8b(&vYo<9X|mR&X0&F zMLg9NiWE!5l)m1b5rZn=9X<@~_IoZaE^*>0$?kAbl8H9+l(-%5s1?#|HR5TWDI~+I z*`wN`X>HCJo-5YlA{vb8+;=^eVv~Z2j?BpM}}Zs@}b!r zQN%mDi$jlm$4CqT=iQ3E`o5Zt3EooAgEI`*0~O)}K87abDtIH^($ab=t=Xt+86OSB zIqC0N0H$|pM_Vedw>~hgr8sNLN>GnA33XVv@D_3O%@B8-(K|vrA92nkQ5B&$?XGGy zz_dFyV1(SZ*NCXdN=q7Vc7jE^!Eh7J|5xz6S#Tpet_!xd>=#m5T6R~dy@x>?`rW9%*Y+Dpb8aQ@OJhPhaaX8KH0`*&vh-z;Ha|pJ zf@J5Z(LD;k@RDY(I|=?%1lX?EitV-6T%U^qt(0`Ce_WV->_zC&zq_7jQej(03@5F5RsQ;!9&c8vl|GSTVr5n%r$?53X>-m0keJ>|F z?oum0)y~mYGTAd9|2v0r9u;1=_!B{ZHV)od`~4sesBO|DL=xg!bWbX(xkYDrRMWd? z6b`CynFcMAUdo#K+|!>I^6MbRV6{RLP04JHOqMPJoSlcR=O&@;S2M1G<{{XvIBLmE zha)v9r&=lE*zYb0K+TzwW_%cznlx>o25*fRq$*m^?lZMmjkD{wL_O9c?Em2%QccYa z&0%ZKOVktfI1Om_%*V{b?aUY_>(uDh4thBY^W>>{WRz<@yS`>OUb5d@u?ZJ!!v&jR z$HivP<^Gb3-431M_U@jC!#%mRr!A?llS{6jzhrl@XS3boLLjSiw5eC2Y0j%s+SW?8BQDW^ehdL0Og!kRM0Fv%eN1yRzy@@S_Ku4Rwb)G3 zR_9V>QO$L601enbAwH^RL!5)%#mLRg4cp5-+s&5kcF$(JV;uGj!v-I=cpq@yno+&~ z_#=P#{Wsh_yeCRzXeI92mju5tV&S)h z5E;V-J_I&yOB}3^sM$H!#4pEov*YE<$n$5`Wmd#d=gjTxC*Hk%!|8D1c$i32LNztz zw%uyRPas0^xq<$scy|Y$OyIfR-|$y|^;i7mFaL^*i#=O65JO~x5%I%x;LZ1MIQ+xR zryp;vQ#+QruP7ziZOK&HT?pD7i5`NlEkYrS!f)kD7R~em(o^7?V-1ZYJA@4bQUfIy z=2K-lO-v^P(9_8XcyDg9_%~Lww9fI>m7EjcK3{UlXaZ|6Sssad%kR#9zW@e!1R9_< zCh5~o)(DUDeGD35bggMj2M?_4v!~|uR@SQ8G9$E!TDpjb77}QLusJQ~JwYtJ+M-P~ zkXDxt&OIvJiEbPQh9R22@xHBiM36ubS>Zp+p671vkSTwPspvD+~Y1EUUhape&qW4 zIlub#Z+QLsbMDIrZf|dSclbRI4-Yt*ZSDN!K?kypVlsfYI^=tOK=fpVT zm)qqcHwR7 zEXK$djmBUPUpf&+4s%bRo>5mZfJEqKm=mkzx>vD7~VJ zP6h>{!)|rha9inFExl1v3sCqLz4p$V9hdq@81G{og7qEf_6l9=XMMZJHKp0I@SZKEuuVoR`thN;?s zG&{VKT6y%^Yj|t6&iuZH=Koq_QD+%~-5GXL-_Pv40hcsv7aoZnXW$Ke^7{1g|B;YB z1qJ87tJ=~W+S})Z_$TSr|Jr^#vF^WrLc*z>A&K_d-s@54N6+*9%1VMuHDlMw;zEL- z9Fm?L&(nu+9oScn&d#=|&$z-HVD9W5O$9dxZFjF!d=FE6; z!K+uFv)gX)PAnbLo66{hfO^Mltppgnw}w~6NT?YMT^yB&J0oXjX&6uDiK%eSnOG|a z(B`xVI0l>!=&a0l!krXc&A3|88GKN4OedHRkuhBJ{Mj?U`0VGrxOv5H*faVa(T_wo z;+&A?nIC`rz{CB-G!;S|*bEys`z;sap8a^qxY-fo26c|9m_t)9OmpFzZ@=X@%}gm% zaSWRsmls=Na9m$sGsfp!UXFy2dGqGT!`+FGKi+Y7cc9dXs*|aSXF`P!j$yMQjvG`x zS*s2%mByQAgWI~X#l+a?g{zrQ>QmOTZ~aBE4|}h-}VwQ z2CFctkBnRK+R})Xe($^$q#Gy+?G`;D1}X)q);xpUqPGG#!G+#jsx{+KHKfoCKdqyp zwgv~irf4C;ONU09V8!Be0Cu~PKl{Zm`18N`4WE7SC6||1>~>eJY03pLjyT!1&gwf- zO8oAdZ*Xc-OV*${`!}E_3Pi@gU3ykc}|?}Cr-x`xA%Aa@bM#` z?k(D+y@pCnu+s|JStddk@kC7Q(?N0GQfn8-r>$VhCw-T+DTnI4}Q|5G<0Z-0GVzrT;tE(F>udjIi z;syKbD@${&;A*sc-p`r4yIZEiWF6M$Rv%AKi4P`@NLo9i3Y_L6$N31S2ln}r>*yFq zYl7uB1K#hbwGgrq=}F18@3hITh+prUd z-wtg36`S1!&wuuu+uK{deg6$9{f=-P8GJ#)7Es(^K)Y&U*2Hv7{P5;S#`u;oY#G8e zn=vrN5$^*r?u_K*5kaWQ=E)E?JiB@c6b^?6PV+7EbmCs2YOqFiS`bc4^P^h4t+`S` zXS5!eXS?0rd{m~>Oi4{VDQ06-E&5zqDURfx<<>=^4i3AZ)Z&sAG<(CWEgV~WCt-Eq ze2e%6V%Ttf{fy5(|B~0Qf5zq2HM`9yZ5mP$I@cG3RFoXOc*a>iLX-&(9rC!m(WN`$BDWMe{C%Y=9lb#=qqlp z-Vhx#*!|99@Wjwayeiu6O>KDAnlM?3g7p*79#IzGZYSwYAahnWV5L&FtzJ9pouz*p zK~}q4MZZN?pfw1@GHZrbYUkGmp8(NGyNziR0;Kg9kN~|=BTyPz1$*J&iwkB^L(7@-LUMk zKB^JmpX^YdzVYO<|K9gxeShJSPe`FY`F#2Q8HszekEi>QKfT?b{7#G<}i$i6t(o$lq+^K z3J*HB8mgIXN*w1CMJrQI)M;W9B7+xn2gv+)C)7nfXLJ>%KUb2h^z zPDZFg%?9YETu7x7H(U0XH(Xy{vEN;?+wQp-FBts>9|lAMxmFI-#9?~ikdAz~`@nZ^ zzvcTMe&9GK_E*<@`SV|Jx!*C21I`T$(Twu#?I*tZ=3Bo0`ggqf{w=BA<3oZo6>_;` z-Xfr>WKPLa|4`{;wsJ+LiMP#Xsxt5AH-_dL+B+0gE>I&n%^pD6I0Y#8WO?b zTaz!B3&j;9#0h+~liilcvZV($ ze#an%fxzkRzz=WUaeO$jyST)M$lWnIT zd`g^76QxvMJb%G%cfqTNXZ*{*{0sm1%`JDgcT_CPAUE<*oT;mJU*1(5=#3UnIr06w zADHLA<#areKAm`YcwoAHU_MRcI&*(`;NkF*qM0JS+i=TV>GMn0@)OslpJlR?B}&kn zUz~SwUUS(o`__q2P~vFiCnf+WxYF(bAWJq#QHP!;dVO}cjnX!)i&3-}-|YTEZm}|i zr*>*7ky^j@nB;a5vTvvLs8~&*EWUT?q^TgHR;JK^y#2JP{OwDR8jv*5U8Ul&$Siqn zbkb8%wPlY4AC~)q(*!M4my8O9C1o+j$Y!%)yW27hqcv+%>s~H0lan>^6Uk^Pmdct< zJW1J7lxv$$(w&?Gb!TFODA^UfD-5A5sg-N}uv^-D*!WmPS1>_du{#CiV)HlU%IS2X zsxqX)=``8;F($+?j11cybI#m8+;N;{((K5&;B+AR2+46c94M&}yw!4U#t~dZRhi4o z@pPn4iJX&xXiO|gIa4$f$3V_UYT1Ib?$SX`nDy4r*94Ga_Z1(vk#VzOvl)n+h#x!} zDv24@N|1oMEyO^)^jz*D9HZT)DJt9j1;az&cs#cH*^e9!2SAB#1e72x3g)(K2O~96 zHk4vzMMA)bffz?(7#N4G-BPevlgn8v!%(@n099LO_ro0zhYbh!fX+hj6O#_)Jd@qV zYL43)SIl4K*>Na|)1loqC)*t9o&A^V93tb`{_Q-miHSu^OV#fpdQZn~(KXChxTg{U}d|}U6mp-!o!#Q z^5qtiDa4YP$|R*fWNI$dm=y$z#mKrA#w0cLwi*d2M`2N!TBz1AnMy2?Q$9;cQkH8m zc{UL;)>_{mwNG60?OYpI4LZjv$(~e2B-6kw&^1{jdqmD8CIz^veV{E#8?0JUz!1KLdp8f1m&S3~;vN%tBnh z@@kvV8W{e!uT}K>IT(BXxu0F*fA@2Hl?A}c^|$8GTI=A{P^>5n>vOF$x(x(3pG6O^ zz-)1hn*X0tW}K=BVrYb^R*AS_vItLvN~f7z=OHIM*8!JQ7hWEk`EBo+uBr893Vxk4 zGcbHUb~7=iE&=`7@q0Eeq>VWvFwd=U0QZ)VQ?Y|Ll?I|F;dxVJKMR>HNU9+jF;n#dg=R+xPTcpzj02 zHn7`m@LR`WeB|+d;(YkT#F=-SPjuZ+oK7QM*aCqPC0k)}QrBrLS2s7@-M--Z>V{3X z6$+c{uy|?LV1qb!7@;9q7{?QxanvbM#*xlh_Pc?u_Y_-5Mfyp`ha*4!{lEAh|M&mo zzyADZ9uJTBE`n0DYF+5=wL+?ysh-I7%;{2@Ql=Q$RC1QAlqq0~w8UxySur%>k2&I? zrn}7xkPXIEiK+|bt)Mt1sx1JbQ(UP`P5i>B@JG!~`<4r+H&y6BttKYtLP?^Co1$Tw5|fIFS!?Kr zj_aFib~~XS{{9bt;9vgj-}&a-@3?;TioWl0ek(mAZ4cE@CNDLv#nE+@mv^7>hj0Ix z-VJ>G_<_UYTi$zM?n`SmlJH94xX4731 z09(^~+DF-xjio7)8`GqaTJ&5a)CS28P;`D}1aoJN001BWNklFEQVYBRiYfX-#wzt)qRQU-x$Q(l8et~+AbnP?kviXOG(}%UmH3Hp zl@oes*LV1?lb-L!sK|;T1cUblYbR=vb~b60(vuV=>zcG5c-0KBP*9;d9cRsIwO|3I zP>S^3_1YWU&;4O##H_V=57lbFPa^=M)GBkWAS(Z5B*!eu>0L)wC$iMahY#B0&b~~xV_MTp;;?+uh-DNyeDO{o@o5e;JC)v70B;}Em zCMpTv6*}(;!BVopWyz@4$x3NJshA`}MzJIg=SQ;5bY)-|2KtRC#BVGFAMitu%^nh@ zOJYiy(|FG*szI@4x>(3ba zE#7qk`n!$|y|gtf1Emy#wIa?&kF{RZ*~7rl?bw7PL)kM zD-5eNBds@Yx)>hsFWi4Ra&vd4-%V5-iFlHU&}D*y?6m^jX&rygI3wj7t~xqZ{GUs? zn%`BS&{_h?g)N|>&MM5cN(YRlRxEGn7i_EaERFO?Wby8eQ4Oz)FPDM&0#xzni zduN(^3>IfkGKtv)r{=RL`}1#F{q$){H`GqC~Cr)kt=Z%(aSY>sML0)y3&lGirQS zS2`Qurhco5f+x?b0eeHnn1VG$ghot}KIVfZ>;iu4DPFHN7mnw`*%kISvo|;NVZc;_ zFP30Dz47!u&{@@RHLHzbzK^CrsL`tR-&mYMSr`I>oegw;U^iUT`<^eqc+KaZzZ815 zv-r-^4}sDp-ah=q>3HIU`^fq9$d7N{aynnw4g*~`;9ZAB>YT2&H@vue#ohG_Zmw^+ zxxQuS1}q+&M0$;J;HBk(GnTHG%!>2kP*Nk_S?-SqHdi~Sk@p{d;yj%gr;#y^oDQG( z;ctK9Pk;Ikj)w;khHw^CMKxolIJ;AtD!_A6yC8=67>BQUw-uk-~8sc z+}z$U?Do8R^_tgTeGMUSOo?+5r^kng_ab0rl&)v8#aYko^$qTK-|_P9702U&Paog# zmp}iBzjb0cudh8_7l`S=+6wC|DBGtKj=EElLV zIoCug7FWDD&z+|dL^P=up$f%{@424d$7Jf{YP|s@g)f22UYSMHfJ8%yR*fh+#Tyt=59pwH6*9 z9yuINr0hj}X%y%7dUH!>1F!e5*}fR)d=F@*xe84+rNk63#5fX5)ZlS}+3qNH5edTe z!L!#4x{Xq<o5zoH8rfk706jj~O=!-atN3EKs_u4m|XocklY?a02IxJ(xwFOQtZ3%CnDID9W9 zVYsBVpi)i*|&G!RFz)anrB zUj@Jl*oB73yvITnO$Z~M3>vxLw9=#^?2}@c1s&V|DK(P@Y^B-;rrSnal)m561y)p? z@oJleE#WGdT7-_On{+V(q*KjICQ8OIR-sHM&CE(~0J7G&=3=NNW70&)8C$blq?5HZ zl}L<{DNp2-WS_7GuYf+4NpuEUZ)yrTMe-yfvCaf38Jec0Lk3Wbiu!5LT{I;!=^}u- zL1H;GOrB;qkdZOqE7CdmxN-=vR46&5`>fzBp)<52$B%eF_Ka>J&yPD zKDlN@IkoT2_iMr51+=Tak`;=*cPa^<+nQ1bq%QaS-@kqV9JkH;A7y`k^`$qngb-He zX-?HLc0c>-d`Zv0_m4pQGZ4PJ@_hH*SA6^Jcii6I;5wlx=HfUWFZ}T1pZKr8BrfA8 zl9KYCI4sWs08fT;buDYZrDf|%YHf`QDZ^#V*q}6Jr|mRWCu-5bQba*6CrDA$e6zmi z`YknpZPGO7>?zH8mGP}hk-L&lWPap%e_eTD3$T#ut6D3jCv`@~&}AN{N4|gmJr7J2 z<4D!ux}NL1J3jyNOKx}9)KoDMTy<<*$9~wc?FSWF@d_N9gC~RiJSg%sFkzPHkMid% zp5S_}cXtGD`R<$F@y$11F$|I&a{+vB8O;e?<^9LETwlK>mywt!?jJvKzDP~mW*FEG zdp5gUu5P#7zPMq(+tc+u6%nzLx|WRfUW}TG2-S+zq<9NO#K>-MZopT}J9zu)9pAtI z3&-=3$I}Dn=_2(#4q`A_DerHKQ~D#B0Jk7j`DvOx=A zkTyqM2$GFh8RWJ}wff`bE&U#?nURysCu^}9<&ple%E+)1aB|)gd?)1s#cOTYhV6FG z%g=tt@Bi=zzWnA}HoGkZPuKOhz9&{VO(QuKNFlPw#nQ_7Gj0$j`}jzO7>MAj!^8%)!M`%j2%cRrcRp1psguS zYE;*2vaW25Pz)C4i>nK8oajUGMi0y={wPD~%-ER}inbn(DYsjdh*D}EK z+FC8SwnsEj*T_BdlB`gYwyVf?ZUbVB0q60?OaD-9hoX!+0be;$Q{tCi;zWz`b?fV! zk}#jFv$*Q!&y_6BinC>2w{wlWW}J*Qq>_m_VxyfiF*(Ee5;;6f9PTF`A0p>RL%Q_T z)Il+rVjxe{8WnVdbrol_QlazD%93iM%0qc-3ssxJ=R)M z3p8qWs5A2WP(@hJ)n06~RnR+Bw$q+zKXN>s7>{QzrxV9~=6pUA&Rc1pWiB{xutA=; z^@Y#{j7wZDXJRar;;^O=yu+)nRIAvsF+|305=|E?_O|PKcH0eI*D+oaZ{EJ+}I1 z(=;f=z*&?|jWAeJt`d0FRWC~R3&?1Hu@!8ttLz`kdle;`ZA)bq7d4b8K;I}Z7pSd) zVqIintHgL!F9GOwHft;aCqbK1AxK2ZS0kA|qtsi|vUFDW*`!PsVVYI-0dmbqXQ`=Z5^FH1PvnfV$Of(hcGONTQ`#LD2D9?5|8Br{+qp$*M%-ViUKv=dCuo|_t zx@7H-n_K^RIbWhmP)oaTG#e;bx~l)8K(W-h$9c+VR|nmHtAsS72~vttt^7TXlBF&J z_#IViic5lc!KO3 zU|fA}?Ew5DPOneD^RvJG+BH>iMuuU--Q7!Gzxs^*)t+1oxm3nUoF(%lim?Lwdfevx ztna<7FIGX~b6`Agv@F?RYY~;@27cXwA*^nWROvrgw9a>~4Q}^p7X!IE-Qu7bHE1o` zLY-+eOI=u<$F(+3tQ}}R;PbK7FBmiTm^@7n{OzazBD%=-!wZV_Ou2$_+`W9sluv}O zzhmQj>VyboR8O5EW!TdBPA0KZIi#niS&VZFI;ewHt=1i2alzwjQw^5-$Nlz(&tHGR zZnNRb&%fct?JL=oYLUQ0Ko#!2KC`1EKGzH8I6ArHo(_#U?%--tnJ*`oH+$-S-^N2QKj> zj;jN2E3Rg|FNCgAYm$h6%tD86#>Ij6;5#uA6(e-7lBH*J0~xHxjwM4?6{sN2#2hH8 zS}&}1lx?0gk%4C5jZQX;81`9kr#4z~bJ~~lo4HoAZQ52hXZbHTC7c+L%byQPieV0nHvO$YIRz?C! z16N1PwElEtpp_R?rS}_J;ctsb+cqsN+J>kuL8NB4wRW}nf3pp?%RL!p(>brlHjW0> zZZJ@z&;&v1%0gQM!QuO!&Ptmh=Y)PI%(p_Ulh)}j;O>`RO9_I$YwI~I7puB(@@^EM zC$E;_P-jrvNkP$8CvqH9J)I5Q?DpLBlGzj`a>q1gK7M+~yAN*|r;~1Js(@`Om^_d1 zFWrU&bJupQeYa)D*MOlu{oaz?5r#}yLK@e=8d8&3X!4;^Og z@UF*oJ(uyqR4>w_-HfVRAoS!ZPQ;6p9&I-}t&fy8J{P0o|%nujtQIB$}5E#I`lhuu}}XY5ylGe^M)~|26wwXJE42b7MCe zsyeu`=!9PG8I09F<^q($j4foVb4Q3)vs$YLSdIGcItDNYYm*Vj+hxQDj#+|K z8sv}4_Gsc=6ltB9W0Jn+Su?Lx(Zp!>PHFWuRSoJkMx6MVIm!N-ie{iE=?k8#QpIba z8bd4+tcv4VyL=?^?X;A~E3?Nc5T2^&CQP+TTTC^6t_qXQBf&JBqtrsoS$q+tf14s= ziLQ#UV6|2-P!?geRPvHkGYcCtsh`yhu9@eT?p#`P-1dPoQ@RS-Bw-O52_g!EvDH&o z)m4$V#4WXdFa<^0I479E&Z0^SbTM|JZF^_&&A^v})Mz#5q%D@`fTpf~_YVN_?8yH7 zPxIf`Aa?B_v|}$+UtMS`z-?B?m>r~FxTIfw{n`iB!8#pB{{Htja^=iY7``K8TXFsp+mt_vf^%jhA6kEx4=53`vK2Wfn zC&{L~`{|a>RX*Qe^Ww|juphS6u@I+)#5i&P@W7ilZ~64;lh%`YrpYjl7g8LF zQ-?E^-uGOF6A$*D%Q50iz}a4e4@@BVo)8AoRQdSvfycuE>pWLC*WBFQ(e;+XgfWp? zC*D82`6Iv&Adck5=clar)<4sl}{D*B_63>^kRVH$zg1_Y=$4&-YFvzN zg2k%yU1YAdIw;v}S>`LUf#s}Jss_fhI^lIm6I$;GT1Vq-H;Yw>%>N|O`;v$;QJKgJ zl&c4V!S+(O5{7~9W{1BTD1G2q6X(-`N@dEKX`DDeoO$?k4`br?=9X8tpRwI+=);b_ z9~k<9&1Oqyq}OLn87@{RRR;Raz}LV14cq=puCK4y^o~Ascnjyti8t@xayX8}IPvNJ z#JRrX;qi>!NI!Ak3wn&a9 zxY}QFdvnWA@3)*zpCpg~5E`vr`$!_Rf}&BkvIeg05kE0{N;hqGy#cEBD!=fZ72s-S zs#ak>Oh)#!5`@NP^#H*^HE!;mTh&+_MU=S~$%-1uQl?mlab!#|#mE$k22wPx-u9#h zVx6)cR&}Zvq>lKRootz6>sW+DR$SheZKSHBYZd<+=v<)p9hMGL4bFCW-_!doz2D&b z4j+Pm-5ez%UoB)PMKUC5GQ=cns10sw<1srhXvu=Au2YTFP}&YdkYgH$HF_<^VklrG zE7=^`7LaN|F-*Y*&!*pVbF+h2J){9=1_pm4S_!_VR`~ewf&cj9|I1~X7~fASu!q*> zXA1EN@NIi-vtx6o1820A$^z&YmXo$Y%SG8!!i-7!m~BwSX5SI4ldQTCod;nO1vY)J z;c6svw~qM`KM-v|G%)V8qxKJ(ffFdK73hs9P7CCjl?DRciySSve`OkaLJAqG-d2 z@1OL#7GpjGVdU9KJD&>;1%6H3d@GOK22!`?D@G_`F8c`eXox@*OeJm0ai16Ei-H-+Exlw zUl&oVvea{~Z-0(}Bh(bzjBo=J)gV1xor)S2s#AkjpN+N7i{-e>?`^wyR|(qI$k{?1 zkJ8M$!ez=_&Lii?5A>n(Vzc9_@45TpTeh1ka)MgK$#d4Lh{e)VQjB_?2do$)AQ*`x z6`)v=hA&ho9+NUI1a`X}cDrTh0?vA+QHj)i94GD%ANli7f8}rAf6vEpj=E*IeJ< z5PC!5La8GupLjUD=gs@SkvX#28Y;fYUQkhLp^DSgl*vgPL6O}@glalN*E_mSCP`9y zO3I0tRAn^@dteTNm1XX(o%VS{S=FLfod`|vfzoP8j8KVc#TdV+^1`oXo1QP;Ss@zf z%ZCL#*lIAn6EwtkM6C4D~rAB`G_?|bXO83{lP)#7kM4A%Q6d6w=<7MP(*z-?+ z_$L9t+Z~&3M;Cg$mwu?($Q&)fLhrG?CzOs`bH~k#8-|c1yHPT^6dsNT-n@Cs4?q3H z!^1tvK-Z6S=aH-P#BjS|zn5Oqeh6%Ws7%HwbGBz}E?m5q%C214_@4c4$EMp#59QFa z+wIuhTv2PK|EcG2IP=r{A2}Z*rxei?z6^*xE2wPZ9{H(w-hZ>l)Rn#Z+54$!d^T5R zUu*`_Gxw|J8DLi1Caz9pYgMIK)g!YgV&*bYav@zZr}KsJSQ#&o@lr*sEH5h1Gmy0g zqnTFeH!I^H09Y1RX>ByD+HEaIu&PjOoc66$gF@Hn=ATm zPv31sVK!{=!E-*H`04E%-n@OwWju>cgvm@XahVF^q)v>{sCuK7tp;1Nr_ITcdP4yW zdqUXYT_CtX7kY-S$9Y38Bhz>kM>a=L(JZSplAN<-O}l|tuRi08&wsAIaZ3E~!;gIW^oc)(KSH&_%+Ma>>pgSLT$z1b!&1877IpBP6O}XviDxHC6$7m? z1S`EFoihx5V87ciY_@EIWIBztbIU=CVbcxVTwT+-ozwzvrS5Li?=a5sa6HiYAU{9c zbBQB%nuxK}3=%ZTv#G*5GPbd&AjgrCBDF{zU*~#tghdp}VI-rTG|N;C#W=jN*a~@) zKHG+XHvwB@A1hG+a2>UsQkDMcw|BR6Lx-uaaNg7PhRsIG!KPS6Z)iPpP@O#R7COJSwJ8EcK`q&07*naRD2%@R0u+o-PR;Z_Q$~SbR=g{ zvX14%6eDr0U@Tqe+3mLU!E4D))a+O%LDSCA1<8o#oP<7`Eh$#I&U1CO=hcf&sJcEd z*nwbsdedWyVH`(3-QUyq1J~C#6k8d#J)8ZY8DJ@`C`LflTxz6&E#s_EJdM@bPYKT2 z79?V&@luXU-A74J3cXDY@Bxjq+zU9Wqp0=zo= z(Nwd{xn}Eik0@=OAi;cN<$|n{a*JAoDqZGaf0;!cqcsw#sf(gWt&Q=d=eI_kgG#}I zN4i*46g7`*8=jid`!a>jloi?(Q-vg$yF4) zjZmeXHMCwYts9ZF8WUqCD$kNhmhuZ(timp+Dil{#JkDqfOKC}JRA{ZLJ*`E89?Sq( zDApybdU;I3KFNY#vTZ^&ld5S#lXFd2 zbC`^Rw_m)U79g^}^7r*E7C4_HmoYxQ=lKH?wb$~6C--Dl&cu^@tg8UP>Kg0nnCn;j zoM}MUg9{Kk5VdtPXK?57ZH{I(I#E{+<+E!P+to%@pJ8dyIr)XLUJY8&$eT=-#8QhU zUtS&8JRJw?n&G$7f+cvV^P41lS^!GLlt?^RzW?)o@_%U4o8Ef9{pLG1S63olVLF@* zTFYz2*)1*eSd=y|l%GT;YlhfXu(e>a&_2sJkkoh7KiaVn}6TjAzDpWXe0NOI%%VcyT8V-Q|=>Qz55`!{d?1 zhX>*`NwanfF`oGN;Y=zgF7bg&Ix?n5rg&tE2Qm}ROBARWxt~%iq%tcviXo7ExYMlu zTH!lu^YWMrW6X?`Q1nV(dPHmRc%Gl@Imqf~W0@8F8l7p~dPO{Ui_z@vT<2@dqTa^> zaOHc2QViA>mO5?OP@nX(Q*eORh~}EHTIVAz#FF;&)td0uc&^rYx(Dm^K9e_|XZdz@3IMA@8+ih#VhdCATG zidT298TtXUmm1U}pbKe3U8}*a9U~YA7?{0fTkRi3Ai?)i;o=aZZIeit~LwXQoRcPKIeJbN|L> z=bZv<>kQ6I7ED0!0)Wdb1SP$7owHJ#>s91P`%gB9>6G`YZnR z_x~HOUc9F3wwjgguqIF|+<&^KL_<6m4*pD`GEO7s2=Od^QVWJ^GsPr~E%G)k3f6jk zw>DH2YdiY>iks_KY&O^QVW96M^SK?iVi!;M+~2=b0A#49NXrRi?bIyiy)uTY>uWyy z;!EyszQCI+O7Z0Asl{Lk_?Q_Uj`)7S`i`np)Kco)j;uVH2pW)R|7wQaDF7GIJ^>b4 zso#=?5y3|9MX7l+0M%++H7nWzs<`S^G^rGbIYG4y{f3t>U-Q|k&*;Mrs=*XtU36hX zOo;*`mKC zPzkB0>jpM{WSl19uTGVk)qyq3n_4l>&}}>X=7y`QE3B1lu=SF$^}WFb2OgQ1)=`b4 zR4W;?SQNBtR&l-9VWIgKnOnk6kY{MU!*v~!@Uo$AgrCc}JWkVw|WK$yS%B z-!*~0+p`_K3XCZLHe$zWu{e`}k!c#4(xfG4mf$<~`#o3tE4t82?Q#|NmM?)k$=*8j z6IWL^^!)}LbVEnC4TRofyoy;lqx56(EsB*I`05%nL>L6KANK6k=%md}G_wJ0Unq+) zHAqR3KJnQn$1Ju`?V?eK+%!80i#9>~fIha`>`(h#L4z}Dk`(|}^VA7$-5zQKS9-n% zuouSIB1$N8uc|*QVBZ0i^o`I))U*mJ4Fk!$bSSeWb*_sB694~36I2lo> zuSNy56kD~-@tg^4`@|C;O7D+~2&$oiu)5|9;4)|R*;Z9iZ#oJsz+t3)WCO`HisHD<6;mJ^M==sm%hfQc_C)K1V^Dg3EpyN^ z=QJm9i&C$uSxP{raU@O`N{I^qwiVxIcUx#rgn#E5GS9ImV0d1!qcmx%UEyKcv9l!SH0rHwP|=cH2YsR2j}nyD#8 zP=d7Wq!WnF`i0T@L*1uYV+X z%XZkX-ER2m%T62+Cm9GRlA+6)nv>L(VyU_qqp?gtG=|)$v)Z>VmrTu(T14o?Iwz5^ zTBT=RkqmH56UXC;`}=#&=aGIG*x%i-zZBRXgb-C0^7Xo)TH{4#`3MJcCVjekM?zumVu_rj$q}QA`mUkkv?= z&LS}gb6A2o>Wf5}r%{~mR3PTclwgXQ`PGS7%d$!6J~;*V#>I)D1VOUNvQ3U)XT*&GEJ@VdnJsS@e=WU!n#Pd5sZg)5%$2zQpQM`Br7yH zsnK;CkMo|*W=|X=Z{NIwYS~{M384qK#TZAfLZ6%tlhh1@m;OW|th zxxKmN?rP81UwzGHw`Ujz>_%$i>7eTZW`NeGGK4^I9Wf@dFVKVQ0$~^!_BWJL=!QMp zt<>5Z3_-nBTc8HZ%kmnm<@)xD42gRPK@<|ckkZtpZ^tkdwDyvPiEz2vod&V zBd2q24$@Vg*w)2JF0;g1xt`hXusT-T%o;=4F!w>v35t`=qS)p?Rg8_Q)Cnb3rEVEf zj~%5)_IS=rV!kbw3NcMg=^}w9TSdP>0q_h!G!RoX zcqBD&no(8!m#;tPv)5mM>4+&4qhvQqwRE?4ys#bJt1lU+i77@7_xF5w z`;N!^kK~f5W@4PA@A4RrVB%aq)z)avkWz)}*lw@*?6a@={PS~=HSRIurC8L8ReY%jFaG%{7qL>VhK zrc~8tSXb@J%ULMOiZYs+Z;J5LB1{*|ynoqhvA!etK=46Yf*Gkjl>U@WZCYyiQqIyg zCJP9-y?Vj#e)C&?|J}dv;>AmxZDkCiepa*PcsjAqg%CP!UcBVx<4eB(al_kpZ%B+# zz#C8RdjXok;ex@3pgo778mB!=1pqr0jA`r!Yn(W;wG&1|c3du2>ivgA-B-qO#CHRo zmrQ2}LHj)mRXFEDXM_3((ktA!D8U)8ipjkMeCUKdW`dKR_BKEj7K^D%5c6lRC;pfS zI-&kT^;QBOU7&NGzU!zZNxfytI2>nt;(}$G&eUp2si;q3u_oaCfT0qC7y(-~V4e*W zL-tw{Q>9&C(4dERUVF&*!fdD#Y$rMqz5=ZG^qUQ#@328^sv9geI2FsYa{yv4(@`gP z7DjcBYUEliP6Zv8acMxXwd$$*$NJ1koc;EBP+M(#I}!8xYAxT;ee7r7TwwuYo438- zt!kgw$hZB!JoAwiMC&i--_N)~fh+>1-E7z7Gu9NW5#TFXU>V7^v6aMURqSD&{C-CJ zG$1U%*qTP+)}YKfdsABmyU3N*=2wY;RH+iMDmJ42Lp}EWU7`OIYel#0bsP8!b-Q4O~X^x z%=gyXd6n9dRa(x6L9(T-oKx_PV1)=;memq@UiY1ao?BNSc)hDU`}vpb+B(bIK-)|O zUVLRa#LC%e4~;5W@}_7v16s2hU-irl;=LFZB%#P+Y2r_75ZuoFv0CA@yOr)`oH);haKC^hMY66?q0DQ_H@1%dWzB~YR*8w+5n-aI>*HrMj#qXb`sfg z&TB@?6RgK=Dj`?A(nCthq-i3K7s@nhFreVQ=lbS`u)pQ*vpt)==XCzaWqf46-x1Ru zcTB{1=1~fvYGBit`_fyi*dz+`6)z&zD3K$1z!^MVaZ* z61^0lV&*y33~39lw5-v*)mFJK=Nz@R8ZB|&fG0iWT+4)Mc4obqmr_V65wp}g=bUE% z+?u+ZT9iIkDJt+^RQ$mP0T3}xGkTf@vr;Bas&<>QsHtl!v6i)PzTo{xb!QQ&n<62M zSetOZW9aU<+TGy2WX7)d*X(wChHe8GY15~R=JD~7%apLrQ)~}dQtc(f@p$2MI5E9H za5@}tX~dXHU}Ce8Z0_CNEnmER$;(%-*x%gJ4+FIqT4Q!nBb4eSL7$>oq$;)eE(o`* zBDBNFN2b%6v0SKl@SO%hB+_kiWU7&Bq2CU?c=>|9@7Nv#(>QXDJ*VRdgA-d4Wxf;* zq%>cN=eBWW51Va$k|}OLS3hsn?l!Z!cD|lCTUs_#odDpJAVsjY1yd>}CQ`Dbn6bXK zOhM|>i`cq!E}YMq@gi+{iuR%{?f9(hpfLpBv)k_3?)UWlKW{Xk|zVdQ)+oX>?6 zr51O(OuYN?J?}rhXKZWMS^+#oCdl*sS%BIyC))Tr=bz2Dmc6nvZ;K;Nl~ki-ip!+W zwN1z+_$vVu%Zt00eEpl>^3VVJZ+!9PZ|S<87%Oqgl<0(YQ!>R{hO0e0e?#y+m&=)9 zKhO;whtmVQ{f_I~EyHHOcSidSJ6!Noiqh_7!Wr#lY`s$fzcxQCA#?;g5PYCSs{j!; zL&4FJH<{`z{UBN4VHgNj0I>5NxnzdiEm=8ha8Bl`@#1gb@e-8nfo{!!`V%rvl}b3y8dX35Vq`YvyZc(R1m!OJ@r6Ofboin zwJ6j+eaSYu7-6$IuTXXyQ$boJ3IGqPNotx*jG4U#NpU4xX>^|Ju!b(xhh zt1^xiHdw|_#-Y^|w_zzp{N#dYFh~%@(A1tq9a@f)YnfXsLd)FN85@*#k+TSvUWfWW zr2#e?pq6XNChL57`ka>AlOsK0)3H3q(x~z}E=e~mqkvmxmcdm+kpgtt_tk%DWid|G z4rlmeppa#AZTmaSeVW^3E9xK`eeP{KGzcj**$WVyMbwz6h(fw?EvwsnK*_L+sF(q5 zYh;umqYxbFqb)ob=w(l{i(s3d87X!Jz}9GPJ)-{rG_DTgYK$;Nv^Rj z83zqCNX9XP$#aISjY*s5@Du>IJ1rHAHdZ%fi9j|mEFvam9^VF>3oxDz{OM2sfi;$o z@89v&=U?&pt1ozQ^OAi(h}tPgA2baBlvK${2uI{Fak@pRSV zgnvq&BIEf)F_~B+H5+`_aeH^m&h~Uyj{R*%brVy1#Ch3}`@SPijuf%g5vX+&U&z#0Y%CO%7uIGwtrs6q_hSR0vJZ-s*XU^k^^LSxO zQItKWQ3L?A7SS5XuxGLc1@!r9z$9i-6_2eomQHj7a{#4f)tV??&CvMnwxB==Wk;4( zrf$*sqiW_=!KztL^4039RVdo6&b+;?TV=!M@2tRYP9zmtn3ZMAGAD)3RLSaA6||2l zjY3uC%#8%o>%2~KmKv8LOyp%8)Q6h@V=I`EDOb9FgwUL}J-2r+`SP1@`0C5A+3#=J z3|n?Pq1A2tAoayZQDm()NQTf4Sm#JeTOE_7ltlHg-3In%$IVU82647}TNwJDyZsf{ zS6A$=ukb@pa)SDbbp&Tb8~~s$?FUj$#7pFSK5?2x$q43=)9J+fhXZfky&++F_3{-j zZeM7BV#(Uo^CG;6$aOCkU!f-L4`0>Xdx&L%eib-oDYb%9X3`Uy@&EBmZ z^Aqs9e)AOM8r>J>>~H&7qx|iBjmcZJ#yzR9iB*MFW5ABmzNa=@t@E5>WIl`t_>H=5 zRxQKUn}s!&%`oudzAZ>q2$Ez@PU*v z-`l?_U~`%sFLOU&?>F4t-tz5t-}0~j^6z}}&F|Q3_tKsvBQ)r+VHz_zi_nk3<9#n6 z8mLt$h0a0WEwuQLpYHkF-@fPZF@fDNO_j@~az0Otm&Eya=KkY7??1jH=ZJH5~+CQfa0YO`Va=X&{4c2r9$ruHB=m(IHXoGm%i@>0DEamVxdSvCzo?SdCm=^!t=Glw%|f03-K#m~y3e)X z!Y}x;bL+omFK1wAzzPu2ztAG!M!(l===|rFZC;&B0^IXQ7I)fczIsOAdOSNDXL&ZJ zijIJa0=hPLsEf!Ik|CaNeKijAd|B-q4Y*ok=8UlHCGusf&h=V@qyhWVjCrF3w*bD8 ztgT2cRcR?%m)v<1kCG%-A)2~~rvkZZ&}V(2^MI+4*4iJU;T}DQ0?<~|xmJ%}Q`6Va z{mB@uhEF<}$nk7@ezO3oX>f54GGkg&&CqJ%tgW*+nx-IEC$F>MP^IzqCmbxXMGDvgtf@B`*LW6F{Tnq-Y zc_XAM&4tn%u2(l^hjy;h3p zTnpCf*La%ASv~)?L9Qw%pL3OsqHP#Wu*-d-_gjPbC{-%uG39wWu}MN;HO)I!w)Awi;LvI&~8o zDb`_Yz}Fs6CYZutH-wFaevjQ0T%R~k7jlkL*VgLyjMN&OFJ~^7iB12Gx9{I^clQzK zu(gA7!L~?v5m1rxnJFGPo<4CY57chLJE=u;L(lHYlh_keVvG})@xtkH=5#u7I3Br# zkrKs7nqrC5#OZJ#<%yCF*g_M!OPU2!jh9s`t<^eMJ;x^?xMhHA0~L}ruhpn9fuNlA z#=IsbO5I)2%|#;Gi_OqXuz70O=N4QvFkPRtF`Cz>ZlD$`4!epul=TLpbfco1rAb;} zvkDHabp=}H@kzi;jqg~YQP_n`LGvN5`?;NjRzT{^AQVhTG(o!KOoOA59 zTlTv>q2JQ?1HRv4ttH~PTt+^8I&ggaL>v!nhJn{FU$NV4+53*J3j{>Wr+4!It``~j zvn?1B)mS=frK|*IAUB;ZeEjs0_dmVk)2B~7oDQ5X7w)GM$K!!__YZvd@PV;r?r!hc z@Ai_BoJ1`;pGRqbbbsM=J`pb`rZ{mPk6J5r=5jf6K7Z1HTAiu$^Dr7#Du;{RY2!Qt z;PwofU-E3PnM-2Y{MFfD>f(6Mj-Ec-oFE#pg+|i=i=()T`sxNt(LhL}PRAAPY;Cjk zN9!!ZX5i}jhRtS=!7*MUxn@!+T+}uQUDMDaoy{Sb)n2vSWUbKN)2~N_~9e(-#&0TfvG#3>1IXI zQVY3eHvN`wzWzP`{;&T#zyJL|aeaM5McU7l48e6+g3z0%Oio~`$0PNdNtID^F&NXa z-E46#;9W;aj(2bGxxdd?zXJj>^8YdRp51aJNt)i{B1DQSaRHRB7HszNaQ6TIkLBT+ zC5O{fx=;miRf-TU_`%#gJQJwyjdK!-n;9A5;cjl)USk|4hH+#XXJ$XMTDM$ZUlPO2 zaCpWAN6f?&!?I7a-cZw1;Yp#|>mr-H3;21)IT?41IVz$hqM(r;n^{ikCCkNzz%hxeid^>EoEcbSXv-ur7_tUi=v#sv0_RQB__pO!N=yz>7jBoZqZ0jj#!N9 z%GgQ*JyNA!pZ)6e9(=@avJsi@x){gFXi68Z4Y`sstCwr$xyljW+`=tq8AwaBm~E6Z zpFli&SLMH@7B|LXB-O@OK0;VP1U~}c%#rP69K@V*9CQ8{DOQ?LwbPtPgf@upEbA!5 z;*1YDW_xzOnC_#2jJO|zM2fS)Cv&>cQ2kuXI-RBAmN{GQm*rcrk<#;uT$cNoWKb6p zNei&pQ^`>rW&LcaX|95Hi1C@72=aGMg*F9rv`N_!N~^>Zqm-&S$!rWh(jdt49w|}t zk<@!Q>5;XuSmxfRc@;Sz26`%s%yZ$BPN?sOC2xIsM0G zj~^(l3!sQLR!A_4M*sjI07*naREp_K&b%c=jgK0u1Kv;U_D{Tf`<7OB%+tu@W<%d~ zY*uStTm^2fUeGlwx<=u36c7O?M*9>a!3CySfsu`@tRiYFwZS?Pb%0h8gC#nR8v_%L zK+=Avi7*fB#|MtbJw%_PHj#OnIUWY~hmqhS#JAYyKN#l7&Gm1z%^G96Wy2C=VwnkH zB!mIth*Az61KLD!ewY?zB&8!nsb8MvSrD_2BlF-1v(%Uk$C>wU-!tys;Kt{ae(aMH zD|gIE1Et%FUe>g{vQZe82y*g)EQU$uby4!YMF<+eylrEC$Y$@XC}esj8?ps*;E@&)BG;PKHzR4FAo0chms%gE@}dnpa5c!K%^ z+IB(6LCumG;nOv>@jQ2r9N#}OJv=i`jnpoC#b7L5zv1fon$69Y^?F0oZ={c~?TImP z939WYJ-_|(J>UJ~9}G`Vyt=#N^4o8@y1{919&-(nq-MFabplc9U1q6o zj?>KXIPm!UJAU}#2Y&tG2Ob_CI1ERIapd3zX6JaGjyyd*@;vVO#Tbl90(nm0YLm1r zFh^+tq*DF<6f$_+lu}Y%sn^M#WSwP}u6Rb4Ibr#;D906FE)Khem5?*-bj?qb;!ynR zsje>Me!^bT!J=PWGa=;EG)fI}-Ulk}1Dy>fUv%3tuKY*FJMiA~^tfa9Ja8NYebPrS zSq*xY8g6EcUDBFWaRBDhfq24K7o}Dr#a-Lcc0H^9hQ7Pt>1kjZe@F9(caiZJ8IO*G zpK%KGx?_8N#noyHb6|Yl%@ z`26+P++5wEjAooBf-(uUx*V6P?YnM>(L%K7 zC=txAvGiTbW?o5KA{Q7gHgsCy<`F*)gn6W((|+16SO_acbzRbtKqW_lw4-seWC!@f z_l%;H7)ew|>Jk+}qQWUlX_zM7y#0;A2fEb?uPlAP=CiNAC3K1_8)>^9Wjf(ybhimeqRAX44CZmRAr5 zM(ZRppOAP%CLJwC(mYEp;?}qMHYwkV5J@s9a}y!lcW9J{}(>*))A0 zPrl2BzvvlpDT`F89Z&jRev_Z4q<4sn%QTj(xe~=q<2>P+)pzx=I1fHPr@Uuite6ba z?0_%j59(yPi$gMs14T-GvH?pnA##Qo6|1a(;>eYYmo|`k&_@Sxh~)6D<{|hya+0O`#J0g2trI zDFqiG&2w}?I*=q>4X-qU^$gAjri9TlCs1FNvJkzJ{gr`#6*>B!S4flz=>|ikz(TG= zFD@-r?}I!E%bI^oQF#Hf zGF?h9)zkZNc3-U|qHB`noDoWAFR6Ggr)Q?$7@J-h_#=IuqsXNms=9~LsgH0nY>g(> z$u=n65`x0Hh@@LZsR^!A%;RF{)`mm<|8mo0tLUUqDkTvUYa808!8EP(h)o{FkfM3E zTk+!V6`#NUn#=7Co9>eB`T}h&qxTHE9S^%5k55Nl?vK2BamU4GEB$nhA)0^*kyb05 zQg|jNC!1sT6Gj=lbA-|1CkK3r^aLmvt=3r_wRO$JHx%1=uHPkF}s2N_{8KU&_SZ_Ia44TznNaMQ7FS$ zqQ8|9Tnynv*IDfeM1*bWBy3_4>Xlqff>AC1&oYT5Y=YF-D3$46kp6sXIv*h!&6$={ zG{zWdIisTVhYlK@+85+nfS4a788%9?`q33`z=^!C`Cq;FbCft`Gbq3+McY_KmPb5|M4IHFTel(8zx3t z8+m`(v059t#$bDifQup3Y0YF5=WQR+bNR~ zQBT=;*5%G4y(ML}UW+WBisG1*VO25Bll6(^T#_A=5mjIqj|}r~%(G`W3Ys@sQrB&l5ZP@+E4$FXq8I{shH_u*JPF2VnzrZS z@|v5Qmt5bxV7q!jV|wr%!E2&7Oryun0mZ=ce&FHhk-<-x*3eo>1H}cpreV9;uwJd% zZZ3HB;uV|iT3WdEE&Zwk0&m{@!uLOXht`U_m!ENUeT!Z7%)t?&K}C(#4c2t1XlOh% zs};IwiAqT?Of+4$q3f<_T20e-^s6;}x1w!&jO__%rdbTW#&#GhU`)d}GmQh|aRkH} zCK1RQXr)pJ7n`BzKvMr5h;d%_aGLb!lasAl=j8~6PC$$?t)iq&M{!(u@7V8mxEQfb z3)a&1E4+;aW;So%()TO0YMG{q@h~!v6Mhm9$mm7@t}fQhVdnbvod7V|o-j=*%BnF5 zn5Xp}9!bAluQqJA7xb$Qjp=A@OVjo=-HN8M$>A-Lm$pqx`J5brCS~j7wp1}?CFdofGJVVxu2`NBykC&RNgfQ6s`@dCu$QYL1d zMULY5RFzzc)qKU|WUF)?adK3Bh+|Ckvr24_G`{+NxojY(XsbN-q%*~8`abm(CD^w- zQTn3ZYgHCrrju-(rW)KVJ2N_TLDx<;Ro3wZq*1VdjMlU|^-)iTuO=qM?rd0xw8nCN zNp06PuTd0WI4{nPXb`>{#Ss*>AUF#GbU-=e8ZP2=L^+wEs7O)$#qd|f^HkAl&X@&q zmQ^k@wV4-bmPs#4aTVSC#C|+k7^S6w`Fg$P`ud8Sn+sO!9<3GQI54}B*-wP%O7u4? z9C^`823Y;s*?kM@u}Yqy{9rmwL?pF{k@HM`gk%h7+4qq~mY<^%pf%7}rscv+J~a{9 z;iJ>0Ui9tddTBn@`8d+pPEzdBy`1xT&r5UbG=CwD$J#T-rjqe&KwD^_I0B&BD-o54di!b=%^UvuwYl)V6hYJCx6+`gsrB|!c0Zs(>V>R8B?pZQ z8W)@xz(F>CPWj2TzzOhZQHc{}ii8Xo%1l#p<%<#oY^TZ(eeD_lj@6`YT_4 z_62v>uh?w1v|5}Nv>k2NF*(n}{qH%skUkvN2cpo@!ptaNY)`lw>fbvo&Y>X zQE+^i@NQ;K2;?PPomyI`C|-6!0M$#hL8sI$m2najF(i+=7Vr7?@|v%{{+6%4`75tp zf5FxI4n>1IYTOtJlfg}%FlvVV#LvI~!jC`y$lDLU@%;3}!}x%;mYWwheD&2AeEG#! zynJ!Tc6-TcwW9Ak`mRG8DIs`z`oJ(AI1I13xV+$-Z~x5A?Ms?Xk5K^~Jf4UOn&=|a zG!4tWEMu+F3;d-cLMy_?`Xk5v_Xx-a;q9zO>FU)t)Az+pbp({)lTLx3@1) zO;5B2H%`oMmelniAb(m5+OW1#^V&2502%cHs3hZ7sily`c#ky(=Tixa;lu&yQ-+Ps zSaB$eo@ZJ%pnJIlVAx+>BlnLYUD;(X^JPYfFlz(FrWm^jOmfFjJCa zGTt-~iS}Zl5iuuXdY+<>lb>IVrX^@|8abCGNd`kEwn_;^tNRr>k;YMHixr(BBRG>V zMatmGfSa{Es58x$&qDcKP1~hLJ*O_`{^Ddl5Q?E&vLaZF?ZPXnzsWNi%WPKTT_!&} z{-rirCw*f{bT2EfRONiiQ7BH16Ob~}UR6t)vKXYxycY*Vy1phz8M~3Ft<{RAF|>`Q zv4$p$#a}2Zhvr` z*>ek}rvGOHxK`%K*RQ+{xek%I%tbbEy@M%DN;aa;nPtj^JW=q9$8E`QDrv`A*n7W3 zKb)8IqY{n5`$_yXA=T54j%kWasc)=L#&=E~ECa0n|EW2v=QJtGS|{)$E1)5yK8?Aa zLXmphrj|uYMch2$d|;j(!|}+|!vnwl`UW>mJUqSQ;rSiw?M4h>CsD&$!Qd7HIA&Dq z5OMR2KhC)0OmqPgrCpB>pq0ZKsdbWCJsG!c8dj?wqcz+01-F;4nI};k=XvJ+hj)Dc z!*|?2-s7XgGZWQ>G8)quiOSp5kIidB0`787+9r87p>?G1dRD77ZQIM7Icd2Qqi4Sx znGc3lV_A1s++4k2rC;!;&orHF33K2d-~WfCWIi4VVZ=lQVJ60acLG$TKs?W>9z*If z_^2NC(_WvH1W^fw+MAnedh6c5lFi^#L?!pyiwVSTsSQ5O3rj#}N)oPxZ%Gf{NK%k; zkHrwtUg4uobR&@rkHM!V?1I=B@aa|azmu9(7T!_lHa&Elpy2j1V`a~uY)Z*Tbg^Ut}uxhAN{aU7YWV+x+p zJEr5rVLvbpBja)8`RRe<@yI+&#C5aT^4Vu!@YPpe(64%&3%FFn+O;dXe#JOD4(T_$ z{ejtej>jXr=Vx~NJ%__y4B`EraU6)=rR)n$jLFUICHj(c;)K5^Be=?pDqx?9?&?yH z1avAoM78&8@vf4xE-n5nZ6lyo#t6E4B;dybZrmqF2ja}oV)R>Uu&NQ1dj)QG+)q0K z4sT$bN4o75M3_fGx=+3+d~kU0&<>1k=vrw5WNky+c4$4IXN^@Wn#N#SLlXneP12Ly zCx9U%POYG`@@+YHC>1cJ>e-8PhEE?KBO2>ZeD;a+&n_6xKThCUx$ZE6v=t&L;5nk5 zYL=sPZ527^MVE;&Vzi}ebwSofNg0!E4PDpKwo+1)Z6zHWv@$7br^+4`kfdzre&Trw zv7Ei1JYaGRpP9AApv|d+^^c3<8B0X=(?>RP^zu70A5}%a`Xiw(x2UPU;;resKU&wK zhNrY=`8#EWRb$JBU*`YWF!M=3l)k;m`yLV#&jHV6>X&EulyfG3o@J2O6tR$dtj>WX zin4>O`dgl0i99dLz3lBJvXo0%>e*Nhow{3)*FI)CFooH~eBCnQYHmNW%~at@wT_jM z!c`RkmM_DJJTu8&uqm?J=qP>94YZA>Yc-A02|plKYndG0Xm?cu8;@Qv* zp&CoRcV3q|`cUz=yv|vv%-}}~k!>PC&kW!+A4}4WClaJbuZMXGOmmdh5DxrA0t#8~ z^@(NpXiiQTaMCDi#;;H*g~{Tzq*?|a7>+Y<-@K!V|KRD}j?S(LPT`$Irl)ygzu)ux z^dKN>)1K$&cQjpFJke5HY>7&G?@4`HVl8RB)+?F_O=G3^aJNp8)_}2~TMuStayv%1 zr!htlc-I?Ashu^77Go5{IPm=s|H=J_dv=E>sUwRsK8}DWLB>S1k$MWW!Y82{@EnID z``r^Ucs84jJV$~6cfk?IBjXTwdK}QcXZ51xa(hdsuLzgW#FnnjCO9AS!V2$B$IPl$f-|_GN{_lMM!}qvp=IZK- z+pBB3u0wZH@7AwYY%jK~?Fu)~sDl9fG%=!Fz(tRnCl2E?@7}-T$KU>oH*bFB!{Ila zpP`YSpCKXMDnkOpiv;OmCQd?mTcJ8>+`BS%CQ-@$_6BE4w1mm1IA8 zoDV1$QK~@)U5wPpes1``^z)!5L{>YkO}prU4b z(Q$jd<;BgGbz@j{J=?2G{{HvB^XI?(g`1mOnzj=+V}#ky9ET(C-~Y}}KmEX)UwOiAsm}VXx-!XnS^SpcD;`Vjwe=Ewm#Uz@F(!)E<9ETC2Aq1rKA%bE=D@~&&af&q! zO^o;^rfvadc}S2_oPS}Up0<bda@HhqO!#@sYeE9MsPW! z3RmSwpOnIt1b#|7c$9N$9kX008wpC}SZxH?=N3$XlR;#8DdUV(I`Ti&r$0V2Eu5yX z*WcG=Aq&G*NhYWz^jVCO#gJ6xyCOrXzhjgPuDmvRs>&3F6a}uw3Ki`xxDR<~%k`nu z-e$QGs`T#^S*<(M2w%`Av!Gc@YZk|as`h}qYn5w(^@d4Qe6I#a1gT64JcMnwz2o$hk3vo}k>2*eL=EftyQU{Goe72 zTkDi&mW(SYaHe>*orgFtMpH~i6v^Ut&T~9CLU5SDCFUv*?_8=|t%VGfsHI_vR_4iB z(kj(}*It`!_$^exDMQH$Ogv++X)|TzrgG#g_g-k{`p(j^{uv#87BlUW>jJ1vs=VvHv8|*snHH@r-V5rZMq#v}RhCvYtk+wv zudZ3Gw`gPVaRwcUc4j|3@#gm*nTH+gzT;y3g6pdrVYW{CNNNqc!;Yr;nc{^|o)||$ zJc2T*4mXzC3fb3E!)KFs@NhUX9FGjcOvFNHnOiy6ImdAH91fm~RmWy^#ddRrjT^j< z*x1syJw~;xR~M|>4PCQAD?@8+N{`pHZNqxKrfFJcH?!M6v-3|J^^T}UqH>(nPgHy8 zqcsOYssUCpR_y??0IO0ya(jRv%8Du}si{XGh+$l!2Mh6Jo)Ig$DJeIRbb7bhg1pMVuTaM7p-)=IWAfzxkFwefc$aSJ!x@nd6KKFdrvA{C>|bKmNr1 z`wtitH@7eN)1Us#H{X84_F{`_T0ur#uUPdftXDkTKk)eTTYmfP4Nnh`Ow$BzV0JUl z<2_GLkG$Xg!sF8u1J9CbFF_EjPGCPqkS=ixpOj@uvy&qtIfXROky`kDp_Q6u!rA9} zjZfuWIcEv3nDlqb1jvzzm<4o6@GonrSd{a6EemzU@=^Isb^sS1yXfvR^onO^Bb{p8 zIm5?XjsuTRkNo!QFTDBXXNJR`&8lY@ z5B&1WPmFG47zd8ikzpQiVJ7HU`lz-|BRtJVOn}v<h=k2e*GamwvAD)x79fZ zY6d+f!y`Gk!m@v}986Ub3tgYdu%d>X%dnE><%vFNX1Z2r7vx!q{)z!?RL)9~eWgvH zX%*8v@_2vGJWV{00~Z&UG`d46O{Y5Awm}<}(26JN^Xnxgx@j!d8ln;xwolZrt-;V> z`qalW*Da=Onvl?&rNxjTsFY<C+0IUl zCqku0Qm+62AOJ~3K~yrIxDc0Cx}X8ew;8pTVhAUx2B_-#!rzv(#(d9ZeLgZ!vvW89 zS$lgVyuK&vcRp3$P!;&xnZ{D}9~}6cv_|qsrLJhE}nOiX|HBx5}W6Cm`_o zdE(hKmtb4<`vuK8tzk$N$3^+BuA$V)y<;+DOLB6|^OFp?GXpp$*Vv5|Rlx3sAniTOhiq?QNy1aK<3|~VAHcf^lOKmsl z?>q`s)~L7umz9dSR|pFdI&z`1GooBWr>rNf0&qAbhnjqOH6{}K}+!lKl zv{f{gRND-;1_8+ioP>vU@^B=(+6SDMmMXY~*qj1ot%6O&K*k+Daq_{QB1Rd%F1^UE9*w2Gc5(2|VqdxPQ8*->&%T+poEM`HHUVurwHqw4{kDp(r0w5!$Au zH4UBZ*j`+5adCxdS|;Zi<|BcCH#5g^WWRIlpJy&EEJm*}T2fOTUV38Aj>F-|e!rL6 zEhCX_QEq2Yv(#{zRG*a$z7P%3x3q0XX9ZAZ92~(NLK%S&w*lQWY%i|){PkBfR};KwXQjBLSFSf-JcyB~4d}#NGeeQakP90~bf3jwHi*mr9Xvk{{P5lPfTrKx z(6&9nbSN}kx20=46fGJ>s|{__qJ7}~+xP4rpIF(Jo6o=G#fw`$|Lis2e)A1qfB6;L zi!FOMp@5mlZrF2pJ`iTl&Gv%3t81=ruKDKculf4xuerRsA~pi76tx(L^KM`oNABN$ z;D_(N=lz>sIUEl7>Bu}!Ogu_$v3bNNdH!bzb4=EWEdwivG|c17I87XeBLNHE6M{jHJK_{!gfIuf zd?ZXG<8cSd(e?(EG=xxKqXS;OvlVDb(>r(V?ik;jK;9v&ZY z-g9wz$;H(r#x^)FsjFIR8f^(KGHeGfFD|&fxnrvj`(bdVWzh$+P0@#x2)DZUDpwUXPQR(e#QFYg7tRGs$ZjxNpe3hd&lS< zK_%cXYfx$S`vmQjHc0>EDA&rD zP&pMg8xC1!C4r@K6h6Nyu!O3fugKe)QRU~!OzC9MCti-^T>d8;qJGYb0p|M7(#B9O zL?o70M@7bF115$=u2%OI84?%XUKy?-QXEQUoH5aBHdvFlvyM0}b*9VMBTMvf@x$u$ z+44z=BtvqnhEkupOr7X5*%_NrhjXXg9F@;{O0UyM>WsGILzTooW24g!^6vMY`E?M;#Y`Qh;cEzSyv2J@-sfVf< zzy@t0M#pdOe&feqe#CT|&+k6xi!Z;V@4M6h6pWJgPKW)GLvutcP2crm1lyLrU(>W5 zlMlGrF%DvA%{U%D9Jzmg;Ba&tuRM?U2c|(%%cgn8JAoD6AD(#HJrjX$)zhy!Y-0*S zr7=qS2R90|p1xhP?k{m`Mb~Y(+`M4Dx}|F`Fs4VV9#o4lJ=d2nSzX+s zx|Ot|P@bq8yfIAkgzj5jfAIw`U%lk^@{+5|EBdyRRM~z-+w~0N#7{r}fcJ1b4vh0i zL=5-n9Wl((L(MsI4NRe@vg|3XKkw3*P&d!XLHhKF=U!!^NrEC7s@fQ8z>_)^H4DoS zmKb0Cy~w>-(rh*2wO3lBO&YMVDR`sG5OTd`Ze37}qWpatZmgc&yU6qXkstrR|6+JL zu-e?P*=*Ttu34`)#0!UBZ?NqKr8UFsxj!7(KRojE_>7+&fBO0>zWVAbKL6r#?q0m$ z=JuBDW=)8Z`5^s!-Ry}@(HhI^+n2oD-eRrA_AN$f9`7I6@Agc1rr9xtM7s}r-oJg% z<4?cw{_R_yo*&sg?-+K^%x)rddm3wq{g4#EP#Fl4lJ9f9bXG(ZOFNJZg&oAJEGfZ@ z0$6zLIWO@QFUjxvRDh~l*cDPyoTr_^A1eZRed~I{e7kCd=^D%ZilC+9t<|{B@0P&` zbC9t{6U~u@;-IZ`or2<@2UcB=Jk|igdqPl5F4CKT-wize`i>vQ|3s+{KO3eg;Epr% z=n0cY1u!_Q0u^S4{f@`uBQ7}H4}rsY9y~fQyJ@sq#{5B04FAA$m|jcvk~W zt5bs`jm4qE06}UcqiRJ62G2Z?+<$n_ySHyS90m@<$TUn$qqOFFe%^B&2QII!*j`<+ z+H5e!GLDl(aibQT2n*|e&8xfDtlAZgZRxu;ZPU|s9c|NbJns0f@BhJc{J+`l1?61F ztaQ1|Ez0D^$Vaqve$>wPy1RlzV_LNCv3i9ymKXv)PK0D&s)Ud#U`mqGt&J+JLC~Or zAQ!6`P)h34BA$8Nv2!DnU2}PHg}J9vNzBH;KcVEx`26IURK9!l6C^@+Zan_+lbm0B`Tw~CGaId9AfH}GDlDcctT#IY>br$u9j7uRfV2drd5tZr7&dT%u4C`vezG-d)M>-&uOxJ zuVlQD<@*>H1GH(N=@H|`$~nqLtVIM*YIkFdq(W;Gi$WNqMDb0kd(Z59D4uRSlgH6lASUse!gC5`(90*Ekp1 z4bR{d$}3F5krfZ3g=lECA~p>QO`BUtSc_6E-WldOFprUW47eB==9%Y*k=?_@;W+W3 zeMSdqpAe$dl^U(-*Oq{zZCWm`F0oUjTMNphF}g&Ao5s?#R#Kl`01sLR8e>`Y8}4pj z^78gGu5Vs(bMuO>yTF(gT6g%+FiwGK1Z{fu!^Aj0l~i@B8;mlHhk>9K-~9Pc++JSs z`u3LfYK_%P3b~Jw`^QHf9`B_mt=2NnO(&?oY9a)w5BAAnQG{is)W@>f7Gy)In+d3p zHj)x_Po+%Z0oln`_XC#5L=qNi+1!e3EG&GY{#{8MO0*}va#PYy4C18Hhytd8)aFNP zgU(VlEQ0V4$y$;2IBa@DqbzZ91T)fZF1Weea(DNV{^FXZ=`eN$z<4P6`($YdD&#O{75+GnoAqXg9_H6sq#?Hlv8z9X049^~|e`Oq9!2y}v%sdOa z@#JROu3>w5MZa3HUat${z4PKJ$>{gScJ!MI6pGDi%c@%osFX6OsCfVW9lPVe_dooM zd4G>{UX*1O3Cak~W>n&Hy}nwXtfuI+HMCLK*0Nr$S*=$zO^dNDwrOelm9*O-rhdwg zc<)l3uf?>MwrOaL0MQvMDczZNXF|d0&^U5INW5vDq?^X` z&Y{gc&RMiJbiI`Qtkxr|^@gs$kPIo)B`5DnYJ)-An|V@Z&uPkUJTov)KI2oLohWOR z2=NKESHC;o3pLMRaRTLaSlpdD)ko&5F6n6^J7lwpvtNvmEQ{*8`l8-MiNMEVTGLMW!2$*;r^Tg?w2UV`154zt4(=p#tz37xdZjUc#9(6Sd3`$k z@X7PD(G{|h5@lSap7&(YDyEfWbOt>N_0z|y6sk5(l5qIQMIK{vtX89qr_>V@tz>%5 z(b)W1sS8bqjw17Oop45L4rx@mr(qx@=cO?Fn3;22=mR1?8)=oUb25)A&u!LW(%_dH-KKk`pOUQ_04tE+6ykrW#lzJI^RZYZR^3v^LV{NLM1kDSMR^&}6a6R2px& zfA!2+MO$iqm;G2Dn#G_$5r#==D6^6b-+J5S9?}s3J~c`@;ux(?fVIR~6_zY5#YxGi zNxj`AGa+KTPIA(9vp_>DrIS)x7!srH&}Ps!5zDo_0qb9v^wU zf9C%Fp8Kbn<1ymqvlQBTja2=4uJK4yeL@iN^oR9zvQko3gTmm--+!#j7DieO$m%|| zkgRkfjDn_x^+t1XW4OH9(ycVQ0c9NEr4Gr@%+5!1G07oUAa-``;E3ai#A8kBAlNK{UbhuO`{ZYHbbjcVB5T=8mrjd>JHe;fxf zI%5moB-yNpG(@HFJ`l%10YTD8vu@pBZAWVZIymOpp+ZBL72|H^xjC@zI<^-pF>X6U z*EOs!dW?-|<8Wc%!&4-vQ6h%kGmax|Z)jsfMu3cILbO&`+pu13ShX9jE^m1C@=G?G z8;BM+E8MI(>>Y>QGmrOsVo*HTd%y_bld?2c08tKy113hke*Ky+zxyFZFDW657^U$lN}%jK63Z+6@UKUzTq!_`x94JH)vxCS}{e3^Dw%Z=W*s~KQIjeZCcjXYfS3t+4nuO zikSO*K74oJ?ehco`vW((H(b9IN5@8Y^j*(Qw`IHCFz%lCzy8PnVE6Qa<9x*138k_! zmMXQPFF=JZS;8&>$rzs$0hfiHBq`-+z0B1DLRH#A)O=yl;Z9KU|A>7E50tgmYDp=B zMd4AH6D3445K@NmC$1~j*McjOFf|LWl}sLq0!}UnU|W;afRFw1<*o_P{y;y91YZo&lzLE&BQ3?cf6Z5os@#N?1`nwHh} zg3FiU;Ok6>RTkxC;(`kd^Tf@~E!WrA{PtVV-Vem+6a7eU>cml&MLyHT%G#vQwAHNF zYi{md@bcv=F1DAnU59RZw6PLB3W4#k<3orH!x0^I>b=|2^sN}bMqzCRvXYB?|8Wg~ ziV?g3&BQ3m_F)fi-ztXjiLTw?y=R)7WKC_P?81jM_ua_)aAbQK**eF{LDROhO% z5~Px?vM5b4_0KK_*@>4U5(*V%2<<%+P}VAIr&-nY73ZpQbX%A}77q zmwNF)evtg^6<)TA_!JfM6%VQBT2*rDQ`rt=BQY+K=T9DgFvH0KZwI=q$8W)7eO46pe{k9Wgqj{=Q{LBt7la3@BN;C$~FY%hSJgSr1hN-eM2Q zzO8@*t83&rheW$73b-lqyg}#auNb}|#B)r|)S@X?_(|D;7O|VH2p8K4gEm&D6t{&n zX`^X6sSh)D7R0<>)AyFfXhPKVTg&FcuwFOVHlWNi&&|YejM73UM;FzySw33tv~Z#T z=jk}#d1t>##9X5`M#a)R(*41G-~`y@{HPV)`ZI-igu5QDt~b2?V#D3b8&($vZ6ZDn z%zj`Pj~s@`@hD(dl6ssNyj~VHM|10^jFAcqVtJK$i4nue#83W3S)bqBL;(4 z3YXAl=NOpAfx#V#(P51uDvdIl#=?uwE@&_0CQT=8WR#LV!zwn!m=uu!adI*@3ZgRT zrln~+EGiYb8Ju@0W4YemaJjl47)sB6#9JAV23Cw}_jJKq2P z8{=V*iVhuoG9JA+3A`t|AdV780l+J5l(MYIM$f+zw1tNLh#SZeLP!R%Mki0SQecfu z>EuRgscp^%5E==op3XZbQE07&aob#jyhJ=glH?h(#)ps)7!#p}g%>D=04cPFzHeEr zRy2)8>4;Y&N5AJ`e9!zavY$Nr{ek1?@bk=kn0Wv89n;~!oxY;mSXSFcka1&Vh>mfb zIL5#@Ox*8}JUl<4Vj~ga+e@0p612nH24gh633Lw^*vk#KHy8ZZ@*@}TCq|s z)>t-(v*qdSTl(+*6K5226sM0Oqr*n#D9kdXwnr{4i`Oxs<_hCcE~kQ}TEe8T<+_}h zlusQi5Sq*n(!K*e;=Ki=L@hL>vUOOL3-!_Y@n3m4spvAlvfRj*|I}{~SyHF)<#Dww ztX2(O*PygT8$lm-vuAfaFbpH}oWT65(VZ$O6yUZjZ%Pey1iaKJ-CkVsw?F-jzx?U% zTwUFwV#_pn{H$3w(9jZRPjGvl@)g_7 z4eM@0-}bDV6`k#{w#AqRt0hw=67bP8%sbxQ|ISZue&GJ;1O0l%?TcHs+pQRVrl-|C zjqWit#Ha~g;pWKUF!K2P$n)We{c+Fkuwxn>4b$!F;;*yK26;W;RF5tW-BCQOao0z5v zA0xAi;%q<*3cd~4#$wZ+l2qTN-ZJkOpD6b{?U7h1wOXC*zHIoOM}lGuNohyQCX&$% zDLdm63jfE~$m60!icZfz{aqw3sjJi_E|HIaoy>_SMqrE?qa~$m{;!C%>{zRXVj53b z)qi4FXXX@@P-%#@K}V8Po?_U4bo&JdK^`=%kv#M#<~YmiWxR@y&&&1Fu~=LA^W_@y zznJDgOi3~HavFOcldOSsfk?j#0i6Wx$(;+c4kfaD8Xry(zw_tH*U5rAMPG^mjJzwY zN;-X(RTfvxsB(lmyZiL}3n(UmKt9^Eno@zNP7P zNz+6rf{)Czv^Q{W7Vs2*;5asHHY?U+!)DXdbvD%>7`m0>>SluvBR(j!+0mGp{lUQ~ zh{p>7EE7;qWW9N7)j0R&s|~4hhLrc_KVwwqM0IYf{i{Pf{fgDfaC39P-OFokZZEK1 zz=xS(9tg9?`3WDS=dm&ge!G#n67K_M0%s%hEQ?ZtuaSaESro=k^SVWWi_7@411-Pj zdf?!z=x_ReL36GrK%Kr+H9>#0A^+*INS@^x^zwP|k#U@Oc>jSnzx=|xx9|Ak)t8ul z!s>>oJ&wQ>ya0QIiQ_o1+dVLh2U@FGZ#sfD_y8sbLOau%mX|*#0 zjmFF^1SMYjuEX{nZP$a+1f>ZIjB{9Pxx2aJ_1$N}TfV#Nc-9 zhbJDM-}3PAz&H*}eiYy#zb7h3|JX511GB$nyWY}hD<0s0C~6pD3>=38es+w9iRZ^X z!+yd|nsER(YBuc^w^vtOY_DnCHCA_E8g|El_iujV?a#k3k0VVCSOs@4ZZXOboV1vl z$BBoBdw%%wdw%)(2lh{oDCcAjgXF{q?@_ZO&YtL^0N^G1$*HmtPLO*~X*3DMk6u(B zVL;`~6J2V5my0ZHSeTdq$!Mcf4{3|BCJE@Iz$AenpdzYVCWeStu>jFXJu$@KQ}kg; ztvcUZbLIC30DM&}80fWb2z2UekF4$nBh$AyvE z&v+t32prwO-Ur5cV(&(V=;>^S`TrSv)88`G-tULh3;fI;&eo!+%0?1-}N+bXeKkU?7U)^`))^m;%&!)2j=Oh9yi@PkloC(Zf&S9-`KQ0|!^fZa{QSuC*yHJoAz&&Buy(ql zDb|W98D<1{V2K8()~qr+ODI~JQ(k7dU`4NgO#rNsE)`jHR!Cl1S1NdHg|(S?h^#`L zRj{9Jd@EY^T3hNhx994m&T4(c-L9qUT8s(Id5SU-tRq@WvWY6=<=5UPF9nKq__Gmx zSLZwKc6Z$0z2SKGz&Hvi4|v-ULd)IpNZU1FM=%rTz9;1f3?K<%L?lVX-W>n{AOJ~3 zK~$13rJ94_Lc@pOyyu_)>A&&EKl~F94|NIZUdHasG>uCHAZ#$f6u{0nWosy=^<@w5&$IpCu`pT!z zzwqOaf8o>PN4|V|=HLGH-}(CVNYk~d02shpLesF@A9(xrJ@4Ot&+%{v0>gDA4GFT< zG=!vd`fzv0e!s^W%Qz`?d1yT9V^aV0_!EokSuYqJU>oIdZcYe ztn(P_)w6++QY0s6>>YmB5z|CUBWcP=k~#O+J4X|orj!*~E9Q~w^}>`ArXWfy)=EJ^ zwV9j~DfV2`g(Si_PFT}&ygzU_G<^U4JFI`hI8I!yO4pnZx~Jo)20@<@A|eoF!uXbs z7GwO3fc)AX(lz_~{sU%DXjNoW@%B~p=NBHyHCdkvGH>_W945KiH}-Zzmg~e+uWwPh ziUzNWV^*3}qL69{qIn+{!Agn(Q$c>VeO#25b>r6xc9qYzN?4&hD=%UFMP{C|7ThY` zsqb40OsjXUUUB1to3F3f8@FD%SC6V>yfVkP=VW!glK*c#eet%}2qWguW1XWJ@OH&N z@@h<%mll4$YU7dvTs)}NLwjp1DFn6}HEJ$*5)EEXrYN-4$Ut33r5Bs-Eo)-{;y@k0 zsRO)HMp^bimaWQLX$*Dzq^`7beU(F`8j}~{|22_&##ULiL-`@|{M7PBnhK+7nLFnR z-qG1ia2owEm#wO5zvLwfX0z57IjWY4TrbAO@5+4Ryv63F`9eCJ$8dSetEx`vmMo4H zTSD7Kqam`9nRgnNHBwXKX6MCPr!nC7cbb3Ly+0`rOw-6PUKyuA zj3Y5Oq%_iY3cqii(;S!JX!n7`T}#RnIXj|UNIA_yvk0?_zG41_K;2sV=ApR}q}Fq= z-iv0Qpq28tr5%gnE8m!#n`_tW*I5l0x7HG;iRY(hB3JtU%5^+zXqQZiRBJR}uw5k+4kSS|MIX8CAhfgc;mQ=5j(s>6JzKU9Z^} zJ1w)6^;o@MUK_;q@!F1Ee^=(dD(5L?CP~EWGk^Z~Kl3l&|1b8t2R=;D9UqX;FbVXj zXG|kQI&-=_ayow{rGb6tInvR4kIO|_i)wgiyO#U#o(Eh!>oVjKjpoUp{di&YZ7LT!s^u@tNy*rk|ea zuGJ#B{yz`1K195BGTEAVG?eX&iZadgSZlXP&-( zW*V-LC&(i?O{6rDqvjM!%vxS0uktN!;`T)r?_E`TK^cOPniIVIzFthms5kc({dr^g zGpJ>=D!?T)R$r$|{cM3R49^&=wYRHqU~*A%HEcGyw8|Z>q1&r4O4m?Hf&lCmiLPRh7ZDT(t2?7->zm5-nQf_2YeExGM*KHwU~EZ@KB z@H~EAAc+iPdJ@UeEjhzo=(s7X2Ac8;ZJ}4lLE+$Fb*Sf9=Mz@ zJpK3+|Msu{%9qD43{y|G6W%$^^_B(6xq`aP+jh&>W&>NU1bC)9#jsK6*F42*8gpYL z*+kgDM(JIUSGPQ2USGMsbH#{fgNs?O9Bqr4<*7x;krhLih1S)3W+r~q-jvmFms3XQ z%b2LgZk#5Knvm^%hC);A5<)$PQ9}V*DeuV4rA#k<&*!gCJe@CecMo7Z#wm@e0B?$f z>@^B0PsB8#^%_;N(!I9`Zy|WT`|yE({;&UqfBeV)i@Upbbgmg=-wYB!h8A(SXZGYeqYe5=jyQ!E03kM3_dM-{Bd)#532Ouxk^$ z{hq@i&~=^SMznTL!$>mG4?UOuOpK8b3|-gKcAmCrXj@0q1VV6#$vmIG5T^vg1p|2F zNLJUcRC;Aqkh z{4K+-LDpR z&a#RsSXNtI>r0L5`nBM#6HE|X1Ic_e4@HDf0s4~Z#{jIme`^F%g6b^}occB!H5 zv_@T$h-8mQRIjJExS)WLmDz8+j%A#eMy@uqQNahP0;$rJa-AMAHqlQ5{g8+mtW$8T(3Vet5FBl%o&uksX*@X_ zrorO;h#})h3`Q7@Y?R@am^1{cL%1yalqLfjvXd9SQ@-*739Tck{6=W z!OE&}ktdL>d7^KA_dxRBBV&&vGsd2N82I?hFMN6Yg?_q_WFp&0Hkm0WhB(qs1D9cB zmoFEjOExno#+qoZ^MQ43SBtNi4P&5+k+ntftzLqhX9lt? z$Hg05p1v}YEuQF{)x(lYsCP=4oHT4MOX;&&Se}TM3bR(roit5gx9;K2+r(YPQrR#RQ|J@(>-S2;oYYw<3(_-+ggDhO8 zM}GM62mbs2`0xDi!(T`_AxR^1PR~!oY2wG9|HQxj>;J23Hw$L8iljSa4Fx}IZRyY$ z?!!SNBb*_{o*3iey)lK^lzl$ak4kf@5u}E}*V1-{ro0Nsx}x)TnTE|Zwiq~Gi=N+D zx~1|3*_{8I4q;;~oehF4jJL`dMSh&yU9V3WhCxViLYU^xi7e|*R?nzoI)`ADQgn*~ ztZx>he^bKEvp|}J)1~LUj3Y+Lq_@XL1^FUhr+ewH_NB z;tg3cQ=GV-uY8<-=Ja$@AS&Y_8*+)T2*%Jk$HT*sfBxrxX18nj;jjOP&tE<=#WU4l zAglaVE50B#2SNx0*ARlkJEf5rXhKWZ9oX*=><@R`-5ojX54257aK(e_EMkPoCSsiE z#|t?}LSxzQI-1t1JY;fFJSK+msz8)6FYU1^v{aP)n(L;ae(E{%PQ}&d(=$K(@MpSR z$L~zb-SM8L^`smbN5!0|KsZ)1DMw6J8ass!A0uwg_;c9IY8Mn?cUD+m-(SnVy9rD+ zHHyd1Woj1ht8NAj-PBy+r9@1o0tU(Iz8Cv@My$`}?cZqMiq_Z97HswPqweL(O{;R<>Ux21_F?TktP0?|b+xL??R@^N^mC@U zYngi`BiHe`jdWSm-Q~tbnOTI_)kwVZZg}xv*Z{E^yX6(a$}?L*lu8;vE^9MUfwRoE zg;jPaa>)`AU1zsM%Sz2(FYmV1OS@tkr5$Sn%HlCroDwODw3N1|qL|JlmuAJj^wumn z#tWa)dcMIsI-hA9%b~F}-V>a*-R25nRb;Z-pOWh%n*q>%*}7+op~ApTTbSEvWKo#c z)3}+@swbEliL=b-%R5%@S*@*?Vfr!~lW)%}53VT<%cFfvBPm(5?x$KCHEBH~QUt@8 z3qe%?Crn=kK7&bfSa3>_aX6P!Dw!z{t`C}37hnxO5x zB1&3X5JL=_6rQ5iiPe0DR4i6YGpq1amCx$Uz3s=w$^l4(RCI-uG$mT95O_NV3msX; zuB_qNI9r~TiwAl0ob~b@h13egD22#=Q&|8o8p9=|^E!_&|F!+-hD9KU~u z-!+6b5*h(FkY&Jo1z!;|LzFqM*ohz}lT0S30GE;T@R1l>BnP}b68s(B90_hu>yGT2 zBVBW(Z3L16vfwO{#3i2?k^;-nB<{ZJ2>ai_Fkn+=ntFUNJe|LCx;$a5!8aBc977!V z^!PK^^NCBJ7?LHM2FZ?`JktQvkeOTtuV{T_!Is=iYZVa2IH!Vgg>nm z->MY8#xG~E$U@9Ec`jKBK-KC~u2GM$qRQG*k8)l%c2z>4{$2?GCNy@Y7wfgS2y^;; z&F@VqF~!I@PE2DYPKh`b1vr+xtD=C&?V2vXDlp(34-XIAKXmvuFf|hy;c9xUF^p*< zPFjA&qUBGV(Q;VNr?33W|Nb9j5r$;h-`(+d*MBCOGwt0yRN=}-Tg z|M5TnCm%olJkyC3CvqH0do@N`QlXJi!#*3gr)ygdF7WWsad>kqwDwGjlh&=iUa+|c zpLU_sX4UE0AtFmk#RfcYjXJfK!|XC{EBJ#geWftj8^Nlqq-6@S)^7e=Jr^5Abp3Pv z{fbYRRbOxCd@b{)f{49-+ExYF%C=RRUVql@-;6~Wcw-IOz-1ix@zXCv`>*`@$DfEJ zoKF|xB_Rb9$a_!Nfe(hm;SLuJhrQ+~r!;aoKf|?GP(~6lM!tOh!cRZ`#M?JNW3r{S zEfT>dr4bfOPQvAK;qmJukIzp$pP%^a$G`H|kALCo`75K_^Xd63$J1A)*5mVp^NElX zon(TGNHoMTlZQ;6gfvV{dBAp_cfa|LyEg|Uk64?vWMHGpukl)gdKd?u&nGUI6XQ6L zQsg>av=maaqiGv#1Hn2DO-I)RzWeSS_wVkxd)V{C4+r||6UKO)Z4_k7TD%Q-*I=+H z5LZN!;JsznwX|)^?yzUKJJ9V8G)+enI?atPpjsBEo_nVY)-(p^9b>w3y`GqIulzDa z;uOiLC+3MMpXrASPtRYu^j8I0taQyfAQjNQ>RHlFmQfVxn1tu&Ct~^&Su#l){_w}Y zr|aI~yc}ZVbS}BGmMRqMJ#%^EoA%fK7FA&N!u2mJrEex- zRY@%UH`{U3oZ>}!*(%gk(bRr@JJfjH|6ikl3k4POA{(w1_7}>;cFxyeSZjs6aON@w zd8TCwh*ms{MKNAlu^@A6E7l&dGU~Fz>6pi*8b#R5-Ky0u+O~S^+}n&|#?(w61yNe) z_p<7=U$%_jW^I_|$+b+NdMqlF%owdQTb6-FgI1goGq*RtKv&PJxyVu)W|-GTosT87 zS4*AMw6NA&+9q&ti8cgw#Q|waYHX^g6gB#S%AaI|d9iqYYbl}vLb@J@)$g<3Gy z$LH&da9;bnCYZB8QwQu7h4F7a45faQS0STmq3t}j6^s?42w}_&lX?iI2=scRvn7`& zMMCQd!O!S}F$sB-+`LkDWhE@G!Lo$crd#hTQ07&56^n-O*2ynpwxO$=hb#j*3u^^U zl-1>?D&w+zcx{Zglw*6oMgx@JnV=spe6&9i-Z<{xHiX^C!5%b{KmZ1;ois#P5-CMu zQot04w$odSaUeD^B}maBQ-_tEUXW0aueVq_tZ1m9nIW{{qz;l$VH6X(Z~;nFjldt&bKZDwb* zgxQ;iH@taxVAmcn*^#D995em(!sjoaxSSrD#)%w9ipv{BW@R_YlD_aNua(!Qx-z8O zT(GqVRth4gEgDp1e5x$f5=V9x4r^{x6&Q_E!e4WMRT)&g*Nj1umIKN$6JsRC$P}Yu z9K?wj6R~)I=MdV}ey~Qpx4T_KXd6Q7d3ZST{fB$*?~nMP?@N<{4kadXAIYP>vxYob zG&m~diF5x<95wgvnlsJ0<&vKGdisH;JunOt!=RBS!ysI*SAO~B7e4;{GsE?&<5O~Y zT!E^wCLyKxw<^I3Vzh7eJluC2n>`kTPqtW{brV~wLb0piD3ITB}etMaCSe$!`TF>8%4;XZ=IB8nUlF#mnf@m?snE3kj8OeXa*aOZuKK!?Ctx16_J@Di;!nJrCjCa{WtQp7-q%WRu7z6 zz<5dvnPt~+Fut`%s-h56c$Bv5Mwq*OLLmbBCMoi&S;@P3F#@mWi&e_e&GV#QuxV*g zLe2K<2Kek%Cazw}?Hs6bTPt!@<;Ad4Y-^uqD`e@RDJF?|JXdH9D`nHL9rG-@Hn+xt zWu9uNb3N2!zf5~B%2q7%l*Caz!a`n!^KZvGmz=#C*eu4g9^l1MB^#!)@l+b^XPwX4 z0P>n~qb|7>KYPs}RbOU{12T9+2%epXCV0An`fSKrTB?G#NSfE$0-(jrAk~9wDiqi( zk4dS?UG?!LYU5=Gw!Vp%^kf5yHg|Qs&tx?ehH603%eJy4n6j2`)^_0`X8p6gw>HVg zDT1YxKvJz=vU+2(sJA3%(VU-x8f*vkYC5kWe`Cyq>lG128yv@pI4b(BmS)lC+fqkR zYU6GM5A_JG7EB=uwq!gfDd9sbIj%LY*p|JJsz5Q1&@1!v9~|=@S`B6mS!)9951#wC zp5y%v+aP>99F*;@YaHGrE_ax z_;&2K^mF^u00Dvz9PjUVdpvNzYk6ob#}YX!-^Prw!cZc^!fDp4x2N+`{iiQ?uZwN*;F(XmE4^BN0$y_-PpZN6nk;l(xrpts(2C{m5o6ga+ zf&E>};jSZC&(vp9Qh>W*?73bq41G_W26CL3V_MhB4$KzQUps`YmF=}VRH4b_T=uug z#R_X@rZ|TkRZuKvu}*7~mkWv#sL1u!S;Q2&MN;8$wlG$DrV97$=}jg4xf1@Ha5&!4bPfCcj^iPK6|UE3`myIKS7M5cX4G1zX~IZmuA_(=Eh?U6q@dkf zVVDMf{^`n>FF#^zP@_&VOk-r6V46napt;$t)6h&sa5T6A#VwM^rPyt@f-vEX(3prz zJ!ulgn2-Stq0XA87^hLK(58-inS;WV)&{P1==++EQ?}oWJ#7{tZBDg*jpwgD_&2hm zspr-;gI-xvw<~T<$3?azNB-8ej0*cR4TP8YG^_DgMqol0lSKtskGA>rP;=m zXD2WjyewrX;*?4KfB@dL?Ajgs-925q!v>2F>g|u?q@lZH&Ng98CZ?WY>`6&$dFwt% zT+S!{@_+ust8EI4ZsXGmmDlB>pI@Od(Xqe1Ks{W2!SX# zWPMgXS4w^Te?1o4Ay>Y)Qha7PnDzKj%01Q7)mUD~VEw+EHm;Sin^2XypXRw1UY*;G z*LSUinWddCpIaHn0;2TVu~vZA_ixCoQ6;wm94)eNQPpnRoU*QgWL3e|l${b0AVzDf zV-Or#xu8D7%#Pf3*`9fit{PPp*|kwu@;a3(Ln-|=x42kxHFJIOfL4ReoM&4aVJLP4 zZWYI@Rlv4xf8q%3MF`F2JWnax_kNwq$(NY=6l zWg8^gbw_W6u$64JjMcBuwJLN~E55a=^zROahlhsu9}e8Vxx<8sA@*FZ1DJ^^XQrqM zaILZ1_sr#MAYe=f|HpJ%3~v9yvc}f@v_>(Xr$G@jDKO9f#vRZ^Ao* zuYhod7$>GY9bKK;P+bz+i;5%hi+RG5nsX&UKMq?1G| zspOD3oYmYe5kum_7{74of8laHGxZslTfAxUrYXaoh*Qtg<5z}jGS|1LJU=(IB%JQYzl* zm^8W}2sl|B3Q~mSya+c^BAl$~T*mRtIgea%q?k#A6vjMgsVnK#$Z4gNa+BJ;WjmL5 zeSwa?cfO6pB13gpdFsCjjjAyfu`yJ8lB>(>R*x|TNia?v3T#b z%$TE;mh&`Cg9(Ogg^3ZP%-Te|(7-e(k3Ax+RiQS@rDhn;k(cCMAL~G`k)9y(Kgc+~41`-yQKGAh`eyN-->= zz?|xxS~R0uFYqkTo0p;f-=y(33dt5k=~n1vqp+&i(_(EE@HAX>4U}c=sxd~f62ufb zTMfARB~pBSSIyU)+xKcO{rf?qJMX+b*RF3L~3RI+DRm zFchUO#jU=RYxve2X0GVZar$=N>bik7H*o&l*ky27eOK?PvQF9S+vxq3(zxi(^WfYL zQdQ_)+xON%2!_L*=i%+1H}CE^J{-W0Tn8bW$doMIqy~Uk9uniK?=1Z{rYM=dD4ew| zRhebmuDPu%#T2vru3mNxh49{Etye3))y10ggiTt1Fxw@>+Oi0L_4(E=LpG1)YEb4e zmF@Y>Lb#ph*QDBca8+r4cyq@e|Nf8s(|`F#e*bqLI2;>nlZX--`YY%D8Eod=`!~G( z?sv4iHyCz^1Qi&KCB`eCKmE*bxo|yS5Sx)kFmAw4&-m#RV;6CpF*%S@ASJ^PVNAkx zoVW}<*LbE+J=ft0J6&l^B*%d%4(yse5BKl+@ZlZrzkARAaKyR*C6p#gBsoiWJo5Xd z<^6AdOBSPoh8yX}XH1Or?nH7UQ}zVov~H%gq&$*xq8}rvk6ebH=IZg@7PLyMo)a9G z^O}kv7%JlLvMj7IC10)HP?)x;!L5c?Ib({Kzl1r95K|(Fh5}0g zxMIbC3VSQR*Y{hT%`?Hc4c!wFrg7lu`75XM6GFl{%Wm)Kx)$d%z9|U$7KP+@mh6&( z_lz3mNK#mKv6K)yTUwx@%-$N37@R=`05W1BIU!jz|20)bpH0cLl$iOLp`=|DAy+|= z6ah9Cz#vtYV_|B_#F7V-Q1sz7%`_|TrBsDfX-6tFV_qw0JLV-}c)9fpLtVaG*wn2t zq%NqMFL--YC7}wrd3Ap-kDhak_?Do`%%A7qGjk|-#WSfixzfLNw<|AN8;WLrl2`ZD z>&j2(;CQ#=;r^a|yT@CrsJupVa3zDu0q+7`IB3qQQ3U8HPRneKJ#n1qhbxdUE@K_| zqUfmnZLyN(G;K91XHp&!naWx**d~-{CtbtFWlbfK39<^0iCC-xBiHj+e);JyoSvWQ zr^uxr8K=aQgno)lF|*&@;mySHt|5$uOBTj45@RMN1@Ve8A{3(+wkW??h_ea`Y2VNPi@g5TbWJ64eXbraQID{61 zRlvcvBL#;G4&xP$+ga$E2C~o;MU-T?_5U<@R!uif}SXj=@XMABK>?nvA2@Xa3Y0(g&gp55IY?>~It{fFQ2 z=HV@7_n_tB!X5kFo~GHWu^<^8>r`m;Dx9zi&#;7>*0u85u}NQeg>Jrn*sUS|CY*5z ziM9n0?B$_tE59!i`*u%C%^}_@5Hr1_(1-G@wb^a0pzDv9?N}7k?YWt4u4J~&JwQbb zmMYZGl?-G(&%d5r6#pU>+=8>zfW6)!=^r5<>VY^cwx z>tC12YSl|Yy1p67Ir2bskBF2tSq5IJG6S;$%u0FJzZWjQEUiVmuywp&U1%>)Zr4p6 z)LTX5CMTJSE>PyQp!<6D^d{mI>2=7MrjdS(8cx(F#!(fyiUMmAjHRgWRPuGS#^zFI zHdSQMx*5yg-vZECq>FlwEcKmcle^UQx)6n%8I$D^Ww2IX8a9Jcy%U?`6-rZ;%g|VM z`-Z#Yj>FxKrVS*Uu*qpn(%@*i$N|AOhH-*a6yhlwV#-X@V$n|tBRf{8r)F3{e?ib8~*?8S4<} z*N!^Jt2{$B1{7i4Xt?Lo^CQpKM3SB)BYk}0IzH3xTH3DV``>ol-@U<@11UL7Q2?fF zXxQOWhlwr5WWW(k;(0m~FCTey&yZUr8m4F&#>{ofj8Svmb6v0|V_o7HET-v*Sui2+ z=KdXj`0ej`|Mq*DZjV?;Uuyx!fpHqJMreY=whg)h5*`C3Y=gl5k4{2TMD(E|nWX%$US&zqI7 zF^4&?Nw2B-zIGwqe zsFIdMQ`1e&z7a*O6dlWikVeHCpe)at0#fJ7p@zDq7{V-#?y2NTXtHnXOjl$Y=-MOW z6uDdn#vzt5HnJ(|F77?m#kdokp_rv_%OeTNRFj<_~Mslq%F%M>3X);xR(VUKzATR(ZsENCs;J zA2U8BRaB>h_btb}2fqLQcMRh|mJ6rz7mN{YtI_auQy7=#Am*~Cg@C2&j(q>&cUtzz zbvWk;{y^{n>sws#h(JslUG(tgEysuV9F9k%J7TOwjC!z*QE)CWtg6Cca#c3gLBx6} zkWrQH3!qg_ukPEwP5G^lT7@*PMktC} z$+<1aA|$CizP8q`XX2*ssvuTcuO}2ZtCpXd6+Nj2jJz6{8g9L1NR^*yNxDT*gc{nv z$U^fHzZv)Xy)8X(lJ%1^&S=#Mi^H0%GFMf|OMarJhb?-=;t7^T`QA){%mTlze;uyn zwmObpE>o)(6VCKlxNR>uLO?uc$u<3XOgq*SD$lcnj(E4 zu~R0AT4VcbV(26ND5}V<&^~ikK&+fp;4&-#pjG*;j+d(M%+`UTz)>{xTyph7DBu-o zffTPua@z34^Sp2l@rBElrB196c^z`KsOZ{Kq~+#xyh_34o@L7y|%apHQtkkUlg z2JQ|!8s8T2Qi0v9BpMTVclVYz?Vcg`OfrydB-zNde`XpZDLyd{iR*QspDyG)lJkV5 ztmQDUSTR~&WHQ|C4!k>l;5YC8z`KXvvTF_m(-C}w$MN)Z;`HTAumNu!!8TS<1OBqf@Hl2H!}fUF~-F*$*dIDkmnkP zRP5n8Z#BkO1WBa^UlLOJRJ;G?Qzd}c`1JbRT3T8Wj+7!yX#QSfu)$zFm|$rSJC1Me zY4>fZrKv3*rk*iIn(K)e62{rNjEOOZSU9VpDD`NFjYy$QQsK~6VSOb%qVlt}26QZj z24^*I*;%hS)5a2`6yZ-;<0#a^2u?GoX=NcACa7kQspq&YdI^tb+fU9b(w5WsG?qiuuIqNX7l!=yq5k~20%j9A1u4Tl!5-r1rdi5Q}RoD(J~76Sm* zU=2h`*d$nSnwJOuqRQ8H0BY`c5`G#Q}>4%Ba=OY^0`Br`ObJx^6=e-{ou%1$xjkRovp%vx(X$0= zVoPyldIUSchT*wY;|B`pYrnUsS!UD%un}P60M8 z3fEfhcsbMGY~gBH%*>Z=?^xuD`OM9C`nQi!82Slgot9ld!{mk`Gmf$-zU!tHVMu1g zie=-@;8dx|PO?($inp?998II;2y#{?)-(+NLKT$k|a_#80!eZ(KH?21q>?0 z^kd?5x`4T2ZDbsTDZaF1Zo=%!ysZUOm}OY3qO9Y+p=%Wl)H${CW;D-l6H>nFbJZ>8 zJ+YPo&C-ThX|CawX1Qh__uI8wzpK}-_w`LUY;BK-FpdMy&%faOM9e$xjvd|3s&XGZ z3Bx3bPoI89_+Nbf{6q*37}Mg#;f$xX;EizX_OyP_uJHtK0IycJs78TlN=$abdgyi* z>sl}#haL;Eb&y0O!8Yg0k2oY-&)@57}LZG0> zIsJn)53&z#aKUC|m8x7Yg0#oogf7nug9wd!0s@Ep>BR zN)@gJl3%=yRpj_4zfb z)YQLM?-tSh^!$8b97aN|ohlB4Ly}<}A~Avwf#cmf-o5>f`{R3#4|}X_iUHZ-tjCC@ z?|Z&{{mkR@6GML`OC%Ws)~S7=q)<4MOD=p7OJ?O*Kh6bwXmLK^yoUE%=P=HavT*Ht zuKk5Ejz~^;Q>r&OSMqZm)-@RGu`b{y&+z$7mJ8M>e{@aIvCo1}8J`m_O*rv**I-+R zhA5R%Avqy&VjLsa%a>X3bk^ZrAXrD^Jx%ah_cF9Y@9oZ?6S1$DgHO#i;AQ4mm zopb1v2_{69=7O?mFr=&o0NoO%81NgU1sj!iSZhhC!F$IrUU|NJPu~xmFB6%lMrxDE z)+3ULX@VTJ6jTwAjdU1xcy~v)KVnc&ykQ)PQPdELV~lV*4P1vu@|S1sj-NSv_@2AF zBW{1BYbWBAiET#+JA(Hm_t(s-$0C@%z8P-w7}UIK8?a7muu$PHzfsbHHI}sM`^E}+fh4h*JEumw)DpoCLfHh{RV@>;t@1Cruev5 z3hDY-ufxB^=(F|^*PpL0VX1lSEP_Nax>xM4~FCMjyG@K z(lqVt?XlKzK3@d-W zuX*VDZ;jX3fNRZ5Qe_NM%mtBlqzOCj?^=!zExUcdb)G1Z(>OAw#4w&2#uMJ}v<9ZJ zIFs-g8s|8Kj=Qem(6uzqk;O4h!Zc-K%y^ryXdbNh9%H?F^~X%k6IgI~oNMTuMH+)^ zJ)zsh>vmQadXlep&c${hMF)V$i_yqUphY}s4YsI}B8XEr?Kl!+{|#~gLEbmiBNTVbKB`3)kz-Cko1OS-_XJhmDL)<@17S#iB2#y-s!eIr`0G(|{J zkgN(;XeNvgJiPmkw{PC#Y)gt6vcq-Q!$f7$-h|`pi!sf8y!WTmgmUU z^Z86lTI+J(?V)KfA~&8UNl+mUl|&2!((UR+?v<-dr@5NY(#tcepBW$uisHU{8S!O ztcD;GX6_{>P6p}f^Gj~eo}pjj(Mf&YaUz_?~UQJ{xrqQ%SsV8 zs@RHXgqkYJ+AyhWpp-`3)E(XoyM6htRlm1u{N;RE+%guoy*C=wQw;@M#j~VUlzteg z>%Zzz$}5%Mmi<{GQLHtDBBNFQVKGHFs4MzEoSdcKuPDX3UYGlCLB8g%MdmkYkguo} zp`bpRd467|Tc{2xF9&a46WjCi`YZd%NTt=c>wJCR&37XB6fHxq;4xZCLI3;1XQ0JGYli(CK_vK#Nfr@v%$Ei;g2?Br^GaF z5eui7m_`-cbC!|=u;fb5if-*2tG=%3J{t0D0n|87oM7mMX-cF#so-p589Sp0nbr~- zg-WkUeb!joPJw*dF3_|A?{)C|q1XD4m(251OI2;}@PIyK1mm1oX9l zU3sf3IitZ>Z*L%YgJnXpf{(Oq!@j+vLjlG@`@r%34Tt>^XIoXsV%Az+Xl%XhKRQVV;o2+@qBvX)0a<-mw{c=@!jz)Zw~i#yFE?UVY&v_HrUWA`rjn@ z04*TF5goLnXBsVC=h^K%-Okgrie&7ZqO2#GxLnVip1<(;_=%^}C;IW3DP9<-3)kVq z^Z5(s^CLrlVj3=_eqb5~QjGH&$x%HYhwi|;hwpeezN2gJ07s1KX0`u6W$)c3H?m}T z{>A|eIJ5>NK)p6PzQJ2QLs`+t@_BYJzfUI`YNDk1>5+CR)4Ktv{4Z*fjCnIQm& z!-ZY5Yu9oh%z=l;Cq6$sa6D?+n-o>#4hdj1l8Qy^j|R;Jwt_BN4x~|xEJ^3N%PVui zI8{hK-0r!(-_h+mOsB9j#Xy*5?3h790SdVoWOZpaB~qy+pp3n$1DX>#2hCZg{7#{i zE-Lkd6z78Qil?})DU0Bp)YOy>fG%rP%`?uvtdDhly2P-$Uh<}Gwk`!1 zz;~Nhme*G|07TE5uh!~f{7RwFNvV&s5U2(K03ZNKL_t)V?eZ*h-HbDfA@Mr4u(oTt zpXptq=HK}F(=P-(``aDwKfL4Sc2Db+W^1k0 z_1AWc$BAD)e&YG@1>0!eeABmx6|zwpv}p|S4FoqGE z4Q&PS#x4#P<1D6a5$DLxk*z8oi*aBbWP@Z~Z1ToH+XCI!BSoWqiXFE3db#AC>Uan_ zG0hX_nw?QXEA6Q|RW=f@{CoTbHy(!8Cq1RJq2kt7wi*gA$)ad)M3 z8WGYPwrV}BHA>&++MwU|m|eQ=5=dP3ZZ*6Y(Vm*q@s*=Suxl{jts^aViPGBF>qZoK zynT%&=k|?Y(iZ$}Su_{X*FuF6vx0@Z`94?c8%rCtZ@w0dUo{jq?cH9xE_h4((#3Z# z!EEWBH~L}QX1>^(zwfARzOZMdg5EdA!yC%UOBPdM{KP_OPKyLoaoSXoE2GRW9RshU zmb%`r4{)0$m2+l`)AagM`k^`i>fbtdO*Wqe@-ES1ruo4G;MDYEpaSf8|?6=EvUN=OO z)%m^lpZ>e<>vfJ$)UQ|Ycn!9<^I{#J6*#SJ{LRRA)_+{i7C)G^dh7b~=|uO!K>3lT_rSgk(%s zb!aOMwG524mSN|#l+U4Kw;vdW24l1|#OZWqIvbuIPxRdjpFhovXQg~sv7`+Pe(mJV z@1>@&RpY!G_Mt?R`p)t0-JZL<9YX=)``y5>ON`^0DZC)&hW2ov?|1CF9-O1;4)ntf z&N|I|3nPA>h_lBcSlO|sC7KeAOBUlCu2B`$-~u@t!a4Eu{KDUU{u@92`~x{ezWe4I zzWH#VIe_hfCXq}crGSc|3Ly!}>SEO4h)v5a1I`87)-fDfy58X0Ld%edmx*~g^6}Td z@xu@Qi(h{EftTZFLOhbwL?)1u$A>fXtUrDp@qQ-yr0EE`jz`08=-KUWaBd(Z;WP$p zo=9HE0m7Vket71`AAaJ0|NFo5@bJJi&84)CCiUi|WwD4lbZYsYWKa>hT#N`|aeP<< zs@Q69t)m+{4tE{9`+;U?2quw31fP&-RE^XL!6cAaHepp?HeyOGJA-i!>nzqNS1spE z%CXEZjkagWCC}Kc&a&c(F-FID*Yym;j*?pv}~M6!l!^w$^yutr@5@ttBRF&AQSNF;(+ z;3E`vN4Y-*U0NC@Ju{yyacmGHv~EY=_A1O|6o6vX0Lq1)V6DTs1}k>4fSq-S&Ddl~ zbH-+avzE?vdOo|BbaahIvyE#?$s|WMmTXECaAVNIT6Uuv+iZT<=WArmEz~(uoGrz< z6;e`VY44e5&pb_<(iLIX@7W#hxx2sR{==TTyBpe_0z^~xV^_+oy}Uf~zvlnRFTZ}` z)2ByXPA6uc`2J7dvpXDc&XSxXPpW_6TtnCIkZy+&%fs=7)8iRypK;>AXdj667-Min zAHZHH%PQModt8@8x;~89V(eCr=#{~GWnF(Y@Ao32r0k(r0zh8?tjqUvb(*Hv?}0ix zxQKMJf+XZBGJSntri_znm&&yh?~S&T-~9V6FnkRewN2|^*ZqF+y=wbX zzjP_0^%{_FnF3t=zXG4@qXMjYsGiT-^1P*za=E5nx3@YN7ho%EBr&7(cFOOJQkrvF zbhpspRjSJd;pV*78UyO2iNdArfmY zUpa3yo6Tr5FE1WSHPGPecm9=Qdv5hal&`4D;2`=Dw=hc1DfUdFhOKHI|Em+clZS=`(4JP7GJ5 z+E%K!ITOOnJZIWo5vpq(x3@REyT8ZCo@tDH{&eEwFQ0jOeCB)}nP<=WJaanDc%K%5 zl(dZS5~;35x$T;h7(yZkXdBBPe)oaD{>y*n_kZ}F{eDN&Do}Vie&oj=|DDq`BXsO{ z@3}p^N4l0|4B{F9#_@%5nh4VoKb^@wmS{lYh_z3}w%LWr3lmLwL_v~Mg4l#Y-ma-I<)IY(lg@qS{SCqkIXsnC6M0iYJT zwqdv1V{OA}ocQ?hGmmzLAS5qL=b7X4iC=&I$S;5Ug@=a+&gYSF8cPnaf{ZQbsp3{K z6z~PB3N$*loE03VL~I#5psMnxB}+q@Z=0L#VkwTPk$j zxbhN_>DpGEM7It7uEz};sh+ZD@-xXp&XEv`@nE7xU2OS&<8anu#i)@y&-f6qA>#2E zJU#`I_;vo2qpovCl&WWQCK)}CF}Xwwa}m7LHKFP@#Hed;4lIh%wZ`}Ye(T;Lt8rJ; zFOp7`74+6pOPhvm4X-VLs4t5Y>T~T^DgJJ`0==@{xWz6TZ>B`yOL~bl23HiqQxbK4 zd2|nnajCDnb#>R0Z*LlEwI75f;8gI@66wvXn`Vla=ic7;0&KVEh6`$Wjp)}7+KS0l z7!gv5{@&g4m;dxn{MY~Te{*;Lf#3}>WV&X@Zn&Xs_JGBp<$&7eK-ccHR8kgv^i1=_ z@%X~S!voL96ESAmwqt+TtMc@&r*B&t*OYc?P2CtHA=R7IA8QUvB(PVl%5oE@Qp|L$(+hd(zTSwdX48xvo*JEu%78OD?R_p(+dcTzhUFe5zjFEa2 zlX7|R)!<7xK`djil#mQDqPf71zT5Hc-3Nqs+}w5C-raEj{+9iIM--3uGZMi%rK2O6 z(RpID9AC8j+Vl8KHiA10^!pq7-JZrplF0-gaiLWsUL5&G6>!ICQb%@s#sQiB&x)&vp-a51d((Bjd4NLSb<=1U=XIY0uorKDUsipE{0k+r8c_r$U zFJJr8QCS|!BzXfi3T*3|zC{uJlAzahglqfxt;6N@cP`h(1#JE1-Ml`}-_r-%@4SZA zSD&fpE`JE6?9p$`oSX|uvqpMeUH5g)t$wrer}6@XBSPhWAwrTWZj~<<*ZhihUjS_p zTU>xw*~I>yo)TCpRG3n#%a-S3t4kr5_sgDVH$YiLmi^0I(NZN>*V-ZvsQb_YMoigH zS%GtX3t9H9n#OqD?$@1LodjQYKP+2azW(YZ_}#v)7nF4oErFG|vA(ji!u9W=s zXKe=+@GmV|zx!$;ZEt7Oc-efX+MiDIMk8625{oEJ$kc@Gl*lGyv*zt3o5}>ptLO1c0%xXc!0)nSWqkD@2axpfxB|VlovQVMd8_JjC`Bgt{Z+6>_QVhOp zCt@y!|Ft7eWG#Qx_nB^RG(*HSnpfasWSq6Mk&kM))F_Ct1w7XQS)N-gd0(kUev480 z#d|7!aPeS84bwNpTMWuz{J@_#f8)FFKG5|o)=rs+(ICsLXaG9g>W(C~C}_z2DpNFI^gLKIR+%;TBk%QKHpzwqhv&m6~3By%R2 z!1MVd|L@N;AdHh|_K}c5T*Llw!@Cdf+27t_+YT{?gy!UWA2i1{c%E`9hM+F|5lu4~ zPcMA>_%lz>9|`e{5f5gDqVk+#AO=qiGbzsG=#iYX#7!ATjWe`ugL94;6ORv19G^VV z8^RdzV`Mx}ygVIw{Pf7n<1^j|1c*snqcx~CFI;S19N?)mI96-C{1{QkPv;s{wsux& zg+`6h(>#;rNdw6_BOxO`>F+rb=0uv+;ItwoPp&CS#kS0Eb*`<{otne0AV_Q}k7R5y zm;*W2G9sDOKxz}Yi3IC0cGl>JfMmf1M;o0+grnws8^3zDFXnzJ%jKGe{o%le_xIes zAJ`xEG&>E2ALlbqFVCd&Q|TyG7FQ)^L)SL+T}R)vT8p{SvP3CFrr9%3o_U^C#dSP$ zlp{=@P@}{f7EF}2ctfQ=RTa%t#Js9Atvc4Wwc9I|xt24kp4aXEQR!*1tTk1b`W4Hj z?oVZmR1jQAi*>!On~W3$Sd}lgxre|~0?pclGb)~@4%On(w)Ha=Q0smBS@j8m&*T(H zH7~p@mWzQ?*79l}ZI{jJw6#W*;b08bX?tpJxaRujmA|3QDs8RCjAU0fX z;f6vH+c=#Jv~9!Pw;%ZSkALKwKmC!z;g;!~nCFOdJ9dXVcEg>5T{@iYXd4B;P8!{- zbHsbk{&b>0+;DR`lVZZTmagmQ+m^O%=-P&^Edq*C=)CoQ*?8)!U{=iJ?AV2oIZoKw zfYr#d=GR(`vDy}=xyfyp=y&h==DR?K0&E>(gqWi;DWYeZ&z$lLK1?_)tu$Cx04&*J zfF?IMX=!A@h@mw-U9;2t{H~?n59|&H`rQsOnh&c$&gsTn7rb1p#?3S1(%{Q=OjGpb zb5%eB66cXzN+9_JF?deLsA)}e zVmy1MG}8b4k=?sH?(gq;e>2cFJ;@rT^Ng7-8DZB_$|ZFiPbWqJCr<04m(-V(Gbu)r zu_RO0lHWM0vHM#Q;V%KMuK}?wxLYDaRarOZlA>caLS1N@SD|o!F$%c>fFf($3lXxh zB-tpn2#W*oYj^lo{v)tZovR4etM8R~-?}E{<+qM4S=QwBI-9lfO91^V$2PU+LPYCp z-`V`G{kmL#yFZpytb+VYN_AGH_+^jC%V%@0gx|}Bw1Uu!wr=mEfZi-M(hFJY^Itk` znS=Fv`db&}v~@;^P-|dUTDVm9$yGlsEYfBFG8aJBiB&4{2KzzAiVDp+RF^t2#YLszzU#c1-=Wolx1VDpn7>eZw%1O6tF8W^2S$QIh@`) z50~?)nhi_wsbwyu4RFp>PxLzOi)>jgEAT7F&g&bx0PI)Z?`_(ZbIuZ@0*b|0$+D$k z>zAq;TrLx18C;tiEl~<%OIxJObu~6<=0kE?c>yqXxiF$f{&P;P=oM0{hxaJDi?^dsWy^q>o zOAg+b+WbcQUww8pCOG7OH7zkcN5^9#qL*Lj@O8Pax|?>!6yU9XCm^E`7t zpRri}{O3RLPk;Ffzx)1s4u_#cV-j;xy6sU<~A3W?wYemZhKKJ#+?%s4*d)#0gs35NJiCZ zlgmgWnAXsCj@CQ;?C{5#U!@V$uQUdW_m%Z$jB45^axo+3SxUBZRhzhtlCvIJKBCvY7;g>*WIwcxnt<>Fs4DWrga!vFqWibJ0x3NaP*Bs zx{lo(NU<Uey{nT9z`no7_bjM!yNR*JUGmM|oU7Gt6Blv3UG zmbUNc236~C`yLP^1Y)d_DvkP@C8F?_G4R?*hhpI6V*b|wKrQE@W8S$2Czjmxjn49WNEryKPRsvUf1AOjM6%56!_~$nbXVoUl)zH z!0#gFlP}NxMF5?&F1mdcjn&UD(L)S+oRxKzmuo2S&7x|{v5eVJ7WiE6vAlj!SNE!a^ggzc zFLi=wf27N2D(f@T^KJJpvqW^A6wyoSzE-|o+V9XHp~OOt!ymW<6A> zDriY4G=!2VwC)J=Hjj6Eg6)X8UQxE~md(#^9j`{=8x7u^J7w_O`$fG*)~P!prju=hL(1y5_(*o%!L1f9F5`<3~Pz{>0~p7yjetkF>iM zGdK>n2ln?ZO>Z$S;9RC_1e_q^NKpuR#s^16NNFSmqt7XNLhz*djGxZY++0A}DAiM?@lGGR_IPGgxT}7UpRtc#SSrgpkP# zot})+on`$Sbk16%b*B5FV;BaU?UjC1P+E+FpEL70GS7h&&=N&6#0hK^4*Qndn|t2f zzoYL4nx?@RL-1Pq>~ubY?d>feK78Q)`&;&h9kv%zPMFpZf@cmB#ByDP zl$4&4Vj`5qA*D!;2|s&;QX71V_}OcDDj!v_D&~c%T-T>mpN}a8qf8+bWm(qYdJnSs z;p(^9tasbAkynl~HlNw9EgK_qwa8c;nWl^vLp6rfKu~&?+0^x|OO@vM*+ytPOTUBN z;BZ4K&JopB5GW<9L~Bz=eg4LQYZ9i(n3RwWJz1R@daY_4i)?a&Mf=w|6@==Co}t(A z-E<8(XQpYyGU=LW3^A()#_R)e%8Qd$P?n7}3S>=5JFyO$-q5tIM)5-`fLfhIb(&eD zETgUnP|@tz-`=r1+|YCbIEU$4hQ2|>(sT#9;Q&of5(~8CZ1Ab1EtNLeEQm9hrls#3 zeaz&d;}K&b7jcd#YD`FuOMW(}Q)-%K&Zm)an#m!eiXi&gWHWBp(@2YTW)b=mW3jHm zwH>bSajplnDA&KJxM7NA~Y;Xc1x zSnH4gAx3-|@Ublss3OQ{sagy5C{Y)qB3QCPep}=Iw~o~|zx@7h9ouN#)*!xMid;tq zix|p9RJIt7#n%42fZ}C4%D1!dR$U3q$RMouuuWspIg*xO+4_9-y)TUktsPs1 zx+nm+{7`dzDgCmx{!*Cfs{O^WusGfFHO*Yp87ly%0C{D^>b|j*Qxv5%8!&IeRc4KW zD4{ICei`WXNF~QAhFHpoY>cULsNt$0m~2!OD#f)##Kt(Qi&-iYv(opr3Z)gyT`29n z1%Q9!p5-h3Qa9Cl&6Z5?X|uHSg-$I9RqKTw#^>< z<~gs=SFc|UtQvt7z-cb7a|%$M6B=h}8i#X6|L+`D4D&qm{QQKUkDQJp<7p!Jz+7@u zy`M-a5>udQ1G}9eMnS|9gWzmK-}j5csI|J`_I=%$nB*`nBQaq@F>KTV2NKpy5CbWRI(&jUhKN}gK`D!p z(Yl(pL>jDdx@a~ID;6tO^X;W25lc?$gcnhRND|f>$Xef1Fsfi&&Rq>u$(}5p9EDu? zt{OFs7#qmeV{O2?Sio{b5-KW{lID(yt}_IXM~HSd^63bQ^BV>p|$(xNH=o^`GDerBF$y!VT!RoX^l zDQisuns%W&<%@OLhW&2=&hwfRd5t)OGoHVM~)X(QQrb@oU=vetVRVgYEDB(WGiL7$gR*hVx` zUf2t=fXix}nX=!O2t(;CsdJSzf@iFjE30WfP2z(n#Hk@YxFCt z&|gTAarC@AtBUb7PFMrO(6Jvn`o3jncZH>)f_SwKaITAoSb`A}k(`s7bh+%M#X!%M zHf1udbqwrqO|z5$GaGoh#x_d9&e`Cr!!Oq{a1{kAgZS+# z5wiX0V(#W*=x)qkrO&5~X*FKci01v16Dc*s=*XzhXwx(*{xy3Vugcpo1bi_dtAirO zj1f!U?yw?Ee!_dt^Yb%L50C8nJq!)5R86q0qwjjUw!=wF%89u|G`$o`do@;5mEhsk z{cpkVwlBUG`FsUVmo;KlmA*cYpq4Dbejxws19f^@3XGxH z3tM3LCVL^j8e=twxUw%+XLnv82Gu*feMXf|nlH!t^4X;+uL19G9ox@r=gQmjQoihX zd}}T&=gx1v{iPGF_XfD3AC%G?W@0p&j}|=9dsT649D+szL-2*FxEfBGVq_JgEmI6Z zk;Pcos9^1o^?ovW6=-`p3-5!6f!0S#J=GA5iv6{b;R63>WHDGvAP&# z962XKn3(3oJO?cq5(9>elYoAEI#nX~}lhtH49Q{d(0g=rdzDIqDp5=yER z@|Xf42SW19IgmH?AXTtQoe^_LG;_uor=?CJ$fTuH(i98ej3o+_7fjdZkbkIN5aZx5g_1-Cc&Ef<> zmi=^zq;3taZRB@Z8Y}I&7zGR6vF1S)PdZlUI!m`RG`(P2NH*Z}j3hy_*D@oh)moaAnNba4*#$+8U6$k;D|3rd)*jZn(RU_ikXnA23br*T_6gJUz~Q{OIVKj`Mk9oIK++F;6q| z9F{qrLgYNn9Mc5H6Js`nBz%52@$GlN=;+`oIz?(PF^KM-w4LYXZgWvVC3iNzU5 zXAF(Cbhf3nS_a1%qcv}<9b`?(!8fF+CAz%#jN`=VbmsZ#h2!Z&PKlv&h;_IQy1gtB z+p6L$#nQ_dVqO7DN>SIk9H}(KC9f`TqVm>Yy9RNl0Oq>pvKYAavBeZ=yP(lZ3ltVe zHsx=lH0!kNs|r>PW--L-+`2xNF|$n9)lnkofR`*KCt8-t;u>Z97({Dw7S=<`wum;? zy>`uys#*gg4k@|GDdn!oG$wmovu7q5@sqyc~7q?fs(>ucAl%?k+sVjbf8-Gr1}%eUH8R3z3Q zK>1y1r72zIKrgk=O5#beQ-AA78>98Y=-=GwHTc!nSjGap2AefMdJDd<|9|n>679)L zn^^a??R{+R>Fovc=A32!y{28SdCBG8St;i%z`EE?1srbfsEm)*`Gl}UFRz-i=4NLW z5iHFjUDx&XFiSKP*3`4*x>t^!%Yfvi;Vp&Ar1z>Hs-jjV>$+vQ?BDh5wKGyFN;}MQy83+6db*1vUA?Fe^LnZ-_qV-K-kQ6`ska$dI$rE0=BRtdSB|$* z0IrX%^QE?ajo`}W)ytcy^Wg6R-q+V#$NzRlf*W=N-Ur%7^Fl(YhYVH_l0rr=DFTp z3lOKkx9?%UH{9F~9QIn~C`FC(ryPkM+J3loAcj;lik8B}7#K z#X;9tauTK~;zl(9Y_^aLxiMI=B=O{&@j(jhFyiN+xwk;y2(EF|2(J-cX_e`qWoYRFjV@r$wD&uVm(+`4*&^L zDS5QDS7J)|7%|Bc5?a5u7_g1Cn69N2OLCFaWtyhryKlbZumAj4{`${<<@@ixr)eB9 zXbB=?3|-rEK94*-J#s#uNOSRymJ%!o_k^6;T4OLfyS#^Rj8T1V3=u(X|ux!FG9oU&^Y0WT#ongcOJa`dE_$zGqa%vwz#c_qiMPVPV54JpB|t1{^0{J zFV7e^b9Z;k{Wl%^!@w};Iyy%!KQzrAv7V;Q+}-sI{Z8APMOg?_WE>~P^ThM>3y%*^ zoX?(d48-gi#~(R9pZW2JkKDiez|GwUZtvgG-`wMxjvx&o3BEYY1Vhubx(9b1yS8ON z4BYGw?00+i{f@rvXl;kJj@EXxMVKv%){FOE*$(IPnd9-uG@r3H)ASAf;Bb8=*^w#E zfK_J-b^FzUU~E$WodP>++yYWy<7`3-ExLfy43Z7j7K(BCS?y#|inf45%N^+(x#X)Q zN)r^<84yz#6_h-|3To4OjpY)uj@g>)S@X=c5v@8QR$(Zu$zGAXln*8fEg?f?A&6*n zD<-WTp`uw81lPQ11=y|YIP|wFBH3wMf}Pk6J6h>f@js+8Z!$?TvD8VADS{Z{5;rSG z{dIWn3#qZy*xw%2xV;8l8p*AFarvFCnAL9?uJv4(^wi7G*kv%R2GU!R(_EiVHm}|< z-&zdLv|$^trG;+*)Drc|>uc-3mqzur4X*{6G=1YbGPVFkxrB=~Pgt(b@!Bw~Yq%PN z7tv>cs_nD1Z3Ck6_8gmY7u#bSAqJLeAJy!Xi*we~%BmBj7v0?RT7P;SPpc8DTT+bx z7yGB!XPNw_TJ-i_m-jcKulpe)n7mS* zH3D2TSeD3db)^;OeWhqGwpIlqZ{Mgo-!@a3Y6HC<=Zm94>fC<|P<#b!lr?SpsV^U| z=fGQYzS<(2My_+|ttMQo2iI-=daJf`M&t^3=ZtGztA!NWj>F9X=bAD>4PDm~qvxle ze!@>P=hIn@@GJUr%HRwPear3LExVo8-wYw*ec))0#CXDopbJx4?ECfaV)$KP#=Lq( z%+>W4w#?O9@TE0Y^5xq0c1N$j>oclG-kXln`hmB`)b$#5Imcg*x$E=ftKV;3b9=7q z`>rL38U?|wSw$E$*H9HxZ4#0zD!M5VN{N`Zom8bWtI=u5MLo1p5hmv}Pfsl4IO1n` zemUXX3H59U)(D6Ffp5O~miPA`xH;T1bUR!vMUf#z&4WCTCr;yu^Z3H)eB|Z)nU~We z$MG2-Ct@v(YBR32SSJXY@0)_=*9EJYwAnyH^NB-H_2n3}He(8b##l_-6> zx?>w}$RWcl8b$Y+7!xU*GM&~*n6u`>gp}~33UMXZb8GI|9qxGl?e~29&G+=3I&GA4 zDR}RBd3n~-CDQ{h$7dd%KJxJJiR0`w&p8DhZ!wqBZyJTJ!H%jHTqE+y|C{w*E2!0SN5xrLGzwD4rQ}*J^?)k~D2|b3qbusm7ySWS!I>JgFjAw=vH)On z;T_cTHqOy@Lf?0EozQkIwr?@k63v;E1Hq_cC*3k%nBhDGxy~jEM@mhCxdSRT-sx^=jUEeb7Z)x4WI1oEhf-u8)9{K$FiJyM@S%s5g z#>a`tCzAJ!PfvWD5-*>hX!oD!c6*w3j~K_44L+nYhBH=#*0l_M&(QZAhJm|M&hGy1 zp4*#y_PYZ^zh@YB9Cmjw0NG%$n&L8!OykHnj?D8&%6e~YFEni?=8@xR<|TUqMd7~e z^&w`&TDpEu+YL0X$GVozb#!g7iqKLcuz3-WscTJA)PiKunwWXb&Rv19EKZCyUpcXo zDn$XYQRQ@HjiilZX^q0E%TVdkb@RWVZpv%0S0_XD9jPI@Aatco0+Fai*bdTK2m;zWD$#9JJngpRrDe&Z~0wexQ+#95nqz(7Z%j68&S0h)HYo zZZVAX_flHLnqrXF`(HnQ4M=}0vU4%#3t(FE@V6(w?&nSPcPl&utIf9N2ERt^Ij52) zv^phzOSCJ)#U@wNfXG_E`l5}m+FOmg6)>*3lvSXoo_ci}$Eq#8PsweCHmOk93I9@)_b;qxOo0ESvG9s*v0WRs&)Ue<-2bh4|JoV#>J#e% zbM;2O_S;}iF8;39d4n#yIqfCem({}^THl(EV(p-#rlZ`IANomia8s1l6x&|+5vzI|uelL$s^p6D# zZU*Bum@I*juTGxp=OOjAvNvAP|K2*Tf$ZCB)ax;HxsK}bHK4w|&h@dGH`ODRlNyWT zIg-YPhKDTcdlk=RBX8=7~9+csafB>2c4e&mHb$ znf#e((gJ|Rg6W~@ERB;QcA`#dF~WYhVZXnjZ3YaMlwh7C(|P3O`Gp7nD`!8E%ls2^iPA{{ zRzftamaCMUyi^p`>)2UQz7^?-@n>G=%=0CfvQ9z5K?+<+Y?H~E4fBXx7 z_~Y-meRo6K_GHnV&>RzC^rX|7X`VTc`a33dzEuFEPW(Vhfe;k{`{)T-YhdaoWr}*f zMmj@M5t-z5EJ)D3#RMTokf8ZLIm%j!jk-CmK)9N@))@}Bd;aj3Kk%Rb<)8V7|MXA% z`Okmm-Q9Z{*XSLKMIwaYIUSEYK0om5(@z*2r_&2$Q)-+CQq)}EkW@G=EdmJQP0O%5a~@|hPNUH6p0*!o_II@X4%_TV8P0R!6emXSiSw*ZKr<4D84jAFLemi2 zk`?2*()u38kwdu<8)-6Cyb56-8pO6d(@Jm7RVB7~))xaW7b7zRc{Q#QnVhvYcpa~T zS;tD5yD3CnD?$ZTbqZ z)z6h^tSNcZ);f*KH!ZmzaFRI;1367P&sd4F|Y0PoEm zEqx}kFi6UbxwxmAlB8B^!k^_qR%pzVLRJpu0F@v%JIhQ8e~9%mI_ zaBBFyoSymg=@aMkxqu68cTMb8@C&VVNHUDa6XTJk5PS%cX`D;Mu}q+1d}%ad(QuF~Mw*NX_+rpH3vFx3L=b432IqtnA*PwrSu;l6 zNyRsERwdu@qzcg@8WjvV;r+MyblDQ z@N;B5&5UPHNKxtAT}S5*4DF7->1jGaOvZ;Z6U6{AvCvo}k`fXV9*rz%-;6xDCrHBM z!wXs&P62R;fyqzIv)4$;-a*!~K_aSpdz?q`C!B4$zx$3q{QgfIcDG2fgrND&=hKPnf$7;f+O{Qghh@ZFz2FuWU}6M|Kh?2v@u1LxC`AAbCi|MhSG#*aV!#CbepL`5$M zp?KvpS!#~#Oo)LH14%O3>Y|qgHDIMY?Wn5d*+YsMiYS-Ftb0=B%BJf)1~ncsWi!Gc zk{Na_zx(6w`0IcDFZ|2D{*`b4_

Jdr#|n6+!cbmhJ=N`OMS91HXLyg`YqF#HY`{ z^7-+B({W^;OU`GCtN2)1OBL&B-ws2opsj0G3a+u_^zzypu=7&^AD$8Un@|y1r8-Xp?me zd(U{D@sm>Vk;s1EVR_HZ&4KU6$UJ$h?YX(RqdUB#9d@*bceri`wkJk7Pl2bG6A!#OL)#`y0%r}op;e<$Vwnp` z*EgdRIJ;c-!=xfurcu3vrRVdlsuJ-9`zd9vb11Km zYp_`z2n#)X^Zh#CZE=!lySIiQ3xg=4<1eR-MKEGjH=umX$O@opipch;z~|aXUo|1r zMv(<{Z`Z=|43^Kn?t@oR{Sx?YKr|>oU)DtduFCwpajau| zePPK7%^Q7)@^{|+zfPR%N0dvuDvi7L-U4hYuti?qPdU%lG|r_It1K7U?m26Jy>+kG zEQU*}{_E$V`&x5I}Hz0c3zxg%by?$m==j`=oWPSSEYi++?>FX4m z_3}cOf4a|~KOqF&Xx8pYv1+n>th*Ao6m9e z`F!=>Ti@sJ_-uJ!Hs{^8vl_-CC2A5^BiYrulpBCw>lBJ4npPtSyIsd_7_bIX3QW_; zG@kKuU_2ig$G|uS=24jE%sd)=$V{VWJV)mFZ-kI>wx{oRH1B$xZE2jAs;Dv|7^SZI zc*Zn|Ah-B*CYv+O5vCH6jW&YGWK)!3$&f^8orU^FH3E#*j?FnCjl*`1+ubeqxA*kT zfW@i-?gNq>bD!A{Aaul(=(>*k+jrdG-m&lZ^i7X#V4RLTKL1L}g0sE0E33+K%IXL> zk0aAOkt0mg#KXg9jxR@yxMKHJHCh##8~PplVXt*Li=)Y4nN4CkJ!%BL894Os_;C9@ zcen4z*^ojeCn3bZHy@7N9PVh`z)wH@2h;R|6eHXkmGRF&bQu%CloDQ;gp~437y0-U zV3jq(kw_Y$>{NN%w1U`#loCxTD5brzu)DYPcNXs^KF<$`Kayzh0nTH>A196Kkuhsp$atRAK%W9nkB|KPw;%YAzx}|&^GBxn z%p8wQ^H_uiSDAYe5GxCX*g8wwwe)>Q(>OKWl1A8b3ZytQP30WRBC{Gh%etA@wIG-M za--$8uG?2RL5s-Gb~6!K^CYEGh>Jr-YUKFJ&|9ui6@sOxQ75H37ZJUb^?6QtBE-m? z0wE@125S@9mQA!$x$C$rYilmg+iWj4Bd= zf8^We_jqUR001BWNkl)9dz&y=JayZ*yO;0~K9bX8NEFkQLTfY7FckJJPOFQhL+k#XU=wt$czke6-gHWY(E&_?&Rf- z%pT7ZNnWQ5I2Ukj;TU&EZd?Q*>(wDmmrJq>q0m)Dt) zv)5O7U*P2D8M|liuz6-|qU&G*xW|A~7nPKO?V8T2_!Wy6T#U?-t>u1pwVo8^bzRj) zciR>4HtQ}qY2*5#j{9wS*3-YwkTjiyhnn(RE}NE!n%;9V7D`R(0`N)_#_}Fyjz%nO z|7HC#>wL`2)VI{NO|xt{-AqB&r4N2(ZY|F#xw}6DCbFStN$^;8$XZ8Qul4B|$m&iY zM{La@{TZ0(SU7XeYFnq89KYigayQE?I1SG}f?#KKg85SfzuzBnJ2W5j6(&4YY}bA_jqt@PrPi=XT-e?N^nIJxneYstyyXHK1)Rr)XA zZ#E3(gF+5}jA;SA1pqsfv4m64y-36up>8Z)*W#RI8hiG;iv6zV@o|Ur6Vs%iW*A@^ zBGU-N2-BF@?e5s`N1&qHZ0RcEHhfe;ReI>IiM!THqBruj}!H@s0hqxaIcYEHy{h9l_dmXaY%?o*wgrtZN ziD^;-y{yoRSY2Rk7AT3FFP){9h_XHhlf#{}f{=lrnXOz!VJY)yC17U-LGy)gKi=}c z{{8>u@#7u8`@4aGM~rZ-I^QyNtkxd}%9L58m?ryogyXED}H~6~7B$#5L zl#?*Y<}sz<*cp%U31>R38D335VhTHAI4}%@l1d#OIPCX~;{*bA)v(O+};^Oj(&2~%GR@f>NLDU{o zdu%R2=53AO2q};d1^6j4P9ulmz%cX(iLO(^LWmgAkS&KO@mT^J5>@5s>JD2qS@2fW zZKr@f!8i_#hXaShfye!h$HPub`s90KwE_V)E5ni%rR=FMwT+jxEot=vZ}FqW_YS{z zRF%~de^rI68=SATbepYluEUuI>pZR^*HK?I?>Ve-PBzZqmYmmFK<=r&kk|LJ%rCj0 zy0ehzqzp1=rq`lGTT615s`5H^D=j(a9aNRm=q9W6%ayEcRJm=n?}Affm^jI7-p5MB zDTJSaa5*5QBemnV(~kP%8P?{rz}c8p9%Tl;Xv$7))o5E=lX)*xz9`eT$s8I& z6idRWj5H98Xmm(65=ypoDxs2w#_Rih+LmKaa9I~@UXPw9@mlXcBD6ZQ=@4FllQqsL z2F46l<{aviOD*2%r@zg=e`Y&1R!aG{K5f4L(=m}0<*itu^_k+@Gn^xJ@>0w)pBArg zX}p*vcltgPp0@BmyDiUNp6Rz-Z;9H1*{Pfj7UcqG^WvXgX>nd2 zomX<0Z|!|N@sKaiek34PAg}B@Ii{ROgKO$3Q1=P%d#sT;ti9AQHNX_$_Wr>4Km5RpmoIqv>J{B(hx3UknM{H; zGL8@I50C8o2ZrIm6nn-nU~QypD_T=)*jo1V#X^pgOX5sZPfC+|4qPt5WY8Lz&QMn^ zH&@rZdijb?cZp02GQDXaSuUE$p&1x220~EstGd$A$-1toDo<5a?1zV3?#WU6OE#O9 zs&YBhvcg(nw|_*EVHzjW)GJeGilnIE1tU41xTdKawwnuH-n`pw+KQ@ixY~eMFFYoK33(1{$leqq{r)3AKRod8IPtg>rUAm} z2%{xV9v1{RB*J0Dgov`lX5o}Qbtx(UPNc?uKc~;znY-Kq35R`-}2$zFMN1)LmWpuu(`g*T1#DdD(5j+rm>@GHHW*ZJezGt z-D)Vc_fbjYDrEtF*zMRK_L~3c494Y9yQDR%Lk@9{NitcJdW1=<#oC*hZ8Ie$gTt&! zTdja^5l@Q@HNP1IA1Q}sy;v@S(K<4*oaV}VmqVX(D5FM5L}Jh?15+j$nnZ{xJL+=| zvvn|*^`pq=kjG}pWuDuXMP5l+VFAf82~!xer+9hNxz2Sl0D66vaT>V2`^ftbzwq+a zmsCxQ#S=qX>OUql>LfW3hqV<3a8^B&Nd{t^NMS-kLSjvdBN9E%HndHh8PF>>T}#u{ z)K!hMUPFj`O+y++$Ni&cssz_JjN<60KtE~P0(OIS6*g5ktLZH%2JRm3xZ6J~GzY63km3C4Sx zw&C*XlBV5)@g&I+ILQ#lfE^}GKVgOuJB;`k5o_?y=TP><7z5*=sV9Zh%wni3Pg6I! ztdEXXx2~z$P9u)$EtT)62swn?Xq{{UjMu&(Gcf0Ma|XJq z0dlIcl^n}uHf1Gy7O^=kWHq;n=ViWjIn^%Zq^x&XF*s+byumn41Hgcjq$QkCMbKG? zAXuy6;Nr_A7XqglP^~6wthiT)q6H%?ptDHUGtW zTZjFYzmLhQ)&_(n%zFm3zwt&#Vb4dvwZmtY#NBYHQjCw0L%=&9Fa-a51lH+~8G*D!k&lW1G z893-7pQ6)}6hQ|^-=WV_J02kR#V~2x58ewGm6Qw@FlI*F|ui;N<~M z0PY!qvA$+e_I@QrWxmI(G(LCyb7S;3Tz{6L<;|_%;QDj@JkQPcvi}tDT8^)=8b773 zXpF1A&w1QNd88Jh6=AQ9hus4| zzWtu-mp4o@(X}lGh;bss2}wOM3{0UX#fc~rViMk4Hrq@BQ)i35_au~&xSs|dcRL<- zw;YB&iGY#9Caf0rQf{YhJDR$s@->DESJgCbi$#^pO*Iii#2QQOoQ5M8*MrmAlVktD zZ~$*FxVYSMeSJk$`D_%ZuwJO|Kk@L;lj0rI*z4)m=X}lz?>tSbO6hic&C8ds`SSJe zdHwQBx@v<-+P^6XRXt#A!}V2Qv$^2r>Y9tq1(nxQCSi&^JnXo;yW``>kNouRN51>+ zJ3f8-L_hST6!0bxf`){foU@yfWOAe>yfhV0ThuYp)P~K*v%P58UUqaB4OOdkIumLb zku+gl$eu_wOpFp3#)Az#E^GX4tSiYEzGy|5(8TNPggnpp9fu?Dg z3+4*6O~q!D%i>V+^3@Br7qv1u*NLX7u{NSDkdfzfkpqPdUh^VXO4Ku=rg(I*a#A00QQ9<=Q$fGxG%5hr zHbyNiCd#@UQY3`PD9pfD%L6R{xZn}91|@mjC@ECs_cGUIwVoWya9RDIqI1ok1qfpy z#*zEGTRwew&%?tlS67$Rwj~KT@hhZlX9jt)BA}@NN-8x?ktrEsvWThie#52%>7wT4 z7hbnoPx@83VaikyB3+$^4HWyc1wlA=FQgn<% zWXSpD$vdjHVbetnhQ?)*$`}zdAu%!x6Z`(aFM$Nunk7;xLe8piU#P9ucCRk9ua3iFn^2 z&fu&@(#%ppo}UZAD&%?bj$~|r5%a6Mte7R_nw*2~jRBXzg@H5^=}7i`hSh{*_B30k zW}Q?fM*+C21{kC1FRHjIF_p|An8%;0iynt4u5(+T3tu!jI$|c-Dp!>S=q=YMtn+qe zn$;+b;`w#>3=FJ<+`6KCrwp7cMD)30?vorluh+_boUF~pz@^-gMiwl6x!y`GQZ1*q ztPg8=tom~C?3{#)9$iaTpJjBd`*jJIE^>4YYD?rnzR20z90NmH1l#)eH3%@rV`DjY z8P~JtSJt3t8FTA%jx4McfV;@s>~mKcSp@U(1@cj<97|U41+;V{lDR1|Xgvk8t3Fu& z_9U#F1-O-6=OPl0u6@Q@BuR66fw}g1IZta!uW)hF^|I8ee$sbmJjb7lz%cf7036S& zdjA?5XP(SnY?%;QeKpX@%lhgpmR&$jsddpNqz`W|OM@aYrIdB7{r@OcydQdJ|L zIFFU}obbjN&DYI@Jt<5e4VA6&*5|s71}hGe4v->YN=Hglk%`tS8+20}1;7rp-fLva zB{yboLq1 z=SGFB_RGmJ=9%x${eARuPmYo2pTE4TdFo|3?pL0ANidB{pr!YT7!&6(^{P?^O%bh2 zJ55Pza<2NWyqB_&B?9k0{zCfq|C_hJyk)cLsOpN^JLXxQ%u{cb!)V86r9kpvA zIb3C^%|?|juO43`C@btVGE6=Deb4TGK!WFT`}}ejR@XV_@^!GYIqQcF&$69yp;+s22lEM(GXri!va&0 z%gedz971EvY(z5N;JusYl(m_>$f{!EePOKDh=^GsNrDL}=eBCtB9b&@KIRbn5*ZYi z^qF&F+nCudk*(A#AY7D>44`LGYdKmB?aA@QSf`|X5XOn|Fp$Q8O$nC?nlwDlX&E?c zQHEEUt;#|m5|o*J3QQ>yRSU=23RkxnXYfu#!<{YOg`}b3$j=G=VPyZf zpdw)=9ZCq%8mPU7 zD+f#ERNf?#Dv;LbT&Ebfg)~JZ%FGI_Mt0>DQ6fHz^#VR=Xt1c~G@?cbo&EzMM2uC> zud{+PCD&DXB(Q=K%;{hdF>~$FdHk>RoB~3AEll{>F_dP#K_ySh3TRP&$~D!aD|v2c zkp!W5JWuDQWTTsuv0M(CX<-$(&Ri*LkIGRj#PN142NvKvvnr!G!>79VlEb^+XS2*s zbNyVKHEYX4Zl_Gxx!j-?tP@=J0=k(wH>vS0W$#u@i^mj=bP|)R9heeYD%l3AYl;4s zG$#{g@~X3;+~v7X^|bP=@-&ol{rl4#%x8{WgR##ci8EWtt34N1`UDu4`{hOSEC`mT z{#i*SpO))lkMSsK@K`lfqcTrDlgn?j zk7@P0oq_Lpz<9dNHLb}Ytfcmw3Gdf*(Phr11lAt+ugQj}PnWv=>pL;T`EHdZAKRGb#KeBH7^J9GtP|q0}P7XfXuvxAiwP1NtbGmQkeSU5` zegA7OG;ox+?3p`w?AhJ?$N>8U%)Nkn>vjVWp zYYMBM&v%q8eP6zx9}>$k&tCNO#9yCh=YjG$u)FpguRYDDAb6JA%pv9!rSRmsrGHag z`q?_LlPaX6rs>T&+ohJML34zi3#%G^`p#krQ9QYqRp$ox50C8n10O!U=f%qx+}yli zd%2}E32_#0EX1Cn-!YE8D%noBxw)dLYqpyW##RUxNfjm~S_j)okd3GITl#Pyq=CqQ z$s}2o_iVaLE;d&*)rQ8mw0=wDI;?3RIZWj-I4oLk6_gx{%n-fbjojb&jJ?n`*IeCP z@%rX97nc_b{zP-=`rRjXkAcHJVQAQNo~z3(FJIj7^2H4|*Dtxcyr$b|Ss-s~oNLsg zonRP8`rW|pamS~Rx9ko*-NhyC=7NM_7!`QNDR4L(`01yg_@DptfARhI{~sSeec*6- zB&7-KlGc7MrKZwifJ#w4NTsBVNM2Yh)U~pJ-@MrJ>diHmms@Bqs4b^8JuNVu@+0zMI;YAB}aQEwD)Ld2D--@=Iq@p!bhyd86{@Xy68VKOas5% zz31}s3Rn4@^QseK8hhGY#%LM`9#T)=AJ`o}GL9oDGlY-h$T&^R9-~}7E5@V%pcwVC zZn18IIVphMsS7F1^Dyng&oc zP63?D7H+FK&^CKEom1uAX4xT8!`j7aDLk9(9D!2gmgMJLM+g<~Y|)u!F=iIAm|xi} z4mp$FO4{Ux{VIGc2)Bx1? z17qk_`OhwEW37^@SkYReMvWX(7?_5U!{NZg{R4NmcN`9TDyJob7#+q&Y+d0iM^$BJ zS}Qa@;l0qb4pVn@tyf=XPD>i6KpZCdS(8XG%(AaArArYuPZvbVgK!?#Wo$|&ppiUp z?J^JN5;1uc7n!)+yMT#R+elEz>Q*4({8m!o4CmO4*WruC6rzaZ&6tHKNTb4Xh_q1) zl!k2Qxm)_pq^y)Dl`{sdq%gPi_&#$9qztx9_Uvm+#$p6DMx%tpY8;WpW}QeEJCjO@ zt;MjZ=jlta#RGK)%pT=cp3AGFh~{UJ$hCOhFRSx1rdXKpm$C3%=<4ad zqqby_npnyt&AFQ^*HZ~}mKpHo?4s2r%g9};rLc_i(jLPSVqMk&Ghe8z=Q&=&l>F#C zPS4atD&uq+%O(@yEt@^*^Us2*Gak%S0G4v?Xf*^cW8ZLGV#&@P<6Pz7gw6SMJDr6` z#uApdUHW5Y($4FuIf)7>ZPRi#|q~Z$93l)pO@tL{MmxF9uUvHrSDWIyZ~ z(vBz-NW$BerrP3N2Sv&8HMVYWroo7(kVz&u)Vxw zyS>1BPm;tq4eTH9dH>5T@88{$qUFt-Z@AcYTx>U7ZnwO+zT(BrE83>qbL+~0G1d(YkdJ!b-0r(DGN=lC3xD_v)y)Fzqsb=`jWcwB$=3!mLeMCq~tYmB*g(q6G+fu zCpnih3Ni^UIj*{bu-`F^j~dzFOK5Ng;CYcK#)A@y&a8}s zWENh~=MNz*rRAdL>`Ron?AZ~+zNnSB3GJ>SkM@U1;fQ&Y8Cdd9k- zGBT5TiOpb7J4{3QjfQlK&7huzLA1Qj!pMEPtsFdHvUe%Vt|F3+$#Oe`S#laq@$k;q zk!8Hk9^jSYl>|J7x~_S7b;ZleD>hB59wlK05e|bh4ue&8^q6vW1Z9~HV`S(j4*P*| z8da&Ui?V01lG$pLXf#!v2*arC`s2Vb4oqP}K#dMn&ZV~Ce4?tX=D^|rkCQ~4M#lbt zrOvf|6_^i)k;A^HA2cPQA0p!v0f%=Ljq7M#P1{ri7l>&jC1vO)X$|y??UwE3hB&`f z;{X6407*naRHm!xnvSkjqOTzY4nxo5?!e>Wz@Z_MhiOQyIJk~ULS7Dr6K=7Iv;Y4RF^RbMxdAJtu$VwzVr#8sySR*=E z3t3Q6`qwZ}=S(4WI#ynn_GDR>1!wV6osvJTw?z>@2A%5hwMW2smLaopor8q)C7f9R zfQXXJiR3IRvm*S-x``Tv;_REY8ITJru$h*S*a8nkwDh1F36mPJvu9bIiK?U+t95@P z7O@(cAW4+7%@xu?q6;6CpawkOAu+wt`J>weca{nT@N ze4W$pc|A4fj@5%^UHIt!Ik$E0+vRHOJm8|I&nwN54xZP%0&Zso+st#NqzBm9vs%mv zX}-ofJp2?Gu6l`ceW#4fPxl|?o}TPq`e$|N{81_*P{wLbU$EJjWGwUV)|g|NFk5)R zoI{>x+VNzYjX_zx&!ET@D@k7DW|hX2bcgZ|j)AyYgUS`yUWdb-5UI!^9Vl! zV9Ko*5-T}2IO)xnce1+D5%@g;z>+V1+D3nUb&UwrzGu7H@|VB-m4E!>UwHZDH(2j6 zcti~Mx1YG*_iR7h@o=|iKo>VjmaB^m-~RshyngeBwym+oFvfwq`&&Lu_Z$wYcss9U zcAPVd#V1)NljbnLvf0u{WimZKE{=d~>6HSEkGlMs6==4imCno~Mb^Fhx$WF>=h}O2 z-?8p_{Q0@-JZnVsvW2Aq0H^F z&sw$iO);=L?74fmr;j5^A`*K<0ulx-uXK1IOcS@a_w4rv`abacUC+(cYr1Ab<1Hq6 zVlWu-G^WG(DtizNG9`wHTK@;(@nIm0pGe^rYdzb|1DoywZ(5wGuv8fFRCp@uwfH#( z?<(qTL$|p^5Upk0Hu$Q>8cR%pe(c%r_uPKE<=xNk7!CukUcTY=n;WjLuBg1j8AI(o zhKjqpJ@4Ot`}S zQq`Wet?1r1JUrfli8yD7X=1;-XBtLg&|K5P0&X2t-q5z5rg2n_qiGwuuA$qsY_=U$ zV=+#Uqzt4nMW!$@Od~O9=@iN76NOkUW{_<$ytruj>do)?$KU_SKmPhpUSEAfqJm7S^kkeO_P-XqIKLiYP!c zr~v97;H`?G^IEE_s;n~8RvNOnB;%?9M2TiHQIv6+^dq7Lv_b}c zQFDOfLYOzRSC@7ly@%!1$SPW87L^vfHS^n-%oMKmKa+Z;^7tt-Z7r*ug}QNUHXWPI zC0CbMyngjHFK=E_S8C8m#RD0ShqC`g=2 zecP09-m%$kK%i|}Hk%ILR`|NYHD1du83*D~5+~*682SMtdyR|{uhBST#3q9`4pTXr z##7Y|+xCLZ=7LS5Tmmr!_WM1D!;WD%FovG0@?5^ya&>)0-PK@~cJ2YsaVcn+bg`yeb@w3>^nFD`2$A3uvDQ=rHB?M^UsG2G z>phiMZ@&?NJ?WE~tZVJ@PNho6uWyC9{oIQyK&%)$RT)$EV*5h|g__tDi*X z^<_O)kO%=)O1;xH(PqW5$gI)^;aDgi^{dHXH=T4rmMOzH@$u6~c85K_aS94-RMH%i z5XqXc7^W%k{{08WF|yzH{NbCxS6_aE-&|qEXt^NcsC`3S8+=_;`3Bhw<1{f2%4&M| z>46X?`h$j?w#_A*?vk#$pshMuzoGRV+jh&g+tT=k%Gc0Z+P2bKm(JmRg>jZBFieqQ z?0MYX^UM2R`0=N=eE9g0wspLG`H~keU(nSxB=ufA-0wK-Kk)J6Cw}!zN|s;KKZ^ z=Xh^u+ltM$qU|c0w#7RKR!i|zwWF#n*hrK~6#?bkCMFGO9LJF`jf4)dfv;f#5kzkumfTHUD!O6aC@9r;nfb@y8!|`}Qq&clXLgkhFA2`6sKfdb-dX zDdA{~vN12dQo!z#t2vKFQRI~*^FhiiJcK8y{$z!&+{=5oy1L}+ufODrFTUXF>LuIFmhJY2>#J+JZi};O z09M&$W;T5gOj18ZAxv}DAKeS}MtDxV5nkBoY}kRUqWBY@cv$#MlYzYJ4>@#DQwkl8{a`Y~7Xj zoWb^z!E{NEy=bWWkp#YZf(m4m~YEFIVd*47AAmz9zN zGET`|o&yTTXnoZ*=Rn69toR)E5mUm=R(oYYPua+4y?THXIYJ|2Ix#wD*NT486OYNk z zte%%8l_XKt-5gnEph&PL5f7UQ;$!Exazry4C6TMgHY$m*dj{ zWS8^Kry-PMWFEIC&j9#o9F%MVp+6k>?mxcc?c28+#)yEi80T;}LI@1~sEQPco0}W{ z+duw0|MqYH##di_o$Giek_fl=?{QYW23J=%e7t+hVgH!fVX9npm?Fgju^Qlc z9G9gb%32s5kKQ#${4X3bg<`D)*3V@?~jHfb0Z;uaPq4LAy6oR42` zM=RDd?J5GJD44k%>?{w@v{9m7Isk43I%Wff&F>@sT_(B9?JMD%DLj2YWJO2>hF;58 z*n{SrwYAMG)A@SN;&X^~42iqjJ0w9l^(Q{0~*sOFJ$)T;Xl$^@!#0r9y3@_%8+f=-HdE7=3 zc8>!;y?sw@{vUpM|48jG5pl%mNmC*Yk>SwuaC^tQcR%y~mvFZR?ns3vFJotjNr`DyaZqB}fZl88^?V8-=Gp@^M!e72kgQJO22GKXb9Y!26b_ zuBlv$B;oGcEk&TkD&TxHo&7c4L7yirN|Hjwfe9gt? z8edgPSmiv{wSXZ-?R8an9i@PVF&=9ZeqK97OClMEw+&OO2q|c-(lliT?Svs5S)}KP z2BYn|q5vnS%LJR4Br>ORM6!WhFeT@mqWq<7Y|t9P&O0j8&;+d)J>_%(V*-*4 zVF---kt8Fovg&YkV0<=FWcGU_iIfZ>O^8@RG{8t=KyVoQfO8er)VN%exv~|FYpAOV z@3ii^cb>}Ecwgmw?g9u_LMzLTQr6|yw>$_894+w0fRsvcGiHTQso2bt-*+N2moh`z zGP}gBW=~)aQO>(hGkZ-A6+YeP^L3oj{w=`POE#QIn$L?#^K|w4A(yjCYS<_dHcu3# z^V!O$1_coS1bJh=wr@MgQ`I1F9($mZFskBbO6wrR6FwA3Ny&j5P zId06EcP2;Uy#UDa9E(vRx8qDMyhcD-4ZAlBiKI29-_Cg6SKwDm2I}8y;9DXcp>k2W9^Yc5WQQ~l#}NbUId64@mS!C3*w z^LLdc&ppBnq-Q|2`VH{={Z7NMMh$Pg{rHJ~7#SzEq*j&F9Jg*mT{l35v60K|mT&*? zNB;F+|CK-g`EPW-QO{3X<15eA^#$9DOWu6-il2UZ%fJ7R#1Ds&ao8>1iwu@x&P$wu z8F?UZ42TP{Q`S+Bo@XsXi`U@Sw$;0x6_D9*Rqk2V6tnub-t3uu<@ob5{0RKo_4#F@ z7R^;w$Ny)x^|P-+3(t1RGS-$|C5+NB8y$>YEfl%U&Oue9o>!+f;22>V6O$E85H)V3 zm5s(MeOkb>35nnYmkeI4TFbJcVF7C*)0o)pcD(=ao{zVm`0~rZ#fuA?=28`!7!icZ z)+7)1!842_`~87o?1|%mgrEzzSQ=Y#-Cgp{o3Hrt^;cYWH+0p8y6UKXgUKw{7(*0g zn|}Y{1MlAd%!f}O+4p;6b8oez&IYjMv@uWAMOcpVj2cw2$|3&WDCB&kh(UA zad{lrnbDUh>e=Zk($w?t@gsY?196b+{>GqTllS*`{P_J3eD~dd@a~tl^rM!7Qfo&* zE$u?p8oI9L@?y)?}6HApbiJYf^$dXq?VK~f!-@sWY6Z`#+anyRW-Z@q3t%kdP@x_;X{q@&uHy!F>%1A9(THmsN zeB|Nwo_?rR5wi(Nfn;+|R+fu%K3Ey_l{Pbpa> zWkLs|b8bqLdQGf`SUGXv3?bzOC<fBpv-+Y2h+;+)5uiWG&1hey7A^ECb=S=K306HQDQwIR?Zj8#l}(SZ20{s>0#&u{sO|Ow8lXU{k`!K#)Kb zM-naXmNFqwN}1p(hd&#XNxrTdy0+20SYKgngYz}M+2UM93Job4ti7P}7g%bhKGDY= zhMu|!G~I@#vQ$($*cW($aR$Rrm}l zjZ?3$SuM%}q^umqmfle|W#A%J^Wbi1^ZCpoFD+qShQTdv-?bx&(-fJnVwHIjKOjhHH9QrNw7%57s z%yT%BnW2T*tFaDkmKBqbF$#(o3s^~q(7r4R{z9l^NGA&J%v=jInblfp_o$5Uc`^55 z7DE{t_8BGWyaN_xC>11gxYyep33No>QWF1DmS-hQH|4tbOIWgq zV3U$yX@9D!ZA5Ttzsbg!W6-$pGL-&aYRc+$^|(?Z@}$uVD4apx@iFT$auim2q{OQX znvJ-UjT=^tbz1ph$;~aGbq3+9%N*&2Ggw?m+SZ#bz&p3UjKH}n0|wGlfcIq6PFO(v z>i%+i;2iEwzGvx={5e-MSjK@dhIrEd8j`+*CB|$dDZM=(d+xohwt4>KV@eKiA+A#* zNIUaq=>80VVV<*3nABzQ?pkX!wPrmv=H{iNejv}qQYLB1?Ug6@c@pmYzp)jgkF3AT zV!$k=HH#5uZL~V|_CD9o1-LG)ERhWJm6+MWS7s$SGni#P*jL93;D=#gnkL3!Vi+gJ zJ~9q^p}IC~Izv}Gn#xmGo+*H@EH@W7{PnMYscGUrOg41#Cxkt{U&^JA|RQl*UMJh7Ge{0luJhmQX?$Hz+fEI|0l1)1yS z7La~)?Xzfeb-FyowFQWa@Dx1DuY6yRmGxFkWoLlyljGMyF)N?Ruvmvp2ESRBIuA_) zUFWH5W%Ug~82XWMj7(!>oRp2UJWezPsL0&Blr%KX`-t(Vf?>5hg~K3T@GcRf@UXk* zhqpg){qjq;FRr<2D#jE!36~=0qal&Y+pcEJm6SsGF{P6Zie*F16?jJrf#skJATqe+{e4=t{ z(U6olJoJ>gRXk-X9QEa=6cubZ&9AJz$NLg&XKCsU&RK?jU{~$%E@Dj$#v`TtN(Oz? zG;uiW*&lX{)1JhnxserA71WibX+4{+rtLgf&3&6;~-!qN_VhqkXnr_3_ z-~5gjuU_N4qiHKdgpVI@`TmFR`S|f;u0>fX2~pE=vALvcZg6y%RA)A4nU%}hRdjVr zTQ}6c(S?2vfldqC`)WGR@+gNx&!9dl9Hj(W zB#)$+h*q$!c=wWmWzoFMX`GlwS&Swn4BKQmxRPUKO(^+)jfXG3xZz*^@n89`|ME}1 z{_0z*s>T`xBi2+%6fQ4EE-r5P`m1j>?cw$#KmYtQ5BK+oBy8nKDYBn-)J?-*{_;ou z`scrKbMr#U?DG8$K3mfr&S=>bV^hxG1ue^^zaNDo6Yz{eD2kKn_xbYO)vBwi=y~!J!LA z@&2f#i&B^{l395T7_0ITtH5H23V?Uh4slR-EmhNCE2m|Wd_`5jZ?+OA5vCXzV_+Hr z{h?=nIMDY!hr@wgHV*9`?vOOl)`HI-O7AQ!j>cCw*I<IL0LOQQw1gMpF=6 z12|Gt!U`KJHN+YaiNvT%bIE^nSw0w3VXPyT=m5?D8_L37j#$mhlZ8JO*(8z`VaZB< znkTvD=pWywuouG$xU%RPY2|g(sa=((#i>xl} z(#LsW%8b4Wi9D@ie4?B@^)yM&_t#ZwNp(C?jFQLvn+ZF zES|#S&|pf)!%8(+d&`+UJ9Dd!FoAh8CX0Shcs$hTXK+^a0dHjnzQ(T3o*R(g*b}TE z*+`m>+AtgVSI>3ShqLM;xpn6~a5KyHDJIGx^y@URvTyBqMdTQa=5$tVxAHkH-r=X9 zcL{SQ8`l@Z!~6)R&$WCU0qRAgJ0~MJxp(OR)d&In@}pWtymR=C!F$7I+i-okq3c?V ztpQ!wo4VrFn^*kq_uug5)hjNy7bs(?rLJp?wKQ>}u6hn;PY5vdk!h4UN3h8I0(@6x zt&YlDtQA>Jh+oj}?72lJLt35tIsCaY6s<14n(u3=Q}RDffn)wxLV?#?k~8;TOPjLj z#AV<7EM=`YIsWK6>wmvxJM*l+^*l)`e~y6m3h0!bCg+fvELg2iI3KVX2v0FDipJ*i z(vfMkL<9i2rmm-QHiw*95SN?a>H8fYKK;ba$18?(pdTk5_B~UG7?XJ1J@Uib|KRrS z199x>wp(7me8HEmUURj1fj2dczvAW17reZAOoIN~RdoVGC0}qdP9QqziqU~yIlRe%} zORRXC$!;uATiWX_7Z*2FuGKP7;*gk_#t|W~*><#TMblWVscBG>tJ=^shPL+9bwyQM zj7x+x=6b!Er8OwLwccoMnG?i;M_u#+qHeS%b=zuf z=s3drpFid26O0Izt7x2O3?pF-nuq9We13n3)$rjQP_RzZIsJSx_p|aWPMKY;S<3sA z5bZ^_3dv{$fRY;pl2u?QCG=S|XFFPQJx>icb}92b1Yrt^G%b0*Gx#-&{4aUT0Nc)T zxxJw4TCO%*{`9AB`RBjoLZ#4|}XNyn6M5m#<#peWm4kGMSahz_WNtb(}9@XBL-BUX?sh zSi=fsjnCsSN1Tuh5)3h9vaD2UZ#xVXl>=Al`dQbtG8yB5ipp-HdIbYwp5De zh>sAmV$)2bR~S>zWw#WZWe>2^g}If)CIrSf5{UZlEF`Ou7b&G2 zwbSc!WKTLtkSN3{C=u4s(~mvFup^8+tVvvKx72RKwzX<3sw%3=QP;|IV13Sq79ohx zr-%s?Ax+>czH8~W7x;FAwH1iRh=t%tlOU677PgeKGMX2ka(alH^8gEwJ6*UJ<#9Gx z8Ka>51eDIl%c4liQtL+N@66fYvBnTnLQLpwH=D0p`k^OcC+~o6% zcTk@xW$<-O5x*ckYb;4L8l#Za8PI5((|2>`eU&v!atSS)!CJX~$;%bafZersF0X3^ zh_2VUd^bwtBm;M|TH?y}6iggZw9RLy0+h^Cz%#FX6e9yVRtvDs%K16aQJ%HDAd%(S zlBkFM=*fSR9=qzB0wzz+vuDEf_5QlAj6^rLYuRs%M(nTxe@Dh2YgS{t0A8cyX*q(= zTdVTWB~1;mIg-j0y(!Jtd%oY8jXFn9e==4+&tk1(qY&dQ*D4{@3!L!a#a>&`4`Tn1RGD8{J+1ch@)x|n9A|t}x z0ob*Fs2KqF%xdnqNMvOA0S63bYWh^4KFzt-!xfsXY2%fXI?A~&y4HH7^BsNH(RDk# z?+{eU)R@Ba(>>#S=J|N$-TMcQrxSCWIiF8FKHf7;X9nM~+xNVE^M*hFvp?gLS6|@G zfGK;t-Q!G0NiAzt2q~!GOVXOfujZz3!pVqDYYJ?i4Za=2W%8FUKK{A;7dlF zc30HCv9bUrX91U0w8W^2b*zd;jd|SWy{TBfG`hbjw3a>@tt-wrO!kyyAlI791}m0G zXRBeYkainUZ#4UAyqmM3AD4@@RO&HJF&}J1>O@s#=BrI+o@X8&-t*H>KXWrqgq&0W z4MFn0T*nxU(e^8*c)@Rf_c>qw z<}2=A+;Mw&$!DMahA%$!t5zsLJM&JRc#)Xs9CWP|r3VjTNnR0pNkAoOWE6UQUx z5E~6qnTN!EN z#VXummboBR(?PJt(e)j!4CI`NB{HYLJdccFVjd^X=QHy(BSz?bk26kBHkGPtprVH7 z=|l);N|`tuJp0{SZf*vK-r_rtu})QetzaogPNZojk0UXJnpK_&DNu~9wzu|*H9f`- z)u%BeDP&`j0?s;|by(BZjK@07V7K+8wkNOtG9OZSMW}$VEI!P(*--;c&EZ_=$hG~E z7_Arg&Z!d~B1tEvW@JmsoiXTNZFi+5tI_V$pGux%~)wbccnNN z+T71;Uu2OQT&m|%vlXdk0a|#wo#6`PFP;C(j80bCZ$aAvQa;oZ$hoRH*YiRB(_G&v zbyK0=kj)x%Rb7%J)x!-z^wh|Gs#=y=QwuADsX7L09Lr z-GdMIZzCVcs9v5!ssP>;uIAH+Znm%ryR}QVQt8c=ec_D38iO^Z+P=yRl2qG7*L}BX zlW++tH>7UWP`NsZm1->?Jol#_*YDY8$gjtQ>*pG9+`Qg=fh_=TcXEzKus|MU#s{$ZS?{)~0G>)|R ziLvSc_x%p!ke#oHD({3kjtgi z_nWf*e|1Pc{Ek1dRxi$Du?KSXysQTAB16pj-PPy07;{@iuGCMKT8CCCa=9$ovX&M3 z=*3%-T1y7pUJZ1O_A$z>+xjB}Mfh*Me_hElXSfh4q5 z%SBO*9xI_V=oB>zV=9|qSL>_}`&))#hqWEnXsy`zbRs-F@$mkEpWpq$ZH2M%|4^llGvr!7OWsq?aKpBWZG4dd7kd#o|MynR8Df~C~Vv^oLK zIC|&leWw7T^5RR;O+IF&8c#X!G(OXR`;Ywi(>>%LNjVcjW)6`o1(U%@tP9_8oJO9; zGvEFAJ-r{WI7n8V=%Dq*$LA*=9_~4f?=ddY^#<#`W~ZItykHzu;*id{ShSuus`7M9 zsX8J;N`{=YkElsXWlX38V2aUzfp-`Z$rLR$P7vbE6lOr{zP3vD%X-}aH0>E2bzPQ- zA!}EiY>?urbH*igs2)T=uj#_;DC2cxYmK&U=*-PhUfEyS{ws|lCQIGZG|&9-!w+CA z{ccCLqO{F^pzAz{A;!Qw&oz)!h#^5SynX!%uU@?2=H`~Z->Gt|SaQxhNXPqkkDQ)I z=4r%`HTdH+8!@MmDa^!>6htK*CsQoB5!E;LZyAxspla(iFEDOd&uvq0&O}}!!4=@< ztTn!+P?%9-R&6=6!Fnw?w)jW&`0aaPW8d2Mnw1S?4BXvzeEH?4{Pkb_C;s}c|BBCk z^CkQJf!-h3?*@$TRoOf=M_Ouat{x;;FHg@)OB0;;m;&CrrPfreCFMjenQ;n4QD=Gy z&{o5?ZMUG*^SaT}>I-Y8NEEQt2x94q&nqVI<5fJ z6s?D|wJlUmi7`w(ot}CB^uY7^N!8_JAg6@$j@{7XtRc;TJkO*UnWmBR_{=z;NGTwa z>3c^f2a0p#PMB>ZOVDwjGbIL?0%<%`&Swoul9)?kk_6V0UQDA{)r$CAsBHQkTJMlL`pY38sYvf5Ti zmF8Q#x^9>J`vzKSuQY9m;ZXH8Z@ZJDWy{P9G%W zwqtC{WfpTeS6SN>{V9N}=kqIC0)@@JUVWkbD{~XL%>Kd$^SG^_<@vVfx9=(C3jEet z)8<}T*#-?a=;toKV~Ydz_lM`aK6N!$%k|T;&abQY(;{32+&oT5E?BA2466!+B#cpa2DsTz3>0<@zKE3azIvZ@gtwv-mew~_YS-_ z^u4g#^(sD;GvhcjO*7M62y;E@_Ot!2mhCQ9{ zv3NCf!BXZz2?2X5?6N1(Lk>ue;0;6P8HNt)4S~dQKJj=yvg-_;c$}$DoKfmpDTYq0 z)&tfo(o)}Hs?n^n$F1+7L;GwtwaqonshQlA3$bJdGT!fbxOw8He?{+ZDZyZnn$4?` zYE%#>#mqcM=J`8P$dFZ)Sc=7Dv$;>|NM&Y>O;``E*9@?BP01itWT#~9gISpz4aA64 z=hQVSwo^rSRO}{GDA{5KjI%fc*=CYWHPfwO%ak&ywykIYr_Jfy=9`{w9h zxT5K!k8K8JGv7*!z+4&Qt>M!R_7W5$W-%5`K~iWN3v0He{aqtqF(iKZ`5lkPlLr2b zsyM5FPjzSjV=cSgju&@#yngkXPu~89w{JdSzrR(LXXCUTlIsu(y>XnLp2;B)<{8Ks zW9YpC>WAkCPUn#@x0-Eq9*D(>kcj+8k0oe#wdv$ikgGbMRpg@1#aw&clBfdyOXsnkf%M7wqs zT&|J%TELi-sT*k(H)&3I)>^D+a}7FaE3YYO(5{%~$Y`rGD~>I7tOa9Q4Vv!Y>pE{2 zuV7dso+7ej!H5NkAW1OEU~u}$*1krv+7Jw;tXy{ES|+lm6h}^uoGe9Dq$#DsJVnN7 zVw`7Arz20#PrN_9=RBXuHqrH-ZntNDxM4VS_`b*c9p3j?(__RTB@?DdP7xvFouP9( z{C-F89G&0cy~o%NjK!J`BTmKfN~uAZ>U0ZK)VI`jr&N#(5{hQzqN=8!rV|g3_q@CR zh2wanNUoXVjKsp}Tqr3J#xrrANGXtGAf%a?XLVf3$Rs?@9lxA+^n(XumVU3L6iiC^ zoUk#`rKH*ZD$vzC!FD~SGgu4Qgq4V)AY_bnbbi3$bw9VzxkBfu)c9BfastxqfL2~s zY5^1#DAJtkM!~&du<8^87;4>o)__XMfjH01vnra0Fp^?K40!Ju_B}&C(0i{XG}a;B zU}|Pn>KbUmb}hKusL7@nuI2CwfL)bn^?g(jQJwVGhG|jUPnCxKryZ5DG0fY{=&xlA z^>82R#J77Z`AQt8=mygOLJR7}RND;ZxsGcc2V0XmP8kE%3c_aN`ju;F0UzznTyN*b zA(e|CS?gvicu}x)VKHfa*BeMvpGuip?Rrzu;G=GP+kLSDj0M2A=h@KFt3|5;-L`Fh zl+I1tW6LHeQZ}Qa|7(8sB`x(M;BI@|t9^*&eANz@O_q5*+WMgdOtx>UQHwQ0$l|-M z-+!q%Ev@#Z{moYQLf56;+!NKK(Y?hrz)LOlX#pqEdZbo&ucolj$n%Car}IZC%*(a? z{{X)NU@k{p{qwTXq0U zwYNkMt5dT0B5W4HuiL9%8Kgfwh&sXGgLU0Dt>)mj=bIPZ>R62`B<}~yem`)y>A1N$ zV7()Rz~keQg4SS$<)k*hKL%DWF5v39a`nFL@5RI4y#M;zDll0l=#`_|3|$-MQYxLX zu+;D71kPu27m!M=^xk9bz;5tLzss`L9*JPA!y4@ec-ZfF`{p$-U)*U+B=7Ln;jE>1 z1KxQo9bhn7YqWC8k*$O#Jfx9WfYsw`Y(S4DNuJ zL1|^lkfYX6Iq&gZk2s5QPL)_&pQq%JoUwp4g3sz?l$dm*%9=@Pbv~&;%8e@M8M+%@ z-hRR-ufHIckzo(kM?xAI=Obg72yrINfpHue&m(b4NLE2GD@wm>o20R=Piw9Vs7Ar- z{mp1pz7^=^1Tp0bWOO5NVi03-)@U0R>s0KfbXAeqR9bMYeKZQX<~R}4L<)&isg(=8 z)oj*Bty67NjLjNv(ZsE>(haWC&OYEXNo7kkDo&ffvK(x6$_g!Gyj>8o_J3H7i%!TI z>8(`8wjr9;*%`-)<2aEh#1QU}yng+b&p-Q|-+uKKUw-)&pMLrohrTJ;3>U!FG6)x!vCM%5k8Fov zv;NvRDHu-GT&&M;?@z1MT{IiY3UUjTR=eJY3v(>hmTZ4F8{GH8Z$5p?pMU*(e*0%% z^WxPTiglbq#N@K5$)-APwzS&c`garWSR6=YGufuiS|H~{3^UKiBai1J(=;*Vpw5ZY za*N&WK-c$pv(|T6W2?{+NUk8Jw9L&q&`pIj<%GCKJQV`8e`)dgAHniKpWOr}0QGBYp3<+k5u= zj&A4i4hRz^Ow61(XQ332a|6zHYOjh0XZo(E_gaJAS%-H$&U!GOT(pikgh+^KDUDDO zhG+=0`GIjhqP>zcg_)cuQksb23^`&XV@$#L zg6j)TvZ`p8M96{Xn0P)4W~y@osLwDr>J%>l6n?eZ#610XT# z=9*I`rAUYhg2OZsV?Zb*r{h#oMEX76d$1Z{$V;ZNQChXOziigNG*QMj533nfzpHF| zm^S@|vILvdK4e-iaIN9rILaG?)btQc^$(jt*n)sujll=NVB=_CJl*z-PXz0^@Oi=9=! zS;g%TWlDz7)bQiNw$T8zD5bqqT6+_~6ARYb#m~wqQbbEqa!!jd<;q^U9IssM_VU~^ zycJ}(Yx%%=-Y7J0fbYegyUeW$zgJ9E&qeAt=TU@cZs%6>V^z{qs`NgTq zvY%c*F6K<#CmXCKx#dbks;^ZR73Kxdw3^?A7P?ag)pS{FdAC4z z!Bm@Nxt(7hr88eWCs$*#O@eG+zxG`|_S~;AGIWp9#-soiyPfuEhIUgwmkVqj?So<-;T611XWxX_&&<$U_ zO`SI3^agHH+*|Ow{r|_V{a0SQz_}aX*L;!EoHtt?`>lfys|0wR1Y)4?4L3JCZf*`7 zZaluTs=OP=N|mgtsA>KD^+{d%tgC^!e&J&m(|%vGC4PlHaecf3x}wZ_E_JQzYlYg& zan0!Yig2vWI0yUPfj4j8ayz_)q9D*3hcOP8ZC{PZZWws+>XyS{U+Ix~F;d=o_Pag% z;RbI#PCBfp7G=(vb3F6@>4E*bJNysd^21{ynSgZ$=M1R?o{sOCjseLI7YA(aFr~v3 zi$Sv*)_VG3PruWeV_fZ{>9oGxi!gK@JMZbdtCX`P(67=<(kM=KQ_LFq$2eZUe9P~@ z{!4D|_GD)Iz7XP(Umkws-+%a)(`jO!0x_tQXi8Rr90#4XcCzRcqx8 z6kCl}t~ApI4ylp23KpuMl^AV%q|T$LkWY4C{6a~VTA!R#ApH7>`aa%twPhR zexm~wD5ho^i{kTKG^1eaZ9B0mRqPPhW&HUz4C`mupm6}0MYRGIgx=nw;h{HJrZv{vp zGEEbw`OM?fBM-+Xb%sT=fTgzjD;1fS%6>9p@Xq0__GPx!agmbOph6vooOG=zMLQ7Z zNQqgq&z0?B>bex!(9jWTCs#@_wS`w3z7Fqq4BY|idQ!H8xez5FWTq+c{CMQu`*+;m z-*X(_gB0#=9k1?gc=ckS?;RLNOp)_65<+AOg*hY&9bLb}`5nf3#Ax8p3OFZ3QE{=5 zXPhZZ3poV`8JfzeQP5eW24@6a*rIezZv-o9GoqcqOdvCbXEM)-IRek5d?Lk>Tt+e@ zrOb$lbX}qE1nUKBsUmHKSZZ(fI5VXx)Fn-=+hVbJaTtW0g;43ls&sDY#A9>DL?~k> z$Viqmm=19PGZZo%(>yUvLKq|AtnHUdklMaV=d-bvt{>RlYN?K?y}q4jR(9~6wo$TP z=U5fjuwt~`lURiW*{W7X(iU~8D!yBU-gkH-JN$?xwOKS{8l<+KmNk zYOuyou*R%ZXIj8H(ms6KepNFk1<5H=hMnQ{uBVd zI5t%U+B!?;Y72~t>T;`v6s2srTJxgFIWdh-%+nKd)EYu#I-K`drxf2bPk0G*wvbIG zNnAF^ZHCC!Gbx!>A-dI!Z|_##xU}2r+B#pG*RFy;|MBC>IcptTFjdgQ*E(KTUvuk6 zOHt51&uBKcD6LPGcOAxPjpQ5?r}LTTjJBd0xiQ&xw0ngS7ZoMKU`WM?hAzGvTidZ*b1S3qLI zl!CEdGbX;rIjfFD%WDFL951FqnoC#D}y&q9V;@ato`J)HV81XZPvjOwU#Qtm9!)R(R$omI>_4A zD27Ow0_XFQp1KVeDeA&zyJF8 z{FndwU-LENg;t$?v*r`Cw92ukh0 z2EboW)0;WVtPUM(Wtc!K- zNF5jj3WB2U%5JEEAjuZVjvOJ!z#Ou+O-g~1g>ei#Jso*`y65=(NX!#muVQ?fMN;P} z#K0W1^-)TB6-1K)DG|y@VWb#?OC3cbrU#6{Sa8Nrtj;+nN)xr7DmGSuPbsy>aX|Z! zE0}0Cra31{o{*xowlR-{_@0>Vp}a@RkrbZ@`I%fskQwJPeJ2cqrRxOiWYN-qf-M=F zk}`6N_C8IyAW7TZNJjgNXI1nkscmr9AhuA9B@sA{nJGRKVo@fFw#3Ui}UUuR~tuR#6G21H3!|88{BjMnll0zD#^&TDDliMQUA<{;5yH++i7{4b1Z7ntNB{?f#v?7LP~ARDY8<` zTl+4pSIx}xT!WoQ9v>fhcYn|O$4AcRGdX9R7rfW|>YUY&ZF&IQEa38x~t_?t?i<10Js8NYcz;rbFRQxYJERd z6i(`X&}!IKKcy_dB~@X$dVUM=T>-F&22@fhDkPUbp8aeLgG**aD_y$=iw$^R+?g6g z+5pD-<~CM;DqFg(4_?bBHlJDWR?)H(YKD9BxtuTO;o^mrO#-t4{VRWB3w}Rjfvnf1 z-?OgTvN^By{pExC-cJmd#a#V>N&=1hNU_oEWFf`Ba$B%BrHMQ&`1hS9*o+ zIZHsG^-SK{nC1juTuTG7&2C(ks$D;}q7)ZHa`l;ZE)4`j-V69;ag)vNsL~M-AVdUNYJD!j4 z5y@C@c>VSz{Y#;^%;De=lQ|xr7{>``ptC*wAnaVnVgG`|?vBCT;q4Bw17Jzfl9FLg znbSBkhMABR;m^}Vo=1)pY{=v(LP*$LFs`HP2fXia&esjg5_4jXGjkZ3!^jwpjPsEY zj!fed?|y#Z{lgQ-^-rWsNq#=<;i&f~=M^ThMh$UH?3 z`#mpTyyS4W!FeI4#Qoy~fB1j@iNE{1|G^*r@Q*w_KWVVAOZBod*y(IATz#MXP8 zRl!`Hv~`n_<|H=O1ubi{4I=1g+8EdtH7}r<2bA)k3rSE=%4(+@@D*y{P*wn3T2Qex z$|Q81;q{xheD=i`y#3@;y!RAS)pxB2(AGgIVP?&+x>%i28i;7ERE*LB>-C3e=JDx? zpK1%UWC}MoHymExu;1@-Lyzw~(rbx>DsxxW;bIoyoK#{BD%5$Cu54xX7MsbGBAYox zizY7W;(woghZIFI=97963lbvd>)ynNdrn&Ss&y1%;TdF zvd4QNBuFXK>gsdRD1=Z{?U|97wN;yoo+2~i0-=mx9EJ{SI|ei3P1m%mSybASw#Q0w zB*uvpXL63j638Wy$;;~@OvE@6)5IK)jNz!|QTYU%pq!vg7?V`TptD%V0)EBhrOvoW z0nrvjrD$MKw5JJ*!83?e-2&fXjK`S{>x8be_|8!Tra5qm+NlC8CI@WF%=1LbM^Y3> zJ*HSX=`pt{?ObR2@l$okLdn+p$`<~Nz&wh8qZW!oXSA&IKRi$l*H7bl} zjKgFVLzCK4OxaWFR4bSb#1yN5n!_7iD@{m61IKFba?)-DF>2-x4Oo>XiGvTrP_l!=G&UD&0{XA8$iuMx3xr3K%p8TR+W}Zq14{uraHs2 zI2sCiOw(JaYdu#A^WtcC+J`y1mX)sVXo>5QqFY{5IHZ47&l^H$sF6k(t;Z>w{dx1+7JzJh$->&7wmyXG&#xK2?fEPW==|ZiuolX5YkLV@ z)KwJ^OHPGp3QQ7+aVEwHMbVp16hrnpm3!|svSt(B=L!ggj8jEZ%2GR;vN}^aD}^j2 z&7`he^Nq8xr9^LjxEjap<5qEW%|Cu4GA&Y>ryOOuaTogWJ818 z%b>S&P6@_IYfjqf=L|8`UYL=k=2nbSTwMjh%|Xn$(!HGEi!4(7ZIa|lmCA)xSm0N{ z@0Mv%;Hq9@gDEy+-iB!#NZbTwm*bYr7)ntPtU!3?kKg{pKmEfuyuA60;m=-jxV@wA zhC1I0B`PPjRGMyzN^1)#l5!-bP(@Z^t=-W83_zS_o}M3gczQ>QC-(cE{f+0wz2t=% z$dWKFGR|-z`^R56&FAVk z>bhuw1$9!Yv9;F9@!+uaIR~6_HlWTo$CRC~BQk9e2JSjz~)7qc8MnSE? zSWnjt_-;qezRp?g9XgE@<9TA5W>Qr3+J3O~y~q11erC&(9fG0(rBuLFU{>o`8)(Y) zgv>I*&2rt#8b#@$3fQ(A;l{YNVA|$WP>F1XC3?J2npr_`ix{uRWsPQ*vW%UsadrK- z3e`E~rSCI!ZO$PO=8R-d&Jco8XSx_VH(+*_{cex3z0#t`iR1H;fBBbx<-h-rzvqAd z??3SV{R74-6)WYenc7m8K!CAU70I1NY^vv%muuIzX&t;|yEs7&0=F^H|7^FECS;~r zz;?~Km};|&2JIpkyD@-Ee4Cdv)WW+4PqSPTn)r3SjeTUJyj(w znVMV*bJ3u7tX@Q_>d=xkyXM6%SuGXfi;L~C#(rRnmA37cOwc?jODojRMWX@Gxt>?9 zp0h4#!PU&IOF${LPpehHX)V?%dr9>^oMt3IfiEiJnW=JIVn|lUCD|Hy%}{bC&OzB@ z&u7l3Gvm`U(|IJ$>I)iU==&b;Z4Iu4>Wt|;&XU!~86$HXF}}l39ljrN(+N4cT58x~ zeTVfu-LPZmcgi@cVvO3WS{DDW_GqE8PnMQ?TM$&1)urRt?0I!KFIZ5U%~|Sk*92Cn zfR@eU3J7n0+BudA)ECQ`XD6cwDy$k_~IX8V%rBYjLJ#bn6PRt<FK zI_P)8?QO^5&ape}a6=-d!1L*u^B6R9n;>Q?aIb#{r9ih}e~gvtxw%IT)NXVemV2cR z(0UCiL*H3mytw0VbAzvaT(f8tCZ)vj`I&d`9yy-^o4|+~s5OXLBPv{g-{ll!eNTIC z@rP-S8XIeMHSy%~{YxBJU<&YW-~32Sf5+35d6)x#@mH2NpM1*Rd&KF+Y-N!E(VDqj zklKq<(oCsaPbLwwW*16IjOR0U7W%!1vSYXF*zFC*0V!~vCeC4G3THx?NhRY<0h>uS zaL&)fW8vxah~u8l4)onChVBk8FEC}m7~K$e#v>T)&?qn(SHHFf~jYKI?15P>DdZ$8>3UsW~x#m4$HApeffoYz!y-!jKTi17Z zudSAboyBzqF^NL1k!_s>EdyvV)d|swwA4~9>$bJCsgq7xJ<~cN*Np9Ub#Eg-mzMH6 zI=#;CtBrCy={KKUt5`Nbo6TgG^}R7hrgxl&7#@BJO%C_-t)tc zKX5u78PAVAK0fkq|Mo5a_z(Zclh9(-8HjX< zj}M%u6XGn#lOg?*IiJt$rxP(pZY>P`P|IDk6v(@(wqC$ifGU+%Xi!H=vr#LkHKjVi zW@bc~OQe)UG8U28u=O%VZPY+1uMHD7hf~DS`5q@b_PyZjj{W|I-EfPu9Vx>&%{16Kr-^Brh#@jhGou^v zuBRV*cKbrHHLH)1#gdKCS?vcc*;1otl%zJlqd@Le+_0W|j-^tZ+eWWJNY^RVS+j;_ z$;hf>q8Yro1TH`Whg0)gnrviUX~{3UqHuIZ>j)=7gaJUmB3zs8ct< zV#?Y!%9Pd4>))#*9YO$9`11Mq%=7az<2(^U;5dyOPbZ$nk&u*(X~iI&)$Rt;^a8l} z9#fe#opn1maN&t_Anp#1?!w_T|8Ppa#LHjnhN}E9gNB&s(`iNYT#R%0%6J#V{32wBxs9rIZ#SyOznlXq}`3M@v#%o>N|NO8utooZK??)@xkfqt{s0d2)3P z?XQL*b4wrquImfdL{fH2w~~h~=4B zH?|nZ`q`H0)5E6>xrts?Ah~EyRbaLBk-NHy3y9qyw+lbceE6AdV&vla3Yv|Deh}_n z4ZL`@XLlHoE;EiN&f&!TEIb_x(^RR>>GD_&*qRDF7vK(yTHoe=EH5lVQb|F0d%S%0 zg1`NnzvZj1zG6S@Fm;2CDKm{T-~Ic)^S}O||H*gX{7jzf;8_K~y4WwrrDCaz39=}~ z)^XX6VZ$ERL$(A0&3d2O1U6~@8irPnZGoV-@N*iq2JLNhcmVs zT6OBx-Y9^G&5#&$^S0V+F^3skq~96D?4YPn8;Wqn(}x1S>!8=4 zeze7V`JoH2Tz{vO7RBx`YprG5TXYlCg(9`)uQ);E%=?EYzWw$ae)!=#9viBHfA7>gs@E zvI=Ff0_06xj7H_s_F>f+p>{WfjCUO`U%uqC&%fZ+tJmD#z2W7{m%M)a8E;;{q2J#? zDTJii5wg)tRn6Yyq&GR$KD#qIf8Rad^T%)h$PYjN%;|j6+WDNZb+0lh(C<9E!wviW z0kNHCk>-hUJkyP53=l0aH}K#aRkf#{g8P zpz9FpIG;yO=l4vf6FHBFWMV4JQy|O<=RCXH11~zqt}{r9-w5P6Qbsk&miIOQrDQG2Ie5bV;xdcWGdtRt*Oe z6}0ua)#FE{^2Sgp(VBtLjIlb@#%8Fk?G`#w<(;a}lPT6CR#XH{R-FXB5?9+FWn2}F zDz)dcLD>-^`NBdLG^k)o(GnnA=X&iEY|{E}shMaEjzw}x8vGW)V;A9}ZI&`;n5JoU z_#>R3M}B#D$4@{1#Jl%T%ps5(-PCHZ$yDGgIai^?TFfFv1<|_d8+4jQ&2|4sRrIB} z4(mLnDmvrzd8y~0nyPe4TKAj^QVKTf?zQ+hC~(O+>h*cScMj|7e66KlR5n92hS{hR zbt;+I0-UBptfx4KaUScG3T?f^cO9;lV7b~O+*yYex3u&zVr!d3gbBSuJ>zr>wTDgi`#kyXpdug*VE!VvTXCh|l7SO<@Y6O%@ zt=97}HPdzhfV1)>mZYDl$IUeuWg8=6{mk9z@c zEa%w1yZN-LRnbZiVl6vb{kj!cUu2W><{UOwV;$EPq^Tf&!F6pO$>JxLx|g+o6qA(Y zIC`Gzh_%4Z7W{|^F2zJFs%)rrAf_6^c7Z~QiFuw0aVExQ$ZOQfrYh)QtHEo|X3{#K z90@rPVFbqa?(IRD9jUtNewR>hr7)YvjK%$0KYx4whvu@UJOcSw1Rbp7k9V(=CjZE%fI?7 zUcY>UHI^6^P)$?d#oZfD&qp5Kop_v{DXBDHfAMSE`Lwaq+T^+cUY*lc)f(z&ntj~N zom!G~fdekS&#Lq11Y#Ca%>4Y*5B%T%^Y4i%@^JqPUwrZfxBFWL*DFO$I=uDtro)LP zr>KrYoV9k^%mlQST8|$QlJ;31SR&;bNXSYt4~UtGlpSsoL7;HloBDRfJPQeOod!#y-!t-47r;G~K= zi1>Pc)KLl{F@?-Lr>Y#5ke+TDxGhQr}w_n#AQ*~mZBNYIRrw` z{+z8ryfIowibz#AUE3vH3)q#qQLJF20?1`PDs@xe@)1D1{71K_Uo{R_j|RY7AZR&u zJCAzwrevz~T!T>*w6AOloK7ds=QCkeMust3k5!T`Zfh*!41&^j?;qathd=xS-+uEi z9FNbWthL{oiBel23yxH$%UHqsf^mYexw2|77i?|O>#Dn2z9vLs3q2Es3Qs?&opaObz=lq zW{kj#{f+@w;rgb)&;hH$#q}cQ1xNWR;8k} zSAk>pS-Q1N+;Tbp1fr-_Z3ta2*+lb0$b81qBk; zI{I#)6J?M%DSCbT9Z*^*L6N`{m?s^@2`c~Ai>YdT$DbVzZSqCpld?@{}iQ)Osmb?%LG82_HWALtLa z><+r6_q3jKtv|Zg$ROn4|TqtOz6mqPYrbyM$(EDu9ngMR2P_3HJM>jzw?VBLAIz0Hlq)U2>|3Wkld z7;lww-(K6$r?n%DEY6|^4X%BR?Zf~8AOJ~3K~zE=ZCuj|N*ah%CXFn9HKMN-O6~J2 z6f3pwc`f-Ux_6ic<`#;m-V0MVXsL6lW%Wx7^p>)UUm1fTS2556Sw&UJs8T$&CRamN z3chM>xKKqNa$}g}?Pagvv30r-x$skH^CIV3Z@vOx5n1MR1J+G|(k`Nc4OpwMBhjp% zlj;*~_FF3W)0Syzt&5jh?{C&}gC)CPN)1x4_jT)2rK?O>oyMBnX&NK-CvF71Hbbxk z3AQYQ|L7r-tKU%VNCipK=F$f6Hk@Ghwv@QiKvRttY)(+rx$}d=92_YMl2z5WbB3G} z)9K7Sj{1Ec8N3a9_@Wqm@m;wbm@SoedozR;4CNpqYYmBm|{8msY>~ zkuNG6@OgD#)^nFiC1{LLsrAQJ+fS%+wBdL>^6%e$&ljJ6#hcf^!S}sx`eJc1@cE}- z^7Yq$$&Ww%#CRN;#-KrW(d#u%kJlzZN|)y&oA3YFV;f{@iI3~IUVwdJp!-1XOu^$e+y?xD_mv8vw?hUtxTRP{EQphE88c+Om z{F(dH15-X@ys*FVync1Z>sNR5y|ywcRc$UOuLiR?N=i!>veixIlsUyCDS7t018?8F z<>qjQ^`6eXz`H%d4KX_HcUhzOW37KT)@Vx#-{H^*qARLODplsVWbFeg86F<*`Im40 zm4Euzf9A(`KQV?g#w8?2vQZ(0Vhv(vQdZ!Ua#qo)5DBTOQr5OSShHk`V~(V`pf&p{ zs$#^`9CHy{H~b7(N;bq$nCHSY*E-|I9H1!0e2$PNQWUMpPiioFzoWQ@$kY&q5XmVp zg^?*tDz;M{i=?NyC}yT=2TCoblFFix>L9e}p)M@1HU_XcG3&ZpCgca!w!L3A z@Bh%KWWY4ux)z)>L`lRDc=zrd-+%u- z_xJajIWro$HI<2@HMAPk5^ZdWu?l>RS%Fthv4XU;h>Vp|BkH2HOx9_DQkfQ+l!Rnc zjo|CXU~0ePrJrGqbgvO!y+_%o^VZlNR=_r{WQ`^kQ8AFVDLZF)`SLYi{r0!~?zex= zn>TN;Zm%>?t19fNxVlj^by8O&*ct(Mwos&KZ4jDyi7C}SqifLCRvTnWq3=B}U%lXq zFF)tA&wtC^-5tjE0JYU$CKgCBX>GEgOq9jpyJSSs+7t;a4osVyxkcdXfm*7g&Z73g zh5THp+*n!m)4YiO)TqA^4Wb#Ca$uS=vC=$Gr-}3FOdOAdNdtvV{n-G6^BfL)y8RC0 z9COLcNh!0+9Le;)=P(?Yhg+g3{ZE|57)v%rUBjF?ACDLU29G!YA8GI1B*&Fxd;YEn zm6;^~f~v{pOwSYF|EsL6+1oe$*51f&Hc1dbRf-T-?H}$pBC0_4+S(?q3}7KMGQ<_` z$Im(5avUVFZrh%|mjK**L)UqX&&=V*$LF8;_*9se05;%!qL4^&W?pXG<_ptuC8inc zGi~cJw#8*}bry}W7hs`Cr6i@eqlk)@+qGWgG{&k~jZzY=0qaOsm^LP7h?!g>#U^dr zBzj=cfJ*Or?>)XTSeGbvBqae-ZL+xF2^mOUhiWVApwi=zUiD4m@%A8qzH#hX7jcQq z<3yO0DH0auC5sz$*JFK>woJ9hweRrG(>k#w?5d7mSrJC15hlyN7M4g1La8f=G@~f0 zW!;u|8l{J&pypUwQ7K96q=VBnNU7XT180-veZszuN=pW#?Tv~`Uy76U#e6 zyj4wC&7`(qLnzA5S~??%WNnj#Rv5z)x!!Kv&Npt?E4SOkG)>Ioge#s?ccSx=m<7a2 zB@4YhW|b_7$4E(1$T0*-SO5e;`@U@1+>|vMl*Bx!p_Uvk=CUR>(uT0In)Ji&Wwpv^ zEKsR;rc^4gto6nfr9ey4E42Qt;!_Qtimt8JiaU4H_4rO01ATvBI1Kc|KsyX{Lr>H7 z;u`I}^rZHUR)syT@z|!pdhz<8KL~lSw*FJrfKe)+P`sf!ixp~8Y_Qqk>e8=kq$G1v zaV`q<2~dzoC6o7ig%$A5u%@<~`BAO*CHX$9-79JwYBk1j3QpH{MOJCf-UzVagvPJ} zj!vJixGxKcBvK_Y*sJE9tnS5?>9kddY9C%n%2eu9|FNF;T4~jawvpt2bLh@07gBKC zR_T}C4P{;#o7q@oS|!zcl(OvklK7_Gu~7p(OSW140(kK%x;E7FtO>DbeAg$TzY~DB zCcQc5wU>1k8}uz7*EzdUoj*@7)++69R4MibcP}c{JJ4)T4Hx$ic7t&DjCQ}M6m7Y; zGX8wd4HB?AN-7#yNN}4|QuH#5Sy3^x*3%pvM?cUtf+!8cf#xI=&$loy6W8U!G)9&s z6Be{*nYch(3&-QYH{X2C>Q1iU^`r%`M501{S$4|(Ylt? z@gDQ-Kk#ro;XBW8cVOr>D9#acc6^#Yk*0;~?U_QvD1V zAb?Fy1(Kyw8J7?!zN58?`}+sp+`pqc4jAWY+yQ4>a&9Ts5Q!@&GR6zjJj)ni4AZSJO$qNOoHvvrTD2t# zjkAC@s)J%GVy^UwtmZ_vrSUyY!|G^jtrh3blr%cAR1M{ev0G5L@gmOKF^N1uU8ueD z6d%ahiy2onL&%YwgRn!g(5Wj!W8ab^mt6u}&=w^?mPD;490u9=ULtv#OuTY|{5*%P zU(Ab*;J03%>0b4KWk2BceFB_p)qy&p4Q99Y6y{~-`TWe&^D}c;=(|ne&m;*f97(z$mVFBnoVUYVSLl#YVf#LRWqW&O@e4w3R=lK>a|{lHIf{7qnoVE z0cQ*)N^n@}e;VAFstYfI?#7e_{8I*xao`(h8esyi386uPIHey}(4lR69v>h1$3Olf z-+uEQr_(*oHIxJ~MPVP4E>3_!vjNq zpz#Au)6+B(QpO}y<`8boX_PVVEtm#OArlEPGR-%xw=GTHUEk1m zo~D(!MyRk>sQ0PC6bGRtMnegW&cOz<#kvDsf1>N(&~`_hzmv*~$`4!-_3$zVuIDq; z`NlX+%uAq9=-ZC_eqcD9@QqaIyl?3Hfxhh+Op7y?M%|$|E=pZwH6dN1fH@ji6t^Y3 zMkPenT8uh|=P1T~Ig7l-slkmix-R4(l-@daQ_(mnGtUz-hz=5^*`oV>Rsbi}SX~d0 ztW1y;MN((71m3;C1Qr$0PsQ@`gwrYTDD&PRC-gdv$mb#xQ5UT5Pt)x0l)m)JT z!)4jGt&_dP7)b!F+bXeufI3F2`G~xyYHBUI-tRUyQyDy<>^s)?3tP1&%ym7l>0j*| zT$4=wec5#I#tJYEFJqJ1X0EoVt)O1rUrRC+6DY=2fv$R~6mb`?Ac5}vRZA?NmAE0T z!9oQ%%(ic>6;xoY^w$L2u0X{4@ltj_8(6Yda(Bn9;K7y*=e4@L2j$kPezq%x-Ifs_kMkH zFJ2nUQ;SslB)GOn`mI;aK&)m85Jxz>8<*z`^SF>sg&Z?E78a%Ib=|<1Uw+M>{_&4Y z(-qr_fr#@mAf|EVe7&zm){ygeh2$t|{?o*S@9#0jGMol%*E1C`#S&8?%@gD8nejR^&R3>oWDX}^6L#=)t-&`9ZPy7Pumnn2>eE;Qd}r2Q32+l-jHj%+ zbnPv1%#PKlNbjHD2G|KV5u^4Guc%P+qWLRfWj)%a}vvl`QA!poZAR^4_4W5^^mIMVYj zl}@J{fG#*$gObfTSF6S)i6guAz^ur7N|_L0iCd3$VeiOyl%(JWyLC8&F;dOz`vb!; z@aFLyKm70mfBNCS@a;E$pzn^-86e7&sogqKU7M6Lm5hL9DXCU{3d9hI%S4QkYZ#fP ziKpumC1oD&?>HWh+}#h-#>Etx#`ADGa(8!+HI5k6vC!CUAuej@qX5eqbSs!vgNW6H zrT%{@yR~u$hSWW!MvdEOr0TM$2!AyTTQ?@vV#Ubia^-rP853N`k;}NSEK&9$z#=r$ zw-1lB&S9)qcT+3tPmC<{4Lb+gz9TwmA-62E%rR$Z+J@8dj$=PyQ^4j-v@(N|$!hfC zY1)pqKhbpun)ZOR4JlhvDl927&l9)v6XWH=G@qHLEA#S1%3)n&VhoJamCNOs=kq5n zw@=LB1~!pOE3V?+V7yS8nbNJ-kqbbU*2!1$iViS}FqX$cyW5lw1P zGpZEITH*3mG~aFGXd7vZBW)q2Kdx0z2h(`G=^2_MO*xR0r35FM;%JBgFda>IqC4Et zc1LV;hqoSw*ET|}ctnK4e0n52ER54Al8F>?UCXIIiTtLiNsH{2hvC4%A8CApOJZEM zBJoA4b14;^545dpL{6*t#oH|b)+!3@0{0|9YTdVe4c1H4$5z;!^~FeyQpidAAXi> zih4{4fHzLuu2-&4pLl+H;&y%_#(;H&u4@^3Pv3QTZxwhK+21$?=6PWZk?Zx!`FfQK z^fVGob$)DC?y~lUbV#zigrfsp>YuGmpZ9gy^dYVq9Rz{Lc zhY{LvNxC=7^?3xSFgRf*6i>;96wM~d(F$<3P#TA6Jkg8aLEP=*!k!UXj;r7&(weAq z;RdMSw2hs$KCTzfCg+U*=G#9)E-XP1(s8^oO(Rx&)H>%? z*WfuGkNoi65B$@g{=_%${>WiC3BqZu^!Ux0_aFbtG-v+p-~N?lf+ZPZC~II{q6AIT zb>^49{le2PH^P$0QFl7@D0ynFWrZ{ED6X*x|5WZ+5f z+>G~@KYsrm504#%1b(KJNQhT1*JpnI=_4^s%!?%isQ}c@44(l3fA89MH}(aXX?DkP z+p)K#U+E~$iB_!b8Ty`16JUd<6nK9A#9#m7NFnifJ=3~YmR0ZYPL{aS=>ZzYZM={Y zoSzqdZJxPZ78)y#lSYvSV%-)nYxT4Pv>WH$$az8w;YfEg~O@C zHxAPmwD_Cm~dQpKAGfP>>F^YLZ5$9(N ztNB|^W{nEoL0$RC8MvWUR})B!TD+~>WKV%RpA#C@i)HD z)b|*6>x)@kCYL$z*T4SA|M`FY5ANQ*LZ(cH@jCL;fBua>|F1vu@x!l_ zteQA>bSX6rs!3|uCBQQO61GTiQP7HB*%I>&1gycTC|k2uW{q;pa!#UeuLd`|!8;>K zN82{^y%z^mEZ#K&gu23QymGmmS(YNboU8YMHJlCu-+c8IUw`=r-n@C_t1th+ci(-- zmv6tO?*~$L3dX53tp=--_!{w@$Pyf;lt{BwLeK9%a=YD#%S_6NF^nP=C^H7bn=jt* z?YG~qvIv*OsG;?;hplZt3hM(bYbvRm0is{4Ph4o9n-l5F*9Oc8m2L}`>X@vp2ZaTGz03rFK$jRZ}+8 z8rr@kdstFfeHAc;rfX=O_LxlxlM|7xudQnw!||S`?`gW0m=m}2v$XA+14|HHZU_tW z?ZQ0Wh|86fCJf^0Y)mAjnQ^{xxm-A(FWhcd=6Pa?K{U};m`lckafM8?0@l_zS;yvu zab8#!k)jw|#HhxC^WohM>R zYW^h!hpg3`q}>prO_;1ETN>!g*sOHRx*X~HRFln8B>7!O>IUq|Rw)&}T77CX;dBUa zR&rjex6(>Wj^Z>Ks|jkUW@YLsZB+}LtR^;Qn-?H0uB_$r|T_kEB))m_zp^uy*5UX zAkFi_b)LD66Sr~Xdb@I+N2vsdpvgxC%90voDia|Jg?wFO*D9YZm@zI)^T@PJqEWT= zl6Hx&Rsp3YnA145XgfjJxBIb1SbsDk3n;q2q>|UxlB7(TGHHn{W+WM_<3-teZA;sU zT*s-Ir8gpca_TMM)DYCD$(FMoV?5S07}JuAC8|z7D>#^ts$7~aI7_rbudWryloBaN zQb{;tkqFSxWM%7E>2*Bo*!3!%vL%UjJtd5R#v$#$ylT6h>Z}`!u};P*BCkt1Yh^QI ztrHNeCcrv|$-9<5dDGdhl}@V;-#Z4uZWE9gNtsEKAjQZyPF$}Sp52oK&OzFpR5v;28s5Bl%OC#XPki$a|HK!MU(vNa#x&%d8JCIa za^^fGK0J?{FSF2fvsnY*tdz&Fz{d|yeERrI4uZ<(;Gh_6*6OoX)tuQ_wsk?Mf8Rf_ zE%_DAK`q|YctrPwP3K`0O|jMaOu0>TeDTEt|MkEB6W@LJ9mipy?>d|plcZ&ls*P{%`R3~{3He**<;L^%C!U`_ z@N~UUt_y{Lu?a6A;8yh5WG37B?qWP+w)fVT-QB->f9hx1e=f5kzou*h+?!rSBWOl@>?V zDN^d?dz#@u)AbbBP*8`^EQ^0y#NaH1piG6t^?Ko#Uw-D-U&T>2qzP-wx*@dPfNL{T zct>36ZsEo)PBeYPci(@<4? zp8ZF1ludQX3u!4VV`iGfwYg|zHYL%~_k-tjY&jfHobDbt93L2l6OC_`ZYXUcQc6OR zi;*Qoq8eVMn*2s}V;7|Zx`*POl}*7n7$bV_93?1ADXyj$DgndloXd5-W!83Qdr;`b zJgM^n-AIt?g)?5!#XXqxGWp%;Hfpl*8TGkxS^oZOA0YnrOULp4f7j27h9{cL<$C2` z|Lxxy?*0${<>#MBOD0?kaY>XLOykJ))0y}0f8lz4rmT&`%SsvJbvCHJt(v)%RSR6KVK@xDdGo--!y`>MV2z_~2l}q(HqZR~ zzyCXz%S28=DqY57on;t$e)!|}{P+L%-}%G0f8caFay&lp@NiGto|Gmifhk4;Xk(lP zkpgxIH8T^VRPN^6jSn9`^8UvknWkx@k~yKaHQsX=2Ht(~1z)`Vg8RE(HcsskswzxM zsmQq`!iAUS94`z_D*CN&sIf==y}VzZ)QUWtI+Fh0DBJ(9KCq&JV3ve#4v}#j8JEa3 z2PW-D+_o)k*E0+!4u=De4`1;1?OP7r0ZPGU>0|DSC8bf0GmYdq!3~m$;?$lNa!D9( zXj@O~yv)B^nL@k;mN0{X!|B5Pe531+lw!m{FGQAHC`Q`Mm*nZ*$|mq1Q4 zVIH~NE?ln{rs+mdr|z1(Ela|N>M3r z32c^iglx!BfQP2>Sko%-AZCbUCkz7&XVIoQ1J)1~n9s$qgoG_KITxG} zuZz_wSB-tdP*8$TYM`65P@XjjcGj$jb#+L!8oe5&55{$|70O512l}v~Y{iP}u7YZH zzpoVJsP52FgYaUi&Ts=0Gm?0VFF|@ShboIgZ4q|5(5m;Z;9#9c2@oB$#BEV!d@4zE z(6-XA{&YHEXc>lqrjcMdr67CbvJjSq9Oa9nG8}~c;&82}W5BeYZWxGhk!qt;3Uy;> z8ZT|JK$0h2%c?hkfV* zP!b^~IR`bZG8jsRfOOgjxe#-v>59n9yf!##jkaAy%%U14-OWrd1}lbdDOuSY5s3%L^PogbGMg5dE#D|PD<~D$%62y3i~vS2D#E(A zY?03ZNKL_t*ZGw!FKcz>QnOO-9lvhaL<;^W7U{P>rD?@Js9CBay$&}_+Xwu1N#!@#?D@3_CeCnZT_9^bs>@$n75 zX()<-8Y^uiE~Dd@UniC@aT_n(ZqH2fgMi_kRxdlOfKSTSjxJ9%7Co^gi?B(Q957C+c$6c#~*&+&BI#>s*NuCRvHGK zZ)dFajLXQUr;kkIEWuk_`{SvuBS$p^xlw?nM5bjS2bmNuI!vr4LYW*h%e?UM{DJo$ ze&KSvC?!c+b4VK@OEHPtbl`mX#MAknkgXt|(UAg_B{JVe=Icm_g}a9%Up&6$@&2A+ z=y6UqznrCo$vED4|Nd8g`T1vVmkT9H`wizBy7tJ@O53gMEUihHMuQSEhoRxkzyFnG4x~w>94uA> zE9HWloOkno?eJI+Dod3$(x${(q0WogNld2J%5+()?=Mdr+4M-5-AP-U*NtXRgOcBg z8Orf+#QI)ZVA)Q9iSfqc<6GugSSZ6VNHE!UJUl$`k3aka-+%u-$Kz3g zY}2wV5~yGhO(jO?uIf@P68_rfH?HR;{slo3guvlA@b>K^hr@vJvXNyIY1@|L-GRPq z1hFoON`tlP$eL|!%Vd=WA@@!+zVO-*!4$iK5;Zxl)U=oT(FR%=V|OT_JlCz?qEz=a zYG22%&>6*{IYx26k5MEpr_+fyhdbJSpy>|`ha<+!=OVc|VS9TRWh$*n#7Ovwn(=_qv`4gAxGjHF%F>+Q^KyfBR;A z_lZ6o+4tocN&7}=&D8pq*d~HsXi9^@;msg>Wb0^cN0VAIp6npyD0;_~wOfLWg`A5_ zeE=(_RlzdVMtk-1{(%%)_|TmzZLMQBePa~Yf@T) zr!5xJeHemxa8;*3cJp($GhI;C$kKr$NN?a?^4H8|H`N~>U29XgE_lb?NjlB>C7 z5#uGPhG`|qSd~f@T{-1mhMb8Zkdsz=oSFeS0ey_K_|B0^W}HTDJl*tX9~WR>RruWxQ1ffeg7Z`0VsKD6L-ah0h+}HFWd}M(Q4* zfp4wCRef*;;fju#tk0u@73$2U|0e7plM~h@nxrs?KZA<)mQ8>fd72lcQ{aXDMJx z(Sk|TN@}4Bm7LuY-;J&-`)^e9R7q?F`jG?}ymxpDYpWlWO098nN|_kuwe??N%R>YZ zaW4`&S!Y!85ta=sK_pN)Wlc=0!Pfq>R-~{hgN-38xKjUJ!32$ktMOf>8W-(?P-OtM z@-0A;fSFahTle;uqQsD@bCv_CbG1`5wpumL71&c#&Pr26yFPfoCcx{nT=5|JpS4w& zCewbJ7s3))mJN|jS~W1qvKT3uPa*Nk$B+E@>nHku{+|@v%j8S2EDO{1%I$XJ_WXhK z`3V~*Fb(!GIZA z!pNud2R=T3;BtE+qzO!>X)Jx;5JF1~5qn(=>!7az3BA z-mXHSPFoUV_f=rF0NUtJ(F&BwNrKKI)LV^;H5t~)V+~7+jMI&ng3yziUZ0Qjc}qFd zG!4h$z}@MN7#G^k@c8DA)1krHLQy(h211HlmNU~ba$C-Pc>2KjG}4%s$L=k?JK&7P z>jN!0V&a0$kGY;B{Q9$`Q@*F#n=yoB&HxSWa7LKmq1Bk#O1p0 zxOXS6dE|Bzci@tRmN$+g@87@YKmX%D_}fo^;d(oZF^Dl7hdaJ_)AR0a=5`y2VTO{3 zX=a+P-y&_08bZk2ZnyQhO`{~f<2)+mE{fJ!0gIBLq9RU{-{WAp zyX!d~Pqa-(Dsa0kEVFEmvWT-*#?Zg#!YW%>Sp{t4WL-+@{6@f_uJ!cIAg-xd`sFrO zNKh#x=4Bzp4XoONwOX0@e7?P)zSL2=1IP9omfbHlzxUE>t+A!qevL6gC&Eboz~>Ji z30jdbNrRp&8-_1+^V-gH4Sd#_t*F1Vy98Je{<5B@(f9LWEqR&K@AWd<8Gl9vuRujs z0IU%co|p5WTNq&H;<2e|NVD7K0aX7fGZXGOi|a%IumaWL76iH-g#1j>-EO@>CEMPBTO?XsL9mj%=Icd$6^;S z8Pi0ZH#Dtd7$8S$|Q;jELP0>N=kUdiMDYq-bIXQu*PFez`6$O65bcAYuAaLq6Ez)2SSpTZjgwb z!ITD5q+e^Jtz^2kW9Uz`-H}Yk91U~o^m!Lu6Fkld^%^7U{Us$#2?G3-EIL5z#rO+^ z(ru*TQG;RByfB-hI&aniX6&X<-@oiSPG7DC`&Ugq_V0PQ#>%}<`<-5cUCq^h_a(t~ z{XYet*g!W)Wb1X*AUBh3{tS#-udjZVS{YS<+*k!uq>D(3NodT1IG)<&gdow#E2W68)>?$9 zE81#lcPB3C7G)h|G5U(rEMq(d%5)>!27E`;9~lmrwhLGvu-ZP#I!EJMoNJ{OpcM}i zX;)Ug3tGJe(hA9EgHb)TGj>aWi(H2-l_8q2K%-;WYN9Fb$ug7*>hxWd{+zQgpt4rQ zb$aGp-b<(ltQBIX|G(*A*;V>Cy>3oB ziZeh_uxNF@tiP8kuJi*&yC?|Akz>-H)k#6I9Vmjt=rLre#78wut+nZ5SL4?gzARSe zbxI=ri!ms`B?+)mFlW6(21-r>Xoet?JF_Lg6-c&bS5Y@x0vw_+8mloJ>ZWasXuiF= zYS*=MUl5H7pw_Cjzm212=L_?!I^f%lah`?lh}_I6MQ+o`6lJ0>$q-|v6fvkE$j$a8 z3o2uD;ZzZPDRQG)bzStPl|hn)0z2O#w=jK{aQ?r&YL@?EG2X`{6>w);;8$U}VeQ9T zkFz?odwsB5Y(UOx5~NAsi^!gJJbZS3@?f?m6Zfh^ZxpOo%h0b&yHXG}6-IFdVtR zzo+keiZQEjy_CW@j?Bx%G+Wg^?0^Z4BWn`01D!Sb1(Pz?L`p?KU)?gf=@znKnnr&7 z@kfrsk?}k-bi>-GE@6by8z;_}XJU*rO~cSP+#TWwBBf^R7$VoPRRu2^U2hK9qTXE+Q>p%Z6cV;Yw8mD}`@r}Ks9 z%SDp3EY9iPH{9Rd6UxYSex~b=lp>m{oHHp#=4s^PhY$Sn^WQk1Kao?Qlz?;4b`6h@ zkF@Qey+s2#CC2H@)AI-B@j};o`k^J4%rcDvNM*}31)iVIoX;2Ld0`1r65wf;#%;kI~J)cQ&{;c|2lfX65V_(VG2*q-)8ydE+{F-$@|JJMU zn-hEY+p^1yjS-j1k~Qr%4&&W=9tH)U6ag+-B9{sx2sTvpc{@#usn@N6Db@69m%`b7 z@+*2USE+QbliwN)S*t9Kgh|>qqVeQXczQZ>yG_Jo2r&?rOxJgO_x&IF;g5gh@$n0x zI|(`V6C>G5sh&*8QZ14MJc1Zpue_G5QM%4-Dabh?#9VV*(|%Hxc+;Q zaj}iR?KuhcTI4In_4%1;yfKFx^E?sqjZzZ0K+`!6$A;r+plN%IvE*zB%gjOz=n_joF zz??JgHuLe>fSa&Q&m0qT6yHs0<6&?%LrH}B#&|mu#xr3anQH<(U04=LesfN&CU1J{ zN(LgtA{Ad_V}*AlSW|q#Rc)9PQyXhN6p^45HS;K?h`+}QE+y6dsfkaL7FxzG)Cy^B zvr>$(TVm2S8`cwiL+g67KY-~erYD;od{5J#uztWTz#^{iPHBQ&+ezSG!~s50SW3ba z^{haspxM=G$`+THy84)1TdZ}gYVuVTI#fj8~3t^R46Z+00*g-g6f;?%yXia_$Pcxw1Zcqu`L-rL1ed0HE2RT5w(KN?H9n08I{5dWIEK*DT*736FXC ztTb5{<*T0idShi{&uX5Oj8yqzTv$fK1cU{e#Wjue zz;+GZiNRi@R9CAE8dHRtZGm767D(v|Gda#WL44 z0j^-wYRbiq1-GmCzRq`2u3Ge@tN}gFDmhkWRJP(~o>hmTpv@ZbsAq*tx5~W8E5%wE zT(!j<>pS+>Q%cz=+XeM|k;t&FXVv?~>_3x|bQ@VKss(lq>ekkN%JyX(g)m9vy0W@_ z8~ilSa^gYU=;nFmHjZ4b7fFPSpssTfyL>@Lw+d2G{fWT1Ru^hTN>Wy|L9X3<==(uh zD7aSVmKU1fG6K_!hxhum&*WbsncL!BHNc-$I6iyj7s0tf6J96ngPH-MzN#Z;PLlXe zi|jM$_mW?;ZDRGusj-2Y@rg#ky}ZWiK zaUZ?jm?r75w=9cJjBSqZ&~+UYFYdUxFwc?q`4gYQ$oc7K zuH#kPv{;&^rPvYcU#5mq~`t*VG_=zQr5*Vh0w~pKGrq>_DSu!q)Z44%Mv8{O&efj^d1hq<>9{N{xr}w zvRId#S>nVrE!@V)I3<=j6XVLX+Savd-c~^zT`%k6g)9#O{?uRT``W(Y@y#2)diO0| z)8mZCTaQVO@iq}t;c~hD?s~A>sn?VPUc`f+edfhK)d2GKa9)FxmqYyJ0kU2J*Q%<17M=jvtMH@>=X z*8YH26NIXQ+V+p4&%vw@*sKHiWguO4CTy>s{yNsRdWBLLUk$vvAFZ{0v(qt}dKjg> zS&PTewJnFCm+J%OX<}MLOK4q7DR8^o2=fdvvfOTb`t>I+muF%gNqJ!@SC%l5%1qNZ zj`ss0-jmA-%tVYH>x|OrB`{p#!tHiu2_wY>noa{nzi?eXlAb3pVo;SZ6g4rD;h4x# zT)LO(Mx1WMc_b_o({yE7Mp6=OZ8elIl(kB;!wFUZHLcd>yY<6ZoYS7BUeJDL1o8K# zsJ>U8i??cSw9ZqhxTUfXgC%SK_=2Hv4PAS{`xfIn=|$|E06gsx*WclqJBoG8#j-4@ zt1a}_k)6Y~9$OsVwF+c3w7$b+C)Xnb5M#98cTp;~K(}Y?6kY2|4X`UPs#T&KMFSa@MZvp;Fb7G1V_JcO-o@uKomMLqsI2odl^9OL0v1rsZ=b%GUVMc%g-bl3S_jjha@0L#4H?`Kt0yFN`V2+A1D3JO(lDA&X}*YKzA zZ$_6A2W-H7-5%>YT0wZ(M$3AhVrtpwcu8`7nn$l5BXuV>GEY2J&Z+aeo`0!8jLd}! z0JTM#7Djt%8#PfhTTkWMr+K%ftYZW==7_&tZ-S!7g*ixnz5QU2MJQoOG`?WHq4kEC z#iS~#Ay0`?MUaI)2Kn^exjiT46C3im%l$aE+DemBqz6zCQ3a*4B02u${LNc`Ht25V+buvo$o$%k!;t zREn52R61oYnJ_OreVQ0=6Hm8KJfF`jX`<~MZ{9Y1@$P|l?!e*hEnPn_96B(Laa0{a z31aRLgm&qD!|8O#{oOr7dy<}U7NRK67Dv{b zoY&`H2rjTJj@E0CoFcx+L|NN`l)`Pg@_c@Rpl+VlOXK%`5aWfuq3b)^W5eOtZyR0) zYg<8&OQt00vul7H9AShsS;CaLjL%$uy)pQXV?Rg_O)qUKVhN15E7N?Xr=xWZcf*Ot z(<4LI1D;YuH#5x(natDEM-F{Qu~D=P&Z#Ex#N*?@>EN_=Oj=R8Wtq90KXRLXVqBg? zR}zyLxfIK?Ogw-3K;6h>>{zT7V;N&0CUwhQX68j$0n-$jrocQ&!kZL?l4BPQJak@J zNq)N??oL8^J{&rnF~k&@)1uY?$UGP6=UwOfE&6L`7U6nN#t);M{3}*Um(n@B=}{8 z`St3tQHu9cj5;6ceOZ$zw!U*)nhXY^MXv3BP1TszgRlZ76ruMQikd{gt3^?dS&zL{ zNbGv~GI7^{$r^e8I&o!V=(>)^3-iKxCwi@vajwv|ojRtfQ>Ll>$Po5eKo(*U^;J4^s`6I&fKbOf%krVY}>VYah!_AYfV?jK{b3T!v3iV zxG@;=%Q0!p>g*~;K51oL$WxN@?^_S2BW;RYJ{cMt@g{-|U;@O6m@drA$h;I%=`d!& zx`45P7$t$UmCk8p9<<)#4jrk~Kn9`V`$S>_7IAYe0$Svl#7Jt1#3c}>k!2pq%SZ}~ z^n6{U%9gTF0V`-z_sNRhQ!6W)kfQ)}eVNH)lgQy|6Ru7#)6B5vVypd2#=l*k8?aU}tM<3(`|_*L?_;(4=j-pV`vkw()zhKQwMu>7A7}r{ zS$dYIoJd*vMbFD3EVfbPKRG2a*h6B@kR`s!l^Pk-`hC_K)fiW;rPTz#rn+Tack4}D z$xrL06(|W;H2JOjW=&{|82(kWv0Ty`=ohx+rY8C#A+stUG@`FH0=tTl-PSs&-uJA! zJ^_04UROiV`fTNt);3J?IJF+U2NUhemz8rc!jOn2ive2orpX19BUZnE2@7E~80VpB zwI{K-o;Phr({!}0tpBcQXnjN5wF0pAV*Xl;m3Et`G@wEJLW&WvqUL{PyY_+@#c8^? z4qQ_adR~t8{eDsR%=+(Zg*oq8q`y)9-B)j4kI_=}JSA~|;c%>_*tO?&)y^^Vg*fM7Gn&1lv z%o;C(4wX8#OATkt%AT-UL5THsmX|-ez!lBT>wL*MugqRK;zotGJ7YOxz+bOdj4|SZ z7bIY=G%TH`%7qs?QZj;48Ko-KjV!%5N&VuwP}UR8MOzpo$RfBd(Fmn?N*k?mw+_~u z@mmXCeZX?>?fU;KP4cr6CF`JheYo{p4QfyX#3XHyl=d97k8!S5?^mza$!~Rg_FDDz z9()U3XYtMUAafRhf70WZk~m*4oG&**uq;a=%$a!#%;`#qbwUdrz_<4dr-su*&*|~N z;m~1iM|bc-O*C0)XEVM@c<<f%@fiHe?O^gg^w zM9OY#>K-l5uOSm$WC?+;?KVquQ#LNYEeI+n^rajN&NNtK=-rXy;Xrrn>4%=~)N(ux zoK6REJ#G#({wM)djEWpLiW)XFcHr*tmhm+5{`NDs%az4W#4xhV4L2t)d?_cUc_!vW z+qZOT0%eR>lO8K>b%-lojET1Ic=z>JyfJChyELBTVc>2Uum$2gvWyd9T8K-OmLMNL zaQ^rU*ZC^JSSsRJS}b$E%KS*O8T$sB#wn0gk+zKvIWOWKyDV9M!s_Nnmc^%5eCu;D zJ75M1%REz(B&NA!ViF^;3C>VIRoU8T~uU&Wkx;7x~XVUQinCK9H;9-Mspd4{YE>)t8xVJ=C>y-PFkI zhGKIeISo8arBMmeY^%nzSWW)w`X?LK>IP|rQrt8WeB7Px==+Xhow%DvNq~pL3FjNK zvBbLPt@I^>F;1M@jo0yq7-OVDZVDu!IA1O!<1`Ypv~%bW2k!6hr4Ootr6na&3OH-H zzrVvbo)BglrI>o}rNxC(L~Y&dN`1~-(!c+E1xd=w2w?Zzw`a0G>(4d~)@oL*QoS&J z-e#)+03ZNKL_t(yt4TClQd~Fay@pEmZ!r*BgRLBymzi+PJxG!MR9bA>~<&!mKzqe~&=%p3wyD{Eni%;U^-yNV=Z5iMoOQTHEhZ=pc2_iFOvjI<`QvQ|{UtgPQJ zW`qLfsHV_vbh%t=1+!KFR2yi}HZIZ%#UM05SyPK94O%HP8Rsp>(@DAz+`j?WkZdb! zQt=q1cXhl*rWm*`3&~iHIA{lae-f8zM0bw&l=@S&eNk5Wsx>O9aoTcDl3k|(m4H*M zPP8dyb%a$^dDX<$ackFrc}*5~!F8Pvt6p$jqw)%v$>E9`=V`j7<1z1&-u0uJ_{yo& z1+cbf(|GK&(z1e5T4>oSznclr-z#QRaHP&#qsI_;SClm(eUZZw#dZIBWxC$P>@`W% zH6j}CkOL`3{e9VtkMx*pfn?P#Yh_xsx@$sMqzYBrq1E|abAqTeNV6LK=^m@|f|{Uc zaQd2|tZ?4u#;hP&1v}hI6R+#bZeP(o#84Af@z}6tTW{)lN>BE(ULUAr0HGAiWXX68 z$%r>giy=FaLy!%oc-1&-ViqDL7Sd8gt8FG014VmBi+gW_>pGgImCiG*r|la0!@zJj zF!UXRlNLqAI{HSW1x8y}i6*%A0JoqCaVc42>NTCzvA(U-zn5FovAFIEb*!3gf2eEw z3vl#>j#Dx_{l;~S)qh))!BPObjxnJKZ~rDHpS3z$_Zh42MNQ}wlz9>NR0c&|GAgiZ z*n?K`m#V{;?-afG_Kvl3{`#dL9-8D9WiixbU^TC20QmgOVGPiw| zS%*qw4#YT9SeT}$Zj>XJ>y2fCc@e>T zN`++>2RTfkX*PqD>Jpi%!9)^6Eb5wAR&(3+*3?a$sPqN5S+nPol!}prrXo)eV~Qk? zUB_`aaXQ{}ce>~P@eA(m@A19pM@%D?l*T*Sz6a|iKrEuuF37`-DUqU~Yfrp+ct;u+ z(i}NwWNh0^EVCfPDG;Ne$X$Qn;q3!oeDx)FZy)it5wX5L@^N1H@ac(!tJKXdu`k;|t~%;zg<4lFq^hlOjN2v&?bazT(JbxqGYFpQ4F5TUlP z0ig$`RK&DkDJ&sN>#kRw`v= zNuS`;1rpNE1xH(&Ri9l0l;7Q|N?9LHMH1`gRMElxjo5Em`zo=)Y>CZpyo^rvvb(pd zW8?lt>v1=vcBl7RkD*m$Y9(+>e%A!pZnSPwSPd{rF57~yi+@Q4XN$@$46bh2)k(C{ z2@P9tqk)ul;_O*bQssyL*Sl`mRPE4(gm$h0q@~mwlNJ6{n zyIyp8DRUcdq-cb3qz%@WFpEi&28GrAIfsRQ7O>hKm&p**0%ECk-@8 zW|?O`efpK_?MgC^B}PKbDrpelt%QXX7Q*$+c)1YDm0~9-3x*)BtzC!lE!K&vf7iEk zozse_IFlAN3A4&xskym9#-Csq60qki)btP&OOhU`VU*S}af;k7Bj=|l#_L30w#~Dy zTh@sL$5~I;wRByJZyc_1INz+THF7Crq;F}=fn1{QGg=*2sg=Yu+nkl&kz%kTZn5Gv zZfiFJ3O0)&j>S;2***87-2-Mg-$=y}lU42GmP{^7;5tsk6lrjhOxZ}|qg-Io;M6RT zMj8__#p~0xYR-l9g4ZC_Y65Ia4U{*dOGBmh8=)~Obyk8@G-3L!imy~xY#m>(z`zX> z+GxC46U53&s6lZ(@Tz;vb*z^4_v@ZT4MG4LLFB%FKe1TX-ZhcfRKBuq=k=UkzH~nR zKa{=cb|goVrTOV%i@O7eol9oc)>Sp{|2{o4r?RJ#%p@5RfUjnz+x!qwHFGessvA7P z2mtQpX1a*V6}fUn1AEr#TEMpcrt>s&yQ-rKu5$!%i3F?KaDVGs(s zUG0;rw_9EtHyv-yK)2dyxe02k8>&xlvWQ=qW|ZU^t3q`tZQa=F>lJ7}Ep`QJS=LoD zl}RJ5E)zk2F3(w7q;K9AJ~rrgO@(NhrVaO+p!Fz)EE0f)RaMM zKZOZmvy%XgQ#yMMP&QOm*Y*k)R{S8~w3IA9$Oin@*VXfv4eod~VXx*uvbd>UM@w_= zK0g;?6G+p~sxhx*5dlS`V~hUVsQ;at9lP^Gs({;_FSxQa%61KJ_Iz85cMm~ZU+wvI zos{-pzI)#qZd6;dDaWYU-%M$HrnGCD)kA9cy18@<^5nYsoBvu5uzH3`cZSVl=$YZK z*DD6e0LK)`T89{Nl!DSr&vW;_H13fbLF+vP5 zFA%~?qpyLOy01!+b<=f*esFZ&N`S*l7I~T?^DQ$kvVXb``a#xM4N4hZ<5uxO$>4m) z)7uYx|Hpsihd=!bA3lD^^TwJ8~ zH%`2qZiE<_r-eC8#1QGM;p4}TbnkXNJ_=2)?|PgcFxK9Q_KBk<^hsOSO_N>w9Ym1- z*KycJ@#_%10>3p_vZZpGvO4c*&|-BktLR8n@vgQ4)S)yKtxL^F_AHTzv2YDnVoY2^ zU~L&vw+~5RG=QV3bd@nd0FeVW>7M~(h@}!dn;Wxi4c@#hgN!@toi4cXXZIjikCJZ zNmvubB5amU3}P-|jAdQ|$CKzvjN=2&4M_c*DBgB%r0)hgx5K**Zw7{b#3xUgA|#=2 z=2)cmROh!Sy~;UH-zz=TOXt&^GFAhlrGhNSy)MHhAef=mGu9e7qmHIkyI09vrU7gH z`4;$Yz;8C|UTA_r8$h_-E3p0fHuGkG@2qX!n{&bB_5Q4Wmh~3fIi*SddwzFh17 z+1T@KV6)smTm7nmjh3;kpsql!rqQO+49 z)ig|yJiY5>uUW6{-3-P$IUH@i6Mm~0|1PuHf;+Wt zJ!6qloO9YpnsKkT zyE=aBaud*7OM%u$mVZ=tvt>+QxiwoKNp5#l7ndhqYl^Bb0_MJKKm-5slmEJOb$fSW z=j3`i+G_v6811>ep^R@qaJ|8H`fmcJJ}e8RK!_?1kd`K)EtI98Hy{QhX@)da5UkJa z>SxKhgflCU#MHFAW;|;|1LVVg$msD+Vyi3 z;4A^2UlyKE3z#eWJ$(4s@!{j1r>94ro*von_oBQy?1(|yJ;W#^C&~6XFkWgp^wCNY z0TD|t*?g*FtW=v))e#HMS;ldX?|Z!6NtVb<|HkQd7h1H3%;9Mv|pm5 zrGY;E4v<>e>2@Q`(#$>NL@ZMOcb%?Gal-eWZtO@Uvm~MRWd)PQ6@1^(J0}wy7mUyB z_5&qZwY!F50*;RCtjO{Y9myHyoVbRC6b&I}T(S@g^R!^F?1mk}cIyE{j)icUIDUTS z>zB{mZZAM!=sI?9-eC3xo24gREQxEGxaFA;7pi8&%y&}eSW4fF%E%bgMjR)pM0&kQo0W?$l`)Rb? z)Wbm6=Bo?_+n>q8-5dz@N540+-^@;EcCg7tvV!032UcG&n`(jd;Mv{>-}uaWKl-1k zS2Kuz=@36M+-8JKAjb!>NHOpz{)}mPzV@NS_ zIiFdU1?P6!j=*6^oKH7?{q+l%TV@z~_I@W>xmcA#WqhJOPT%)fD=ecBf~c`ZRk3%T zeo(=Uw2)H5l|VlvvWXZMIgBH3-w(Wb*K;^ntncVLN3osEbF|HwLjiEk8K;!E-$ncp z!e~-&?e}$D&5LUT`|YEsQk=JI^4@vQT924=Xu)KgBM~`QjWZN0b>gXLmK6b*i_)O4 z%Z)iKgd8<$--vSbd~jnAKd!go8cJ>W2|)-@j3j|cYSllBhL)3f>i^ zKWjENtBWdtraJ5DG~U&h^E>lZG)R_9(IA;-l#B{At;U!w0(<2yy|USvmODDt4e8aMbqk)Dr~G~&K1~*`49jvue9q}E4VK@R$F1E6-@m81gRN)IRnJD$y(0T z{F*5%ZS?MptDvf8!s_AJ99j8GGT%!5GPO6Z1Vn5-j}To1r}e(Y7${cD5Dmp{+TaLzTzb7a{2(P}&Wm2fuHT7ng$72)PQdZd2{0a1 zjoMeu0ApHdXA3avnY!L*gXj8l?Hg}5XGI-T5T@Q{-QNM~t=LvsrKRfkwcdNZUZo-% zO^VRKZ9#podbzw#V+EXT|JCo=+-LoqTs8O$t#@~WmTdv)%Qw4tc~qs?Wz#HK zqQn5TUzyZBYPPc00v2IzIuG8aRdl8Lgo?REgXRsGtbm@jSaQyiDa}dx@EWZvRzaaQ zmaPVOz26ExwqufuOiKZB(As4E{IGzvfx?Lp3NaYwNp9peOBOM`Qk42sKhIM4p{*>6 zkqmHJ61Oywm%nm3Um#m9rwiA!^b`#yft8w*Vl#Aw-NQ(K@KWFEBE}W0k2oi_g)Tar z8W2}3-Z;A4iKAQsLSyi_Zilq>Dx5Dj{_^u*2~og(j+UGXeU?mbj+qpq^fDbJ5*mFwwBTq2$I_|7qS&(L`~BMsIQnI$cB;ewe@+$I&kNQs27B2s~>vR=wc#V;H1 zYYhy8;c&3{-s5`_wLwb{Bx@q9gZ*LP-MdFVefOTXZ{A9MXU<&C7rs93__F`P@a4qI zOJJI15hh(*C9QiJpzAG<4^RBdKmQ~D`p^G^4{GI2efI6gmfe17I~ zJkeXv51;*-TBe!0K5EocyYwhi8iM{ZT9%9zZS;=Vn&S~gp6;?953U`GYO zLU|S^(R;7vmRD~xg0R(m%}DLg(s@af|Rc8>$&uA|pNH0KXkV_4!u zjFH{g^ZxxC_HR3!%M_bPwvbIHj-=B_dQnj^?N?}0HQsfOS2|}MyXt(^39Feg%1U>$ z^|h4s+-ebNo&JrYHdzGcN(sa`6Vi>CCt{ZV>}0Juj9Igas3R?(k@f72C6EYUXN(IN z6I1|3Y_Lsomi5Kst;1UpFLQ&`-dFYGY&3I>C@>qJ8t8R3JKTw0gjWDuslHJ)0ZggE z5(CaE+eyW^x}L#}bnXDj5vIs8MRF+Qkhor-Ilg@1I(-4N;GGCriHMaxi?5EG^x%{O z)QRpwF)DJUlcy13Qj<4cr#V4*H>I97lHh2gY%v-whmg2i_bWIqV-O!w&Bpev_ijC9Q%->d@2x zSW^*hnN_uSrJ9meaH=kTV@w0MS$`)wIi-nkRVTXHqWbpocc{?C>V0e-L68t3ww zoGhmK3eGuFjNGP))9J$bbmDlvaJ}BR-9lrTEz3ekg_Kt6p^#7{LTp7fN)5Ks$~Ru- z-C03aQ7m~tg92$I;h0>VG(CH2POAE?H6zu6ZMNDFwIkLx@KvEhJv(Zqva(U?__uN$ zqz#fOtF4oH*gVVTSEUrlwylBfIoJYvucj=Q^>r0kR9jg+@O!4FfYv%9g-Vx~`>cf} z_5HH7ot9aMKvXt`5|#Z_5|PZ}3}(`^*P&Tq5l!s7PS_G&0C5GvyWNhVy{4!4a>n^; zLzJ0RF+oh~@5)4w(6XYO#3pP8rDbaYm+EgSwOX%-V#=@4$O`Ru;fNp(`?e%l>L`qwe_13pU1}V9yFjWnO zUZ|)KwGL(tMAx&q8l+98ck2LEkXF`b7tuiO0DRpq6|by!E&)-GHA+p$1XY`qM!~8` zW@}3csp+kBGxB`~xSb!UpetF^;FWS*#dg#dRghWMe;c)&n*fVm^S^dz>jT!*clmoS zzI&gHTC1>o^&VHpw+`6GAQ*k#E!CuDk2ebd1ue0j+4{E*U#tHuMV;!FGT(g8b}T@G z1)Bgu>ls(;IV~&;9A7fi?aK4#g!d;(HqsMzSqLGLRT0>GIaFlaqdEhbQnZ$WMaM~< zw4}hcHItU_r)eRE3nedm%x?a`VUeziVYP)cfK4~GXH zA0P3)!&=AC@96su=OMUZ9_l{%^k|iE8-g$<> z(GNWb>&ZDw&rKh>%txRQOOG*@g!ae|Mk&FP4fFJp3D4SMO>3H)a<4Do6l!Y`eO!3ThIWmPKA&CZqOq!Nun1nZ8=Z=>7 z4Ji;~V9rrmxTHWPW2|JKYOQYXB@;NBk->{7jQ3vbM~$4J=agG(ySuSx7<+ubGLvY4 zz6QAyvzB;-Bz2N<&qYCr!P-n`I!6D%VSHrh-jIW1@e84kln8Ma>i6Yx65yx-LDxwO zruyvEeWP2<841E{MGIC3e036A%PY0xqFdqQnM+1wdXyeW!4!wlTKS0Vt&|E`4V)=P z1TQ1xkVzpE^TLv6a>*EPq-Uvj(vR4Ju@2`)Y(L=rfUzE9C$e?S(*>q8E-v^IAxIg{ zJUQm;LY@pI6dXN%>@bXCYcir}Trw#H2@sl$ahBKxmbB34g+6%+M3m}W)zR626>F$P zqSjQEVEMf*PHbN(&DPZS!Pb_^>uT@LM4dDFO4UXy2()UC^2SbY`w{urz z{rdH5d5B)U*)qM6BAL*nz_T7|4N&NNCE!zmZmq2}C}N`0rAwi`rYe+IKU)B{*^EOS zQ>gT{T#U55%+fZ<6-XM0Nm+Wnr@Zkcon&|=@H?nde8}3>e|gEir!M4m&WWXisf`1>zc@l zpGuvtd%q{^{rpaGUC*;kVNTntC2wwc`<_znf?Vr^ZRVz4r(#p?=dyy@YF$i2tg=r2 zE4uStGT|Hdw(iI^fKdM}XNEz7oMnTJGui6>l*(|aIw-OpeaZr6V$Av{k<&f+bxtU1 zq=dIo=p^cm)tX*wRt~uYQVXv3>oT?2S#F{QN(xf1Rf_alF84s!+=0+_pkEKp-QV9X zDbeIioi?~DfUglb{dER$( zq_s|0a9zQ=LP6Sh`66^LYYm2lk`|T_RZ%)q67*fi)5C#x`%jGifOkFK)@&Ux001BW zNklC z`O5QOkNo=EFPyI@QeIS$C<6&+GTvK;-ZKt89#1iaSOZE$=FeG6b{6k*TSw*9oY$aJ z*Et@ZM&7)6;P5ok^%hJ76A{XlYx8KmrRzPz=qWz4lv!INB|=`vHsgB7xF0!$2)1Ca z(z2u!T@SGuQ3-mS&li6B%TIVS@bvI2&Wu8>%i?70b|W7?yyxTl_l)Bxhmy4z1s=EC zjSp`=a2R&<&hfvNh50l~OSFnAo4V;Y9ErN8YQ$-~A=|e7J*D!b8*mqYfs{=xH@~MqT)hZfN`24c(@47=T)!{Zxv^zU{_ zTMlKcGol^gvi6!Uq@0K)5|Z{VO_7j-fLT*1%L3%R_l#D0n2(HfuEQEf2$A#c%59!x zEWN|`hOT#XgQf31!{F%$k8xRQY!}U%MQI5WlYp-n)4Fe}qoI*uao|d85d&6~{+FyG zj*=}&Ib)4w=tqowz;~HpXBbAuFm!a4N=+bP5rEtlH5-&NZpZ&U^xle^d-|f zLn*bdypZ4IBI+1rN1;d5QzI!GRVQDSVoS>8n92Gad66-SMF6skhT?&)V4Txl^cHUt zT}(JK&Sfk~0c9lTz+zx_23H*8cwj#~up0>*B0M#G7mt($X`%lAudv3W@4$s=!wjj*6+%A`WsgE4Yzb zV67+I*hpZbbo<|bRgqJ%wG!QzfQG{&+8fg}G2JHSd1jg>Zs!}9>y_y?Gi&eg5To`W zPiy@qRTK#=?Px5Q%w9#6hd`-9|##+_;qxyxwF@pXWxMUbVjE zP1eu^8FU=(9MAP(UqAfs!SB{URG;|o4X8n~Fs_sSzqV!?mGd96P^D5{2OBmr=CAJe zb^ZJHKDM{tmcG5ezmo3(cLT*n>O65PP_Ll9wq3GjJ@YYgK)-q1aoF$h?trx(YpTN( zIG&D7wFJ6kg~W8Za68{H5xU|riy_{mmuU4Ss*0vH4(ui)%Le$iO?>Zcw2is?EE@;A?#J~F zTdGXGaM^6YwTiYnCq`<2)X-N$*rK$>tm1ryw*JK=ib{LeIaP*71@gdPpbH);yMAqPJi!`h>!GE6tbN|<9fSsyI!UBT@2(b&ZE;lole`CdFNWju!;4N3CltW z7fgzzU@4)9&{?tA3}fG6-@F0S;e5pUjO#M4v(hizuMTn6^G1Mp)N>+;+H{CYO|)QK zI}4n%pb*pwYPdx~cITmhd9 z-Wa@-V6VgCGT2n`HE?Z&Nn#4*=}PberGH}g_{7tjH|&N72Kz|g?HKK&%&X}nbDCwp zE>YK3O#o;{LnzXjLL}ylm9!Nps|t0?4yKK@xOdXT#LD%o1|PCjHeI!~#;ItZyf3x- zJTZE;?NBS1FIC8IHBUknUu_@gIc}_K$JAQ&>g3D3rj(hMnd?Pp&ew~q(RrR(rbQTS zF{!3NR{OSX1B9NLl|C=FIG0uAsi7Acl`phH(W>BW?q2uW zRgzX`cEvQWz)~%LsF$@>@TmoxxPK0v^s=2)v#z^}xf^rs4nS6cFIxG{>+5ejnyf!x zbq-9W$F`d2LN>W6?o+_WR8{fnhf6)0Gc@q){kkcoe^|zv)Q0d5tk!?4qTX6BS~vb` z09K>C^2#fhyzYT@BX7rMV}$=Vzl>cSw7Z{cG|F{`e(31;j@@oYH%Na;>m{bQ#Mo$X zqGG%dQ`9y@;t=FJ-Fr8##t(V%Tt+0vo z8kTDr-H@fgZrJhh{g1qT^A7JG!~w{jlrk?bN3NHIcahzbXLlHIUZSu53#0ltB)=Y&Uyf(m{`n0%30Ql4o+)%lQn{_hjzh`iiM;O00nP6 zLv+v!#ljkKXS{Wc-45UFaBg56cI?L|9uALu|KT6_@%umVxO;~wju0Iw8kX5`zMgnK z-dF;B{O|`py#L5Q{`e>U;SYb}yLX>>*gw!)PmVgJ5lzsLPR zH#lkCF;8R@Fg9Ym%Cj4bF`}%RZ6+d=aF?XyfnrD@Nt60H5~3(k<7&p(DIGp32ov?@ zr1iilCBky%d_Ln43aB^-LSg#bm%s6He&(0oe&OBQ_l(1iaTpnU5p&5QFwZxp>xH-^ zI@hu5ci2>;(i%gE%wcAlXKpvC9gi`#vk+T*hzh7JO8L$?5JN}k zyb9&07?zPWZLI@e=!yj-gFAGhT%9wb`W&*QLU*=! z0bYsbih~0<UY+< zK#cZ8FZGPAV8B+tTPVf;voGSEICTK6I<%6|&}?rh% zoR%!TN~lyo*!Bj(CbLxxsRkRX1BQSX^uB8Ok15-+m*HPUHSYlw_34VRSrRI)RdNfc zh#Oafk<}NI&{Jvk`YM=q=d`1sM*aL!d)w9o$;wcuUkxEBFmo2ox^9461q%hu7%4zh zHLxO6PhKLCg<#gTX1o#hffojl^&Q@KbVJWD4tUKLd++7vzLR7|*VA=gRN1Y;_*x31 za~qQc*Xm>@scUb&$~CoWlrONh9lD>7N~2#DzjZBCm{5Iydw8Uo{LLI^2~gbUm%owW zHLri5ujBXNTraKw9Al5*L#jIdd z7Gled$o-afuf9H4>sh99#?I0v-)W>{+eE!$N#|&TP#<0xH#MrKjn7Nb$aV!m;E_ge4vO+khGIcfI?+-?3!^=Jm7I@I1V>^+CWf$_2D@UUn9uxH$j^6X@- zse+Uum&=*s`NHisu`ClykeaQO>cO*_JMN#W&aL`5^gTR0bnJFgw@_;;LO|3Er$y>m zj6^eiFTEVcz0lZvCz+vKW}slKM(mB3mQ{0-1JW3lWnoHJ;*yEc5M$H zOnURyyOH-#2cDiDcsRUa9QXA7fpIwS_VAvu z+p{cEmv%l!ra5swCw}?m3qSw#GX={(|I5Geum9s;`Q!IL^6t$$9)<^OvE-PEOQg62 zK4bfyaev^Aeb4tfGR2AWbmsHd-*|rcN+Gh}4;=PA`+Y}07z&ZwbmG^~j_2z$W+Sg( zwAL=?suWqB72B8?RY5N-v-Ec^iDCn;EBM|>2BP*pvr({%^jp0i?kLSg!DspQ zL0`e>Dt`6fd~NOVW>0_XTv!i)YS@L2WU57OkwR?|my)zau#rkAtJls6QC!Vs<8&(E ztZtLqoX!iNeEV_7$M4>-+gma>LRd6AA`$UrDgt=zL`;G6`OI#&!x_gsFLd3&$B!R* zdU%U@d_z`sPisYGGv~tXHWT6m1-$8HeHJJ8ygkTG5en&&xy@IWcq5mY5F)?+_P>bf zgnP&$*40m~a@cl*qw9M<>^}1F@IYVQNCwyM@!k`&*UknS za9g4TE~7M^_d1R-F9KZCP1--r6LY)}mJ5_Z^oBWGh*e@;13*YCpe4%qVno4ro{wBE zXKuF_N>1!|9y=O3XGks)m1>x4jd#(ugQ>Pd%3w0is5n(?`y|gVt&kFVPJ|_p=S-L* zF$Ii=$6?RY+ehBMd*pD~;|C}uk#j_-)=|%^C|ONwh5n~>R_g=+_roY>iB)m2rlP70 zscgiiB)LARU~*FMEB$VrEp)wzt`*x6Qe=semrNyzh-J~*=NPpdOG{+J!fl=e_$;CM zAI8Z}lJ+W=Y#;=s$HzdJ14Ca$aXM9ow)!ke1MUi4XEDZ8vL!`J4v?aeav9Z)h;t$> zfuc&4(tfB2jooTy(^!gdjm4?WqWjS7j*+pMiY1rd$SHD}W)8atY#E5LkY*$Hca}c% zIcShI*NzRVJ#S14E8<_?Ys(kout|F;Yex-}wV_ebYF-6wwRP06+wt)Dz&`I8^Pb*} z40cfFfdV=s0nKVRw>GG}0$q2)PSga0r3$81GwQMcddZ@@mhoMJv@<%LP8^RXj>i`+ zmn&fsLADes)j2ke3jtwg-sYIKVg z@46(h#Zj-9m6lu6f)${*^J4=JwptZyh~oZheZ6U|m)M+ZwFbE!KDjz+rQ8Wvq1nlL zW)#)xvFqt1zLo~KY{e0!`k8varG3;o&(+y}<*PR!Z>nEj&qO^|O9jBP4hnL1R>su* z_vNk~QOgjQf~cUb{%B=yw%}S3JC#flt(Bnd^C~#9PHbD>(GNZSD8hEW>*zWW+Zu+E zUfVA9ozSYg&bO>EAglnus=ri>vS#$2D~j^TQWdYi1u$O&+s3v<-dBSGjUDoLzMA?t zI^KGpX7fAI)X>?l6zIQu#n&HTnlNa+?za}PdHsv>>b`3%r>tv6)`)5EyN|owzuzb_ zXr%xezN>4jeo3ZVuIaa{*g9z@ZH%Gw5=j%9)@C6!2iV}f5H?ETuEy6Ht-(=4DDTap z@~ibGrL;h4d+4Iy*Rk0=W;5dO--F=4_q7GT)Q#_)s>6APq0?xx)QgCUsvNc6WQ;Y$ zWQeh&51y1fxpWd;wX_WI@7RiUg3RXcO#nftic+ZWy%gk!RM<~@=1J&&;vkE1=WaJ} zc<4FocMPM$T0=|=F$M)p4re{{JoEf=;(ERD<;z!M{LJlQm~K%W23c__WropnyAHhA zDqglAwF?XLGLdp>8SDINLDgq!!N{VKN27u=MhdKpS*Z*~4RdW=yS1GX1uBgnUL$FS zb=<6#gHwQ^2uP{hMdy0<;~PG_`^3}ZJ84l=uuq3i=0kZ z(vtZ2{u3WRz31bn4?MnmOTXJuoF`>NaSl3<&)_pF`Y1x#9?PD6eBf|6@af|xj4kwo zfJlhU%Zc;(E63xRuV0@z9z_r+sAHZ~gibPga`1ZYL0sKWOB6~gWPA^U@%T=7@y19n zr4(_PrPm}FldvwTqlRR&=SY|XaSo)AwKrvHtpF+j_r3@vTi15&2i!C>G_q6b^p#9b zGq*Xg#2Ycq41?u-8L*}>_>rOOd3t={hws1Vup7xaO5b3mu!j)%?YH0fpa1j!=0E=Y zXRenk*%T3}Ymvgu0iwp_^>{TKP}EU)eSjNX*MG;h)L8fW>pBki^dDsO8)X-^4nter zG9PLrN{RX?r3H8Dv&d%{-K(~35TWBjZw$Ch*LOTT4!r;Hz{l^Nc=!G-<0!PvC3vQJ zW||gh5k@A&nI%Dtk<0l?=RIiqpto;7@cj=z^6Are?Dhu=Rsp!hI!891+im80oAJ)G zdwgI&j`X${im8=DD3wf%fhAAG5a=$2<9W}U^T6pialL&eq$Bnc>H3Z`EI4b~^-`Ps z_VC0w4jP=54)Zd-hR%0%UKBnL!=vI^;&P99mzR-g3=d;KC?@Sl7u4J>1>1~ z`)^K$Wtr*cncnr>_6wyHlGZ~elO!lp0e%kT5P_LYpyWs_foVB%n@-H(EUXRhFs^_T z=Q8Ff4s(%O_}cqbYEiRh5X2>pno&s8EKVC)+63i<(EzfIO2xB<&N+s$V;DNDD`cXU z?IZ=giI@W+1}KHzcetG;4`TzES=qlR#*(^5o1 z-U{tHDR_w`h=-_s-Io}cmqprS={STKS?17$jU*_i0z+EwUW!m)LHhkh?|(Tcy6j0Uf?O{A$=E6vKQpEeFX zL*LVP9%sDifvL7luu>y}2Shb!uADqy=8rbEeiCx4>)4n0no$drBRb zEz8U5SYX#IU!$igIuxJU)Ffd88*)6W@m`BCC*DDM7}4SqQg@n|BTPc3n?54#JM;MQy(urKY&{=^nJy$Jfp# z)o1W_edt^;QPyBAx+2S(;45{=H{;iV^Sjrt_g1e}nFu-~BKDit`z$&Kl*;`rYX-lqb-7kO=iB4_AL6~b3@TZm(zcto zSn9ees-CZ^lD0^6#ag3kie6l~oEyL0SqpuK%Z9#R4TCs4N|BWz*cb&Gy{UrV`ls2L zdS2?^ub;UF@z#l0sf^n%vl+;{FAZg_+27TfEk$TIw`sy=M6@L@48ujDyasStfu>{; zrfFtgWj;q4YAtOHn(Q;Jf?zq`8!6qUKdI^v&;+qPTC&$uH)gcXa6_~g)gg` zFQP;#(bC8;?07glN@hkUwJ!3P;|r(L#4?|lrVF>*!tIioZmQ~w)C?N~bFfVF6=!RG zkJg`g*^yZtwDvr8rESJtBBKVBY6PfA0!?6{o*&ti&B3^?*lK`lnMtX03ex-734OF1 zI?05OTF2q69E8S`lMykNxv&hGB`)G*q(TZurrXTR%ZaaFo;jUoVo0Pc!13Yn!2ZFL z%8k?IE7n_%w-IAH3Rde}YUPx{qoNT=_SQS0b?tULeAi)&P>8SBBVV6?<(FUo!mq#n z%-5G+csYIL<@S~9bY>0{DON!i4G`t3Ms7A^p;0m0@`Qj@5v5)tkhy}p zNzp7VMX1W8LJpa@1mY58|7JylQN&@AW`yg$s&=c+`??3!(3sNta2hN|+q86@A*6}V zUw`4tm(SR2d3=22U;gQz`KN#U6My={9~g$7Tm;ysl89m9>F1v~T`qk2`c(u@HZ@*% zHUg-T{BK26x9@rV{<_Y-^}9CaH39<)PPczHL4f+6&H7)JGfM-)t!72DHTBY!p0n<+ zYE$Jytb@LH?Dhk@abWiZZ{9xf;lqLVAKvryZcpELHy2eaQU<1WOjFH~s zknp}R3=ZE*8;-+%kl?DZDjcLW{(2BsF`T-NN|7vN&=Q-HvbIIi7`+i^#uc%7zKCF# zwX%qoC2=}smLzJ=T`#qBDX*;!B}y)>v7GgCE~!{f%&DpMmr^j=POE0>T+ISkwSOZW zW^+!YCF%1BQ^*>J>%sR9Tq5K^NRza8GD7c9B{6GRQCPI*wFtdBhAcJ3dEE+92dP<& zyaEvKEer!4hEhB^Ic;BO$=->Mr_G2Cq@naR$Ok1?!B0!UN?REcR&B6J;v~utXDJc$ zR!Ip0eno^%vf?Ggwzo~h^mH=T<4LSmNbBtOTqP?$ETi$!vnkFk**u)tg1@a+TtS2uq8yHyc4Az zq1L23XEflc887d(K02#EqxLP!o@lL3GHp%0E?KMg(5VWuF$Smp!LkVOJ)h4Uk4FK& z=QHy>NsaG33u7ajJG)-XguIpn+|ixehl}sBsVJ%uv<=v;2iOLXvLP7hKl0Z0>lr6b zbW+o;9H;=H2>&K(V$NV<#-u_CnGiF{1(tcnbsfc> zCHT~NtrZp@bl3MH64^;2ZE&JA-Dy(G8!x@tjcvLvcUY!kBXsUwi&brgt%5phj4;GX z`G&}pFfL7feS?6tC$-Vn$g5wgNml?<1Ng5ubpy8gV_To60s0oTx$l^x_Of2Cu`imw zK=qg88Jh3QtM$qzaAH<(SoVwp?TRJq^3cz&IMEw)vpS&zo02uV+X2hyQH3gIi852u|G8+SO(~RF`rf|IuL~`OyN!Q053C?~eemi~-q!=a_Kh25 zs18!wXn@unl?7souw<-rO!E!rovN}MrMeWM%cVq$wECQsB+z#Ufc0LbUP$9_n;EQj zc*+oB|%Xi$4;Hio^aOxBFP zF%&E{U1&7AXxgA?)-vsy9NF)7jAMuI9o{3gaRow%98VXl{laxx zz*wTD=X1;~^TPFfC4?)^Wrp4}jC-L(^h139fS%XPkP7$$>fe zj)%j6_fKzle0b!r8zuVZE!H?v$Q)lz{O4c(ga7!C|A)W)^k<%*f8#bENd%Hzw1zOK z6HE&VIcMour8EVaxI4g)FXtKPvclh3kQ)VS7RRYA2m}8Q9sa%;Cn#xa5l94P^ z%o4pWMnqhaWPEGC>e{xe{-M-J?)`ohKS(T(h@d6Fkn)Y|Epok{h;t+@nWxhukB6S) z`Fob-EyE}^Q7L7TDcH_)czoj1_doE%=P%@(xm+$P8dNs>nazUy#{S>@z4?vWf%3c8 zzJ8h6ZeG@aKm))U5V1y{eH&RfM#NC$%qvL0Up)xP?SNUIW3>;kv1b|;au$Z62(madcFjO7X?VDLypN$E~Sl;T|{jF#Vi{f+6i zsQ!c3`4hpW5T%@A4wCSBA3a0gQ=H6^?PjdAB%X2I#M8T;-NPf+ zb>cX6lEIveIP%_jhCz&GB4KjGWJ4k;5R-^|ZyxZj!M^X$#dlGtmAF&S*~;G2?UA5zZvlF42ukk(mB@{-vyd&aSc5^-LI z&a8F@&El|GGlG$7t}QgdpYyg!N4n^Pi3X;(L2XXZ)T(WI0x z#^47>KX%yOP)sIE-vLUI=gBz{;-X?kQL-_$jx}XWF1RG~AXPD?WtT(~Kpf8A_Z+%C zqubG$POE4vDH);#w0C@Qh0+z=lC>R^R|>6{^V(I$MaFtds%)fE9V(?CcMhjzI7Q18 zY%!Q1waPgq2`DLRK(g^dMb9B)ZNPO0@wKd+UnXY^j=}bH-2e@9ERK~r>g&fzUhwpD$dm(o^zs=UMkt9i0a5G+9v{^ELBJ^HnSGZ5hI%6yyyIsK79B|FtHcwl#UH|Jy#NjZPI! zk_>B8*)Z+2qxLFasqErc*W#XqSL{=~^4i3V?IUD{QQ^NW~MWiDs?tmME0}KFG2C+ES^F zp{>PS$M5gFd7XpWBl+)(bu|~TZIt?XMweaLy#CwsChUQYm$h|*?k=JD?e6-zGIXER z5(XN0-+ao(Kl5Tl48}_v8k&(&<5Ixj<$I$%e!E$qrt<4+O^ieYYGgKLlxDJu=j08@ z*}9uGFr@(0Kr6rd;6BP@?#upco%9VT#+3VqwHt%>I^$y`LSS{EV@kvfXiZc|L7QY3 zy{;&!MP;?*EZJLq%W7u|E4WusZ}MtO?*s|-wK2gGrH}6tGPh}>?9ltl&1TI<0tfs_#z46=U&;0b$U-|3Lzwq*WW}Y%BSyC}9 zrLbga?_rG*!5?pt_Q;|*=&VrDssNPt(o55Oi?JG+wM7J9R9L2NgQDu)%bb}*lxSws z>~BWe>l7ndCKYqD>X4UQ$Z-wqq`LO&+9{PbEdRd4!75mhsuC($l;f?aWDAWgak(V^ z^QS*^*bg`gKmOql^h3{*BE<^Tbr=V}|KWR1N2vo|=7l9Mzca*bomS)VUw+A{`>n|4 z{hHrI+}oIL_WHNZ4|DeyTk3RmysXypiLG<$(wB7)aF6GWK>A(&n3b zwf1Tcrcj&&BV5%wQERE$l9OT4R&>>7S`XpoTnjC=%`pKj!Kj3luUKyxhLJD?tP7G! zDKZyL%UUQ#5~}$Q{4t(#gv+4JWHnLgvlAJMyBS9$$I=!p&E)c z3jPHQ+a}^PXic7zALpE8409Bx)+E^D23*3G?? z(zBo-&c1~9RHeSDgBK%NCU3AsXrXr3M>>~GNtt2`#t4-fJ5umcGhGWq7`Quo?%us) z7~TPvS_XCKC6k+h+wIDlugo)~H522)({o{s3(h~v+GE5zkM{?Rl{qRDM-k5&rV&2{ z_2UxpssRW!ZoUd&r6%zWwKK>#j-uRdWq&e8T8mjbVXem*VS_Zq)t0ec*OhsmxjsDc z`1r{6@rm2@%C)JGud&xpH)VBM|LT)ERdrUYTuRaUP_eTuqu-4)Eu+|+9lf8rM>J`m zUSq35q}3R$$5%uCiux>ut8NavzTcYd<*IX6FosT?_S_Dtqvvf7y>08a${KqSpxuF3 z+V_7I#BJBv0EFy0cH74qfK}(J?%9#LZsg7%Q7gi{|w2pd9;u z-T7_jGt`!OEV|4~1)~>jHp3{d?fLs~mVQN;SAJ<9-Lh7}=P_?|MlS;qe zMrY9ef7uXCYq9hU>NraZ+entnItJ?rP6c*!F<4Xa&Qh$<*w#4nc=^JQ4}anF!y`+K zJ$q*iq?8FZVBL)m9}c)76YP8Q50A)qEq_r(7S!i_goJkQ%1HfuLdc8>5 zRSPv*{|*F~mJL>+>Fy7-x!$JFcA4rw6r3&6PudE50b5w(jo<(NcbHN*4kL%-#Qld4 z;^-o+DU7uojz^BiGhrB{j?b8{jD1J`uZw8je6(QM%gtl|_-b?Q8)fMm?d!w0YwGLT zn68>>yC@c~&i(RwdjLq!Z`m@$IfKozE(9dfsczm)cz3|rgE-3}2ymF3WK-T5zWX+@ zE{$$$SmuQ<51;w*#~-;|p2Vg$fMXq}^Bw2&y#ioy3R1Sj7{Sh}(tDNb9Ux|pi3Yb= z2B6doJi}5j%M;#Nj7vhZtO@I!I2ROE)pZPRkTw-YW}-8q(=det<1jM01I{@DLir!u zAXzjMu*PVsmW?Lqs>i#1#$GbQwiJqU*t+7ZArZyF4iRgGu~L*aEbXIK=4ED%i_&yO z7s9DZD8;FGon#B*I+HXTD9)SEheHcyX{NfU7+Q{n`MUD-@XXWGGchj83Q+*88JKFt z29D0-{D89)&JI}P=;A-sk&=ZuQ&}k`VLgQ4rR|V{8LLKJ1g>=cnJjc_Z}5Wz9G&-| zngS^cWw7L`iv98Tv!@)8rz$S~IwyZbi z+su5qaCv^_@$&;uPfz4|VO^yrUFgnPZJw;vMoVs4WU+~@g-)|mo1o7Z9unWT3=@M+Vh&zZLjI~?S7&9W1TIfZIueOxnu%1ns-px zss5VoW0ux>q@8{DcTtK! zd39~IZ0B^ZH-5EO^n{M+V|PGbE42t_NC3`~ohJ^S;AgJRiI|}uwY*@!2TvF#>B11S zKe2VHJ*1Rr>$dq|QBW>WuT}{Z7B-4>pEJ9$uV%X)eLl6ofZ0B?jrA6+Z-wX0pV{A! zJq>@aS<*m8i#1fmV-0s~$9o&3HCBM^i**;2p|9(z*V%;GRMm>^QuRMJe|cjGm;R>8 zuIX5(OcX`d1!)LvtOzX(LvMwE5ei(UGRKwM?Z!Och%xu$cS`>*J6d0^jdssy_m_6w zzT!6U+kx*3fVLTle!N%euy57<$->_+Qg!k*s$h&TL>uNX$QYLjY4^QetmGYFe|Z7B z=XUpGU-N8spKZs^XvR%t1sjb)+s)xrK7PGj$>qX&tJIY(co4vk5Jm;7I}rOK8^v~9 z_V=h=v)RT$eS{a_T{UmCHI2wnQFkDTwvp*1we;+lL>G8lC!o?f41pn7PNxHRr!&)V#Jj*S92tfQYXd3EO(-Q( zOM;p(EPyC3Z$K!MlIQd1Kk^U%==lAgeupUoIT=U@l{i)M8p&zJPzhlm#YoPEbrpIs zH4vQRc)a8O{!AGB?);Hjve0s9(cEogEG3JYszrlBA_`WEC6+>rRRvTmB^z>tb%m;o z0FaH$==|$~RvI+V5z;C@RT&($^x^L9E&$0qA(^cvg1283Mxtt>DWDUtl*(;c`0>Xd z`Qsmc&-)MWCD7molWxm{ae0&rK$%q;)YO`KPdYch{83}!BVQvfbYdg{Cp<*gq zJhI0yUu`V?JT!-D3(RaPjCC{GRh=_xr((S{;O$yuL$1B! zrl|Gcg*8blxZ5qU%rnLq?(WWfy#K`MbRvw>-_?mq91-c=8Ph_}1|N!)m(;8_#|VIP z(pn&0NhNC*={IN<$&Hv;y&9h4G12z|AayV_1G&VsXs8t8$yVnpnV6e-R@ z9R-{sbjy@h=Cm@WM-lO=3+uXYTW8j|k`QXE2oO137#PNYtD|PED(kY4qwPT2Ai+e} zg!`O$gwGOZ*6~SZJG;>QmQqIeq@{`PQxA3IN|G{!ZQ+>5#c3>c?DC*WyYAo zFnTx`LiMVoE%zQ7N|H8W-fTVL9lDQLsJ2L} zDO)I^;#26|9ZD&bLG8LN*s9NIKha#15}Ac!*)~dXuBHB3Iw44Q-ByRKqPTCfs37N@ zh-sBpbJmbT5M|>W2|1A6NH7)W;Q8`I#gOs?x9h?(tNOPpvJcaN9trb%M#|;vPfH{vS!gP$*Tfkr>vrVCbT&?LI;=Lsj_d6lZTLS>x%U!N?EClver$- z*okT)r36Y%q#5S<#^w2m%kzcn(=*rGjrnq6o@eTsR9`?d&kZoDux0c88uhtn4;8Sq zmUvC1O>WIA08F!YI{++Jzqb==ehM8ZH*l!Va|2wh#<}eqRRTKJ7)((iCf!W8`p(Uk zw?`9!>U3cEYLD6i+_nFkwsu}`XEY#MU+y2!MWXguSh>R8xez;3bac#%??6jaDCmEA zR(j@FH^ox7YuBHqPg8YM-TUJEY;XH_6L_lV*ji!G*cOD?4Q5rF+no{_EKCDXeh=j2 zdiP^cC`w!10GGU|6lw*Ms;4f&v|0&GQM>tL2;eJJOwFR5ViQ=I$Cw+^+EW60VVoF; zkzo|7^x*sp#p&Qj*|)8TPX-rspAuWsFhO-&?d^6qclp~5Q}%zp_1J*!evYd@R5xry zyC-_zBoRMP35FK7d3%+5J2@S@=2r+_cJ=gq74vSm15f40+- z^>-gqeQ$2SLw_hjFYnhR>l+N6cHTd3<+*wTu=_19|7ztl=eov?FS>uIVQ z34_a0Ggy;2)1^lnH(qmFJOW%zr+!*Cux@qn8)q@zDxKLV0L)6`+>hr=!)sh61jFGd zRM8nRvZ#PNgCSGON=`Esq0_ZMRjGxC#~-*{ zE*Rsed7u_?#vKk{Eglj7u*Oh}I3mj$8N-3o`N%kWrsKqikMFsEe@CS<&llEpCg+8m zR@StTvSjmR2rG~~2o`OdLar8@#p#Z@u*6JERm%^wHU`bR?}8rMz@v*cQ6<~E&V_i9 zznvE&EVMyYJoHkB=$eq8bp+?NHGtH(mZCiyVR&h4Eq)}+}vIsJVa zWK%z<*K!qgvTBpShaPqKI`C}p-ZBoJX&f0Q&oqsE`1Fon{_>Z6|BG)qosNVMIG^vh z|M-F9;e<7#0NpZ(^JpZ1Bw4v4nITmtwKi}(KH}V{EP;aeg-Rl&CvLYH8v?b~E z(R9eFK71Gs0_wat`Xy)9oG50M%w>HdrbxC6A$W{~U?L#k_-{9o8wF2-d5`60!bDHy9dv^n4EyY+-Mn_t)*%ENpP--Nn$Sr0b z9-nxge;}vGQg5UjMY$L-lV$WHHdx#swBBk8DMyw?+VCv%LW)t=hCw3xhOSm`s!+&t zlC~~6%bc)QXx_$%sdUzAe|Lu)4mcmML4tLYKT>mHz9i<$%$jbJEvymApNg7#DGSaU zPGywwGOC+lEKOOwBK?TPq04%1PjLd!yVIfpEOLQVq&-lU?5}f{8XVS^?hIKA#yeaH z*x*&XPn^}-!GFYCPttz7w#qnp>+l+Mx6Vms#XzhDpEFBLq?-t5-L5k^CZTRO>uXiy z(b55GF`42d_~(l{t+kbQNc%SLe5cr=jxAPzZ^d?sswicvPhqybu{o@+2sPbUQHkz7 zj#I?AW`!F)H%o6ITe(sBAsZf^9$1#j?J9a6DHlo==lJ8N@3?<|$GdxB#aJh6prYbg zMShcom5|oNvYeSONd%`Z53K8gHCdTmRrlGJZ52whu}w%R0u}2crCwRnj9YKix`I1k zBRE&6SxXj@=rk<1!u4|Db`hHMa=S^d@l{$!T5V&Lv-I-a%I}29;H-)}wJ~qT(Ml=P z=34DVvbLyfd(IlV09`BPle$mojb6~UgRS4XbseBeP{63YFXFKn*>7Bhj4&dLt^;=a zQp=bc4Gt?`OWgGa*mnSMzX>#^nQ0DaZQrzIHoyL!uT`6Oc(D6*?bte9`}}Pg;jI?9 zfnU1M`PQD=j6Z-98!smhZ27DlKrKW306E_MQ59 ztkrkc&7M)A3svr;5%gd|54ya-GDcaDstaE#ra7WIXu0G*ehH{1s>q;T&oDD+Z{aWu zI0e35HD5vqFZvTtLHfXZC;PfHs?e_DhqahK)-v`WtQ|Sw3zlBpAmNLu%({(@-Hjc) zInsXI%TH>&K<7+tqF!w+G`3vrIPwK7`YNdM^+c;LE=S(8O{<+K?Axy2#)@vA#o+C3 z(#ryncQpsH_vfoGD5p6$lLgJN3Tg#cQDodoekB>;D~O~ zORuo^8tVn(WryrvF7B@epw>5ED@rNqKC`C@RCZym!YkV6>%;5;|4+TvzQ4Yu*{glz zqSvD6lN-IEU97y;>j8BCG@AJ{x{2WpZnO+R1S~{^Og4gIH=64P^cziJGnB2?bB`qi zEVV_{UaM4-`_1>xVS=Ytt6h%7*(#+9D2BeFfr#{^D56I-?`XffL2LaRd#etO78f!u z3$4;vT@VVcoflE4!(rrnoR|&+qn|`Mcbqs*2adyuk_>S%tT9v9h{=vI9I)qsR125u zmCN;_s;FR;4kp*{NHH@nH~9|9LiKnP@HP;P#p5KSkcGxHjU%5vedNQZ4}AP|&-vYv zOGS64mxRB!7Gl{7r0l(|aaOvA|N z2U_gjSwm||(rOLcYn!w1^>`ZYXLKW|jc)bw zbbA|Qtx(V{bth(0`zPw|07ln---8W!ZjNlkBw zj(NUet0fEr$LRy(Fyif<2haD=pu$+Gp`NB7s`BF<&J7rM#2QapGLH{WEb}5_hjAgLm6R6=JTQ|> z1XjjTf>v4S?J^d+-m5Z6N|fM~Evi_p)ZL;j)X>at%-heJDY0|`31bRITj^OVdImOl z{NVA!fN@?xWzJpkUex=gf-oULLTgoJH3(hMSVy%QOsGX_g4xo#5ashU{{*qEG`S3)mjavXlBS7p@!1dswyVimT_*~0UC6W1#N8K zWc4!+GzigJ_{gaXxn$NjlcRh-sfc0DMrro}X-8)8!4XF3O=<@bufha9w+AdHYu$c= zk}~m<`11IL@xhZ)Vi+yMFi5b#II>AnS3XEaIhQ1~|M^MVO|9ev%UZ!CN^umjbhEfU zLwXY7vN(zM%W8;}dvwfk+N%v?yy6rfXpt=gU1 z8E-AC=F|tn7_w=OebvCf-N0lI!t`ybXPc!AZ^tNl12pukU~PU^qZ%U#g&k;ZV7~!D zVJ>OM1$6)oJD|N280^RCoj>^cAqReuoDx6xYo9!8>#$l%uMsX)G+v5c7q#xxjnVQ< z?F6E&$O;9syO?UX?hz6Uc{NrvUr6^6!;9dA*Q8*1^_fysgmgz4uC=x>MfVSKLF;;D z|E)1PS9_i-TOgWlCTfj?8ifGt)a?z*9OWfrn>&OZEH^bAOp%E;KhC2CW?FkV_vP=F~!<}Qa_b> zIoP#jBkKkLO}jRoR6@IKTZd*9Z39DE$M6%5ZTnKM2WN}wybX%`V+Zt-v{rpFV0Aa4 zUOe8iJwJ7gW_!6SFu%I27XWxaP_K_;w)fazIGxYDyMK>Ao7K{ZS99YOHv&P6WXXbfjy@^7& zGvKWBt2Go%fnXhXr#pWBv!C8Osn#ehcB6$(|Sk?_gn27>Vcw|Bi3I`JTgc;&ePP4MVT9th!N&vz&N(c;I)x`3+Bx&n!z4=YBeK(yVY+ z06f@!ks){^{cy|A+b|APH^{r>HzZ}n<` z>2~a=54nrpv%A*1z5dptZ%#&-731hRo&v{H;Bayr&w+Oz&V2gzBj0@U4bFPzTa>mY zb0OMkyMLn!n5hMk=U!GXj zl`tL|{2(gfDdUY}2m{tvmUSWB7E(+YR;&&9TJgbicYepW-+ssG-Kc$og@Rn2WIp3; zp^Q}T8HSO=@LmEf<}8tMJ4uZ&gN#+nV)n6pwbScE=&6aAxS z?l>I^OS+Mg)TugaAw--P@UpInxGbz`Wtk)M^~QWn#5Lio7iycf4H5^~Dz#iQ7FtHo z#H5@tSnmklGL4~UqXYnp>NVDPr#{xi?Y8jn^jX@*%nM7p5z|VHi?q7RH*$$8M%Ek` zM^n*lz>A8uT9T}|bS|(x=xAz%BmvZ%3N>n*pIGI0Dl}mXqo2ou_d=~TUh0CSC$h&> z$kvifrn70(5t4ROkd0)`Yp_(!9JdI9#p7#bu#O=YhBYy)Nn1xry>we*O{k}hd!axv z*kWWKEcDE*H3mv0J1?0>qgjP&=)Jg=t>LnzI`NrgTonK}Mp|rUg&v;{TRpbP%uPkxq;qePAm2o^U98MfhXTrg1y|yT~*J7y3peYy# z1wR-Lhk$hh=hKnn@hBAWD!q$^c_KO#G0r^OO34>(r?+5If~eX38mKj~7!7Ew6D4I# zl)lm?d2-IgSV%ES%ROyt)VdjLwTHH^mCZah{Sqmg5u9o$PBYEwaMvbYp~3Q6j0PR$ z_0lpfJF~ml_U-w$Pn2r9IFqo>+J|;QR-{^;TCr{ZtMlFz*4r_yX0IFQYQWag>f&34 zue4RHT1vK8#cgY~)UqXFG#gS4sy~nvK&p~@mTPTUPvrE#AHg1n=*|4x}_-Syf;+XV$o~tTQPI3$6iYVF_3jWg8^ zaedz+tOW!69p1)VO{6eu1^zp;qd`}lDZ4Q=uhvwX6FqyZmu}4t^yu#fez)iKPPD+v zs}deLc$dFJx`KwR}Z z8Z`5_0bm&?0m8rwYC0%j-vRG-{hhLHl)YXmrHXKfq?c8gK{p#&pq^=(I2wY6uEYpAb}@zwQ626&tt(?R;^O0v{2P9xJK8K0aA>snaXj1YY@ zB`?I7Na|!tP0>hDMfqNaT)|)&$0PUeKJv{s&zw&0c>m$dx8HsvPO`OF70anq9v&W< zrXK;gyZ^v6PBK?=##yh;J@&+{Gh#)zc8I=L^d^3;0}CY*FAl9ylEj91fyZ?Yx()Q@iJ- zXrPI1vuGLOHV^ksJC&GLN)@VfF^*g+%MvN|8S5i1BwWqC%;0vrF|QYlDTFXEgn_{e zTf-TvRBWTQj?F2Rp=u6$1B69Y>PwV%M9wUw&#=aIHUw5`m7Vp{Z=8pr&E!3M!QT?uXk*K zplG|H0;WnmGsbJ+ra7I`uJH4hKXbV~VTJ=Cj7;ZyK79Pd>D_z04^+JRUq&eGv67aR zx+dn^jT9HAVZhr;@RsUr-)n2F#N|e*g_u?@*9*7#%CgK9y8;11)l!=vdwos9LRuDb zDzMJ7HltS%BaS{ly7}rIEViTVz$2h7!GK!v)>6IK`@gLrr{ZWn1lb#` zQ!NO&Zxwo`vF!^+F??H#P4ueMuys6IJ%81}ek@H1zV-k!m`>R*?F@a5x5-`f&dN0v z1z=6QxwLbn%|4X9U1-;4gw<#VY5C?y=|AkpgOs9aNt*YAXlV=s<2Vph89!9pJDA9Q zR-o8|21<8*36m;D*<<})e^rhu>!N{XgXxLX4subfWlUdxwbO3*=iR{Y+e}^qU!^@- z37T4X_1{`H`*nb&0d9lA_mk>IT!EUCI8ZssMHit_<}A*BZLJUTmic|_ku%f?-bgza z8)Wm6_AL|8y2aLAJ?pAYkYuxROiFvT8$i`XS#}fT_3zh<>D67OD?j!pcH`RzY6pN{ z-;2fr{;7NP*59wk>Gk{StM}A@;q~TYTcI4+Qh0uN;P!k)CWL^7Wqo3OzLAq;|JwIz zzZ-y6KfV7nfV_Y29w2lqTsLrRjAR~TE~L6@?T)I48x^p^6NZuV>B#APlFUY}#C7F% zyDFV1Ne@$m3L}c#2E6M=C0A(~lC>Xfi>z9$4YD;$5XA`K0AO6HY z|K@irw?$g81P>PGb)h^yGTc1FCTnM<)W1OX= zL|!6sUP-r=<#OTS#~=B}fA|Ofpa1p`{Q5V)CN2v;IGt}>eV|buSxuR=t|Ew|_OO}) z)(SYu1>>uX`4j*OtaHf+cva-!B^+o zgJ7+rs2aUgT3smu>g(>D7_{fOW_~Bn={#`0n>d~ZPREhMY2^L;d)~dfXPS-}1-!ve zSUUj&rB>D@>s-+qq@B{Ovu+Fab&=h``E0_*1BHtUp#BRG0#_SOW<;OX00p1UwQnpaDAU~y79)W{ZY}3 zbMbh4z?n%XUMAq2fMM?(7T*Ildq=E0m#=KO*&8pm4cz*mz`|op1e35v6o|b$h~|Jf zz_a1u@eA?t$h<7f`6_}&c4l3r6M``?jT3k0JI;qQhr@w!6af692XMdRrQdU>X*3!G$= z2%%L8h&K^VssA^4>liYOQ&G`FrIQyRD>F#YMO$UMcB?W~3mNe*auSwG3r4o<6cE}d z%+hww8bd0HOrn|~w!l}4_LQZnK1EK%99dIjP2yAKk{h(Zm<%MWm4#@rxay&9L~5&< z*;qP{Fm{r$*HM zJHu}0(>CF&2Ee*@LMa^>n9hCP{jSX)t()KKkn?!4!P%H@9!kxmEP{S%UWqYwz!`jC z7ze^QNM_O2o)oB{B`{huUoxZ(C~k&E0whYBMmMVtm}Cw0H_P5oOaIP2Grc=(Kay<( zY28bT>|5Siifan`b))M#%^(f~ZU~)jj;z#8{F0UxSBJngP@~@Z&adwMnH%+49mA>_ z>Z(DY=A*Q-f|tNl9<66|J9aNSXnVW*PF355^lYTn+F+yh%-Vk7js31FH*$*P)sozTyLp!2vBO1rv}-?N=L16+aO#^*K`7Is9q?W>TBLQERS`Tb!%()S z-Q9yWC;}Q^CIsvYAZmK~bL}+N_KLo4+i~^Y7}O`KFWx7C;!)h>)V>72tt@8`lB-^0TgM%2)q)EZjKdqP33UNu9L{S0-a$n> zw5}r;nRjc7Qgfa&NwXxtl=XgDD@MoEEbVsuCXiFIllls4s5ox7 zmB0M(8E22&pB=$RO10YaRva;d<8-{o`3dh2R0^pAO8f#GK9c19q``kdXT_U$~V^a%JcIVzC8ZO z<$7UFGcnJsab{T~YbslB?Yi~pO?Q*C>iHoU9cDN}!@9urqWdWAB^3Q+x zJ^%av`G4^Dzxfq51l%|>97f#WFu9QCh56}5y3Q<@E0>2ye)z*5_|qSM&$=$uT3D7W znd?>B!Whu(iA3S7v4k*cy8v-?jdv2At>PR8+cIgb-a;}o)>P>+y%p#Dgz0>_cAA6H zDR}MKuXtzeurD`-wqUyBxI2YmbF?b8E7;c}3$T=4;YF)$@xd?*LU}%&4xG*dcXuZa zC(r44;{N`g@4o$x_xGRhZlo3oERCZE1z&yt>4 zXZZ5@#$Qg)tWknK^C}tzVLWg;oj43ayLNUEp${V}z|MHBv=opk8C0VV1aIt@8@=-N z6fj2WtqhiGRfS%&OtnHbnbBwR?f`oX(t%C!wSc z1B3Sh*jt$ZLY1txWnK}%Cf9_O+FWe%`CxJrQ>hpe`i5>ZQtMVEW15n|uTpv zEYmn~p3WSGgSOcb=QuboYWix&tFshUpsY@ueSk+b`u2(s$d%o?lqh7Y7Q zkX$6&+;u%9IxF@d*FtW!gk_wx34pYFMpM9VpV7J6>SXs|xz;`)Rq5>6WKAAO2BV}Xola6D z8|jnoov;_3_Z<)qVPFWJ5JrY!WE}M0R$APRLE0`kE2SnuMi%S5oofIyZ%IpK}x= zquI0=v&iK)fgO#)nPTv0Gx}1=w$-$34s@HBwQOxue)fxx{ICD>f8js;&416w_a7Lh zdxmksgtHi-lsBNAGbLX|9OvnQzyJIHi_7CP4-b#fHVXX`V zEWg?2>dP!|-8PN(T@~`7a66;+k!D!42v@_#;?{L)gDL|YL>pUVUU(QC09aFq0Qh}OX0`QkF4`= zxm^?Ae`|Pu{|)1CkUnf-P(vq1A?8FFM%KJ?yyndVp1BR@j9VsGOMN8E zt63XwA$XVu%QSdV9CQ+ikEt-vncJLL*UXv=v8Y-!+ghG4H~#4#{u_V#^PljC5i>aK zI1nZgr?D8wnYtFzO(N-Kjq66ck;L@v+IT(8fPoiEyZR2|AtA*kG7dtd4Jul zzpr9k-NdMSqe_fMBS}^PdM9OC8IS4UxqElw{f9}^!6(ZwN`(1vI`aO*Cq91qj^p%> zl09)XG%wwlM%5GntHa^MFqT#hqxQUCKE~LdMfF~2Yl9yJh$z~T++9dE5LHW4Io(j@XE`>ra} z8UbrnBaNm-?wx_6D*PUttAt<~$3TjZ(}{W*dH3$jr}y{V9fWN&4g=E=7{?J8wD+%y zR#hY7df7;8wO-R(ZKpO$7FOtn7_Bu=g}5f-BAp>(@~rEk%F3zNBeKu(D2pt`EKa7X zW|y3WN@y)kL0mZ3Sa#V7!l?={aiZu86^qh;dA#xsD zW$bbE9@qkYw4SqSFW@E;RNG!IfrU61YPqR`veyi@+rSjEmj~|{!^rV?;&l9=_3Bbm z;gMk4mg!T+-$?fQGXKEC;{(rEsXH&G61-=#Ow+_Tsvw>QOl*)AX|>f`S_xozy;f(@y5)B5R*wf5L)KuAGcEIJD77$7 znRT5gt0a895wRoZo%9xWI_HqUtF+40`eR#!QKgxHR-3GvUCp}7{HcvqkyQCS2_?ML z4mz!|(zDvRZZ~Y3;(KSS3gb(H)wu)j7UO7LTV7c_E$z$l-qHkbThe6%AjTLei+aP! zZKaV_lV&Mp>EoAow0!{&8!WL_L=w_C838^BA+ApZ8S~uOYk9`2%RM|q>P$`g= z%h(-j_jg6`LvNa=fXryEw^30|gN)@c44q0YHT>FZy@|Hzzl)*MiF^4(JCHsLTOBx6 z{Q}MO%C&C+j`lTW-z6jtX8-^o07*naR4CZ0ZK|4^qqr%~v)F?M@-@S3oYKQpQQCXY zG)_W`9tK7)`@q=tt=4AL2qVc^kF}n`$zEw2bZo(Z`U+h3+p;m=_Tw)s06B&+V5*h{ zXsE3Vi>hO?Ws5h^U7^=pcXmJvfUyB~(|nx%njEJA-)0kiNs$zjL~(LvU4`0GHBBSY zUs0|d!XQ8+XJX0H8?uOjOGOvGX5-MFw4XkG!@vLc|AGJX-~Ao$?(T8J8S6aRjk+N= z&t2%%IZ6%aAAkQ_{_!9GUsa9GyXeB#kA1=P>*xFHuV3r;OaE#H#caPfQa>B$+yTe0 z4)_`*zkbx0f40M^5B~K>{uPkEKbWyVkPU9{$mg)T?A`I&ckH(0Rk*JQeD)WtSz)_l zg|#S)h$~peVPcvlhDn-y`#~bV>ym{6mV|B=V-gXoxRO((7NJ3}%POsi)~$t8b?sad zUUW!y&{{A_jdHHk3^B@gOG73Mg+nsfxsshYT@F#ibyhN=Pi1BpuiU?1vB7b^zvD0+ zvDQ;^6-U)Mb(kEt`NH$#BROVlajZ`ZKQ2G8t`h0bDU+kLx>%#sPnBBm!Lt%sm&me4 zmUU%SmIbi2waOAjwXTUPWJ*cIbS345RI=9NOQyHiV51wE*7rKivU&^0!@&D@?>HY% zjA6oA$#UOr3s27%F4r4Rx0%Z=vPP*P?&TRdvphYqT%JVne*iND+&GA`t16(HVyLlD zq8I>^=-@Pjf&2IG`0)OoX&SLkL~+I;FopnG9Hc1>y#M%-clY=BX{1`ASkKp)>+^-D zFOU4`kAEPpGR`~GxeMgHj!JIdrO)Q}kp_Ng`}NzAtsc#;djrtc$qr0wB>MHbwVJ`` z4!hda<|sIC8K=PAyNQn&U3!I zK&6_l|per-7lBlrt6)*(tzWXU0LscpOdyf56$1;0A&lrB2XEJ%6nN zZnm}+_A9&JHn-i~e&b=b`)yPt3<$CtSM5n_yHEHSw8Jy z?1iOKjjA4}LXjR%*l4i{tcNvLVluriv1DT;Vpp@YKoY8U5^V!z0${2fKO0#~vekAjUe`aGMHD4r6r70aaH|7U>y*W5Uvkm< zemWR)-U@K8k(@;pwyj}nq?MF0LLDD`U>XB==QHo$f8g%?4dXa5`lDod8Pqv3ozgCI zK>7!l`piQvL=}F+ft?PLiSp7u!&-yuz*!t-3gj4>=gQ@JV||Lml&MJq!>LNb#i`!F zs3Me9D{H{2h@aZl5WLj3t5UAlx@_lE{7X?n308tNK|zW#39NStNTvR_=17As#TZPA zz=CZdRE@OvjHK=hMgyD97*!${;FUGekXyBmksxHu0vPiwB|ld8Y3ar68B`IyA_}@` z*GfjdkOtW`C?vpHfQVCjw$p0sWe8sj0ckmo0>Ks-ePt#$AG)DyBVtP;x?gFG8DSVn zTPo=tE*TT4>z8|Ey$X`Htnm|>6vR# z_kQmaH)jfEVK_(7`||o+``_&v_v*!Rr2O(dI(bV6jr)G8V2YMc)T+R^0X-dilzE_I z&;oj`ZhsT(m3d&Cv>%PevN+jmmf?yUL=z&65@>0nTEj5lLy!&&!@w|1BDQ6eoz!;J z()L&JI@@Tsy|>Wr&r6i!c9eU0)@_;y?fX$BXx~aR4b=LI;@p653wEg=*ZXlpXNK$_ z{k0t^_G?;{_6oJG}-EOm%RF1}{D zzt5K|56_SMczK3lWb_lk8gk843^pgBPTj7|w;Stx;raQA-~8%V{QB3w;qmdAE_}70 zENy6a;Pe4y9KFebF1OtpZ1#GIOrQcuOIc*?^mz2)<;ym*>9cWr><#t&NdG; z(78SAc8-22yYE|QlckO4?zpzEJ2_O<2(m`ahaihbeh!S|#4sEgf@JTEvE+&Ss&*d({vyVqQ)9y;(D98-lT;`jxzr&LJyUU zv+Fc$j0ZEwW^WzNPs9Sx^Ns5|b7v|H9%BRDQ?k&EtBC5!8Qj+VM)ihiq*X&VHPJt?|Y*=YiEWR>ftRj z?ko(0<9t4H|Nfry@hl3E#!-u5Iz)zXWEijDp2+n=Q>se^ijxhLoiVaju6uA+qVGD9 zC1)iWq`x-I~)giPIw+OBfx; z)5zVsiSymaFnXCEgX1`zxx4$0pMC#xe*XQx;oZ9r)G~^l&ViIOF>0Ms-P#1Cl*nX_ zb{CxARM8FS=Aq&)N{4HTxl#uJt3Xu0D=<;i*RxVw{!~hlpc(Hl#ba&4aiPXUGLd3$+IlYa;EvFco8a4i4sHw7 z`lf`B)QhG_s)aQrmUUrXZ$#}S9713W5`%Xw6Y4!7KyZ~|7>N_COXM~daw;5#!0C8o z3ZCE`!{nHbBhxVu#vnQfwql*sDi)+?cu5{?rDmxkH0{6UI9OFv*0qC2$$gUP5msoW z*h;ZbqSZR|D*JwJZ5CT86Q<-o7f@ znWaTzE)bKL^ezI}_BSKJ1ycp^mu$&VY_zn46-O=SOzLfCw5%bEW`xvvtMaNUXpf_) zJj>Q)wDzdM4OQ$oKbet{J82dgET?0*tNdJIMK*Uf*Uvg}pNlBf&ee z7r>Xj(NY(&FD-aeO`($Ix2<4}w)*n|Je((ZPq40M8k?yS(4%YwL7KgezXO6s0XGUN z_5iO1B-nzwMT136aakBBMIDNlz_Wo>Ic6)LF}+<6x@Wl7YO4F(c5^UQ|D*9YjH;`b zTFD&{RxM*wu**IOP z_a45AGwlA|v%|g3(yKRH+sC!!(tC`z+Tdc^eUs}-Ram<%kl&e1ZORxeU!`_&+L$V_ zMAkTCXW93xHw+;#9wx?V1KB~-$g#%+RD8?@AlZMd^djp{2CV#Aj#6-Hy2qv;}E#N zzvt73k9>Ilp1bJ|Yc03yjmO6)%;UpWoSmdqQqGmqS_nB{gXcl>Yv^}q7Rzg+qL z`=9aQo9~$pNAS|Zf*83xJ@fSEKlAyAAGlo}d47K8hd=+B-~RS@+^)AbvE^$AsQr8Y ze5-%^*B-`fzH@)H#qh6r#tIbMqeYa;YuoYqu>+y)?>7=mZ-4HsYfzRzKkOUFX?|hP z0=;(B_cm`=reO_Tfp!`lhr`6-Fv{=afoUA^e#E&Tbp*yzstBE=b!EP-tgB>^DiS@n zLD~XYD>b^NSW?Q&*M;ll!o@5w7h>97pOyAQhvUF>7_d(25{D_^{1b+i;4MQKxPN!g z`}ZF>o=!r~9L32lNor87ZXU5%9-e0+e_{o$rSNTvoQ`+mz-B`&E0oH7yRj_N4$K>= zrE_>uJDnUyf0Ru@osygrkJl%@Jbs~EuiExQ$5yl25-DnZ5u12QCZ#Cqof)kYbJAMM zsPm~*;#T(3?winQAy^m(!#H?tAtU!=T_UDNiLYvXoUz*aq)iG41@a2KHu2Q3NIAXn% zdOfWPY|(>~B00vb25A=&uDW@^rl44LGi|{41(nRodmCt!HLy7xZ7mAj=l@S+tO1>` ztko{S)Lko4lMRmPU^pH}rYYdO>EPmYyyM$%f6jN`{2RXg=4ZUW{~qrLa+0E?h1b=6EA#$(|ez2ky>iro#d648|znGgdRfU|Q32EL*!I5thlhQmZIN zpN=PLDXe9d=`oC0>$qO8TrXF0mYU8O7rggU&wM&D1fgX%hiMu{ro+TRYi5H2hQSS@ z`fNuDQkkuvvD|l~jz_awy2;jUy!X#<`@;6`Hr3^xsMBawL`9u6j3HuFZ5|vWgEt(; zD9Y6)iU^kWORg%ZU(qaHi{$Hdm6GMB*4?#Rsu8i6HD_X4xy6Oc|3}%IZO4uz*Mi%8 z01yMoGvvw4s!~-+S9-W>_5XiFKlD?-^jdwTR;yG>i8+Qks!d=~+=4 zB8FkavEKSzsri z%X5W?(T34!&(i8g=hh}5)mW92YXx!vm5f{qiq&Ycw1pz2Ik!s4*+jHNbV?X$c3#{| zLh42ku+I?Pds_jD6M7ssLJJPwGUE;+x&;AHmCZ?04Os7xeHCEm9h%Y%<2YiBLMwL8 zYw3;{MOLtpv(yNeoY9K35keCdK-J8DHHxi*grWeb0-ajUMZj349$S%2I|vm`ufc&- zWDbror)Q+k7l0pSO|tBdu8nekve;dMQF2+^(LBRB;CMI)BVZKW2KK5r52*$AH2`4v zCfPIBb}BA5%IMc9_NT^;7+OJVW*+}g!)1;0K>W;=wQHDf5X9s-&vh}yB&VoBl#$I^X*K&ybBj%U+g z1iIR^%>CMwp502PFkkInmf2JgsyL?m9tMJC&dK#`Gtr`%w?^rEAaFgr0$o;NJX_DD z?`I~Mh{b4htTcFTC;7zK)b!y$+-@_ zHwm|uCTw&71HiKHvH@JRuV}3YCEVutjm*!H&qY9}$$I@w(Px9~HI>CCE>#1BBtf&1 zE9yLhSu@mL#9Vi2#4hi!lm%l^5F8`Ubdjkrj-S-4mIxO!VToq1Z(0SvJY?P2-4%`v-jU z?mZqJ9uR4eLU&vw(%O4h$-hij5pO}T4%;hHf%Sgaxby}3YjkFM zg*Py@WT^m|5kHtcg1(u`IarRV}~EYvp5P6>^#A$W&4Mht`Ry%5nHmN_9f zkESZ*xm@?t1Cu%q1?0K6bZJ#+7$Fc2hduuAyFcO&fA~kdd3c9m+9AdPF^poD+p*ztzJM#M(UKYu>+zX#!90twmgoUg6jhPlBs;956}U3W zoKcrGIvRXX<-v$R0dDl*%*dCFv?S!5@bTxLF`rL}+Fz0&5!Sq9Ec1*sFKAhnkx6Qp z%s{deRnBSJVT@70cMopc3ChIZ#*~aobOn6-8n}+!UM~_|%)AB8woc@i+u+-aV{*TC*yan&TmX3RAJvZbR$3H&tYd$Fc~EHDYP|f(CMoVVLmt%{!2X>5Q*mzv42Vq(xpUaL!@38!_#67>%yzJ;q_g`*-g!PSVqNb^IcNAC$(anT3rM zKM}!Ha*NkbAjG=%SKn3N+ zZQM9XTk*z{*Kw7$NNR>WKqPFn)uyN_v7&+Cbx#W(br2xcX~>S0@e>hZKo~4rCK=H4 z`GRF$P?EIitJyNIterRn#270>l)$CN(W%m}2?5FeEnrBPK?G_UISXK4h!M!4q=eF* z<@;KIBag}NF-;Sq+sQi6ASl715Md!zJVr){9^-JtI8JcG4&FOdEvE=9HOGM^P+?gk zj|d`%$dmNdNP~8W7{LPRqpJToDy=AfN<7elhpEw&16V6%xY>|V`J~EMY#$J?Rk&!z`NmBrIVU^5eZNzmz~3PG z9+clGdCN;hcNwcX)}RI_bipYW3|5u)*mTb>RX*El6Gj)a^1Af8RR!D1feiRIW+^LB zwt#)Eal=xj!;d(R0J|#c(1S3w#^Z#;;eh?|fN3WhH$#l5al*tCC^EmNto~+q_O~|zMllCbpA(j(F&K91vd&@L627vY~VM( zl6=U?#BR(;IU%(w+21cucz!x#nHOi?cy^aj`EQ+}D1;eY{BQsMFg0SlT>qKVLcA zmV){>AGi0|j@LH7Z(sX+{k!b~Hh`e_^mbnL!#i|roq6fj?AcpBj_VAk`FEu*68UPJi!=?k7t zGmalWOSa5vx|WQRlRED2@$LH$xH}xN8%6|YL?j3`gdtg-k})0ksAzaPKjZmwLTOUt z*4SxVDpsde`unCOqZH|VX@l;Ypw4YDrWHsAf~3B|dx!l_vwPzNA0nb=j?y{f zDLpCJiI}EAok_;vWP^nZs1$H;1KL=DDpfyHM+Fop9ke7cH*s3Xp?Z~eApvdV&>d!* z4`c?ftC_BkUN^E0{Ji#he`2Mu@@A3K)kbT_Qs=xk6U53UdGQeHC0J?(FLS|?7wmb5 z@4i3a```T$-~ZvyxWD@j&JSQ7)zFCZ*eZc)k%j6UXvy%kN&w4y><>H1qN563Fb+~z z2kOS++O+5_CUe@=>DSlXM3}}2(>~yEJYq>F0l?!ZnU&ITa!-h=Z0@~KtU?reU+`;N zf?*h>C#43!LWqb#e|qUN?J4w4%d%hqt|)H+dWQGK-?~BaCNp5pmr)^mLf)>PAarL> zur^&*BU0G`D4@0jjUMDG93t9M(5eF{!!ZH1fFaIHtrcKVNG&C+4uUA_h8Qu7QQC4q*(aO=_mSa{`WuKvk8OsY!ORdI?Nb$xg-?q!v3m><%NweLxrq6dCL* z8Z_vw8Q_LBYf9=cirtoSC`*Vp1_b(QrpERbb7GZMAhzBka8yT7Kys-Wpax?rNDc7X zPO&keF`+hE%N#P`e1Q*HocJbGV`iZTw<3a5)%p@|>gJ423*WT!2*d03R9-W}#-P!} zGrTflw2Tn|_rS8f*Y-*xp^$seh@m16q@b%}9;DaqFpe18fC&>^Kv(JpWDm3&Spjb1 zJhfJPD=T5Ltu$Hya9)9klitas`>P|%_Ub;Qf#}>ILZ_*K$RigL+HsYByk(cr_<-Gz zwbhu{pr>dEm;=$ci9ikqp=TFJpI3Dtb5(U!CU`Gu>drX?61zmL0IJ(TAUF=2IkMX6 zRw0?%)|6%(;iG6{0IYS6&~gQbQ4tz7My*8vJducl<)Zzug#+*OeOxO_VWga~qziIN zqL+Zxp{}){w$ispkl9GdQnFFe^}ZBlq>{0;g31kKz1X#vst8@l#3Cm_ZE|uxR?pOf z;iYu(LiFp^ey@X2+yQ9dM`00j7ul-%d5LO?DAG0q?42@6qSE%E-55f^;DacyZ(7Mn z0$FO2a)7&9dQL^&3{B3KQ47%=@&F#jg+xlo*=avv^QKMc~6GqIk6|2fAjWPQ!1D^h7%fD?i()aW2>#qefZlB|u z-(Lf}+he(#=Wc=R7QAof()DE997FA+8LxgQmig5xP^f{pAd|! zz_I}80#G~S`RRmO8QzKPK6($-h{OIK4iP15Cc-h`fXo?B&rkT}^JhFhKH~A~7wq?Y z#305v&ogq$I3DgW?nbGVq0sH-^v>6u4 zqif>CnWC)r5bhaZn`#Vjh0>0IaSXV>JK}i%&}o96Bz2o9!MTQqHwS$G{r7nP&3mEQ zOcQp)gy5sp4K}FiF2h7Cgz8r@FAF|?{)GSf?;r5#<0q7y*Qx8Q1V@}<*IW;XkUC-1 zH2U1ywcXqPd}Y18G?uO7pg!38z8*!tT2unM%*NP%f_1NfT5Sy}2?e#z8MQL*a>bwi zE>riU!$GnwR={Xx&hZ6T&!vd9MyaT_dF=HSq=n*OM{Zu|6x{ zK{5;kfV36L)B>hyCjeL#zAy8Pyku#`5eUcQ5#yw-RV-6LE7j3EhvQND<%XyrI7+YI z=(SHJe7D(hzPhnm0D{;1#pVQUZm*QFnRB$>9%=Qms-T)9Ab*l(@SNxX=z9qPg>~#| zgQK9pY5;9}XBYqgAOJ~3K~#K!cLP#W(1B=vlYcgo=5*JAmLZ420b@VjQFN;dTv76%_?S z;nkXb1*Lr+Gy&wsT(qEG18c1wYmZoUJ|T2Zq6UyQcygka>RON*<08>rZW2T*+Kxw# zv4Yg!@nEIO64Y-tyv=qQGN`&lxMFO~W%;2(-Xb5U!w9A8*ERog;dKMb+7(Ip<;aEU`*G#a}3^8f#tyAS%xS$3} zXs#t#h86HGpvF}I$B||$9Z3|UNUlvX&jBNI7n^cw*PJPgH_3|SD$FZsIR-GRYQ9l$ zS!}PjJyroq)f!b*vO|X4v&01eX^pb$t^N!ET1vHY6_Kf^FxnYKv{Jlzne)k0kR`Rnk?cZUw$8 zK$d?Z8fA8@=)LVVvl>LNxgjT2q~9n)2iqUyOKl=-fUuT#n0>1fz@o-VRSvyITh{lw zKlPuRYv_BKuKlhajdfmfV`&p=?ZUW8jWfBfQr$dh9lNUdI}uQH7EmafREiF+RovZ= z*be~@hdtih9kHLZjL?fxbRd!$*s{cI)b}E2Ku$#ySCC?JUe2pC`xt6lw-;u!0IQ$H z*DtcZCdp;nr`GW@+e}xV-8>ku>f>NFmYvV9$I4j%!E(9C;Af%i)Krz8DwLhx|C?9f z+o=H#s9vdzGHtL?Q#E(hu%}T_R90W27a*)@AhQ_l^Fn4 zNZ~wH~%p%w`&lU5fAkB=N zfRR%VL>k~zP)phQ?WLHy~ zmF^_jDhEPY65tB%-#y^Z|NIa5AOG?%c>B$J?2kuG`vbx-f?U*=8A{<}C$!O&k>(js zUmo$FfB6gI|22V`@$~f(1XgE4DUG^r*m2(wZs&iqiNhPpjSU-JFU<}BH*3}!yW8s~ zl4KO5*K`JCGgCwF*J!jjJ?lI!rJ~IhDHo(#FfYJd&iLyOKjH3Q{~bSndB(VZi)q>; zPIm}CqCsebj)o4FsI7A+xS;pF^^<9Bb>yHTRF1W`rOqX>{nv)e+E|f#k3M*K4QyE- zSz<;DjQisqcH@NUIN^;cemkXRnIKUqC^><_0^*`5In{PbtmmK( zqtW5|56u8K-V8|qqW2hw9d?tn#dA&tjorPji3cWWr`aW zHFQk|qr#I@Q7~oDxZX&ffb3AQATOd)p1WNUTjNY2w(2}qajQXVHqivw1}E(iy&JBA zav^wacjWtZ5D~JnNq7+Uh>M|9Z=DnRxp!`DrPB2LsR~QN0s_3+cLGVxIzxJ7htS&< z*5_llA-O3G+if_Gc$FTqN; z6xM7RP-;`1ckn^Q*WfqVV+}g8iET+=-=K=}##*oppmQs=8jPL=Z5o01&eYA<;Af}N z(}w-w+}8Y~!J5ix9sTAtFoSCYtDnVHRjomqy;sVyZXBfTcvIM=ZUE$!(`BdYUjO`Wqi(zo zwtww?n`7BVXxZsLKVJEqWe@vsDX3(IWbjEYqZUS~1;Llz8`zr)U$5oR$hOi>YE_j% zYAPlpR6ge#OqH<|>1msj)R0#dQnNYUNdMk20&Ivo(9nNn0e<+;pK-tcS3DdZaNOTv z8g~eB#Qt!^ad(H{2lVWzlOvta&$v9DaflHLV(@+{F=Zqg2dgwhqrf!%_I&q#Cu?HI%Th~cn99CjdeegIm} zyEM2(vPfY!Vt04Io40TA{+n+Qd_bBns5#5#yalw3{`(flihZJ9gDzuqZ3|!#mDjE1 zx>VFicE`)Izpn<@#1u0$1Fss1SHsE@Z7vFoa|KcY%9n)y^?&~dK0RNs-yacnci8Wb z*c~4*?e+-69>XwVHyv$j{PJ%E&@VS}t=!)~>$zjn>Aj1v07 zW46{oQKRpoRJ@;dz_i13m~h-3FpL90B-G!Q#hE6D7)EK26(V8~5FA59*of%K`NfNPXHLLSR?UN2g(f|x1P39ut!AI<-45}VO7%&9^yhGe$ zQYHQnB7&EIi1R|}t!_r;A}Xfjv`)M#n??Xwp{TrvdEdnc4St2b*5;vhi_ zY5;jSP9W{eC~Ch=0fgL7XY}rk)&T=Ra|nLI-SIu%y?uvi+NrRY?sd$lHRI{=3F*Ax z%qlhq@hvL>H2}?56rYiU$Gk}3tW?cr>;7ZCtmT}z1G=CYPwym%Y*Vtg4QWk9T~t_U zOIOu7YxGpIHN*l;#eY-kan;PCjt!A$I)peV`0*O#lhPJ$QIa1CNI9ceTB?Z?@2V>6 z7NF#Wk{8kFD53>Y7Ribg^G?ZkP$k_DB=cYFdKF-2C-#>H$qb61n7GMSW)rXa0E^uZ zPJ#m_d_+~&yxmXhPh0D)U#ab`93g0HGe>4eYtI~4)mCVloiu%%-rf*=bxuN4ZCy~! z`eaiRun^pU*lnQFUs;^(R;#uTlQmUx!D2#j&|3L!J9Vxb*ke{PIn7#Y#?-_&St-0t zRM$4FCXJq`4HTQTW?)bz4xiuldGr6>Mr(2fdD>b#B7MDE%LUWsln z1UKXyt!K5rs-a$Mg0Dq<8#g%85(J>nvwF23O5n-@^9B%|{w+7r=0sf$9;3JLa>~;3 zgQ$Samoq;7^b@{*`P8Y}LQiZ*gW`mhj&9B*>8rQynPr@b#ddV+q=?gKdEKAc-Y6OoLo+kiU)Nd}lD0_j;=38ZDlPe1*LU%ozyphY^v0oZ9_eoYyr zi=1ukX%!@0|x6HO)d+{cHh&WRhy6UFzed zE>qOP^?17R7p=!P;Ux>gY%kSl_Lgkh0={P1P7UC+1z4UgXqN>64pSU4j5{262ORfD zc&Du%YD38h^L#nQp?T--T|X#UP_t~hlX!H++kS;p+}_!A5O@qvD@v?a=~+Jm{s7U*ZE-0{#rdyH-_8C&GXE>u04853GVONE-8KQHO-K2 z-eUu$5pNQwz!adxF0J>gDR^&?`&LWCr%z9Kn$Ped0>g;i{($3~H@LgM$Kn0~$KxH2 zcMoW80f>?6gg^s^7_n$gS5QjQ7$lLq z+G49PY9-WSRALFVTivIqG|Tbff#4LJvt@Z22u(B{P~pjH`*b=fb%i`h-7*_3ShOpu z?s+mWL4q271R;vBV@Z-BQaytCyr5=@7^*LZrsX3wGqS6~a)Qv^Q_k?w_ZoKbwn7IG zV5zaBNPrh0Sc8m@WWt+@g|XJqYTtX1a6$;u#>Z?Dv(ijM@A(a_A1}?JmWl#aDtbkt zgqb|3ImA$fRlrWg6J>p}lQkGLAmRu*#ssd?yOdf(%M4V8FOZG}se*GsO)PY47NC`@ zX3Uxh!R1BNnitamf!N@rYo-#kJV9)jg8=q8XeOJe+h~H-ZK{%a<8A}IW_qtT=x_SQj#2- zE!){pOT}Ck*~`H_+@v(YIjNaehuzw4GH>5%&V$tN8w)@Jsq47}21XM*(qOO- zLPsskEZ~;~M<~1lJ3=5r^#+7kV^`d%w!;6(6}xr*Zq6*Q7u@)+iZLTmn~4- zfMko=(Dk0-H`nPvh`K_zVpqKcL2>JfHQe=kHjn-avtld)HT&LGO!TF%A*CD!Y$cgw z%?+==+imVevpH*HWvn>X(w3${OFcKcM_d|~^BI|EJU=~wA)=hQNZtRq+u_~YcR&NC zVZ=D@WInnk(z1Ak8a0!6>ZZV&r-84GVZ}k-BZgIi6PCpiNSWmS?GtnnTYnKGMP6EOK%bp^+;`P zjO8+e=S3x>#jq99i(#Q5xT>=47D2$e=nQAyV#(Xd(^cPeT(^^EU1)qorzXh2R=WP& zs~~jyeKx@6Px9v9_F;eDP?cXCd;5Lc=eL>Uw)vem@1@Oos6FiM+xj@DVcCHA?R>M( z>pT^Ocnxw;)6ceR&@A>(E$>51YdzyPXr$TQ#5sYzpK*Zibn10?YQYV zdk@f_uzxe+yASX1=YRMU9`4^E_(7>Bgn3R#%NJ4FEPC9sV7^?CmxNX--oJT=2*TH= zFCfQw^X36>-@QQ`qqMEa8M#(G%`?7y{fe*8&-lypGeRT`L%?nqad+I~?yv(75rl@_ zK42X0Rft2Jz&CI1ahc!ad_Lp!{EVl^M?5`0<8qmia*+Y&HDlN*<#lauVi_0<4wysY zyws~$tfp4rd`?*Aidw`Gt!fmT3csW*KP@|A3=W%vc7L7K2^-^4zl0pFHde4?b@KUw z=O2E+4_`jR|NDgK21G;*JRsDF493D0g$d0$3_fCT9-axY$)*&T;6Z39OBqJ3VCkdM z$3_&w4OG6QI=}Yl%20?&9@E(yw;AR>`#c_1jTEi&k zW(@xJHQC!50Ag`QJUhU7S@!`jB~o|*OkK#XmIiJl;!@6c!K+~yMa?t}O0%{|xMXEs z(x9l{ua{YTvv1e0z2;O9j8!C$?LN|-+S_9r2&O2t*hJ_eSv&yVf!iJ}IK(m|fzk4S z+Jw$*8B^x~P!UHcc+DPI&7WjPxdB8T!HsYs!Ub`Phe2!TC&~2g4}1By+he!e<1if& zLIh`_))NZ6mkgGGSb`~NlQV%c*50|Y59X4!o;yi|JOo6og*Js;%c$hmwAKyc)Ie)^ zRs5xGXwGtd3TlmZ+=SLF&U}%6!I@F3LoE)aXf_cJtrBV_IMGlNprxGvTz3Gy0+1>S z*3Kae1IB2rR5V-T9ayQ6DJMKXpKv-|kW%S-DCtu1^yP$-wW%2(Z535YM#v357OB;>c}RrdR#BngJ%Y9c^c1@7uC=0Nt@qR{BU>O1lBg&u z`~nik(Xzm<$pjaHEQxft1|3Av2dGViEAx_Y{`w38!B@-ZYIewJ$A=&_yp_GywCfzu ze!5NpHkxK&sw&TG(6TnCKtAeslLA7?O3E>-#Fkp?&VS>g890FJ>U(-eXt|&yW!tEe zW4@bLTfurB7JPS3dvz;4TG+Cy^VX`d1!TXeZLPCxt*rppnY~93z!M}uU|Bd}PYA$k z#F7lKASkh@v@6`IXdo#*gHeys{ilr`W1w->{ocb9E0o$eom)P9w{5GVD0`HBha@PV zK;5p-zSr!foyB&4mEiNW|418v)}}zE|{VWurL{IHUdR-Uq#2_4OQEa6;J$P8H;x1Rh(hNZA8f%29F!#>;k^c(e1y~eLQ1TpRh-}0C+kTqD%Uz* z9TYbWzBnyO(Yat6JWzXQfh5%uVw*E0ffROxAZou}Yg}ZrlgUtI!>k2F6>t^}3c9dm zp;W6$XzL=7@zprHrKxqGi8hOe)~Jy*YzBPWtb;z=*PCsVSiOc<9h}>r2FSJ#@deBw z;QpQ61iBjxyQ#H&?a`xA^g8Z+0eo-Yum!w)^L_Nn`+ntIc=LX9Shw#p8}Byn>7V6| zc_af9H^=Ao^jg#7xb@Q3XqSR+-5}QH@w%wA)+u_SYK>z+h~nru6;H@1<8rxRSu&PX zO`8D*%W(=B&S5DTKmPm^{_@wq;OCD& zNYsX+~6)cmae<;&J-5{gtnFx)oZB3BD{`2NG83?w+nA>)HPtB$?_pmk`&g#w~+1}pi;@af|xJUu?5l_o7(;@H)Oy_cFjQLZMXH$$?yY^)lofveWrmNg*6Ui<$> zF)_^vrLz!9YRHMuvJ=X3V{p+(97*jcH&cHWg?MTWa1G=gB!8yCBq-?c0e;vB@OTgB zg%a5asIB63KBFeWa*@_mO!)XDr+i0>OmtL z5LY1|C(7WJ25r&eI)H&X_hLr@IEO}7#vx;M9{~W3mYH-Fa4M; z+u2$Hz*^hwd!QcBx@YedFcVtKuuQV4+&Tr$v|17N^Lm#zAroI_c-5yKJ@cMEQ;hYAOv9-S?}M@J`krv>e!2X z)_adQ$ay&vySESvz=il)7)#DSHRy`z8-C1U2y5Vf^mmrye$T4_#+ zfupTU;fUaMa!U<}rkQkK*-i~hQOhFQR?n?Yt^LKD&uk~!YffyRsNKuA$)jQeI$jpd zV=@Zwi$mQU7u~QhG?Ug(2G<$iTR)R-e*e`k*}S~*oBQWppzfFFXnuZYL2CU||J$x% z9iE;A?x(&1%J#RN*K5GvspDvMB{~}b0K*V)I2>?yf512n@S1I?rQ&=#gS-dR2~46m zZhOa7wptPSFbueV^9~<=_d9&}!|$;_-go+N$rYI!nsbP|9d=>F-Qf<${a))29flzy zI^c3X%Q>_k;r)mq?y=uJU}_DiWcc9G7#Q3n>Z6tL`RgwjhXL;nZ}8p22ON%j$?~Y6 zmC%n99#2m=FJ}RA0T_bEI0PK;j+*_EI{C-1&-mq+Px$ol3!a{yG0zuV&SzXM3sNeo zhOPIH0P<@Yf+OwS9K1S)(0;Q5$a5+b$W(th8mf3S>B|yCbbJ-+ab~w5#iaHulI2IskG{k&plY zAOJ~3K~yhx7o-7%l(5Vf{a10FIV~PWIaYS?zFgjo#yW%T1fSRb(S~jD!3aV8W z3u{DMox0z$9X5{EKEkfVIjQjhX=@Q!Bwn2kEv11o1ymUun0l>`QjP#x?G3Q0`K7CK z=&#$&v)$ztaN94*jQHlUW(@3JuC~k~=dX={8AI=k#>$ougSGkr2kd-XpmmXb4r-!8M6kzQfB0wfh>x7#EiuYW5AI|s}8|0YLgkYN!vMS9ie5A zccaJQutP2pAvmHcJ+1Ov(!j+51#qpYs7gl3PXdlv zgN23Ayf~o_l7TBIGL{u!$8hl7W925mW{3l(X@?<1Fga9aq*{92by~EJSt)L$^V}FV zY*9TcmC)dntOpYDIfu@awQ`WgK&iS$JON%r1e3N#p)Yqs zBgz0OUA0;5v6%^OKyzY?%o?a4!?p*o*$xw{(z?!#Lq?=3*Cu$?SnW2$DFcM7WM4@G zxc#h~oKFLH>7`1lebUcaF2`wB)T?^-%e~0G*r$vl+ei~U{j|9QT8SmD8FAZ)4fOh6 zW+Ho#Tfa?)`#1K+?H=2@)wJ*4*lcwY$?5g7CY)5XthcZsrJ%Fk3%+LXh&s4@-U0Af z?Y?Drd;2uDx2}5&`}I1w2_tL!u#7OPoo^PrSrI7ow)SAl>VWIdx;ft8@W;2H;5C-n zdV0!?YHLRL_Ve5O(`*gt>T-JX9c)f$R$YTEPRE6v%7ak>k%NyO!!Y1*yvJ^uaMRolV%RrR$3)~n42k10sB-aEOt+{&tg zCs}UPs@;xsL+DD_)MHHWW(c%q!V2X3jkM2qftK4zdc7!mhWC{T^jnYBNmd8Gt3|EZ zU^^j4n|b}p*OcJ1oB1PF-((M(i@jMmnAFS*@*huuyx8i3S{x8?v22df;j2~-rkd|`=Mia_0aFW+DA5y z5pbQsuzS~31Z4ZZ>(82UuvNj4ov1hnVf_pYQbC<%*%rF^BJE%eZi-X&-n5=qa?;W0?RIA8WVPhihTt} z7Bz4- zUwps$xcctC_nEDPQo9w#I1n7WUSrykuqCq$l=ovRKJfNw>iBL;2R1*#oC+&*l)mB` zxY9a#+kcJvEn7Z`WA0bbY-eX@B&W+TwRdP;c)xFbZruV`n`7(Te7$_?w}J2angZ@k zSOR#-W_|7W+jV6C-qs{3NHCymZ6iS{PzUYOFa|gru^R{c?z?aC```T@_YZFn;;5Py zg9Jq5AZ1N{6t#3MYiVsAD`ru< ml32J(1d4=~qBg+i5T14p@LYZf7sMd9;N|}oI z77`#f<#o+>!}>~_4oS`;JjYO`pJ`eE2vzBd6%Exjc%8)D#2E_|Fvf^+5CBYYV9#i2 z29ZVu+X_e&+jJmgv_M1aj-{=ES9QB?^A$YVVsOxA^jk#v|Ks6aH6Hp!AaO{6H5+g< z5jQ@b{NUG5V+(#stcaNGzvrA+`~J5dzXo78FTeJkc5a>WOzSusU^O=Y4ngt0>Q_PV z?URhoQoJ1(%ck@Vq!CJ%wm>}~f_1!VEl6p>`NTpyVyPo5nURuAT<1uN)d4tX?IPsF z9N9)2;C;aJ^CSNK-~ScAeEf)Mnhaq#Mduh@!{QjT;>Zd%YqmOaRe-C>>?iS-eQOo?(ZJ3EEi1E08cwO znn2`GOF~Ko@EQeXf^$LpvI)i2GI8EHggBrU5!yOG++n#~ke3h!DI8?4*Lz^BJWk_)i{2ISL-qGG*|XCXWz3!r%}F z!Vm?#%jR5>QK85bo`Llwq% zBqtKunzRNnO0L$0H7V5~BB_02YfZC)hgTnFe{`d}h0E3g$^IG5AAqWCYTv@T_6M|j zWk3vjw|CCj9o0=h99uQgQIIG-|fdhQDRg^oucZ5`rC*dJblP^19T zglx?8EHuI|kTVCCYtF}}(HnG#UH`ivrcL!-R0X7idp6c)ME`WkXJsk)Y zL_t-B9Y!30U4)AbKF#o@VV=(dRB}VAq5z(=h%lAP$hC>+5mUFZfCwP*T#@HlYtjh8 zbElF|(}>Y~OhZH*M0FZ0f_o+D{PQ!MXK<_lHDngSp-WnDo-epOU-0;N!ueEDvn1J; z89;4lrGSwEWE2*qPliP6Q*M}-g!z*3^mM`FmxRk%vNYq^Fa*H4jQ!*=eg7VB9)6GG z;Q^=-t%!(K@DaP=0FQ_te)=n(pAtTPdPFVSmdBC&^g`Pd)aYUPHl~K=g1!dHG?N5- z5+@WClqTnSI-PMkpOJFzb%I8rRTO12qTh3yF*aA7&PUn=(S_pgrPj?4@GijnLHeQ& z5#)iTE~1Rw61)P$)|@ivSe3vVip$8}!}}z`BX8f~B`9fvV-zJ*<&<{bqJ;r`R=_pSEV z?BVud8E$L+BF{0ZD!=zUq1&=(Y%HZr#DX@zl{qv}WY^uC*6(lKMeMtra*VncR z``h<&e?oWOjYGT*;4;uzgSI}5Htlr|INrQ2Uy4;cWX)3BbEco+HZ{49q+Jx8lME;U zXw-8{Ml)|WUaYmQ+FqmWI|f?1da^PxnvPFD|E_N&b~G4(+Ux~Zn+m-=*{5FL&up%A zx<2f53`7as)|53wG-~zl`(EX4H7@$B@4l8?Gb#4EeqV6itCG2)_cV|&MRwzaHxCc^ z-M8Q2pZ@e`{OQks!o$NG#OZ(-Bm6MJ$EfYhg0w&az|Hrd*GkPNI4y0lasl6iX6A`f zXWz7@=hXn|ny|JBWmtKGD9D?#xn%#>xzCMz(nH)6(`JFL>4s3Pak(0Ci_l1aPKOvL ztv4E^j)om-krX*J(m}*81gY$IsUIZCkAnb~O)E5sGWJZ;W`Y8%fiuT!RZT-TXfGzt z-|^_tAalg6HequD&h|iT_CmWT-X2T-nUIv0820Pfe)MW^wjS8+sow-dU%b}oM%RjaGl<57TCT{K|v3V?>+hNR&LS{u_Eu*1K#@3vgnj6jsqQ z$PF-RzBNO4PJ~b_c;T#$(FHh?dMRoZkDor`^7JG%#Z$nvo3KCL;q?3-aM&MknJ>sWA!owl z(}Kq0@Gi@O%n20*4GC}+V{jOD6Q(JGbPhTq0ojr9Q18%c5z4SqM7$?>{|QgeGg4|D z&^V>k#R%;89uE&k+`m0yx*IU;9Y7V!IpgVa!k4d)`1s``zCN9CxyUhw0hlI-ySoW@ z4+rcH6Q+H{w2O!_z*;gbDdBXQ@%(hb`MltK&X|{sltsnU#1Cu{+|C!eT|a#@+&G$7 zyT2|l){R;bwh5iczNrAzZ$YS1ZFSN%*MI`B_hL7^X8%kTcw<*OGvr3l;zd??1AI+Q z)SKd_q()>@whXW;6iP(8^$iCar7pF~ymkykne*c=;@!J9_}%Zn$G6{ohi||C9^ZZU zJs$4A!8ncpMOfyjRYpol9OFvez)KH8QCKACb#EL3*>G0cnsov&&@Z=O>uBC?>U8yU z8?CqTSb?wWYx!jqk6!(qdA-+W1K0AGjnIe96Vj}}O=jro{I>UebKke8v<51E{Xwcs z8oV990#v|N=&_M2CqFza>8XvxXcn{J3TL0 zW+`c6Eo)jTAmUOP%n7No)Bx+e&AEx1{3YXbF1VZ+X_l?5<%$`zjL*Xk({RN1-~SOG zzWE;D5w$wF77*Nk-EaUZf&75~`mdic{O~iDMP-#407?e{Mz1u=cS8eO0jtoO^J_rL zsCJUI4;Y65ISF+*=d5c_=ei`I*6-LDEKt zk9!Xy58pgERD?!XLNZp*DdlU{gSK^Ap{*+c;f$OLmL;Jr(CmqTgWCNQ?JwNdh&Z!V z*&ZhR<24iG6l_$e&FRb8Xr;V4?$#eOK)iy6zK+G9>GQ1byUBLz7DBu_`R1g^8h3D1 zdctI571qCOZUE?9Z{E%fz^R6VC4vlsv?c+^YCchGSEkNRwV^5HSATATp)Vb;)ef@) zVAGztee^AL1Ad4$+pGm+U&8V}fLE^TCV+AkKqfslbe-rJ2vynEk-Z<1saGItFbrg@ z&oviq_S%jsWjFG~TEeoPA)B*m`?#Io)v?4cuzPMkdq2z-E8!ZPxZVN@UCgXq-A@hL zUya$dFR{_ilE5ZGeOe37tU+`UE4*eqH2Xq#UFy{f3UsY+GtKh$RS-*j?Hl^Gx7V65 zGY@;bd;1OEy?clI`+JPjB-CQ>K*5Wq3JW-uwp*&4&SC>1d3f&-HIzY4O4ouV3^s68 z{2~b;nPR;SS+~u0Z=F{g=rsAty+Q>xdWJ(bK}u4kR#wUmS4L2V(e@6)vQa~n+8=4M zu3YOXs(&SCiC#2qd~Y;NvkwX)Ei=RFJjqR1dEq**I#t4=N4?2*M|`+)e%8}{x$J*E z`@3~~v}WK};p6p?@U>0s22i3n*PvNnM*FoxZ$RSpiOY{GN9^j}{ECq?(Ar*k&g{W! z$L0+%Hm!>dV7~QtZ5+0rv*)j_4Vz)wjGZYIce=J(=2{yv6_8(RhSY7*x*TimAPy&k zVY2vypnxX=aH5=>Gs?2ah7yFDH-2 z74vDq^Vbuezn<~jMEOzO#leFa#vzaX-3Y^$ftyA=NXsM>2zfC!zXgVwRTO6XcKbeDO(dHO>wD~8-UKuB zJ74T2S4M67J+B*b`@Hi30c${*NvZDC1cWuoY?32@2NbSI3xImUa!$ytX{JnSe90@L zfh9Xf9w^1?X`tYDz+pe(?*523_Yb(cyMr4>$#|B6rhSD|TJZe*h|A@I>Jof#fNx;e zP#UBy+LACY3(_TFxfCpyijoBc6Kh}F%qTUZ6o)tqMc?|8mm+l8oEp-FQD=aQY)9gt zD9CBRFig0Ac#AjhzeQ~kOKLzC#p^K~;1Tfl-HdndzQr`$~gQqQ`4vV^r_#p){-hOVM_$>ao+NDJPPf+*85tk zIv|zuzt*FPpRWq*&Z(|I;qBY+_~SqPiNE{%f8e|CKG64joa?o9P=~dKSQfr~{*3>( zp7}JBPZPEjY|%DO`uxd81+)s$h>|zOk{lT8C};rIRxl!VSmv807fUHg1bj*+mqpj! z6)Z^B*$|gVToP$XEyF3LB1zY-6J?b3xV2ku39HK9@C}eyr7Ma$x@oW{XX)xuiZBgJ zDJ%_eZa@@5jjkYQJNJrJ29LIIDagN5jxDKysnurUlh(zjdXd%cp3Py-Ov^Xt__sDw z0sQ)fGZs`4r8d65CGU-{N1Z2$7gMXYOR(dYl_N2rdvuCC?+3YW{T zsNmBD=vy6R`CAfVrfGyUW8KiWIHe7^oBFDpPb;O-{cT2s-k9p3);~>qy)^&ByjW`l zYpj`SSSiH?*7XB4E1z-7a>#7Nt|Suny04(`Zv*M}3{+n@^*P~mF4M*d>T5#LQlSoZx2{tAn?d{<_^lb<^GMN4tMckt zt_LWa-}S3`6Fpk(i2Qx&>2D9$2Kf1*Ha`1$?sYP6eu~V_GoWg>=X!bm-`Lu5^n3Mr zY=1Z3w%&Jr&fCi}^}cMj7690MFl**lM4CKZC*o=$1QiGo8c@nvYS6XNweH6{i*=m> zV_9%PiruBvk<|!rVworAc_xlYo{b6=ed&H?H|)3yJ8rJ8xx2mQYQGbeS_;>D&)d5_ z&JFB$*L?rsM?QRb&(-c0XMIzmmdulgs+1z;IfOx@@f~g+@xkLehYgP7^29Wa*qph# z9$veAy5Ml$GA%Qo@4xUcf_0fv zB55k*Mf%ZpgX8XP&u)2R?lKz^9KN`S|`5`|E40?T9HeRbd+K3%D$i2a{<_Fe6J zJ4XAXS=o)_!{!=k&!F1u7iBI=wGIlVRyGDYg2QzEnA z64=V3LYN{F@bQgZVT=q&o^xq-#~HQckR}&4HO%rZPS#iZfq7|EAN@-nJ=HeFi$i6&k}f# zMs08Ca4Kdgt+*r**O{;?*(-RLUcE(Cyu}{bl3NY;iq9(c?1WOS_%r83)Ms8)oF;+P z3YUy`jxGd(^J}n2?e_M*OKBQdW9fXrw`X41L_Xzj5s;WMi=o7I5=cMOD0LNV>2tKX zuP)6}_7qtW+VM+yW#I5~Ai_$mIRn3?TujEz*wR5> z+FaN;QkRFV_bIKQum)vbHMD0=-1fvZk+wO9SHHXcv#ytV-|aWPw?^PLhpYg$tWNsY zVXrN2Og+Etsk-(0w&14PLBr}aot>|O=LB?}W4{;LUI;Q-LNEPEQ%ampCr+o6v{%sY zyWr_U(8X0IkT~Ym=@BO&*99|pnKU^`FU|yMDlEs5qYsQ-54`90y2INZL&AH<{`!i$ zx8E@gw+!7CZ?4~Qb9K!y?6Jm4tzML#geIuikv<-09aw1%65}X+gXa z1xe1#)5OtaQj*pX^E{JOC2vVHPmhoMvQtn&~;Wb zxSpINr&Gc#5o4v^FW5jAI{MuXha=r&<}nf{5hj@CiDeQs(UgHBJRMH-JHs$ILgyPj zwq&d7pQhC@J1?~|c{Bct28hz;XU)2*a|WtnX-LKh)iP$1$U?VP1m1|~jtJ3I5d*E2 z)cIV2DA3gDi~c)jRo|@Ovs7DmK2oXqrv)a@;7gV^X z?$39Y{neiDfBeXw{^?Kr!$1BVA3uKN_V$kbe$NngSm#A;H$`$*<=QL)O{KszO?>(C znV)|8iO>x==h&;bT($8lt3n&km)ZnFCVouPVuifU{YF63e^-Y&vM)XW03ZNKL_t)w znTE378|#d=nz7n5*EX>7I(>R$8_vM5ylC1V=g-5mY+p5)>OxhA<{QR$OM5;yQ1yD& zDErx|*89+cD6j0_piyYQs%$F#TqoA!p&bmaKFa5x>ArV)G=XH>i2ys$dv961~h98Zr-W0apM5l6}5 z=2P$4cbkx>AYbjcLo~5YxUtE;-XDH5+Y^~cXEQr|2)A7jD z;lL7;)RzSaK4X2xy1cG;NDx$5V@e@M=9l!CRhEmD8d~cdK6tu*z;_+S*ruX9EfOR+ zo=!YIJ#jc5B!HSCr6dVbIZxMj?00+m&{L3-mG6K5BX7U|K!1Bp9s*O$jB^ydghd!h z!FeR~%m%dr}5a zoqz4ktDr;rG0Qq8!ZHaoLu*(|NSt*d`_GzHD;pMxOd|=hn2k@CwdNPZ$FGz_fQ(&L zo`I%FdTQ4%5hoESA9lB z*Dvv3&V4guOtaB-TQlUcbJLW7>;116RS~Cx(qhi9wVcy|UtSoxR`Ck3tS^*{*OUsp z35ae1w$bCZsQ6~Tbu^wmn|d+LA>G{9%ftVbP0Bb|KcwCt#ldI$Yvw9njH5cd>R7Iy zuRhM!H#TeLetVj=MbcIWw*t{i09?!9UQnuAs-vFh2E1AgzFJGcVtv3E@kyjC%$@Zi zmeLT@g3|(&#dpf89FM9%*K)4YNmz&OxhI4GUI41^GsCdMhk>CR=zUM{p22nsM7;uP zEm1=>8B!Dmqu4Sq3My(jtTk&1Tdlv3F)9GIWGA%ogp}csGtL;|Gz<96RmFcyszcuU0`MuFVTrp6TncFhKTR*P)i5r`;wK3Kpi?OYs%INc~4irFcebAas z%d2e@q`k3oo4`ulvKphl-}Cz)|G@V@{J?J52?!1z>kRWW@%Z$_^Wjk#1_&!5^g96V z@4s^Y@Kr&mM!%d@(GwN#FNK`FI6|>tBGLlJNQ3&WlfJ`UFjy~9K6LCr$Pe&dfANb|hpZV$MpZNUcGp@_H zu7F8&2g!hUotL&AF$xWF6jj*g!xNu>{e@qD{e}DcM~;UR)3^v75^&BCI!o7i`XPt_ zm(x;(T(i5Lu6OLhj$OB7==L}qaf+P$iIW*AMQYBB*T}VzZbWm0cq~kF#JkwWge>_E z@GZ;K7K(B{K2m|WnbNrxYZNG{Ex1K#%po{j2$W=`A8?Ugz@7I5JS7Q0&b29grH(c5 zRIfj`HYPde)~~#%_}*od=9|=IeXY`+o%dM3_7?Tqwnv}=4%$4aps8kiQRQKSEJ8jw zhF##zn_IsB{v*Hp{f~V5^ohH>J3<&J*)UHLW2G&_l5ztlGC!pe{4&p+P6v+1XTmab zJUlXvckFjPwGEjd;r04bZDAKB_%a?xaxV1UAf+$PpJlf}9cy0RJLfFM3(LY;0mAkC z)(mUSyq8N;cD^zOpuc@_ZuYX@GhYt2Me5WIfswaCA9mSDAH zDCs^7U>3c0OCe*ggO+@BU=0rsUzySaDMtZgQzqqEY6kT}owqXXf?r!P73ty-mziQU zyJnnFeM6w{dqVJ{O@L+tmxU8EB^uIVNDC6s%2u)tS)7P!(@{_+Ah&26pw<4@g3i{K zt>~Jvc^rirAP~j-B`%CHb2!bU3A~NO1?E%a-~aPJ_{%SUVVWoD6wrYW3FAG+CG57S zv7rn!nkFDAm4Yz|<1(%&?Jiil-ZJbQp_ialmknVtgvBy11{)H^4A_vFXX)LZiwH3e z!@%{`HCI>HbYT!}3+EVa_MGyE_1}!P9?25c9@mAVlDP;xTTc2=qLT5oPz^$2%zrL9bsJxi_FM_4@zSKac zj@icV(AR4SQof@Bj0$4c8@T>%i3yE<>y|ZY*#PKkcCnrM%XcdF+}h<=*Fw(sYpT;+ z|E`We&Ey)uI(@$R#lDIHQ@LhcpR_L7oFVaY@f_Flu57&esk9@Oq@S>Ns#{QG!EmPFoPdu4lamwPDQY2Q4JGU z1NTXk|CePZ<+vFeie;2SYhbMb-UjHa!I9$T(#D<`R8<3PnG|_At{$Tbd7w34HM&q@ zixy`s{FVYET69tjj7CAqran#8rC!q2ay#cb7}K}Cn~Mp())Lkzh_M#qO`C(Y`1&`u z=Gp5%U;Dh-{BZv7*D|-;zZ;e2wfUm&C25I=wK8a$kQJ+qyad0O`;t0RBR@(TlOKul z#kdgTA}W<>jn+sXNLsc)AEOvxtHCN$olpp!<;PFo^S}Sg|G^*r_V3v5_Ubgti7t!u z!(5glMJk4L;szccpZM4R`+xHM^vJl3Qs3w$%G8($&ftv2<0!?Filr3S#ENdOuDQLr zVc!qZG9+}&lVn?;pPotl#BTqe4BZXRb=+Nl;BWu%NB;J23U6)~5t+&2kj|5U-;`@# z$%W%Q^7#D3iFsV0m^H&#TaIAXwnsT@#-Z;(eE4rp#ICOeWDk*kv#*g0K3x40df{e&lJF-3dx=nBgf}w4kJ7rW^%Ly z+jA-t4_}`7_y72JK7amI+QB(T2;c%3CmBg=vMPt3vo*|%=Zt0yqbS4MjIoJSX38Se z=9nb|8dFxFo9PBaHXi3QDHd{;@jvW3c2_;aUUX41hGHF4n)&lDe_{FgCmv4|wW=sl?HyP|DEiqO{MB3YGX$>b$b7FCLm7Vvmq=z2icrC5X=l8Y$+SJ9g4 zL)AJv=L~rxSX$EvMotEU*83S{0c^T)oXB4sa4>pezflO zTQ%I<(wQc(R?cgK>sEpAnwc#Zf7kE49!&WbqwKG3?R#6*EVCXT75ei*d|MwRxg)}* z7H{mD1+J_w1;Dbe^}1`KF=V1AX7q4?Uri_Il1byb0K3U`doYlFOoH z4uH!TF9`$hJ^e7?gOn?pT5IgJ^W8RmK#mWdOA&~*GOF{Mh_x&c}1PM`hbc$fL|lw&aTnY}Q0<7BVnyEFdxcRqKpAD~1;JP)ZRE>+#Y(*^qFXCfLWFhBu z0hh3i?qoX{H(P$?y*d-ORO5?})j;OAF31$ApRJC_i~6b}nYNsfb_r$$!NyfXx;iCn zBDet78Jvd@gf{2=N|S8O!8Q1ivqXw3$Vrs~w*kPi(>0segtZFncLN_ke&UB8{)TsN zKjMAR%&k#`JaFAFlyoIMGvlniydtM55iVj46w?NX?HnvjTvM2k5t4sw`==+YF zt1GVeR|F?DQqRxNl68K3kQzrzu#QFsx2;n;VzT$M&VX8SC2x1Q8?K4;|lq_lE2JP8|4{rAD1Xe@i>-d^0P)+Me&mgE8uq)GVefFsh3X!ddMv zaHdMX&AQa~K`*e9)+c%|>fSLeeEss3zW*}nf3Tcf%C&c7#z zb8FvUqbGX)-=YSovu2%)>#gIA)L5mI=r9bvqwfv7ZpZE+@bvt|wCq{pOfe%OI-^wR zF_D&t$pvSeXdvjEudIfGM8)Gcvdj~w@x<})EVZu7BKN~N4OAtZb97xN839+wE)mVb z%tTXNu4`XDzrr?mGy`l{Sw49)rwU+uPw)2x+Y_h6;qk;cLz*JwKr)tjp1J@0nfota znWq_N9ep3@hk^@H+Ao@{blZFmuBxk}3?^q)6fjs^XRsaMGucEDyo$PUz|-%W=V~Eiph=R$U#dP=kR!Xx64vK^TN_fUd8l7!lml zzP9s}Smp&LOG*VB<(Srbf)}SWxrE6HYcp7B8QPI%G)Jo4VI@iKGwE{wEJDp zr_HyE`B>d1bD6zsf95uy+CFG5^ZG%x&s7MhKI<1Q+_$oXn|+*Zmp-Ve>xOB&GtdId zr2<+#kC#agfvl$0q+PuK@(kpasIXP= zusWu!HOK4j*IHoHf&k}sehXU94}AgtFV^!_tKssTbxdTt{{0G@w4IA#6`tX= z@0E*vw6;sApI}xot@gT7rB`hA5=>j2OQlkmUC<5`s-xo^!AthlZu}GPd{f1j{fbYt zW%1VQ5Ygj~-F{$qb;EwYUxkpJmAYIbwrHNkH=j=v4-XFn=f$5fB4XvbKtJ>hyFLA| zqwC~cU64`~+lk*0oYWBq>v2XHZB?Jdse(N~E|T@FOOYu?l%zESEc!wl5v*nkjQX(V z+&81(Ly*bny+(nJS5#gHpnfqH%`}Q2jnBGMMR3My-H{9U5D2c56ucKuoO9HOqeLF( zrHI(XI1ANPdpuR1_LkBJO1<0I%oaJklpNQesz6=0OJ2SFqb?qrLul8$E-ve5c!{jV z;;#RG?Y&x0t3a@xn)JMvqXdQH2 zhwEgpVWLKP7t$;d@RTwst$-*O0lifas%~a`UfXLk>-AgfnCHm-mj@i70pQvm#l)HM zcwju-GpqR1GL0gA4c0(Q%8Kk(thdp>;p$gm$cOeenFKX80{=6E=A8V^j`UL>Z4$Rh1-Y{EE$ z?*gIgBwJ|3L2x;!XjbAhE*zhqd3t(eJe`R1!ZOW_$BEM^k)zbdJ14)D-3Lafe8bSO z+wJK44(BYHs7>G_))j1LXmQ|dG@C2+U&}HvFC)`@Vp?XFC9^DGE1zE(OM@6V6?QXvIArs7xJ=jIvsg<_`*E(Bmp18AXZ@zoS#}A+IJ_z;5OHb)yRBQ}snUqpyNs(zfFvk(+ z3xoHBA(PFCDOqCaD0WA-wncbLl-ikTirnAd^XEVR7thbnTwmW1`i>BSUXHd8*ifg} z;NvFq+n6HS)7sX1V^@1z@5h<7*xa+%-L9==X`t&;&tY|9ZF@}yYyIBK@|W#aTCii? z=XU?UwTW|e{&)R`r5b&Iww@UzVkkYq9lLJNo0|-FVdw_NWf1#oPU0+;EEML$$TH28 zn6So3;47$8;XU9;s;0Tj3x~sj!{M3ZQChLhIf>Aqb&`G4d+O>rmO{#g;xjf{Ox%Eu z3WB#=Eql?qU4f0Q^h{-E;2p#Dp0{s4aeMO~PX~*XJnyW>+74?1r)j~I%n$-^@9wZ9 zc0-`s7qAm^GAyxBa-?Jt<)mzMNC4xE2rLE-SoJ|2FKOR_DQEVf7^#ahDyWqyEsF{c z=Okk(EtDMA6;W0uYd}iq)=QjOmJ@}-(05$#9lg(#<(cC&GffN2BK?(1nuy~Q&yQa@ z93=qijOa>8?Xn|fi>Kgh!8tF1Xp9EcL^WL2<=omDi5Q|4R#28;UG3@FU{aCmiLv&d zj!dV8JUU7)_#!M0Nn!*UFNS8UbCL3sq;Zj&y#ZNY#^aGx>(Mnc0~M5*#?-0hOY7WT zK?a%>v71`QHKTly@!f33t_^fryO-)*sfjLn54M508l-81x;l`$Uc6w6LeyRrcXkCW39z+`W^-TK?79dj);~-+vtO;Ac7413^%4wj?m@Xc!uiL} z{$1D77He47z4rckrh1Or=BljwTgSm`$2FVZIvzFvxz&?zf!t+mLVf(pYj0rpqQtfZ zUG)9Sn%~-n=(oDffB@lAit03ML2bJDTZ2R|d}jf~msD&jyGkj~)=ScIr9E!~(#|2e z0Aj!!lSF+WVS9Q>e)XO%bPR)M*bnr>mGm#K&y_k31%#Ar$pzKCNle)p zDXh%Ydfw{P77YI8X3%JY+_0K9Z$TBK13II$7cESVPMslLJe(1M3D?O5o0{&XjbUlf zo|M~dq+QI@k#QV}bCg<^WGFe~6bOp~n>bV1whUF zu~Wvh-Ep;eAjbxH*n{A_E$H2`t&<~ z`0;OebN7i52GUYQv;`4snaYGMi_l4uOn8i=D5$Z);X0?aPol(JG`NsbVwx5Xr=V(z-pR+hpK6^@QuYuNa$>N<& z!n%y_AZSZ6F=RqzP8qFVqygYkWPCa6lqnD-*yUw`ALp5vjue;0Rv4KBl^K$vMBI$E z_+FR>C9Be{W(Ag*czSvyE~7ZD76reeFldt{&vLFJl2BXxRH3Qb+cGr~taZ|^i*wZ@ z*n%l@F`-sabw1b5v!9v)E^DUuB~`3_@qE5&_AaGFo@G&5vMeMww|Cs!+>*29_Vx|e zR~8=vg(wu(7^Q}CKJxhV$mjc?IZaQPuwYH0*vyC@gbAnk@yj1=0t0 znkI57>~;g!R}%59CvT`=cD=5m_rKE5Yn`vtx}r)sZr>=ErlV5iwxCcxc;=XvT3ar! z+E;*VWsaPk-z(3Gi*IeOMV!BtNPYH6^U5*5;rOhX{vzjUj09Dh)35D3inI@mDUou* z;0S);dVhzv9bs|I%gmCkWE!(}Q0RrFOHoapsvgC!(sxBT0*92kK>(Rm)N{$vu5HNW@=*l&%XH@7Y~l z@x$+b&xh~6=X$us+8`Ycyv5rAYdk(r9IviPpFZ*K%?*%5yecfr@rkEHgfWuROfieL z!ZrFVbBw}lt8=l40ym}hWA{z@zO}j2tgMuF$xpH3 zGZ6#MXO;|IXUX$3Uw(Pw@H}(>@W|n`$oxwNOU9L%oMy^$z>x4J;S#u0~^*(0ZgBjEG$&S^G-L(s#Mo79_Wb_?7hV^b9W0 zbsha)bOEfkW~ol-G7Fvl_q+`=ieO=3do*$_Uv80?(b%7dVtxwr^ye*W~K?`)k*em$c^B>~1NWK(w~W zx;&Hh^R^{OW1b_bf`8)-_}^ATG14rnZ1m%&=8?E=5~emC}Mi zYfGfHj{OqUvb~2IY^h`WwJdij%C!Wr$DQp>)q20^vciF0c&^zCt0;47~= z=jpn@puXhpdSJi5qVHwSyCA-^w1`u^kW!jDHN}Z9P;3i$<-GQ@PRk-ev3U}9ZDoro zW!nTRK}z4zg^pdnlYoEMNf56aG@~ub&Z*S$SsCp$K~cL}=u>SEuK9Vnj-uR#N*x3K z{rh)K#ZM^AMQ`NBXi+qal(gMJB9~4N=VgFcr<6Y7hu51@A9glkI2=J~t0L%O5#u~t zNvE@D&@KOlo*v9dKHkh!F=wy8pP-{(po8`vihYtgSDmR*4JncYXsqJXBr53 zb*tdlDroTMZ?|J^_PL5T=w~hiotw{YgA?^Tjq+@eXQ=ADzLS24)j4h1QD14D4r`?* z^>h@4*=5Ph(+YlToj7F$vRh}Unz9;f1-X7_l>V$2QgUHBMSl7D3;X^r;`Ck55^?rI zWu3GlvAq*HHfnmx=swhZqI(dXLohS?cG~GeEJ>lzWYGe-x4#VF%s-fGA^CPc7<^a zq%=ZF6eB#qSY~3HrGKX?oaU5CC28bdoZeClT{jSJd$>}``(m(oES_Z^dAPsl>({TG zP6u*MbXNL*?l*NA-pdWPS+e;FCoF)$(uJ^La#UwKV{M|}S)A|ahoH|p)Afn2kIb{y zNu;7#Re65FJBGg2fJjyw12IQ+sAT>aT_aqu++GdbT7oMIEJUl%x zF0-DaI_5DFf@F7t(=0}|GI>qWjE3~jlt`pFBU!_J6*P&+h&_ud#yv5A|$an9?x8Kw2< zXH4!W-eAa>BA~SM25iQefb}ri6Q?DyEE7vkP%O>|td$k8LoRTGL=70_% zuv=&822U6RZj^q%X_`qfGA}cyapW{D%!|~ZmQ=9XKBo?2?=%ad!<<~TJS2O3dw0i& z_aFG~-Ft3s?zpk)R$$+TIzf^|BcxpzG;(JNDOC?60l}eUI}&TXI?HJE?u*tr;<9 zB;}~jxjL{#N`Q>lHcC#`Nu>Y^n9&+mpg1ELZall$F)j;fUKqzO9G@p1?@v5F9XOn3 zmN`+P!`Om1qJrwmg0Y3yq@vIrG1MxaPLEX0>F zfC&X(ywWCZ(_AqaoDGB^It$r2$lywcvzEb$;LY9snw#5Ou5PXw`d(|SAgNx({rw}S z)5tWAjH(t3$|_J(ca|wr$Ffj?^!Zi;W0zUH4Xikur>0W$S?$I*GnjH?F6QiJuMMD> zb?{%%Su-n;*_O668mzunsmZyj!PR{l^*vskr+pm&uNSL+*UCDQz@bu>FMzEvYxQ(p zvlI`qHE9hF8q<#P;{GV0thTbLo~c)f!SAtFG#9)UF)# zQzIw2@~qUoT0&)O=Z&(ib!*wvc0m=pm6P5-vb1+X$BUETqIW?B8+Y`>z|i$Auqz^t zy=1zr6R_)QEpyQNX0u_b$=(&Uid$#5!hB})1OE2*ic$*RWmQ}(qB7~~h19GH#F!~j zdHQa^T1PHkoK~e+mSiQ%6oH(@0Dw5A`f!DQB)tubs`)wRRIH(3k{F9`W_XQIUG(w1 zbWn6aS10OnU~ZMx8j!QPxa&P?;(*)xwLQ*j;J1Em1AZIr*{sKc4fri*&*Q~bQ}}0* z(#>aIDHYg&(}H)dWeTma(yGK-tk;^IBF|wOM^2{`<7wt}Dom45oSlOZRv@bZSYm=@ zzA&g80PNIy)ounxuS04wCw~6rGck!ViA$sy&BR*6?aej+`1gO{AOHAAe)#x-p&#%@ z0Px~0OHPD`M`G!?8g6CrolcD7iD`P~G*%iGO$}JUuQb}Obq8J7G3*A0VaINN&DG5f z`|CTdZ*H-DU@Vb&KC;Bjc$`_L1)B;vM~p{)j8O)J12RRU{4(*A&^A&gl}JI_mBh3V z?2hk0{EqML-m~9b6Ktn+-X3o~(|F>~|Mj2z+rRxQ|MCC)JIB)lq4Vs99lJrIWK})e z2ZwbAF(LaCE>B4C4)EO3O-8Jy3AE;4KOC&eTxp|OB*1m6)t zFWK%Q8RL{9^D=RoCgwSxWrc=5@c!L*{P6K3yM8ZV)L1fx=i`a;m!Eh(9WZgBQc0b& z?Du|`IPG~SVh_IX%#xiT2vS|Rg1~uyBl67k}%-g7^%>Q#G&^B*!+0b`4wXND0 zy-M?MDb2-5-EnG4)A^M>R|iCZP%c@i*|Ml*yNFFnnI#pzeEv)+g{Q|SuCA}y^?Ulh zBcoKyybyC_$&)znF4ONi2ImCymZClKgwb(0KH}^|Ndw*my20bDXE%8E`+<)iKMECh z*t6g5@Yab#U2LnduUpM}JGVxh8=bo@v@cB6Dx9@7b1%$xdF{@vb$yKnxLMqJB_nX&Y9j+k8v4ANVgHusEC#vVhi+~7@R3vMdXUNH7P!;md z;=2yld#n@INd{?E=+w5CLPwADmM#Xo>%bhe<}~BXs*s+O1hCLRr?a*>6%ydk+nf<+ zCW%cjz30uFH~jG*|A{~S>A&&e(+}+TSNLv^?|Ny;;XJXxk~3HdI0o0LSeh46zHAv! z6Vnvgbv>@^iP5nvh9yE;49gOwU-7sAQS6vLW6912_E*=udHa^Tw{O{BU*oy~>*ZJ! z192hGBlGEq&0ai&I00Go;k0?FttAiEicM8k4@OhrD3CE=z1(l_oB-#^Fy@IoMm&+; z751H@B+n@(rm~QiL^P|iv$0jR9bB9e}zuE?K4uI>nP8pr!6@NBhYuekUM&o$})NpQSR$6hLglds2 z=daiASCFU1OWF->))M_pzWnya9yLZw{jf2clM{8R5m_>exto!^tUx;t>IPYJsYHMw1U(MJU7ANE$g&(tf}W> zYrwW%|K=LC^luy7-HvK2POPwUwHr=C*DhPnV_S;k&cW#RYO9-Mpfa}VmXp-(Pm{qV z*PZXIxvUc4w$;~6EYr+MYl(dq=z102 z>Qmy51V7WPt zDXgtxiq_lKooycCH*JL;XYGBu^8M@L?z{+N#JC6ravV9Ho>drWtpyDph93G(RI)3m z&Iwqw?_*j62X*lhmq5ETI7Kpwy7m>1^w%xRicOeaxX5`i~c*W#>7ucD@xji^X>Lx=N4?_Va) zg|uXS#!lEDN!9*RZvEDlnA$>8$AZ&EPHN6XQNECgIWvwUvjX2naW$d@z2EP+zPVxO z0}hWZmb?^*mgurvj~cp0Y0mjDhk!39xGv>se<@xfubLg<3@$F`AJ0wzhl zg|Tp&N4`9K;WQ<@>lwlwH#ct>ZVbEqKrmMlm`XLWE|FtWl89)n=O)H=%v9IuGk@+1?@vxNVHwx2VT|?Y-B8RNDGs%$XhCW_8xOyKn4IZBhl) z^}}^sni>(@9A7|{Z_cYV4pR&%Es%vy1{u6%@e31)Q#=u8t?lon=F57CgeP?@3q|U^ zgi|HGZ@s1D0IA?z5aF{~YEc)v2-Vel$^fA+xFX{_6shk&6XYqS2{7g)2w=az;qU(b zANcS8{r}{TfBZ-GH*djMqVc36t!}Ir3UtvLc4I|n#2P1HAHy<5<_tDWguWxQP;92y zg!PaJQoizZ;BY(=e4*=%(4#d25{7~6ySLoE`zUKhzXR*Z*($h<V#K?Qe(-;_vTrdL#ALoLML|x)JZCHxrIw;z%tBUOAmRW73OzpT(1&me@OcO}j9`AA!LB^sq zeDi|-+kj@-obUQ&1(-0BH?347!me;KYlxkMG?%!xP24GcXe+4HM4aQeiN%kV3idlo*R#^~nV7>HdjN!qaBlEWs)>*-|SS zzyFnOjihk#`Iq3g`Z{Mp3OFlIC>0Q|cHkv%XFL8cYJCf|aA6apH8pyrhRSUGu(EzP zx8m&=WA{t~zK#2O+$_BPJkJz+K>ECP1mA&i7#qllirX|zOw*)lz#?>JkgV@8z}4Q; zce1F-f~(Ge9`DR)-2@LBXy4fVY6r#1pIU8my{&VJU=xSwnZtDCIFDSDMMN!C^1Edz z8S8rbE;BENXG{Cp!z0VIaI@QS+h4KoJL1q0(@YlxJU%@?aX3CPE4^@ui6utu2e~lM z6UWn$k`wQ4zvs>E9q-@01L_>Eh%725arrXqiCwlXcBQr z%+tc@Bo16t{x(HeZ7RUhj9)Cw)57P^UpXE|5vfW=)n^MaM^4ksti7IPjL1Y2dfh~v z7i_VZY%$4*C|g<$D5~aHQc+rY71yW>wUSad5m}>-y|Gois>Za|1P%bG3D-n%$_zqrR{A$!?s6)#hIseshUo&+Pm;_}$QY)L5DJ z9A5wai)~}mN?TMpKYMGSJ9MAg5LB>?56gvbStO%9tEOz!Y5V2vYmz9A=J%jp0}fgBU3 zGLsf%uGFb;J|)_?k~T)RX|SwaGc@3qswh>>ssJn)E6+apC_y|YS!!=YbW*fQyimyz zn@5qdpxQ1a#>n&YGtbY@Ov}tTj!fgsyv)qAC_U#TD`1wyh($AsdTF-W;f80N&bQ0l zZEka=l+prURs&47+4bsdXWegBkZ>M^D|+wN*VO4XTR>cG)uxf!YXI1owUo$I`(V#) zdOgZT=B>5Uym-H^t>u-zL+i)al~KOC{@d1lZT(!f>zD=j%vWcla*g zLnnf>U5__`&h}!1)K@8$xpWo;kg??7e}AoYptB4TD-LPQnc^0zD0(zfTQ)C+smzoz z>m!yvlgT>CFnLR{kcudjrfJgta*N92i^0w+;!q8^QHR=*mp{?wxWV#>KXE^=R#75?hJE{_)##HN(U zY1Az1Lf(Z}^&#v_b|;8KO!2{N)$^$G`ngx?N9p@aD}MjMHW!#Sn=kb6|>(JU)Nr@$rHC z=U;g`edRPgvcwZ9E#eSpB*`KRd)Mu_yZw%j@4n~lo44HV-!gQ2obU0zlSyg}$y%mm zVSfC|={RzDI!M6h`kKD)7>1tYEjdXILMjVsSwyLN92sYE6qb2mo)?xmavD#J}&1 z)P*CA97arXO_fM*MavN7YE^V&L6FKE>AzxMiTpKq^izH0Q?^)>5+ zl3Uv~2o_ZUoaMfB!N`Q!SqzEJ4@7eybY2wuy(QTQSz8sUOKY8Jv}FnkkEP{B)?jjs zv9Y_V60)%tOxEWsS^bI!>pis!d~Fc{yz855`d!bQ6A#Z%MB^wpOg9kvo%AL5mTV2t z6iO1t$r3ZCapw4Z6amACv_13|vkP<`SURD$ky-MH@f|rEWgJP+DAn4ooSEi@<^F+R zzCJR}k;7@?bQoF2g`5(`8U}B<>I2vNj+?y%JH?h-LeM#-LO2>$P=F=ETQNmBR|_^6 z?4oTRXOHU^$xQf8grq!lz0@m%r6f;|9XV!9j!Z>tZyO^<%41upk^U4E+$I_Yx&q&3 z_oNS28{;Wu=2_Qk7gcD+k$s@p)y4r>f(*=3HYHNxz%OZ`#6-;EKP)jS{W(Eau7MX@ zxy|6#RwQ+f*b3B)1Ys#TIpwz0h8G@j0V(04r!%93-nf9&>5b=-Owo0q2Xs-fo8ohwA;Fh-qP27RE`$u~3>t zR^{2G(P$r}cDd`cokHK^tP`bdZKYI-w9~0<&zh-j0DW^_+j~%hLrp|eYpa^jBCw>w z*RP-XAOHG)k@CXR>4A@*KH@qD7J`#DU2z;aJU{XD{K(<(%xQXJiBH6IA~S>08Zqly zlyTP&eERqUfBT2O<9DC_hPQ9taW#nYsx<*)JjqC#iMeDRo}ajXdS;#?<7vcM!*n|F zaDUHZjx6&;jx!|-b>nz^=IQXnX&i-GKF`dfh?LB8VxDG7f#G(*7thyUzH)qu0)&$E z#XcQI9v&WedU{}*Moyz-m5l}Kjfj_N2H0!wHvvKQI14Fek?PlIKgE+4%NVoPLa%h; zT0RRh2Cb34yCz$l33Q=nw+rM5T^Q-Y#BMipe4ZGOk&+9&^Xx*;&<|46ku#H-7|YUB zrAg{k<|N`RC1YF>hfBvtwuYq?N}8E$6lbV_Hx_Rl!Fo~2HDLu6)CJjXk<2P0krCQZ z15~RZLi3kuB-2QS({E@rmkVcg((1v_7T!83&+yL%ofWXot>Q&qfK1pq_E&pC7l=z_ zTx3jHy+2EwnC6jWqOcS6KLImftbm)A-M|ofs6BcMmL*1>k53$rCsO&9zTb1bd(U^@ zz30RG2j1Sj<=XGD#Smt>7lRvQtQoIut1LKKlxkM|x2VV4dsZE(=G*6rO=xO?$| z3nP2+oeEC3+t~tsks&yzq;dA%%k!rJ@-v6S8gah#`o3{`ZEIPZw%{0{wKZxC3bZpy zR>hlu?<~9ihABUiOCq{ioQaf38RjU?Sk&=h6GFw0T9dv+=6M#D1ob{_sBfiU{$I}C zG)s~txz7A_GBY0{BIh?%p@0HWV3FM<&*?Sv9=i9}r}xlnA;=<7^`@LN26r2D=pQ1g zW*(VY0O{}K%SaD*8`M-q<%(RnVzUH%yx2=)5UMYzEfuUG*%ZU>aNx;{XB=*>Db6tF zD47u}y%{ZqoFdcx9rN8SOG=!kne#L;&5?)Gne*v{cb;cYU-0DS8GYYjv&SSQ%jQgp zk?btSSDgh>wy*uZW6C68iizdn#A#f3IGq{KBWau|QM|%1bcEv$oWX{G>kZxD8Fqnw z2pUw9XIgZhixFa48d%IF6K5HFX2dD>4(kKH>*$9>*JsfSKmuLfTe7#L&Jue|TpTGm zN^(%LW`Q@^oVtdKuv#kK%Bg}S+X4V0j3t@h%{GfEkdiQWDAi9Ws-)`F?}!?E6k!=# z97(}|WG$m4KXRpGif`haWQvO^+JY%VS?z%I;#?i`8Z@hmvlyLUrLG0on1#9k^!Kbm zOcWfo@Jm)ugZja^9ISL*-Rp7-@el7F(nXCKzj%_k+Yhx$x0>2SrF-lcKo=O_p#&B z4D06A9N_Ky7e+=RutlS=wH^n%0?te0qsOg&%LV{`W-`8DbRPR!(%MBX#94K`jfyGd zjLj7cx3cPHoY#XsI(L!!&QuC>O1L@Uy!MuLMh#V+*tCtuYLwUq1zA?4%Z;y~bpj$r zsUj(^HNVXc+ZE)x)`mgoesT=?tmrjMbf~W3m=bT^yk?rt{POP4+&sO;c7@P;p57d} zxw)oumZYF>iW5to$(+b$CZob874AAX2>>p&y-Xn^twok8GEXyU)?)u+*dYt} z+8>Gc6Mz1vf95nUoW_Z967V{Xp`9TP001BWNkl$GmFrO<3%(DA%F9_WWa=sbt(9Z#P?b}q;NOWzkD z`z53Mg_Cc-bMY$w3I)1+eqU{VDG2`TnsjkhpI)w_MO@lvtr4|zG|FD|3sC{EGal;= z-VONZ8Rs)G-Lu4rncT`PVvcBqC8n~fw8q3_>3N>A)P^~w_In%2CP`o2REQeZ7e_7Q zN?i+*S;lC7$Qr_~W4Jothn^{C&f}R>ECov{55z2O&CcV*c^(<3iPL!IJWebrNe}gu zxVgE(+Q@Eav34)^A|@$~S|ZCh^YPOM9?s{BQm9f8wnU8bd0 zNeLanc_+j+YYlCk^Ho=&p2JocP*xC+F(Tr# zi4N7$s8(ON>0gWfu4vz7IllhA0XS_n*$T2XW4!78yOyu(zF^dGFGavsMVM9Xv<;T* zVj{WoWS%VwchDetY%(gO0RxqM`h>&x2B=QiId1!AsD z`^(=~Ab5E_U%O7!nJbOX*xDCaN#&a?^)O$e&V1>(86bhl0`hDUpzmzK+O*z-e%}_r zNEAm1zHm4WjOS}&e8%xG;JuT`tczHea6aN}!kVP?vARLXM%wo~ zp4>d++0ApVk5A~rfXR+nR%0OQr=iBuh$%76(k>(}6Z83jk|WD_A}tH0EaEVl>Wqu? zlBR^ohU@;w&9fVhyCb{dz+rdAet*Ody@1{O4?Mj4$h%LUIGsnPMM?`oZ|HhY$VQwe z;|TPPqP9|*GX-t);T*m8P8-N9c@fp%d6K@)OJP)n@7mkB)E?C?OK)J8@Ydl)u9iM6 z%sCRAqu=kiI^1w|c!IYBrg*&d^e)i(j?Q~kOP2N~#(Gu%mcZBfbmrZ=xBU3iPki|B zK_aOtZ(oXt__)q;9#8!A^N+lK{VOTX*kW*K?Trd9Ip=Ujf+{OmS|jL{=30Yk?PV<0 znfPq|>71!Quj@+RYc-vwy}xeY0(NpyN3-=JUL6Sx>~;gspFijM^JnyZAasu1Vc_cK ziqJXE<47?{`Xp=HtT_gZHN+(fEzxF~2SIwTyJG1=&-L+|SKoZY&Gl14*MSKVRW6=+ zj&z*p&5qGm(XtMTVZ6QP{{1J+BFeDOuWsnOKy3?CDcja5MY3*O8$-Eu3Ld}yT9&vv zP}PalcRw3@Ieu>MZO`9ojx|d8*LH=+*YcQx{k7{|>6Kpq`sT~u+uo1a8rsdr1WY*D zjBC3*Q!rQ&kusV=DOSovl3_{5m>43AAa)03R$)8Ce)dB66BW-rs&AT1Rp3S#n`XQcf|?v6a@u7)e>QKbES- zU$W?dlmg3%x1FQJGhNtGvRr4J7vi)qk27~4-|_a{JC-GCz)V;=IYwY1VWf|FhLWYX zyXmygq_+(Fj{Tu$KZxqRbqVYOCThAw2+u`%#uDF3EK%!Rw{+tQCN+Covel9fC+g|e z;f%P>l`<)rUTLPs)f(Nd!Wz3h+_3+5_vHaw@8p#L%r2I#V>a zB@;2nL`;xv!CEguK2Fu4od=sFSZ%cxRIWRq%vpiMg=A@39>xe=9?%S|*<^Mr*b>@T zTgUZ_Q~>j+TZbf+HR)iQm{zObuWNp@_KcAXaJA2+U4tI7+6!B=fu`B(%Q6R9XN5Hh zAh9?BQgu0tov#5AWm2W0LS(XwRC`g3JddovqgMQ61=^*xl=%vX(;ssdmG8U-N6;wa z-g{NZ^-T>J=Qh;wjosE`+l@9xo!d$Gs~Dq*)T-ilTv8LgY>6amHqW|d^A$KMJ2O{c zS(E}>K~UWjn;q1|h?Z{{D;dEqbmUHg>_OQ_HQ-Tw$@LkoYg9zA>U3Fg!*)NZS|B3U z<<@a;fnD2xcpdAvlRiBGo@3sSt_|&z;AwOC_!g4S?3J_2k z0c%iBhPmo|SY^OS5YANKTQkb8w#8d|bylpj z2{1Xzgv#>JTZD|V3MPFvxz<6KHMF5fDiOY@;@cN~hN4na%i=uY+nCVflUD+*@gMD=q?| z*+5BPmW*4LO;0g(I!LO*tKWHaZ(Hzd9dupC;c(!%zY!5Gjb_HUV6BsuE=iOtE7i_g zLuxcHsb%&BjLqacGtXz10M>Lk8zcfWSaOO|o0<{yj7j7aMQ|z`jP-=< zL{(3uv;oP2$Xt|bYM~uNi^z*ml=hI+Om|8;4l)^I|1{ z@ax-O$q8;h-ExlF-`NVdb}rz3Aow5@oECwV#aijkbx|3ki+7VTS=W70M`)!-mu$!; zx9{hin{i&Veqv0serC49lJQ%cr4OiR~y>~;gw(qm>rBCZYt7LxQ=zdk(UyO+P=*^8GL|bIBm6BEw2))s z^l9dov~c_GHO}@>EGZV^oQQK|nHJ{hf${tx!Ab8ad1B6s0DhvDHA;P{vj*P>tnIXh z-ZAt}#IBqHl4Pc*gnh`Qyb!!YoaemBQb=o#T2>NcY(9o_PC<-VTZfTS)T~)|b?(Ip zx7e_%$UCLxN~wimvWa<-JuW7+90`mm1eb6%*kweGzV^N{gYB^;CE4x)Nz{D(yHo%n++IkIuLRn z7yW#x;8%W5NwbYhx0K-BDfQJa^P9g>rZ6c;U(sX}2Iz^Q9}9mB_dK((Wr zF)pn4SD%O8o2wtNVq>J|x@+Q9R_Ck>PLwPxEELMJFgp>)@?F67d-~l@*fOD`^MQRY zVz>Llf!%IL=z@Uhx|i#H`A@eapKkA%?(fMt;hm)mS=AM@^a<@U-pRyUqGOq(&^6B^ zr?E)HHc73pB?zs{c-=7MMAlleSs$Qeg*4il+PG-+PG(tC-rE)`Zl~5)oUYOi^5s{x zk6YlYr8r=OV%(x03i4LqTO&2AV<*N&400XV?di?t-=+SqK(iB@dk3lCDW)#8d=X`n z<4J@$Z;$uroNY~3d--TM%A@fvNzYf-{m4!W7Fd==>XBRfg~+l<{ozIsdL1Wy=3=-r z<2aGiJ!)~Kp1EXFj*_`BO7&8MCaibq50>3Zjmb&qe&_Kdv|wlGc0K#9Cw0c|MVaJcmDGq{tLhP_6H8b72b&$l_`!y zVxC7{JbBK`Cog#M;#>aw%g?-i|C&$tcif*oFwUp7KHFyOC=uy-o~V5)g<2NStTpdELOOL9=#Ej8-6=H$UStszXGlvtLThw~@K>5OxU;W#i19T?aj zdyZFoUX0JBmb0dhEG?VX^*x8-hO7NEu6NHc#xl!(grf%x=HNt?u{bS3vBa3Uy`T7X zc+H31M-GQ0zyI66vhwVP9YR95*S_ zuYu>)S2i2xisn!~c4{ts9`kvoy1BStK+rXt@c2G2KeU4O|Cu0cJ)PJ~Eqn1+_Zo|< zj+T)qdS@l$W<1(T2p)2f@`4nJGdw&@e7b$$e0m@_L*A*dUEkp}i*F=)BDJ1K5G^Ii zsJ4EzRDA$lTLBD71afR-PKD_q!P$|lZ*(G zm)Yfd{1lhZ0dO-6;*3g%6InMQXp0**ESil!ED5H1t~C?gXz`Ez0&{7j1xKpmziq98 zCbqt?U&uYlGR)+arNDZ9>s-FNlGF$)&)5g3sF!itRf5w0_j;MGcBSEa}y)bxu z23s4b8J%w#S72~~{cfNidiwpIVYeq7j`aHjVSiva%Fn}oPu~yt&|$sDSclU>jkbjw zga7pL#JhL5Ob;{8!O(e@U?oE63T}q36Y(8m3^`eCUsQ-udeKP>9Y;gs^9~g1)-Q0F_+-C zo(m+MZ&(3kqcha=S-s{up&o(a8kMLYukN7D0#>%P7wYxYaWJ2cR}DNgU|c_7)_d8G zK?Of;Op4TKFY}DGGp1g@W)D;Pav$Ipm@4wVw9-l#GeVITI8w_Y(c4<9Bt1oCqoHkX zU|a@MhzrbPWb`B6Sq;<#_5%$4o^Ti#hKb%UjKj=$pSb0YWr?~`6~^(z&p-dj`E=s# zo434r`3+C5p5lza?uUPc@zDke6IY zHe+Ixy4`FsMk&h32HMb^uGx}h;RzF?u2ac+)R)DyujO2XwUAe#v07U%U|$5~a?X7G z_)#OT3(i}HgU5NmPVA4C!}Woyt1E_K01PpSaE(wrwZ#nLC@jmu>ET4mnWxX5ap<4W zy8}i=!>qA5dZfLL7dotFnqm@0k8?96X0G-}j>jurzIe`V7_jOr1{VlHoGYVTz^xVi zYwVj#d%M|u_}oUD$8Xg4AA#6rL-jZ-^|@Kc_C0m8zkJ}oa{XTmu72(N^|W8gRR6W( zZ7F8Lbg+Qf!fX(*YV_c#h|}qWHf?gjL;+5tS!8b>6U$U6*-@-G7pYSJ)GIbtbOn6y zgyiW$Pf7)n=q4nyQ1X`D!n&8#l6`Bm%t^EZ1o25LA?LtbBMc8oT4IZpY!?P^L|ed{ zfHj?zhU~974A+D(;7kX_l9t3cPTb$$a{us&`}>c?GLxg!H0P|PFGhOXd+!Ln3d}jl z25TNv*G(elNG=h`OuAo*lt5{Fqcx~Q@74^Xl@?I~wrfr43KnXH%{c}Cs?{Lx1)P-@ zNhUkyIWhDL58auui%e6`yo}8A#5A6m#z}P=)=Xg0{*}_sW2F)rtE%6+>6T4-hXmnD z+s`X7u{M#5{>cfcK~5N-@d3IZ!50dYDt0M+PPM64X!{YVe^R!PVWkb5ssx>-uDO`Y zpqJ*#6a=j`zb%8T&i@*GdQ@L%id>Y*4FJnJlbXj$yOkC;6##2CqnK4Jw7`~Gn5$r7 z&Av4-v;Dl>lP%J=rCyIUMOug!Y0H(f2fa6={RF@;VJ{t8RmW0BbV&k)K?FdIiz7y_MJwi}POE0y>M)`&iFm zw02&DOi}0W#=(|gaT1>-XSNyp$^vVdaShmrMuJjd>!aV;&Mp1Awh5{k<@U*PX`{dN zlDcyld2uUhX174zfV@X9v%wUf?Ozu@_UimwWZmY?`&-JhQ5J{z+$w0=t}|a8cgvKh zWAS)zmU2n6c?O#8&zYDc2)V?ii4@0NnJ_C}lXG8UpT}#`7~4u09*=V!UyOV!n`I5A zXa<-p^le)tK;{r8X>gW41a6K8o;`og)8|jQzP@62ykgkz3Hu{qcfjxV_}a?UJF>CL z($N6ZrsbIU3(tbFsePQ3z9UM31#iW1 z%SpnSE7foXa8<}peVEm-|CLC3b$Gw@{=YQ>-_}Dl^xFq%Su?+G&HQe&ztv!8N{d(- z)r0EXu-NBpK>GguDfp=augi;cww(Q7&t@I(u%rDxHb_z37H?b_D_BQPH zbp4*rX3qW0gB@As%=vs~i3>IJx5SB$pWbVvb730qvDR@uOP%j&T)4fv`w}a*cC=yVED`?r)jmiLCW`DM!jUiyCQO#RRHD+akTrVpY{t z8~~w~J10)5_p3vcip(pQDuC1Zs1LEELMkGV5cAAwT$ocK83*1GFub^aMz9*uD+Ony z6;J0qrjzIGjFmPx9~9Adz@-b;Gx>zUBLGe_$CWmU*P}LXQbP5USIV zS9V0*u&Vi&D7l=kSjpyEW7J*=tvqWTOm)y?qt`K2r%9ZZRrT0zR4&^J&3TQiUey1t z8_2xOy#M%-^E6USA?F1j3dfs0&&(CqHwSh{!|u>?{Uos4NdQsWejKpIQ3x30Fm6yf zxET0(T1Y7~>~|cFNBVvz8wuicTO%bbM(KM?oQW~BM4>{LQrI8%9CinGyFI}NauRC2 z_nzQ`)^=ag8LPv_ziM;q##3$L#+%$Y7A*+K*X;P0&tue{l#)LC-D7+ASpYPb&kp-F z5PNaX?R7tLj=q$+zC6yOtJ>K93L;9;I#MK%RRdLIl?C<&vn!ZviDh9L7i<>pz99o_E%hAJ>&Z7DTmz+o!{Y1CoGvc@o@LRo43F4<4=F#r<^&T z&QeB|t0<40-Z_K!k_GclGP2bAdj-6?2xzV#*yx0lp)n0aW2NOuE1%GNwobDVDv6z~ zk>1(p9_H5Un5#9JE+}Z|2(BZz9ro zB_hQ@aZ(PnSPcv6gQ)#yQRYDnoY(RgYE7d0Yqm7@7a&<0v&jHsE(2ICGh8m-U)Q4D z_?GoPx9hKdZ|mF_Y9{t^dBvA(k$lc+;9m9-XQfod_d)SqY2rRLTWYNYMP!aT5inHe zzX}u8pl+r5T5E9L(WxDF3V@CJ)iDX}dYNYIvdG?3_c61*X8oh%-Yjqp6lnHPXzX$g z5(v;a??q6^X-3v+wz&;tW#hx2aSg?{c4P%Jllah63cCs|e4d z1XN2xv4VK&^IxarS6{{$?bY2ps`ZyTt-r)(TF+}Pe24b?QWcwP0YYv8q*6)~DHGhQ zV1r7}x9dE^h+6Y!uL_vmBjB6$xK%e}Q@&-C7G3wKTviHn&ZHP6V46z{P^|ZT3AU?G zU4LJ*?sbh;++O!bi<~=|OtDtBks>s;S`S=>P($_iy1;JNb8~aUt8ZTM-FM&d@|zbN zudWEY1KluS`yH<9APg86G=Gy>wDZX4pl4m8{s-V&yt4001BWNkl;u(EhFnFh(pY(ui~TN- zYcBr!?Cw5u5;w=$im$c%HZ)4{Bb%WSuFEeNs3i_o+Ha5A?n}*rH7Ioan208 zj(+HwQWf95j2@g$`>yH`h;bVMjC$W4-iXbe^S1aET&W@ZthbB@$B-N^z0wZ`!PDW2N`AwFPIjrHKP87!~gft`q0e1&!RQV^L5FZ>8*Rl$&e) z3+lLdD}4gb=Ue{#m;a9OFj!0XcYom7@dY+`sUbYtKueWkG$I3cHKBiNu1AT<~U0WGBVZ|4%eRH z3ZX6q$L`p1b!{1Tnaqi4EG!F@bk=ntbE_YoaC3c4*9{EbvmdkuNI`#zDwvcbg$O0e z#)lQBX`Gp+nb^wjEJHuwjMw^5ar~@v_z>{ci|Y7=)kGaNvzn2wndC=}30J46v~&Hn z*B1kP?O6K#FMQ~0S=aV{xqNSXFDnIc;}C!KBG%9Sue=K7;`=f@vi2MWPf(Y=NPD}I z!Ga9~?qI=Y;*|LK=@X>)Ec>4Sm$E)WY4mTW+&)Ds*>HJD~2bi%~`TOJO+4qG`aamZ((9s#h@Vow8vT`cq&WJLY*J&I8jh z)1OA}{R7;e$my)=&8r_}P~oGRkyGGjUD29WPfCf9RKzGrkgV1(dY?rM%*^Br(;P8I zgw%4G$z3nNohl&XF*akI!ev)xa8BO0*0z={)ec)< zv#vD=t97_R)|(A0^|@q-SykFARlKm7OSLthIHy_1AtxzCl)B?ZHCkkjIGwv&Kv>63 zXyP=QJbE6fzikFcK(I0(TnP9+;6lJCvq9RDRS+$`sZBN_RGDS{RM9UPZvi_7hbtD7 zleQGB&j@PQ6A4s{6Kc&R_`S&dHo+=dYnydm)Sz~)wcQ3hw(E8c>~3dMRd3$T#bQju zFSc%a26^^+>e@$mrEGKgcbl6!S6gAY26rCK%?z9SwT-TC(7A`S60IuNz*pyZ#VD6S z9aYFyos=#3-DajQ_RIQBYgwK1=Ji~BuCaPeU7zc5oH2x|)*KvN@N_{KXFfRkzT>dp z^W^%PXHTE<%=S7sIiK7waoQ;%-W`j~(2xMrj z?QZDl`%YAYo!4=sjbn+BmaNWFBrO7ltE`sEnu#}#lrs;vANceC_^%AcG5A3Eo1UBf zGp%>CvQemmX@HU>QobySSfWH4qbS8LDXKbbA)7)fiJO}z{NW$|fp1>EWE#)pw6Kh4 zKE8j)n_qt6{_eIp2gX2g+U(qb^G3y*Tm!$xSQWK_Wz5V=5-_a-6Q((0rmcz9fwdPK zWtAP44SNm9U2M!PbD=;vC#fID;esIq$1oWBpl#Q=l^u~_%6f}US`iOnuww4;KvBtYmk%)65x&{>83nf4#Pc>`XwLmc< zQdJ5VE7>5Fnb4fflq6tdylzC9q3?L{@>_oQw|~cXzx_SWUc6#=ctSTE3E_x$J%(NY zbF{=MQ^JHdFpNjSZb!kkezKTokv=gK@N_-@9DZ; zGlhY!>qtr4B58)XQ>SsghE|Lrb4LMG1>Grmv9SvLYdb`1r43H?+CZ|lTEZj=t`#7f&DGdk)p%F<+XRDj{A^uZTpnO`z8?eN`qN5Vu70XelQ+-f z(ccZon(~FUygGfA#$B%i1Q0hWbp>8o_nQq6G)>4y6>VK@<>C|=d+@TZB^hLtMQEGD zB@|^DGttwLxs{PMUrM29c7IuBDM_sA%(@5G;Ev4k(*9KEPC{1|z?7zxU4uI{_=9GD zZ5OazzyyzRmR!fEtjx}A3fUO4Gl0Y7+yF48X5tl`7wL3<3AO}4mzZQIl0nZ*3Y?IdLj$z%-j%|GfgZ=G;qLFjGON_zoAfZ|)w=rG|SOQ%rsM zIo_>|#l5$5ohNi1T_?7#>pHs7HAar_JihlBZ-_Z^o+e!j8J8Da zDY%?50ZBF)r?Y$YTf|?vypd80{_lVH54`^AEz9&ku)RVvWK7NCZtwRISZ;r)_bpk+ zN^xu7-}t)g!e7r_BQB;{LK(=MGMOw-WHaM}EEs7EA%U2A zUbw$Mk>WeN4bCCdQFeMkokmjtL>O!2P^}$jiQ<^zVXQpK&YF$rC z3%B!I{*?YJogMHD{M~N@*T*MVYmu%}GB>S~lkyx{rkQ1&7{`%^`+M&0?l_%K7;88j zkL<7Z^t&D(JTG3n01%jsTf=UvxxJRZqzW;i6QpE#r= z-UU)DazE2ToTOz^N=5;&D7?mNQTXqMoo1*4J_M`{>MV=ciFZNTPG~@??tp6$vAVMg zBa>mm zJbFEP<6q4vw|m!n6_mXhv-(-Rj^>=yb`|Sk1l+5@QUScDYxi2IsB*mCTAn`fLi;*P zmh=6`x5RQ!j@o%4S3fMnAXG>rcbN{kN^ z_qPw+f4bxSo7cR3{f5&?YTcWYYczvcX~0&Ve-?x(&hRC5;;Tq)C02Vx zZt6e^8JyLitQ}`tKH@>S40%YbHPujfi2` zYv!ZY<|Xw7DsZfUwXDjz3sIRdS=%|)HCKwox_~RSWfM4;h1qRtwp_~BVuWcbprst0 zPgompB~XeX=b&0H0#0hMuP#PYolR4pkLG%-165~y3l?s~7d9``oQ#cAfieb*i2qqd z`nLI&TJ6_FxPT(TSOcn3F7|r6lI><~7S?MQu$0s%TY~_lev;7Ek$%h%Ia%6qk$<_Q8lM@X%X8@qJo_gt_n&u+OS>+0vwGMdb2fE z_^t>wSI5DmtoO8a;KW{9Rok_}3;6XCAgb&!OdU71yw2cE0GF|;T-afmk(Gw;Kn0|# zU!SwwmneFJu?jj>98317wa@LAd7%nC>gUSNBs;|l>IIOl*R&023oxtzt+EsK*rnP? zEeBAxi_9JE`MjM^`u7S<>$qCYI@QcCk6tRir$AV~Vw6f=M0-HzN_|e-;Opb-X!mHU zV4n6v)wxbCE$?^Hk_rK+#nii56EBzLUw{2&T48=odge9^#ugC{3_%sl#pfG_Ub+^9 zpk*zd{eG`X&K<=X4YX+Kob?oATX1LvQ!B1}yltC8(+u!W_s=-^1D)*%HV}N#i7(2n z);j^ec_Gc(i!2rC^*76gRWewcaW3c$>zEnI^EGw3O@yXKUpwCse4r0KAq09WEgF(b zWMC->{n0ydB8`I9O%LFID-f2?ZU$ll+P?OCEum_lP8N`g2kGD2V^zxICh$OgF7@HJ z`?oSVc|OjO{|VI6f{bu8(554i`7*@7x2!JZ54u$Xgvr3 zp5~dtJ@cFhp`+I*l5-x{75bfJNe+x>o{N^yrS^=Ruk=_;7d+R8E0%d?ypEhsBMjT5pk*ljCS65eDAC6Mrvn1@2NXtkjVV!{eq7-VA3#nM@E?KE{#)>nLv?WT; zQnzgk*v=9{PY6BENpK*zo}0rB&!4^I`gl!n0~U`h9+Fwb?NotvDKih#18+XO=GQmB zaC?8pk`|nidhO+YnFpj)_ z_m($r-r~IFyYIil4PFF8VxicqD$a%RJo5hCd)~c$$HT(|#z;@yo11H{t`F>Y9YgQv z2T#{auqY*Et*BD+cs_GJbu9CaB_^hMVVXvzxC@Q^d|J4_n@K5BvLjowO*V*gXDeuv zIbJg@t~lv=?v-X1t2l`|rbzY&Yw1#_jzlCzxPQ23UQPgv%go*F10O$(+~1!`iwOH1 zjvY^)?zy_L_%M;oJ;qyh`)iyH9HX=~%CXZnVv==Nv(0gL;Bd9$&>bW!P@R8s34onu zft}Sx_f#if1+bWn6RG|G8c^O0*CW4IZ9}>E)FrT7!R+c(U%o2dUSX>kzS`ztTl-h2 z4iQZ-XjREH&FTGLetl;5>QxoBo#kQ>3Vfj^ZDk!iJ`S7t)fxrs{u)75)-$emyn6l( zBw<$l_|uN}53hwek|9N*N{g_H1j_P~iSr^E+blI&#<`09bPto#Bj+sFSI>F%?e`oG zPw}BA_#NJNI5Xg^XPRez{`FUW%zxqj{tlBf-a8I`&$HtzuDToY8SZ}l$i2OX>`4jY z1j}5AQ(>MW<9X)c;l%CTJ-2uF+}(cU!-sc#{Pd2PW{T1M)vk_kLA6H2x&s?QI&Dw3 ztv9r`QcDBYdFdxvH@NDcs?)o5wksX8(OoO$yE+2;%&X5MZEy_ML~2j%WVB{hg{`bo zu$>cUT6&Ti%5H$9R6YeLP0Yv`&1y@H@G{Sgz7hriY1ae-tn0O|(_Gpl$&#qg&eIfXQShp3 z#JEi`OcMdpFE?ZI>K_>+AOUN&l&-crG0i4z9lbSEx&|;V=$>T-wCk$XXPi}3N3(=j zBMRrH0xii}8KpWC#KsygwCJJ$SQ{tn+Al4GTQm3Gh|ra{wt?5$=BAV)T`3ySlkcP` z!EZ5fntU*;ZiQ{2t)7<_M6=l{IIU1t>9XGGwTu6WwK}9~pNpaiBS|0Y?5YExvU~LgBKGeToSRxU6tCNdQVos|`4{thQA{Xp9O{R&e_$n1b0nYtx=*U9gP_)O=Y5 z-IzyjOC4_A|7$Svvkk7!C#vaB`d+GMlr>ORWplInUMd@q3Jq+m!c>puat#0>wde(? z{fz-(?;)aR0$@{{2bEAO?UMBK8&C}^Sp51+uBmJ=nXy}K5BYuV6S*Au!P+x1uiC^`Ex>(O}W4VQU3_IlwOZrXYgJ&l$=G~P$<%m1z!I3u?JnV2_&kOsp*!B=$*4t zE2CmQF-ECVYSDm#4MnJ6y->ya&J#Lm#bONloip>4=t9rZ2l}|s1)-Q3ZwQ0e3|wN$ ziI^5#mO7TJ!xh7Bhj&8x+;syE$FdY29?rb}p1#1~ zJ-uDGGbd>yQA)&FOI&7t z{rM;U{Lg>l&9A?bmWAEW(f2+55ZLWJyM4zncy{~1u#@!?-{aDSIng;7+$$&OvWCmi=&-(2zJ#TCcvBmLge_nEFA>2?E$ zt3=-mg|rk)Nj))Tmf0}R3#W5ro)(NrSS#!Sqr0=wOoKS9LH@?IR!7x2UajV(Jr#%S z^Y`mo|FR9TY#7&({rPvuzwe)~vTT1b0ci(tC z)$#u7t9-t%eCc;zKTb8;Uk2ggryD9|(^)G4rBbsLj%ZYHreu0Ay~kZJ?1uwCzCCbz z|A{f)v7ALL$JnBQm?YXBDXnx_Crp-Fm$zoY41G87;`ulH{qO&gr_a9?;F25$N3a9I zcPvZdFg(GVf%hNYlk-B?2d=JnJiETZ%z+O--%{d7(Qh~>rt`#jS~#C(&JPpQxNx3k zPUFaF8aa(4<9sHjg~CEEQok$YQE}E&N-XnCE=k2FHM?B_O&woTGsZ^QBjV>&g>$Rr zB(?S#%_b&#m32HX{J`g6_{C)ZOcw-Pich(dlMCCic{ z)@B7;B2HBb5RHJX5@an=0hZiH&0toWSTjti`9ihcv;ZRdR!V7olIyx@E2ROB8hF&; zT#H#4Y`JV1S+n2m`)J^7lQ60FyFIHSbktgxS=%oa(EjUYEjzMEHpbQ}LxWY}9@lr` zQ!5ZQef4o=BDCXUvXoFjs znq>vNbr)T;zF*G%uGjea?^}>SX{W}b)MrQ6c?G=#SJy`l$2~XK*W5gL!qxQ^yTcX7 zt0ViXYj%eN{UA8iI*+lIj8L7E^%}4;kFIOIzfHva;yL&jBVE_ihXJ9%L|lp~SEEg8L%5^+hb$6!r|xBhAlgp!q*W74(`3uRO)<`{+U5eqRT za(;XhUw%ENJp)_OGBmlNQRGTjC{P0lPU+0vHvn7;WD_w|1%b~8yV{}}Bx`lH`h2V= z@#=RfrKd*S)&8uJ9nAXd3~NR>NH!ETh^Z>NMxnM;T3D^;28hv8>2Kaw;A^$$TxwTh zT9~GZIi_Y1*6Fg|m+sLmicsxu3x=3h($b=_2Gi7etJ7^%{n?m8&XKiQcE%#tzd!8Q z9X4AN>A5{ztl}PdFP`(!w~;+~1ve z{p%ZE|M)YnfBuz!`O7~urZfGZHL*T{hg=rYI5Lh8%*IN66$TG<&e1tf=bh9$yMni1 ztWXYRYs)R#CnJ>+0WinVN#9mco0P1f!I73ko-M`>TwTB7hu{8z-~IlNJb(Uz;5&?Q zc++D|kXqeTNR#w7oR%}Y+YgL$Vu|qWtKZTq`0V-sK2WTaY?QSmWBKrK$EWke?Rnzn zcw*NL_+o{nkffiRK}vkGHB32iIzRCG{W})T%%?b0@`3@T@ywfFf8ovR*No#?)TNzt z!cKW%i4#kLj-H}4FJla;M5g)7G*6_oU`(bTB$K+^4O9V%oHFBiA#|1{jVx)Q8w`{V zX9FesR@YZI*jg`Ti)r(|Iz>KMcHNE;4&tzOLPa0;J^SOHZWrkKfa?lNJoD+U@Gvfn z<05RE=8!nN7Yh6J%@t3cUa>#)n6Thn!nm27Pn;*1mwR&RB!j;MrfK1H7S-JIS?YnW zcF!m!QLaSH%PHH&niT*zYqibP#&)(1{?fM6@(-WC9&hUFdmD>lF8*qtt+u5(rfMv= z0C?-n)(!;ovPcO)&ivp1*Z2O^{{dC~RL_mP(}teiht*1p_xn ze*50VNk0GmL5Qc$g&tLHUZ+^>nKm3NPr>}^yFi!@9qq94L>*YJP2h(wV z^^Rqpg#LW&+3kBMFpm>)jLhTAe4aVopSk^T$EOds+&`Qd$C+`NnU~0trH|@Tq69Te zRy{tcA}hs_Q(-}Z(k>-zSV2)8H{;AoO*N`6+5m7Brjiy$#?}m2RsgI4WGyA~)~OON zEfZU0DAf_xOzWeEnoCg%ZANs0)DP0~kQPX*3e9;H?W%ztp-noB?J!2#>KXM3oOkr5 zm-`8BQ|w(hPM2z}BqCdtAm* zf3Cp>U2Y8^noHnu0h*1)80`_O&!F|(vVAjKxx z?4i1bJ7s2M3}@JbKdiOSIgxp*B}XCa-kT9|hJE&4d%bJD>s`xZ-rXk!_|D*V7U(MU zVKa$+M@Sk^e7l(JrokqPH%_X?f4a zrKz1)Q&+4S&&7GmqsI?;=h;&pJ$}f82M@V;_>l993)Y(p>GQi<;VaRf$Qez}MG1ms z2?Qs_rOOKHX%0*1PW+l_%w)X$ix;oR2`XRF4Us&KKqexh5ym=VjPyff90MjvKTk{n zy%Jfks!B4(u96KQX7U&(Q5_bt<~l0sq$Ws#po`E95XM06B4Hd!gMd2{3kUR6Orbo8 z6XV9|q)l+bhB2j9*Utto14;YN+7f+J*?IJM*?0nhoa3Ca&G(&{R4B=dYc|3FR`0)D z<^1PzE|qI7V8@a{fn!y9+Sbvw4c5tLq|Rw146=Z%b=rzSly{ADN(B{F7?1S5)IW`5WQbBIpK_$3!5O6eg+>;vwKPq`lLwFa@cj?@ z@`qn$vpL5kSxhcDa?I?Hd#+ww@$pYS;pNNM#FVAQOxv=(y`}%*kHA=lm^gMvUcPwE zkAC!!0olIGeCGgBRMFtJJAd=e6{-wK}i{<+EF~WkLyJ%<@(VHDtz2 z5j6>RXp15J5n2=+k0WDm*sL#j_~E{%b@aO<`~8-i zn=5v^BkSgj%V(Fo^HgN$eO*Iki3Yk9*$*8z*SEZS`G%{jE8e`hVO6!%u2$7YGuaQ5 zGsE$~=PzDxv)yty?is?!n>VlJnWaFCqKF;Ff$q4c@B7KINo2;TL9*aUNvL!&2Kqr7 zxgQUEw%aX-hYQ|6zv(;855Yx!vxZ`--5k|SrVF(PJ5n;Gp;CSpv$_f-#c+RR8 z1!(B zQP>93;wD=|5mvX9J#couv0C@1EV>j$*f9|$i&|26rJb8H@0@qEw8DspMg2JvO;lCg zjAUb^&0x%6{Om+)4sQ_{Dj993St6_NJMiF>W>K?Mity~nCnBYW)><#qxlkidOi2j@ zWo?U@nfk3ynaM@H?G$-0>m$!j7R;Y1;-JP*YRn4gN((X7B6^jzb{z7373f0coxtMq z@(spYs;Z`HTk2JdR~-wAPKURP%;zZxPxgL7Wwwozvn}8`EkLBsrlgKP)k_w2!qO4?{-B zae1#LXkjhMIbw2nFKj~5Zkg}nWPdBH3VZ)v?v6uAc8VR&c;~1qOWRhg*EJ6wobl}W z6F&OrL!Lc*%K61P&H9|SUE$j`zN)cRL&gxIs)J*|dYo{%BoKooYrVflNl8T+R0h)Vl!u=2I&p>OQ~3s(5wh3%Nhw_R#*JANLeCjW}*?y*@|-RVnd3^RS70jjFtg{*r}8daCCZ!EZ0`1MCRP2;8v8C#UPbz zO=Jv~%4=j+GX+iUSgl(crJUwyrOsy*Mc#3Q?%2~EM^(uT_X^^de^<;fgY^lhEBGxL z?u;Z^lF%M(5haO zqo43*zh`rKPP;n8Rhm)A2Kq!e4ve=Q{q3IP{+8}|U>rKyref1>7`s642F5;;oFR}! zC~N5GZgvdUJNj#>%RWjTACr{o6@(2EN3B~s9*M(%$CA39<2Xw6It~n>Ckz8IjN}+F zIpT}cnNJ07#xc-!9b@bOp@r`EJ8rf&bX`Z)SWI=!I@gSO5FlPkx2%E6QLP-C*kZD$ zX-2w3nFhq}Db<2#H~k`DSdQt}JKgHBX*yc>Lsov-34oBWrGmBfG<% zoBe_9_J-Tt4ZGW04*Oe%p_iVWQ5@5Z)MCd7V+fpG*7SW%8yv0{=QpMx!eSxNA4j@< zr0aSC!2LjXkj-$je!#=abDlhU#Mx%8^F->EOOM}DXEq1(3h*ny_^vf5#_V)+oN0>b z&hM7r&-cFbMF4t%1Ive}bLJ#gKKS4xE-oLDjb#Xd zg!C{?*)sHjp%0{SB!z&rmUY|Wt?a99TjRVVj1gQ#u8}=4!fF_)HkYg}AMv>BCXp*^ zEp;P;C__xVc>RVS{^*B%^696H$AL){1_vexGm1jzljy!(wluUw9o|j=*jE-;6)@{$ zk0ML%NP|#jk=>bo?5v&*B}*z<^Q0NpWF%M?UB(g-ny7*VrD10)J=3!lKx{FPl4^b! zK-$S!Z%I*tdZJwlxvYZXjz0@8ApwsX=i++jkPfYAhyw2m?*TU->?IZ@!toDH7D z#)>`AjImeBu!+*YbfUDT0yfJEo+=D=ChLsW&zJ8|vSJE)C!Z%JZLL+ZOeG7na0n@I zQG+?0+LWxn%UOau9R2M)Itvp{FOevF)aclSxYI51@G}qg>P%BRZF#MaFvJ3 z>$6@ub&Ft_f^;(v2vb&p5=@v~NuvTlBmvcB6U!0{5nYL;%5}~x&NkTNsH;=gkF>P+sl>}Ke^`LOw=oigjXaCt zzU}q4^9d$V_J$REV$<{m5u&womUyCZYkbWZGnJPYHbmBSX|ff;HKVQ4jQHA_h|iu( zQf-7p&i-DYX8y+vfXjWHW_;()8MfF?74UUVIU<@^@|Fy zi+{DGpD#VQ>{EHeKJmQ9u{v=M`stf;|>(P0L<%(O_Scp_)Xo%!F&^32bKN*%*bUFoulth9O9{+$Do|Uarr~$HOJE383O+RihLz zB%=>$YLzk!gVbJzpo-l_`?o?c3wpR-zco7ExokM6<2*gGhz1t2>hWo&I)-Vn;xrQF zz*nB^ot#6JTJso4`^1%xFly(7>fkCi>kSvH z2V9(8@c7X~Qp&ve{3W+Hd$wa)+;Uhk=@ zhDau)NJt|w1#Jx`4j?I!LSi)H6v*>Wq`}kJgllRp+YM){HP%9kf#fVW%W>?u)l3ID zNF>~Xt36d!>jtC%##frj(AsFF@|E@&IcNG__yc{v=lXijn;&2EgP;5m*H*GoH*0*= zU|j>oQzuVjD^{k$MaU^YjwKe#tLrOn`{M+#qmkfKATg#$7^GLSHI`NF@J9N`k|B+Y!1E;{t8lus*A(R~F*}V>;092X==8*S80@y8~C-1KaJE-Tpw|4UiJf zE!L0z$o;5&(0XF$GtPr`Vnn2NexU0+_Ipve?vL6EEY+NC&UyaqIUl_LB_2O|kG9$1 zSmT_h@{Rns($1#PCTB(BWq|Kwzn+}Qg>5JX;@)cp&~M9>o=~du>3M`AneTl*E`lFH zg@C^M?O%S&x#!n!efwAW{XhIyQc6?yBD@5tteZgZM7_?!Sh{cHmJTMft-o_?C!l@- zl*wgW@7$Ms39@F@)IBSwT1M4PHsFO;nXN~YblKrcR6Xse^!g088TMYotegZ7S0mIRJ(XECD3Xn|D`C- zN-$3XQM1al!MP}k&&E;Osc3blu$WB3+dQ>ebH=DGoGGTxgG*MZpQ(s>#mRrl$%+3I zvg)j4ViFbVqVex+xU&Q|B=k zAb0N=0=|Um?D18FQxI%djjBFto4$Dw1G8Uy0vss5X`1gfpWa7`+M*}riACqUC5*Eu zm>jFnz)SE#13lCE>@;rHN=93JP!+#%l4P+?M7(@mQ`O>sn3C-^OyY4xplf+AdKLkQ zsnDwvBuPFcWhCSz6zGrxrev2Fq0eQR%0z81qH$K%)Dq;&=d;*@#lM$P$D~mOqe65O zRsUpeDo9?;uX0y+=fQHWl;DpoPeOw>$w)xQSgX&v(3yOqIk* zS)e5us6%BI&!f=xB~xuCm2K%TCH5h^Ol7=w&sd&kd9U+MXf<0{p2za#rhT*|sAR02 zlR4|FOxxBpZ9}E%&j#qno-vJNE6E;PwN!PBb1T4Vatov}C*}hCEk_Vq=Mp%@b*k zc*v$J*E`M4vR3Y%zx+O)zE>#GQLi}}Fk*jBgtbf(V30$`jF63pgZat|04{=ZNj4;+ zZYBxHfia4bHfTT8-f%p2^qplK0y$|NKvm&fCPc6{k_Tz8lQg4R{JgSeQ~n~C_wBC| zO`U2$V%9n<-I$G+4cN*gPH`aj366p7&a>J|eXp}d=YXvER5q<#C>-J#j~c;jn}(*Y zNJ#+G%U3V?{PUL_cO%!=TehzS03UBVhED3~nx^5|(|44@QQ>Sw)o!rPv)kWtb#uko zA0bB?>p5#1tl!Ap=cti<6>~90*c5#~FpNF@&@qfh`u>)y>l^l6M<8l@&>HI+ zoL^)8inDsdyHDTcOYeQa#l=H>CF+&VtD$oioFQtorUdw%21eG|;f%*;OJyorTT__| z8zFV0+<)JbW1^{Q)~lALuJBF(aLS1x3>=SpZnoEa{`qHo{PB-@{W24VUY@&|?MP{b zmGa233#1%~XR&RJYlVZ0+bLv)7dAzPV;V;DHz_FTW(@#ga@_HPDAhE=;} zwcc=czUJcmg4Jq`a}uQf(s$Yv+g^FK}rZN&d+)8`TKnM z{+D_B^cih)jx`<=D+!AES~EnI+BiF99E!cWyLPA5{TAT+Hk&&;FS8@@MYUINwHjtV zS8>E+O2iQ6KA6MEZ+`oi?tS%deCxm9pa0SSdh)yP{Ms+^`+xX#V&0e}OcKa6b;FZK zPiU%|)w*TXtoi))rwrpjQ&p^2=hW*)>m~E_3_}1VGPqc|A#YQx#Z z16K7VWXCYT&5PL8K)+NT&aqMmx`aRJ`Y?ZNI+Q$j2N&$gp zunLfsK(!2BDs*FtQt~3xLjjMFbI?+v#MqCF!yo`SM+_xH9C1c~rm;>Hl12By+JrTh z;3}LG4F}`Av@TUIwk#d#`rx#zDw4*eepVLopcq9>dyE>?7P_;5aSbAsQlo_?2}mZ? zgd{*10m2sTcv7X;!^}cNGh^j6`F3inivKd(q~Zh?Ur(7v8m-C;x?zfXje5Vh8MwsJTxd(L#3rYMOo(6`#cQlneyRg(f?F?w@W9|OWHmkfWj5?B!$tF$}A%))l2 zfMmDO=P{+E#Y{nxiJomV0OBOW>Qp4vdja~s@+y|M@Pkd6uWz%1LgTkiGuhcCv@WiB2~jcua}8Ik|!{ntexTYq7S?H%`>wq-`$WF&x0j15~=f+ z`Kzsv%4fBnSj5#Tl4f?Nvc(1Nx%)DUbwUx{niQAi*lxN$eSR*eFD7irx{=^>jDf>( zuZ%}aG!AP$zKPUL!a7Nxg=myvCQu3`DkPhfE5cExP>2nsUL>cvCMzY8=O07R)&!@~i zce1>9-}|E1WGjna)62K6Gw6}_51z7-9 z(=<3^MHM$>#xalyvPnjzl<0Vsdv#xkbQjN0$0k$iS2T{C3l%BOb>+^8T4Is`3q-~^ z5>f;+;@y#|GBlMo(5`BnmCUw0yP&mK0St^*vZZkh(uQX@;9ZSLjuv-4KTXYcremhIgO8%hMnNj2mLs3I3740c8tT390x1`mjfw|0#J&HoUF_xxnI9s3d{GAW@=%cUj^vV0Q&59g7sIZn- z>a*2obXm~yJWs_^?yc*$xC)cAI2poa*7uH~n~uM5E|%E(B*Qv?IiV#p+Wuu61H&-# zop1jK_sq|K@}K?=eINK6-}=w_=YRCSoxJy*U;AZ#_y718#GqLW{k_#puq|0CqxV{} zPt5l|Wr#Iee{W2Rz1K0DG8A7JnLTy5rZ1|aJ^yD0o}1s2w(+#B)uInW2Ne8`NJ!3c$Lr=^igm-oGil2V+V_v@cDP4a{3d1zyOJ}G6-=xm6 z%~A_3LX1LlmB(M6S@}+yDDR8o*n}!B+X_Qdar6oBn^s-0T=h$$X;w! zxHOWmMBSPsLT@o-XYf-%3Z>erYO{h2iz*1G0xiluXQvq~Y&CJ3Y+;?0Ok3GcP&M*J z-K+qfvgX`k(I9Pn7Ix#_D$BE7xtFoaC3CGKWzF0>7%(QyS;7q7B??Q%dJ#o4b%m=c z?V0ODJhk>BSa%0Zl#FENl;JqlPN$5^S%WPS$$G2}6IFQvp?d9N7iNLG zCA-CB@e%H_UdrH!e?QM#=lmoVw-nqmi*wx>?kO2%^PE-8S=QSU;OCUI<+!jIqOvri z_t+xdru$M6S1bObJvp~5@@2bK*=F)vuTd{(-eMMGP(HsjKYy9jFD0m@d%!pTaPiz!oXr@HG? zO7nf7ee&;gx~2*yu#5Wwq@9)qR=o4VJTqoWO1Y-OA)=~UJu?Np(-JFY)$x#s8`%^Q zwo+zNuK)BttOgUQZ!+@J*w-naNm)2pn9yZ~jUWLIUJH0#TB!ZN|LzG2Wv zjb2x}GutN{U;MwNFF4)M;ypOMxf4UE_mLzsT!KAT$HQi6!88n!BKl^GIL##sQ0~{F zN{xOjqJaWBY%PvW)QqCmcob=OpEB8HqLy#6E2)dG8;r5Me*K23aikczY9(7g#=z_A zH{>ufjy+=%TIQG}lh=)+hT8X|2+#!;-cYKebr#>$tT!vpFVDHWJY%z2(XLuntCq@F z#F#kj4jguSx_w6)2U=^XS1rbDWXw#3aTV6B$+;5YoUZ3^ea-FpIi!)gsj;<_dO0hC zT($@b6acRgrIaN47L#Snmd;qAGWuGgzge2S=bRbFf!(%azuU6k?>HXz9Q!@T?m*Wc z>4zix-7Uv%M<%EvlBYHW$w<%2taVu_jZ#CcEz=-jz4R4~x{<^f8Kc1jOEQt68@b&b zxxT*T&Gjw2!;y+g>bX`m)w;&59HxcT1QC*>C-{hM63v<8?4l*4HRB-l_7@jtJb3hg zvx}ByRpaVR#xlmlFa{3Cf!D8IvsyJ&-f``=+}&jl|Gv=Yoz`uRiDD#S{MGuUbC){KxEvE1^m!DX|J6;k@jbns1TX;cQ4rKxP4! z8YdQqFfZtxS>|L6NyGw&k-i%kd(m#lfb*Ud)zK^f*c4$xc{)N#^&~HLQ?+fecrX!T zq!+AY^2Fv!2D{R|F(G0iYWpVPjdBlZ>MeU(Cu>z4NmqE5n!scd5reg9>Md>cn8sSX zs>NpOPS(IYcjs)mwV50WP@bJlv4RrN(QZ}KxR$=5Gf17S%xU&*VQ0!gKxnzT$WHH> zDVSC47kaJb@8w)>v1TXlPMxp3IF>acj7FC8+DiKV8oy9vcDj!I{OqRhPshvZZ<#3o zVA3oWWs-m-p&TbjqDe!}!d@~98)1w9m$+~xO{xE!?PnR6(mLr2**FHUM(<;(_Uz<$ z6Ns4a3ueGlj#2#8l2DVqq^va~*MKlIvW*KxX*-E0WoxF-P6ApFU29WFePMQt5wTWl zEY69}gm%6amV%#4{Iad_RZZ2dXxbKEtuV%sqLU;bUTvae3$rPrY)-M-l0sj=$`=6O zq)LTZ7oq^IJb{*!m7d&7eTj2Mg_{bUM-1THIX?vb{3()xmH%^ zRRMuAnKc^l1=-(!tJl&$(Q)x!dYc(zNN#ojQ-Y8Z#Dup=g)nr^FJ?aPx`nr$ z^9x@Jz$dVL7sx9JPG~kbgNZZfOnMAuYpZhG{QZfwT0>n!RmlgOm1~b7kV1we^>n4K zGDV~HMuqxgu_jF*-|BhGbxf2Zz23sN&pMttmzp63(3zQ^uh*W6NLGjw-4|=I)>En> za#1`T%d-kN7j<%5umZ5A=%n_p%Nb&dm^_eeBHJWUc${q5#$qc^RW+Pnp0PRK;404; zBV*qahD45;o0~oV`d|MUKl;(fqy+E2`yL;C^bueG##i~qH@?n0PoJm&fX6w{{&3*< z`3r8lj_54S`5D;AfswzBy;JIj3n_oNL6XGBx9vxw_eM zv)}Ql!z?2*x--+BO;Mv2{(eUem1CRLzRY zID9skEVQTNe$UO-71vj~)^Sltd(GQ1(HVKBT+bj_vlyVLw1}(x16)akVG8%rW=)xTgv|nJhX9NqYqP zNZlGX=M5=%)|(CImuH+^tZ6s30N_R_W+_96k*4d(jC9?Bt~)ZS!hVd}W8FYiL)#kK zRV`E@XBp#2K1POk5CGUmj>m!BP0#lFmZ3AO+70XWj7JZiaCz~B%CCvRk+Z>4<6R@* zS6LI&2|;PSWpd4Qp<*-h5(rR&Ud2(k?-YNLZ*}*BOVE4zJ2N>mlHrOHE`oo}gk42HYE?w>v@eHCib}n7$)az@X(m&N*r4 zW}gC(Y>-lc&;toyc~+~I)n-k*YB5y>20{`+w$eAa+jd-EZF%wX4TpUPxx!>i$fC-g za^iSAu>17L%hxZcKKU^Ze(;FLPoMGV(GxB%A9J?3VC98z)L74>i%Xt9euuO523vXB zwxX^YoU4#puZ821l)(}QVi*X+NO$aTu3_jh+uJR-w_CdLKuXdAh%qt{$&C0|l&{eM zvYDufLJ^d@+-wZSD=pp_rS}?byCtgQeLpe|kuYYW(#dSHBxBW1WgucqA_M`gRV0tMQo zC;%*>?UAe@rl4akbh*+}C*~yctmvamB3I?5`+NakT5BwzvpA*&tk19IT9P2!VqKwu z@F@y6oeDIIX0;Bm1Y=K}{S&`RYtR=_`}=_>6dWqtz6+`+KgMW#EUUCryEv}VF({WT zf>{{NE*Bry&O$-OVM?k*E?F*}d)cYI5ZYqW)}*CJbpejaSfB(xG;5d>CY?T|IU;xG z{&bCrz^b$ibCqPW=M3;&@H=PPik(YS;6Sslwlr>3o0kO8Gl_i)O*<;+Eq&Upbuu2N z)MP4qBPCg5u3&_D=PD1W1T71$xeI(JyI!W%zm2~>eR;nBvc{}A%{YqG!7@`^0QoHB z355kP&&RS~U?eb`ymXsLQNgB>z1kKwggW2T`KMsmg2oT0_2qB9r5XH|I_0;~puZ?1 zTxx$8sZqgh8qA)JZF;4XkGC66&%V_3X z*If~a6}&MEg{9^AnuWhX!W)Z-Te%egwUG#5%8?i|A!TAOj&2GG>$50F+BDT;oV-f3 zDa{XjdMnL;764TGh^xZt&$IpB%>C#Jo=VEXmg-p() z*1r^#Dm|#8icqKxoEMi~b1K(6e{C9@`2rX3oB8K%kZEailLm?mlg~Q)WQzd9B5{E? zKqbME6lGCHjjX4fv`y8(Fi4+FJE2n%*BB#8!6=J&9)A%Dn`;Kp=SE1nVb1p;MxuPT z0Mpt2l;J7HEyk$z9+lLlS&Ngxu_^cvf-LH~2Gy25Io{2u*6oI>5>>pHuU@gcJwo(^Arg9-|F2%(@cr-qC1Z$u{hL3}H@@*re(tMZ;k^&u z|e~{lEH4{_3YcVF&;WLG!*xe5-7Nu_uI4)IC$eB@t~X@$EvR zt7>S*gi)$%F1un;6derR&M@>H&JWaeN7EjutF27$G12&%_ntiCOV2;x-Dl5u=gCtp zFD|KTaWE|c7>|dZAARyMfBOCJ^T~_PdHvZ7s>-omuh^_NteTdluBm)QWdt6?5C~z= z8gj6{#@8*@*CgYJSbV$U?DCS$#U-t;NzPL{shL`_BIn2u4!pj4!R>L&;c$a7NmN@U z|C%v`X_GUE>SW51zVEoYiv0F}`49NV|I2?redjm7^-KKTAN;X6 zoNjg-6Cp)|im^t*uBx4lj%(TiLCH&MwJM_7*N;uvPO?fK;6r`PPt7y`zUN60~1 z!&xfb9k>YO0*5s)Vh|zAbaY*ff>Tj5#rMJ-63eu3o*7l7f9NB@t28+QSG##Q2CC zq!(pTe>PLgq`7l|vryHN>2gUxC2D_imOk?1FfjCiaY&jyuJKm)DKEAOGATzDuL=sT z6<}C7Ho4Tkig1^WV4Sp3vRRzUMAUk^l3|rD57{}gGdP!tHmiV*M`nRIzcEEoug7Tn z!HVFCJ>!8sc|=bp~5W1pEb-^Kks z9do(P(tfP+m1>Ptldz`Ht<4GOMaL0S0+#x0G1EAjJcEzICXqQ{$RtX4nPq2>nO=Pw zFfrEXHJskAF|%NySr|%d;fri-nI|$w3zKQ_+{*LP&skFf?|GU#(|&Ug6qoas+S>V; zQr|vZ#mVPNMm6VzMKFg0k`+HZC^H~ty@osYw50l%HJWq2*Y)Xy;be<)zB{=OPR8G! z>LHzs<2)ZqkMOygS?kPQ5{%(Rk>7eJqG!&W1_YEjfwQ8Cpn;l#xv~PqjFB=hqb!0{ z>Z8kbsKF@#{`!f!VP z*cJl>-dLi^66lE~3ZauNL5@t^ZsGbe(PzuGE;EJm1Ae;;^|K;46Qjm5fzmQbXOLEk zsVBb&LR5h&-B1<=w#dzwsUWQn;EI~&?5viaoModZ_p;an zq#mWz@_0@*n5hR}5-Kfa+$Z`MSQ>FEf^dDDhxNMQ>}*X{d&)$T_EFMyC&w)Hpiz}F zvpl4vEjQ|>X478s;K4&4oIl087Mm>nalj>TczoTETxPQgJb(T!AAR*Be*PDJfv;B1oi&v(R`)Q?jex zQ+Y?bUU7aQtxftt=)Nh7TCXt;MGemy$#jbFmw<%*F3@*9HYDDE_JA+H{|)}Vf9K!j zy?38;aehwIG?Fz(YQoYG=?)!v%p7kHm}J>?M=I}l_~3#^4<4{ytz@-SF_i1#R6>J4apBIOB-p$a+)LhaJ@mFUGOfMajq* z(^Ly(v3MhGB}#8jZ$(vA1nnd^l{LaFQTIGiDN}?nB!Y@x4dcjhALx&n96jEy@YYay z>1Qqx`%Feu@l6z^+A##;5D8tNJNAS=FpL3GtAcDp@&lSkvPXxAQk@-5({g$709Sd|n}*}i5kil(VsFO7k^MNbKOWfb_T27wjJuBE&=C)j zI0h~+FIcb7XzDfIORFPaNwB5wdtSVLfqk9W9S+1kFdlChUSD&a#N8K_*^0A^3%bLO zuJ3vH_z6|h2qmsrv)-JsI=i4*twry_dB~AC4uqknJM7uMdc(_~e#-05KI7`;OI}}n z%g95`}nM z`nDSxci9iozpEgqHDpz-95st!9k^)lPBQK`IT0m|7Gp%U-jqJYW!^2K(Iw04#PJe! zV&|s4yYw%QArWFweTjiFSW*fKBxgh+5LgtfoiUniD$#c+bkmbSmjdXyH@Y~@q>Le* z%=Kw?OvjObIy2Kimun>5u_t=u=~b9;ORBM1th|f>j%Dl16VRKpI`xEn;LR(Z!iM%uFcxQNP{zOp_aZ>PFH&O((sG>x7a6`+y6|IXGDX8EP-jE zaOa6dnM)11S=K8rK$TH|rh;E?qDtS%MlWWGjJG`fCBRyadlAx_vW75cZ1Y`3WHSdr zZ6?S244~=#L}@Cs`27NcrX($!Q=Z>f06zB(F2H#{PD+K5YUkh&g zd&qByea8@_@1=+@1!6ql#}Vhe%J%zdlFfZ&WfGGk>cdWRK&XpQTAmjEa9#v^OaX_E z2_R25P@Y{0aNY42-bR<6j%SQ4c=aEg(?hHMFTt330wZ+@=<+s}Y&8nFGz8X2q_|vH zp*HKW?>&vh@ypNjnpsZzz~=YM-*Z`0i*cP26QvHrFRotGg#i;IsUHbpkjzAq41H6BX+7Rq8e7x0(nqjq zTbh-$tiiMxQ( zA(i)Kd)G_>WS7X5;mMXKHE_5S~_FrC{xM|{gLhVnomFZ37>rWV|Kf1GCifnEh~-BW`l?v zcnVdgPzenJj+03w#Cc4{VTf9?;mFw$gY-p~Isro*ENQT$!C_K`w~5LcocHR)n3JDE zD-;D*X}2Qw$x+oJ5aeo4GMR4dMWlvEG*P0tMriI`-?6_vvb*lN-R=cMhp3A5;tJ(t z==%}7lU!_wk!ln*?q~yPOoZMMgQcxEJiL6&hwpuZ58nSWPak|p-K?-#vc0tvfZ}aE z)&0tvoXD~ZTV^IFB2yetyNJX=fnbwCoowrg`@!2@_iCw@uLba%z;6&*?Ko=IJ?DGi z_j}*{?-<9CV$e(0A&NG<%oFd4Innn$uU@_6yMO2J^LzjBf1Hl--CzGz{>eZ67gGP3 zOHeLNbaA(EoTtlOI#ud?-*d8xJvMI{k#e4U;+i@dahyBo?)%bb$8gaJ8aqSZrQy#ujxlGXZC4ZrKWAZxgn`?ez+e4fyu^5J97&M#?KE1^WE$j~3@k4KLC9k;LEaP{H^yQ?>hhdnXvF>au04C~c7 z)}LXV2E$yI3~eQLWb6la$1TGs^k?TacnVWHHKx5^pJOgCLqLId6_u3$sIgAwiV<-a zqo7J^7Nx{R0`0;`GBFZ@k?V30T*jr67%;?))Z^w-8!FE|PyaCqkLHqXMdqT@7B(eY zD#-*hwGTTS_n09vj>TEI12J=EYEw}HN}0+2VZo%Nb%*kwQEi9<((M#DI}P+K7SU7} z3@GCVrv9%5m``r@banbX%IC_z6*Sy|f_WJykPdpB$6kh*49 z#H`FB)0UN?XEL_3xF{J#G_Y(6#od&8Uu7w1_BEee^Qldw1jtXuf0@BII_yapQDxs- zj^`o}G9BsUeHl;ZQ~+$6cREiE3ZTn{-Uq+sUS!(ji9TP>FFBcoFqSRXr8CK#&gXoR z)m_f9GKb6FB))YyW_ej#1iVf&$;;#CoG~_Q$(+s$Wo)2e{scxCLsC#$djA%1VJF}* zKc#ZrB@--{FG-`q^t3vrb2fN-JTi94EQdkASDwk;?DG5!Qt7b`Q+!@yGZR*ugIqH^ zVrqjrKiO$%mF%&ZN>WZ;8UM|1{vvf<(^f6x7}(uxxxKxm>$X(3A(IKi8=_ICJ!DdV zI7F<|79-A5Rn6QOUTH%mBN(;LH)kf*yD6)?oSSCORC>MX667$3Ny5KmYnP6~&&vKT zU*$Uy1-NC9mFrV}N1^r>gG?FZnQy;*N!^N-`qGra&DXiS#=AD7P_pNqr26}$*tXm& zcR+Fh!wQr!ob+Ix_Ny$te1o<%6aWmPhpLKrU)n6_g2-8W2%70MC2QNRR-B(-aJD(4 zT{TlL*y7Z0ot+GpC||1ZkP+%?sp*)2w}R(VGj5X5JwR$D0ZbN$#a5QOI_JH2-{t-1 z@3CGrcxS0AOI3Sf8hQ2VC1L0>8S1*myNVPnDP~NnWbTZKzU#T(Ua`I1;vGD=e8T(h zf5e9$eTBylpHur4F0C-x<3j_{kz!&T2k@R_*Aa5$=IWZm@jx~ZOk_-fF7{mCZu!v< zf5`X$?9X`f<`uqjoYxy-9*|^0B9OpIFZ-%uim+C7#d^JFb8*h*{EYSHoVsmsevR`| zvn#8|U~Q#p!vYqJb2QFU+X`1(D%axM zHD{NPcs3llzTNWX%}aLsTaL#ghkYU^X_=K$5a+eua@+41Vh1FKAz_9iLm$}h4(z)~ z)tu3dBcH!|C91_CNfg%@x^BYTXNR}KdIXGFH$-rnJWK4{hRN+YKjCpdF8e(Ie(7=2R79vri*WTb-#PMw< z`tE&&F@_K`V;ng4N4ow<*B==~^jK)0>ry`5^SmjrmmC|-~cV+9RmL+z< zypfG~jT(%M8)F=#EETg}`@y=kM|R|LA|3j`dsL{_FhXfA)V7Qq*>Q3)R>R zPAe0qJG%>d=gYr)$4nm6{2R>4UzQ&?)0@jo*fdUGwAbBp<`o1R4^}frqcD}w{S-U_ z2+`8@Bjd1Rd%fq?)oX4JTL~1#K;L)dK8biq<7nHKRomb&gsvy110iHW2=v3qc6-b2 zX3N-jq&P~XJ123>z0{K?6GeO}2e#V-+uIkqNqO)U){78Idv?KUeMa3hSmPuxG7Jp8 zv{XySJ+VK+&|_1;xkb{8J6jg9Bl1SL7 z(_iP%Bm$_dI-C_6_oS%qmW%FcQ+8?1TUSAOJ~3K~yYE1z?&5 z0MTh^1PPGIsw!>BQ#NS^I)y@QU~;Y5G-oy7EKHQ#za(TME01Fz`*i^E%bw^D`*-y)@gx>L^`oCh^b3vpWHJS*gw@P1h*3yt6Q{NtRpy-~v+2 z*OL?jlpf`2N*Gc09#i(~q+>Y0PT3eTCvq%nCrzJOmJF0Y$<)TE)cU7ckkY+HDY~q^ zQYK(Zo%&*9oIvv8XS!d5)H5$iDh)E<6RPqoy*uUacd*bjcGI8v?H@>59tZeGkKU0! zzByw|Pt%Nyqtvv?iDgjR;g+uJ*bhBpkU@=O0lQLc@05JX0x4$OfyablEP$eL14QYZI{3dawis3Gc&)!kOMk86) zoz}lD#(heDf!Y+SHiJ`24`xxHUyR}6M{R*<2`v57Wk4aH{w^EI1g9v%W+4dpvNq#< zoW_5u-_G;-T;-|jnx<()E!tSEm5~~!Qd=Wp1|D)!M=Po_VNrln5Ue#=7y-aG8iWz7 zk-{vB$RN~NzoHyEg~bi)Tu(Hq7N8@@dAXs zmwsm{&yjTLqb2~@V03+rbp4*=@s^=KkkWubsMU2-v0As(wFuh8oHRP_u!z7|RX5bG zk}`#H5H-*+k}`Dt!0vWW2t8R_r5GcEEm>>W>Z&5U$dG!*Q5XPYh=kN@a3_)(NU0N$ zWi8%8VjLL9j+{qfdz5T~I*UaF#;Dq#IHBUukrhr9q3ffwe+^7D8wR zxq@hP^KsaeaXE_oKC(HFgTZzg+hv;G5PM6o8Juq3QEY&#Jg)NiRLi{g(pqdd9O;IR zLnk!n{eDN^b$U+*ZyoFQjE7Gi(^PAm*&r2Q;#89>x?#`fZ+^(jSD%wPl5>rr!WmId z^sd1-8`@^gv&SFu!Fylg$)o2q)e556;mTE1rRGf&+o`MjKq}q-gkcal4a+8zdc06 z88Y+c9jbb)?j~uPg8gsUfF;s;uqlh|k+cEQ00GgIVF>WEU;ISFfDMxm<|v7V^(2$h zKSIkEXwK}es;;_2W}YcxPkvZy?}&3UZ&Ojo%A4oJiL+zJ9@e+kx4xCxA5Zl62VCBh za}uC8tQt+Sl+44!18J0+w{et+VvM579g}D+oWhZDI!Q?~vgU>r&|KTLr&%>Di<%|b zLlAaDINfo)f6bliWNxTpq*R>{1KpAEWV}gWB^ASYOV>$BH)BMrAZaAS7*${{nGlND zF4jx?tW_Neal*;|Y%tE?7l2aIDr#vXJMYa3BF+rGCg@|;!Bvgh3W8rs~z{mun272LEenN_gKwP;-H1w$R+ZJnOqtC3kXX6r&^&hOE*r*`R_ zm?OGpHIm=cXQhZE##%7hG)5O?k)sW?y3%I;Jk0s##t5_Qec$s4pq1G4eM%`>Z@2vDu!rOTJH;kXiUB)v;f4T{mZz!jq{q?;Cgd=`jK{ zW`R}kYn|SA)Y(_($^xKXepjtG+%_t8o-NOPG75b08qnriopnp#^weD}bAO-GpsI(} zYg=palX`f`QkEoRaNR&>CXv>6g?{MS#0?L-2h9GC(@AsC7CF2kloZvll3I-wWaSI` zas_;~F&Wxs9BwbR*=HHjkd?|#rJU{2soa}X@DpoyzqEdhbZ|U#;-{N&xEWN(5v!SFBc>=7b0#vfJ%>`}QsG?%%OL9*FUXF^Rsj zTyM5KfAyU0%@wQ7iuGzurHB|)#abXn$pLAX|$ zrMYIM5X{7wPu%U_@!8wYczAfA2MBm%%qSBDG);8H13FLL_}CJ zG3Az*ZcLG!b2od0>%cNPAL}@&xqcYdqeFNLMxqXCRW9Qs9sd9O8lFbmTam7{`%uoP_d- zVcoCUzI?{lzWU=lzkS8vZ!p$jicr&2cI@`==vI=qcMR{Oywyr-xpsqL=r?S;=iFS~ z^5LtGc=_TBthx<38OT-yO#CczRu_!APL^r`EvISQfbDF^OK+bqpo`a*k(j>?{GJ(T z3m~_AzdACc%#r-$TpoenZ~ok`GESnJUGujRSyjm|y!l0PiRxNksln4Y^7_qde&LsY zjoSnX}^S%9~ZLSymQIzq^@0>m7 zYH%6>InEitV+@T3myJ|>?J<~@$JrilRzmrv!&%G2?v9W~0h_iELnMwPZ}ta14-(DD zana{>Z#70!5=2{A3w=t1RcX1>+)7KR?M-)&DB}}AXNp-Vq08@=z#ONwYu_nV5 zGP^y*a-@_@2;xM^h{|%;NzSsUiEEVBbfQ$MIs{H@Ryt>}oyDKgNTm;}Qg|g!+oBtH z^{`W#8CRW{%@D6nV`~-;JcCP-5M|wS+2S;>78RDtsgS0^G)2ZSa2h4uWITM&*@7i$n>6(S=Cxx+T2uq7rV7|18RsQuigjme^>SP~ z&Xs9fw5S>L^%ME*^Ow%0vy^}{FnNBR_9=BZn1xDc6*7Vffb0D%0L9|-HIKUF*{H1J zqbf0rK`~3UmXwQl2#D znH69#3)S_@jPdzdw&*RWqVm(=>(ZG}F8Z1ZkS$QG?y*mUxt2bo_uX=OFMuSbwokt^ zUyPCVcco9;7Id4>%Zt8!oNiPjz%sXG9dNdut4;v}wLDxYke4)VqbUo8=E!QjI;sv>=;{XM7 zmCu_U^|`*^V>bVmNy#jFRnMv8;sTrspezDb8Uhq5ZlN?a>a3-QtSyrJ(iX_2S87&= zKC>s6-v^CZ*rLBiDbQyPu7(heN&++Zt(56nQ@#;}mixw~k-6L>va}<{ne9{C*M1Bb zn@KKXawf#Y={Rc6PZFS-iYB%Tu$AXfnn$~pV!+XLol@skbY0&z!c+<=1*PlNT5r?Y zCYBPMP7<}*-#=g{Q6Ao|H>`&(8?U*twrAU4GsF$%;9=-+cEGp+jKy`1_3DPr=7z4{ za=$zB$*1r5fIC5KE20ZPH^0^un*BjQHhIzo<`^QHCa99kpL zvl`Z{SDvmDK@nq-d{O6kxWD7mPd{aUf6}_yBc|+x?&~bpOHJC<)talDE3U3@*lxD0 z)+@a8q?|aNPV9C&_Paf&v8ob7Kfuki4Y$v(=!Z^Jzf+`Sh(R{KhXka;csz0c?w(IS z`;5=uz2TH5{LpiKz2SqGFL?3d8Ed7TyDH?7GgBVfPkY?!fj4(Mj)ym-6c`4Nbs{h` z9Rd%#cT6ENo}_$FoK#3EjGT^A4k)Ln{U?+mQRnWk#y61&*#t#-wbgQ@E^JonR95@U z7^EE4fU`Z$bhsiSP_7z=&X9Z|*hEAr`xy~Cci_FJcZIIYcufT< zrZ7$u$LYivPE27W#EDvBE+>gZ*%C;xU`$8Xt#GcF$PP{;JB5@C-mkd2x~0#SVd&`B zo_^@)ddY2kw)v13x3744`vum+H573gI@{B^0dM;z0H!O@yiS(OrD365+)g!|8!B}n zzcA{c(Il6z&+FdfjcsXU*1vNWFj6DGF-Ro$yWjb{XP^DnH~%r?NgZtkimACn`D{E? z%5!VaBG=4$4=G7b@axa{&M*BczxSIn9r_o)_4fhzy+8O@#B|KYOJh3opl)JDIp>?evKG$y~E#lI_FsV zfz{yo^s`U7yL-)PJdteDGyo~x7Dg>G^aS0sXd?|pa^FpXQlC$a1keAMkyVZ6#0(jg zM%n;THDqd^gGIdTQpr|~^l1v*KaA`S+8W)^L^0QsO2lWceJ14{v7!p?ya-|W&f&b| z-Fsi7zBAA$#b~bToL5!L&xeZrNDEm?qX%*2q0 zQ)U{a4AVGH?We?obD}<%QVLUj(>(Dk7Ps)&@d2iYcvy8( zL#2e5b`R&@*LsTC5SEKoYJHu zb>2B>;$q9bXr+0ZGiPB@&xagIhQy;YC{R&{o zi8(Lzu?^IKZ5`*?KrAvylWy=Sr5Uj0^M#~clf!3d94`caQea^sgtUC?rin) zma}WsoQt`?%NY%`(wP=djmu{_=VOQfmoev)uwA!Kp2e6q=Hf@Y)>z4}F7}B&dFpR9 zp3wa|3;V0BH+9bwswnEc$vB(vDw5!=qw8Fg$v0@N)fmVu7hH>1<=@SE!`0Q6uIng8 zaw=m?Op{D*7bGefjm4PM90{dB%7tl~a0NEbv)XL<;s;;l$A0X`d3E~*x^4j170>Ib&l8#b#oEAQ#O zqc@fm0(Xad((%w9RzD0}KfmS0hp%|?>J`s!M0wdeCwZlPN0(BS>cW*cy zB4vUSnCFE%fd{vN)z!diyJA@PtT#QY^?>tUoCqN@jT2#v3WCn43Wf?CdNtXX2vO#LLrQiILdeDRB*=8xlZd0N(qLc z?^&&SI`6SX){|6?K@7%f`6E;3m2El%7)$RxtM!KMX3el3a6>0TC90B|NMh7$O>^1E z94X3#$RyHKu!n-_40dJcRt~?0zJuIZNkQl`CW<$G3M0qy$nkXGcsdfoB=x6_IEjS5 z2=CtA^ZoDtfa4)xSc%|VvJL!(cw$OByz>m3EBc|Q8+IO;& z#Ys-0T}kBEcDm$O@KraE%Pr{1<(WAbbqRjY*QbBi<41wwYDmT?!go^YD3Vg<+uu6R z`Th2{{xPT1*o@f*JQk)?8xKZHBrMj-`rQT@FDYh@<4Ah_`cY0Wz;}M`@A13;{9lpP z0S16KqWoLE{>%GW+~$*!q#xBs^)u}z%-Jox05$Eq9nzBRmk_m*)wNn3Q!GevTKb6WHbP;>VsqEmDeshj;W3bX)DMht*z z)Iv49mbp_4FSgrl<AFJcKMZh(st*Ft_=$Q={F2?x90wv#Bn$xQ+269a$ zs+XC851EHxeswWJNReOvFl+PN(4Q<(%yYPDS2h{M6s*3!$S7X^j1&+6J$ z5H@9XmS{w}t#xIl8rN*m`eV(4iDZ-zYpb}MR3K@eSpaWaBfw^Uo|h|dyZ@RqZss-f z5(L-wc}y!YcYd4$#`)Thou2i*CHTEutF19o;>cLA8K+UgYz<_~vY?SM7S}carBYwC z;Sxxm_k)69BY~NkPi`0OcFKBP-iN+>=47z#UY6}MEl<1FUbjezx3(Yae;^>*wb##& zx{9=Q=Ca@F*wv__HzES)bd4@Cl0qU)!eSctM|?;p8I0MrK^9YDN`WzqjA3F5fe-^p zOV2bfx>7!3OvDQQ)KIMp_Pm=Z%@@wZtn|*Ps>NA9Ux%%$;O|02t99^u9&BB!&OosK zUZl9HM`ori80Ed2To(*otVHlKL&fs%Nuai(+xtN&aJuoK7Rt zI5JKVVSjPE;cKYYbU-}nY!{rX3|c=d|SW{YVR>@LP5msRN2#c!x)Z?cLxrqxBT$+_i+|Vj>Igr zbVGhV_P<>sxMbp0gTO zjUvBVt>~O%JRN!a`D=Ff4-^uv6SZlKM&jC7k-=JP6|PnTS6A2EKEGzQU1K{Du*pV* z-p13&Tn|_CiIYTF3JIGbdxs4M)8(e5XgjIDnX`(*1j+LWablcK98Y_W`y@%0t!sToAt=Z#SH{J8|p7c^K&Jn{r zNls&sGGe*#2>gEcJO3TW<3uTm%Dg#StExB87TwEa4Xvf?BnMj6>GMn@GZaDyyt}{S zyZ`mC@w@-qub+SK&;LDs`}hAZrm}?mo}wj4TD18+AYYca$9Y;$9Tl9p3dK0ZC^f)GaT1lN?I~(hqk>nZC=)Mg#fq$~EZIYCaZsH0ox$L- zrY!0gOZ{v}@;r*xSXWUSYg}7DSbXR5ka0PW+xl!l?zxWJT0W(Xoq4%BJC=&M1~cb= zg6;zgJ5ColThs}*XxkYOTmWaIVBQ!Vby;!_AoRXZywX7f#imMb&a$|(t-*Gk&4LV5SwcA*>_Ow%5$2jtanSWX4{V# zo684C+fTjL1;#o`1@D4V<@2>fk{YK5+Z+a_NF>{8pr}@MXaG1vwpQk7%Ft(02*fsK zbbhG{wUmk!wRMSlmdi$;^>rOFGcY@+DKDe7_3tVOdp7>eTmq=({62Ne>+xkC^<&!p z5&+lsG&j~#a0?A^$-m_N+9yqXw%#*m*ITy97@0Rs2|^Q1vkT^Xy2<+iA3S1FW9O1{N0 zFzpW<_Xoy@J*WMFX@A6zVFVx|xhSSUj8XDS;wUvQll)Yp!C8xUzM=h63K>yPtn}uZ z7m1|_TWLCjE?iuudFX?Z-+2N2mYey%%TYm~Jh8g4=ykI?N)$|IgzoHX*!?{yv0l^U zOfoY_&g#+1sYp)r0(dT;t##)NZ0FS5TorBASgn+(r5CDwH`3-siLREjo2hwJa(|_L zSif|6TTk?P-Hb20AhQ75MFyyImcHxghk>r|C8}u*)_T0lBvD~SKMxHC5Lst zCxs~aGS}C<`r-#7h_vchUu}5)!H0bK#V>Jvdn0s9BfvK$$(Ii?GaWMHA<^3nAHMt& z-WdvkoP$KhbK*1|IE^D=lKEFOFW*pzVPYh-1taAm29b){gb_+GY}Z@X-5Qg?ZEo0H zZMeF+W<9J}^=rKENFj1K9Cj4MzQr6fWs#GIKzW{Qarrn%fl zDWno8Mjc{F(hIPXJL@zGR8qp(M7QaAwtc}DKlln?{mR$)@Z}d-4Qo2zsp0L&A@ajd zK4IJk?%qDgJnpI|NyTM!(B@KvGG-;`vFkdzu503Lt`|CGA`?s?hNw|vH4t<&Em^37 z7?u3j+&^ax&UJKJ`o#OX874vq9H$ef(~;xx$T*(F_{_qt88$0k-oE1bvzK&!MTrK> z3U7N%=?Nim8Y9Q!$TTK$3HViFvtF@U8GPT<^((fUEzfRlCGy)p!_r|(k9R%ZZSb~J zK^x7LVG&h3+ic9m&*MnryuUx*q~!|c?3$MVuWk6%uCf;kkDi;8M1EsPt&aG&e*Ql? zJMX{x#s8lDews@q)aVGZH5wxZYgR+Q5dq8`xvKkD(OhBFSg1x#jFJ2Md%pY2{|&$U z8~@YU_y5AT|5JYZ_x})LYzCzFx-MDY*3>hjW6{%>fc>fCk~(H)58EEvFSik+8`};d~JI!M& z6FE;}iKR-TENZit*+|y@GPBEBnKotdN^Pea&Bh2gYbfEIX)SD@&dJq4 z%tZyWB1P$iXY2(ttAZ}abe$O}%e#Tt3S<{0azt2bR$LZ1o>e_{c4X8!S;037s#7Yn zgFI$&8s31fpgw2U~)CYdWaCR`CmU`gj>>uIxe?gPLDi%kuO|?5bj+ggi9j!f10YU|+RrpF&ook=h zQ9rNY)*49%7(BM`DAuY&u?CE+Doroz@@h_O-A@q%R_-Tj37@QjdWDjtwsy!+Tq2lx zy`IIm>a)`|zC}W;uJ8G*|K|I7ZSRs!JR6g(jLxI;FLGOT?Eff$+^(aG zS}syfOiE1s=)I!l+A7^MzXu#$I;zWJOug^OB@0CuwEWOHz5DXoAZ2l%`raynW^`Ot zC+4Mq-Q#ux*roqR?HPHq&TVTfuBnG>a8xye;uMI7iRm;F4ksz?yE|~&?-_RorsIh; zPWUiR3P$HbD9d6#6r@4@emddCs#05>h-F)hn}06 zBfsVR8cQ2d*Pg}CfspgUAgeaIcJ;bg|$v{MyHdggeR$87&Wg({?5cI^`7(Gesx-O#xQhi z*29+G4CG???9Cnj&%gZ>KK|@ZD9=U}PpcQO(7d$MG_gM&IE_bk(*qBO2M*&s))aj2 z@qJ>oUh(|-4Y$`X@ves`p7OQZuo4{^6p{KW=Rqt8#J^gycX1m63*7U1^ZrEU~ zV;U2O`y*qB#3WvO3K;7-J?!upUfe$8*;UUlc&$U3B>yx8Q4&7vIGm1*(@4xhsVzke zRZ&JSt*;upB1`|@++6eJFMo-zed+7GeD;c)t6Q$GZrH9j^!jxcQoK~~Q6i$2I7fO6H5U-9ad>Cx)*GH}pYzd| zzri=Y_7i;NOJC#J^$Wc3L_xGzQZ5|#dmi5HFvgR!RSadRw3%iY=}i}%4C19$n)Z0Y zcuR-JI49Bdx`|j3yYYTDV8vrE-eqSTeb))4du3UzdiufQdn=9sqmh;rh%petBi_&C8dsc>e4aeYd8w8=UPR_r#Dmo&tyck>hdXIPM8~FV#R?#F~zwyJEX} z#&+|9p})bh#u`UwSM+|snw9pQP{Ye&^44Xsg0VWmXH$Q9m?zeX*_dpvya$ji(U`e7 zce#$0A`x`S`IVoP65sjud7a;1{N6v|a2#da=X0e`K)lJ&HUV)Ms`Fw246Eo6MHGp% z8fnYu)A4vDguu`Jm%qXv{O|wESv!8=+dsqa{Ifq|ig6J+l}*PPEgJE@F8R^e_vyY= zgZz@3CvPpDL(2m@2g}u{o;M)v2P!Sxs)(P=rDST!yg*Lk)LQjxp5MO2IWHo5>or|x z#Thmo@ZO4=bXN9KskJN>G$ICCF%prNc9pX`sK#akRC2RzKbh&o=cId6k%OrqxaI<$ zKL=w($Z=L^Wp*qWbzX8quMMs&p^?BhlTQwM=158fZ{W1{F9nD$*t()Tse$$jJyhD9yHl z*d|_?ZJJN1QSyQVldw{_2#c1@QF?(qZ`qfPf*dJ3=M?;Do>#eKM<{!6Q9)w{$@9M@ zs%_5Z#aRT6x_&pV;GFjk7^P%CWwbZYQ%93J4`jG4jdLCya*xs{bv&dj<+A`y3zPJn zuIsSgV~nGgV5-#5dEK4u6d4a%+KSosDy1|<=t@7YHchoDLXbHtj=k9lBs-ZJf94$U zUG~4+b7eC|N|-RAqYD#^qm(YQQcJe6K%)f1I#cPN|Y!L@em^8 z>BR9MQM%LdKpaQXG|96pVsl_EXcQTWI?{Ap)M%-$`9%%=<;q&OgBt8Q7tt&YyIit* z>N7By1}5rfpX$fUG56H#v(2<%2dTZZ1oZXD=KMP=>!#7|Ex3y^NXz3)#A|U_1(vjZ zQ1i8Q-s@R&yPt4QT^`05Nmnz5mPApqI%Lir2$H%nKZDCVXr)hvxH~dF960TcOoszu94S*I#|R-pNZ6S0SL-XG(&&a)3gl2kd2tGaAO=cQ zkC(NsMKVkAZDUF)W9_mK``m3yCrN1&UH^8A^UX|ouHRwQ`$~;2=cgB@g=2MoO~0$9 zmgqWA6j0}^w1Of7(d4SGC()~UHoWWIqRYd&C5L9$a1dF`)crSDrDNqiT zz9QF?%{wIlcS&>0Qz{C8<$jsFL=1>1^>R0xHMiU6JiC6z%3ooS`e65O_q==i=Y*7q z;V5EKS@ITo+u^KlO2XJoERjRpbDEAMGtvzmId{TxD3TxMyyQkqF_EUsm`3jM9eo+N zy?)MDzVHQJK7Y=3STXbx4ey5m({-d$IF6D1{=oh)avCQ>48#z~InfUtL+9D9w>-PK z;cC5RzdtE}Q?CpGV*_1p*xCUNaRp$FGlvPPp*oXAnsc07s#nt+T!LC_#TV6bS#TP#OG9SGB0$1A`thMS)Dxj>2 z@t8R5C#Eq&nGK0E53HG0RO?`qH7OFp$mu9Flvp}^Cqg&kRMxyNrHMHwW4Lre0W=y# z?)#2@@N|O{b!#sZCg-G1h+29{7O(1cFSd}T#3@eXxMT3|xW0bD_0(z65e+{_@)8SoD=hnDIlvmz%qIA!k$e@=##2G=i^QSv$`SoaP&y1kI^(adpx*A#Sam_~V()7#feb+OZ5$KGg zo*5U`Yt-jsN?{n*+&V|U>KOU~YZ9m9o`-v@`+=I-rAG6!q!OS)P`Uxu+TRuIN`7w< z(ZG7%**&T1@!3$E9WgVI)6Ess$WkEdWc}(j^~QI~EODky2Z@|2g;q--I!%j6DK(%~ zqky#y5=~PluWA-J=LKwLVWL#tJ1wi z=((j_IHw94g>x9wDaF`=O&XDOc;}npnsaIPSyQORlC6qk88p8SoqtlNSZojhMA?GJ zG;z4*fL=t9e$+8Xi0j|;>vcTHT3-k8(rzmHJS$kCfyo+~wz_`RyynYjUjYG7i#D}A zMxMg_eF$q%sO=Gg!5rn?XbL$-%4$ti@C%EGa}`N#^w#;ljj;lzsq;_UTJ?5>FE0+( zAQ~Ry;mGN5Bp#3C7^S9t1v8}rta;B&OF*?$%tu&HDHckOfbz z*0x@?fHMMss|Ji|kzTb2()^QB67ZW6C8h?5qq6=cO}C6GVN1ak6&khjN; z-Ajd-csLPGBTNxf3cj{M*JoQY{%c?Qh+20MAmqf|yE|ULdCfEhVwxm3u$KSPz7;q; zM_|q$?qUHeG_~Wp2j@IfcB|NxRv&6~X;&B6qyiC9wxaXR@coB1v*{MJZATawE;c&z)gUHqIyf2qsr6V!+I0N|PzTVGrLuKifQ z|Lk+iYhCnNyYAyA$Yj)e%o(id*lf0RexTO%6`HdyEIEo1sxsh(3XY;i%O=eoFD++0 zXZbGi$g7c}W96#v_~P?deDvYhcyarJ_3#YmyhM;fWDF;EhaGR;9yuL$gczij?&_Mp z>u|l)Y_u-pQy~-xCXqmN1=|PJz=t5~f5MJ8~%83@`W(f9jgs+go0| ze97QF-dcPobnt8(X$<6;D9O>;0lylM-0nyz(D!1DW!((!-re!p=N}7AxKC1o$4q1s zWpPsFQtut!^rYU?C)ZLFY7NeuldM?9U^+|Zdm!@q^$*$I?Qx~UJISw=JW)?V)ZO=| z1IO_M-HBlZ-P+;@FiyO;X^Kp7Q z`vzb7;3KYAx2%UNHmhr)VB1O$mpo*-4*}1|!^mzoGL2E98w;9M^U}(wr{y?VtNANt z&d;v^*=qc_SY?@rv1X0MI!EVwY;j^dIkaB27{`T7%7HXV^u3r!Ex%F?#acSWSlN_A zh)ny;LyR1EA2S`{v@?9^3llG&PpsEhtcMN5u*MppYnK8cZkb{PJU*{juQyz6p0nz2 zuy&21!`p$*4LH|ht#74B)a}$PyQU7QbG%}P84z78Fc%PaHm+yK!+CC%KJQW%=bkSz z%jjJN1u@CoohA{yx&*%f54#<<2)IOr_-3P67L2C6tA?ayp;}5ccq+i38#VhLW%JHu zzP}Ix54+uyk>KzC{7>^c|LhNmsfb{mUQ^OjY|FK6xaK{;c1hV>8rzGWZ*4u>77Fe8 zo<)ck54q7rt3!49jF+2&8cxf=K?9gE5CLB@&aLoXsGA`ixxc&P&Fjx8*^pz=yf3Sh z9+dp4f{|K|tQblX?F<7HWl$KRK3k1&B?SozphX{~*3wmqr8QKstrpI#lw>WT=Dk(X zxRusapB+5&$BgdDre;+Lz|#<1N_hc-?b&xb=Wq%ptE#{3p^|7@bA~Gzs4OSybFn&S zC@or+irOOy!aRQT?~ZQA_6F4aPe9ZqPNYYu6FI5l_xi+AvHL zb^UAs)#6m3Oy^GhsUV@u%KtmjoHZ_J5Yj6|PyLRmN7(f2)_>jki2Ti=zedBs_s zr=?I-n9e#U>?8&9p@G-jfNRc$qWfbClG|9RhaT|O(pf9z3TxbV0hHR9FEzET(o$y? z@|Z<4Wz10m3PsC0stZ7~>~UFgcO8|A+FTyWSX`7W%GD8+g?+g+khOinFqJWHoj9#} z?=hX%vG1wW;`V%&&s*2Rr;f7-tFE!+;{svwU_GLsblI#?Mt>f%ygQ1lQGUR3@g@~HLLZSZndWC27EW*d?zAbAwewUF){5Y4!b?$ov;O_{gLT- zqMRneIFU{gyd@?|O86`(9KNo#I@fJ3_(1_o-Sk3=*kU;y4(#tAWWh3;15%hhMrypz zJpFm2UIH;O3N_?egcg)@lABNMWd*>7PB%JNtVVr}L=AH$7Re=Sp8co$^@#^6-%)d9 z>*q=ldJ+o638h6&^Wt-tUP-(7`^*kxzAnspyUWiSop8?0xrfb&)J5)Mo}aDDl81bL z&G+5&^6gqvc-hu!>$dg%(nh>EU!Em+Z&|IjJb(THSKC{Ob~RO2iFQsw6mVrc2rVZ! zLm-`v8Rsosr8%g_$yrOG;DY2(e&yvC`8z-PlYITlKf&#@7xdi~2B#{55Od&R_rPEN z;7|GM@BbC|`+Kan^s8&SevsTx%{88)l&J|xK&DAnJg3$%hCsYKa+jQ_Y)(QSb!h zfI`G}P)q_BF+Srv!+N{s>gt-V8*tvK^SdYK#1sP4I5JI=>s(SbAjJuBfB%O4!##O2 zq)_m-XEkhCudW#SwbZv9BzO7x#g<{S#kfE+dvF0GOgKuigpvgS$B7VgOE2)&;e3xX zPQ1vKqGSx#NCfHC%Mba+*ME#3`|7{X?e+tPZiBajINw5$ytbGKQ)U{4Vj4>p3i;v4 zI7UFCEkd)iP3%goKY86%Dl=N1%bh!#auG*PnG4GoHQ1f?bR9Tbz$A>zI4@3soFh4? zXMPG|6x$?e9xk`}Q|X7M7@4O^56uxy`^4v;z9S$1hP%)9Y`34V*=%_6{3Wkme!zBn zjdfni?i5%JTZVpv@m5P|T`O&Up!Yq4TM16i{|aHsLT6WzqiV3V_E6?L zDpLW>qP>enuo`>PW(2;APUfLM$j#87wg z+^QiK>+hs_j>fSbHoUlf#o>bkyN3sJsFXydz3%JITCBHH z=E%Cmb(x(8wIo_j3f$y+&N>kUD&qK)6e>}3E`_=LQTyRh-d#~(f2QiG=Sj4FP65hl z?8-W(EQ2iIvpTng!kfj(U}Z1z&a+uVwmANk4P0)jg0Czs?I3QIWB5PXRG_PQK9xi zj)@$jGR*=ZPE0Xr;7VFzi{!+*a+Z*^aNO07mT^5hM$6gx^;Ks?V?#7KJe_rP&eJp7*@=zH{2S zX5ODFYss|Nq}f&2v0Y=KuTe^E`#itueHJUue^loIr0?aoP^g{Na&e`C-$L_Mov{`! z`b^tkFXpDzJXWLp|BR|!>t{RPF{}pG{fgdqc$^53j)8a#S3N2wzSb!KLW0htt4+d%mp72sCjS1(`;bIGW)E0_5@SkS+@1k0su z-gR-BCz9NgS=3i%aUJqGm|Zr()b(}=Wb1pJpI;63nlGB6l~7s&*~3(&{@lBwPJgH%X+Q-dBH| zzw=Z70bl#_PjGX6OK;cGzAUu0Tq3)Ndu*QxX~Mp>gcOLTu$vA{A#fT;rqiAfCsH{H z80`|pSxPLzMo5KnEEHACH1wF_h*8G3afq0bwNiMzYcc=wRV7@W5lml!Z4 z3|+T{8?bndHrEj*s@td2k;6gqC@IyMBhia08UrGjX04}?@gAJk%DOK45Hhdc#-|G|Ipk4T|NrGYX>5b9bow^=Bw|?(m5(o;Kw2z8x7}l7l zmg2LvUBqV3z3Pt)%Eut;>={2kMPIj6hEY8%MjgqEsI#e}g?Zku3>31~`xTnn&DAr$ z^5w4yQ==HX6{YBxuU_%;SWm#~ zpb#lm=*w+>UwB|ksbja&6-)amWR05AqG&l6N$<)s_EVBbnl;dMo_-}|AY8_ zM~OnwPni^>I4_I#k#!^=$z4zBwLK||&V{xyEppYXBc`&xTJ#Tuj^|8sVx%NOTXQ~M zR!}cdpX%5af{T?1O0k&c88?t^o6F8R6~?oqQdEIgqV_3Dnu$<@g-YG1C^`lWAZ`+9d6FUUKVwr@+@50m{zG-v*4G>)bzD z`b(Mj#L7<4HP`BZRC9#)<*{n_H!y7U*;fZ;VWuC?Oryp3GXrMeOg;KMGXDg4789BH zM5NCskhNrWqS$8KKW@W&90BdMI$o^VcPwxv)RII^cF z!ZdN*?IDTCs9`5-cC;e?ddQ52k+h4%Q=lA0)wzU(Ng0>W#4lNwT$Z}7OlWEo@ z-xzJuCM62P9950jN?c?Mta}l`VKz~^qVdHW`m=bJZ<&J#uPav$=L;^6y-<^ z6UW1m!|B90PE6xT65(CII`AqCkxC$kL?)8Rl5cJ-&It83rGdWNu({bVYzC4S3N=n> zddD~sPb0hCkGh9eDdjYq@^5;pW*j+v_V<>kZa!IaUKAX++&&9ds+h&8sWE z@)IBN>Vq%Q553H>LGq-Jr#l{w4;Z(?8P70C4%vF0xxL8@zGpqG=#*|3Q(}q}r*UGp zKk(-5Tf!7bF~~-vB2y_vcKbbV-@U`8p198RZX@F&Co$r13XVjzd$+si&70TU-@hZo zfY-i`NsX**)M%X-VVOfRDZKNu610};!WmK64nolv09=}5M@%*q#OX4{WQ+=X#XJ#G zU@SrC>_)ts&VzLhjMH=yFu7;Dx#8LM3%30;xxeHwI9&Ej)5yDb?>HQf91kashZECv z!24c2vCiZB6+^$G?*^>%80Uq;?s}Z{ILW%BMt*Z)5qUU2-bejgu2IWB=50$2%cWCH z*N^(g669Tek5Hmyv6XUJQOBqVUOfeV|KZR5DwF2zRDGwK4_CjvZrn?wqg3ypzE+wC zyuLrfO^Lv1%hf_}5oKxdv2*JH03ZNKL_t(IFz1#(JUsBT-}xo}#qa&*SzCYcJAa?w z`KNzGOx0sqR8*+Qz~E^EeD3S>7wr@0ikVYb0{{Bi<^7v-@xkSV7LTRwK{VrJ0gR0i z2Mkc-Jrdn4YV4^|`n(tRO);zoaa?}&qmTH?SHHs5wdV7ej#4bnt+BS_{%*&!s~23Y zUhwe`K4G_iLrf#nwC8wuV2pc;O(KpdT*j{Vrp31Hd&$(J<$cNz_-?zG91t;aIh%iiqLZM2aH(Xv`6#fWBmz&m{@N zA?qeD48M7!pVw=T^jYd z8TnFkSk7uooUKKzAM5?)8F=a#Gn~(%<(gKE01oG5&UI$_If=xs`$5@HGw?A+ z)UsO+aGBFHYWo3+%q`}lylrQ*($o|m?IT+$>sE!(#CbbdN9P=!w{%XUdG+2ncM4c* zrDn1Bcx3-{&e7#gSeIRDY_5a`o3xybYXEpLO?6Faz_QdHUyLi}em#F!YLeHoO4cZY z%VM>nNFCwzewIe*@|rVM*(_{q{TtQ&sN;%rC(BceoH=l@X#K^Sy1f4KbM>fszL&3G ze%IySDb=-W-s@yt%a5Exxi#$)@SY2wH43!U{z2Fs3Wai_D5JAbcv$?mCrfdJ>YE*#bA?%3??~B0v8>`f}5bkf=%Fx!Rr=bv#cXV zBfK_8NRo2MB9ETN_NZV7JT}M;SjYrU5)LH1J0LKI1x|S-vue|~3?)Un$&f-KhgnFe z=>G9k6!>i1UfLA1^QwVOTYpz^2vaE&PH9+|9-TV5as!ylW2P_{j7e&=x_OZ2N);BG z(o<8#E*9tJ_$do;y|5b=bD&YTrLF1*sQ2t?Ml_%bn6n61b>2uR=u9aG3W1nL&3(%4 zrz$*G>Qw7{ecUY{+BmFt*v?Z>nw_W9j=9)@FQhtlf&(NAfC)AcGm@KD^M9PiaS(B4a5;9T(PS zoC{c!aHeP23=CHTr*z_z&p*YzeND`gyE=x#X$pZy>rb!ksn`bXtTR2ON zl+EL&ZKy_6oO3#o!U4t;j3ZN+BvP;EhJ3iB!^X4@m z(J6`;a^CfL-{akYcRkkjQfk6#{QJ>eQT#_(vZ2C!7WEJ8D^(!kja<>}!|}xyy1&^R=sSTIsFxz0M{hGZ*eDK8&`QXDZvc0~>SW8ZxQY^k()Aws$zARjApY!31uk+cb zueslS&i-)E>(4&n`+xJ7e0KLSW7w0*h?zr0XM5n8k=P8r`b?{WD)am5XZQi#l#mlt&t!9MuiERAcnJuDfU2ASMeKLe1UfWv1cXbv>(-(V(uE}Ssmad(~p-!TO zSR6&izR_=+Kf4@*`8_$3k5~m2sJA|v!RqC2Q8g9}at10XZ9Q6^|9+;`qP=F}EL$8k zS}eX=5h<&pSi+8-$2T@pmf8kS9CKQMtUWoYlh{a*vz9-~r8Fq?l;Bl!bD69wiwwb^_*+xI(@+6*-AM}egdL|*Bsw0K%*6E zj0nW&U{G2}RV}GRmH;2 zN7BXb`lsv-XHoDv2AANy+Q&xwqn4Yh?>pw}7{T|VV5t%I(rEMrp*I&w5y^$RcnIB~ zoGDm0CqkuYql-M56eo_yJvm3E;R_`{<-`<6_QySk; zsRUAv@^@9aPGwdvSGs;qG8R^=4Zhnj_-j`EGuEqT5>?JtghP^NNQr_aCYZvBT&#-A zIeOpY{eW|wFk-C3TZ#U9tF&hFA$smxLRX%eUDx84JOrzyxf%ECx3m)BJzr2_A2DAdSHb3xB4pUq&di{J7- zs{@-l9+}Urw`vM81|A+BFuCwc|LC9aoB#9w*xL2&fB1L#y+8QZgfx4DjgiP;E;7E_ zJ+#&>jiCl9+MgGGg(r`tkzW>nKR)sNp9{CZeBZ4pYE)Zy_8DssW#<%$C1Y*R)mG}9 zTW45rudv>O^K|`y^((CHaDGkSuQ0J=wYuT?%~#lcbYQo8%jche%3u81|HrtC?2mg@ z!Ie7krABmNc3NESd(7kZ(XB4KQypYp%e9n}TiGoWjifR-gH>C?s#;~u3zy4jG%O`? z;zYTIb3tjRUbQ_si7FdYSEz+UU0EwiORs{MrJZLmZmxN2^Be_k4jU>6taBtQm|a{) znIT01z6g<4BiB;297#3kD?GlWg8u)Uz1y>HNpc_b%dD!kzI{38boX@6^o+zv8fiu{ z;RlSx3r_?ugr#v99Dy{t%te-EaD)N~V`KgYcvOS|V?tMtFcAjAl3ww<10F4;KpKst z>FMd~IcHzKZ>?2T$wOvV)%x~6qk+|Ndhh*R)~ah({_^rmfg0o;BzR}YH4_>>=ks9( zl(xof9?nB2cZRYyy?bMn?%qWTgq}6-pz(%QQ?B=I&;j9bDjm8Jfx@uYT*jHPYrIq4-wq%*Ojr~X)tz4F;-E#) zv~ku+*@x*`z1kLE8 zLK6a59w`|Q%xF-t(R&Ph!o2xsulw5gizB6E_xtD_9%rh(S4Z!0zsAyg&G9vW%@IU9 zshFQ{=fM12CZ6~Cm6w-^q8_6C@IDV;?_6Q#gc;iG>!{ryz6SgFh>vv^ zZS;^n)`Rt~cMk3M;hfjDX`LJ;H4>*rcTlUqPvic9lme!iEmYA%NmS66l2Ne13llKZ z8i1tX+X7J!4#6naRhMn`fqS2Iu+D+xPAf4WX?xlu+5iWxXN!4f-Em9EUb!6gobl_0 zJfFtLO95x|s`LKyV?V})FJoA@_m6Y|jR4o5Kj?u&N6-V7SW6FiG*)&pMFE^kK}kn8 z&4F>L+Zs1K6I~dGpo&IFK!_SPR*a3ZiXd*POt2A)ta(GhiqleX|IRJmdFLH15y1&_ zI$%D`n5P-@K|@^+PY<|$;~Ad5@dmCgFEP^r0Rdd29ts&++d8jU)&+N`mjEI@eDM*a zyntk7F|@PP1W!ffjMI9L_dfa-K7RQDq)ynjiWIN#`fH!SCtrUX*Vk9LzIcY$p1g)P zUVjs>z4jWeuCBC39(r+or!<*Rh2|O$Dm2kzDH*DJpYu+>$t-3(% zH26CqXrYQNJ#GNNfq|45msb-mE+=r#K3;ryk8l3bJ9zKicd#x;;f*(5 z!`1WzQbMciCIaMb!BG~h^GS;PnDB`teS9t4< z&*05B-ol%2doD+|zlA24#x~y224a@R) z&hJlu=|9J^Y~6@9Di_Uqt8=XpD0KjF9;(~>y@wR8 z>mV~pLr2pTk*0tI1HNQ?uz}c$S|bV1BO94@32LR*Z1wuFS3{Wf^Kvs0Ky*R-9x&yB+nUe5Q3E2pJn|N19}ZW z`8<%#&W^owF9pxRxu0bYh+T(u!-$9zP}x1s?xB6`^#|iN+^c=A zou6lT;fz1XKR<#{PZjhw`}fq&L$7ShdAq*b=RADAJ5jtH=6#3k+UgFA^Joha7q&fu z!y4e9QXoxYjv9SER0Xq%2~h}12oZ!y0wM=Y0&uMebptYis+HfekmqXpuusbo;cmIX%bS;2x098Gi3pq!qgz0An->$*Ti$GNWY<>(acYqh z8I&iRh*o&oS26=&R`7B-AYN(+Yz@U|)2+tl7C=-WTSYYjDIr0f)Z56#+G)U7s>z@; zGN~a)zdwKcsq+QHE81pzzlC@VRv#wDKGZ^#RB8af=T}<;cDT4u@$hX+8`5Uc5Sh&n zJ;Dy0O+KMz-AW_%v_p1SkHhyKw9#apdkm!#VgRC#sVNzOM8lNHiH_V0qw%DIp|1bSpGJRQp|#xkmzc!FNFc1!a!SWd#5PM6gU?%!qsdO;<=4myjvoHowIB zd_%ZNht1aJYhP9REn z?X}nOLqGIc{O}Kc0iSs7O+2}HhU?2GxV*eZOj?(<){2@p)U2fomi35rxxxMY4PM^8 zhh=+?TyAk%Z&6ky5zE++YsOkMcdIrl2^E#e9Xse1U1Y(mHm=XrDQ&m7NIBNVylb zZ3CdG5a0j`N)i@>5)+1~^{lnr0Nb9YHnXnsom-;Y-2Vjt$*r^wVnuLf{T)%+`F$U| zw}n0Dte)RRy}yrw-=F?3uqzJMzQwzhYcaWnzyjI`}@)}F?iES}fh!?W6b@X#_p zdXC5jr3EGWd_!v&-`(9oMDVwN`5)ka{FVQveecU(`U(8{*MC>b3f8Wq0?F8hySHt8 z*aPo7`eV;D|Nr0D?#`~$jtVjDKj4p35KIGGsD0 z(ZhLTU29-i90d!IC8G+kZTgy!DtIw6szg{Z83;va?4=B#t?v=v9~v2@3nM7PQfER4 zP|83j^s#yOP<|KGzNkn5i|ldsYVBjS+N@Q1DRxFr4|g<~M^Q^MaYBkS<}_;sf~4sZ zUV^IFUaD0M!J6A`s;e3 z#kMr5d3JOJ$Nb8=lLch7-VQj2ySDGB2io-0GdWky0Nzs6%zN)FlVXa0=eaS3+ajCY z!0RFA?ydAQr~%<-=&|T9lfSAX^|rTR@MS~8+HY1L8z!4s^(6Zo`}sgkR>Ji3HYdJk zfCkFX{eaHjLq1;QMig(QJ9WtK(&t+{ZEK^y?y_1xGVBeLIRu6nLw_q_*q--lfC?X< z5dg79T4*;dV&ReRKek3y77i(B=m2(Sq-1;T3{a1tyJ3klP)tHCCD5Z9oJYWoKj)W6 z7r1G-MM|7GP0st*#sj+Mn9Rh^{e5Q%_dV58Q-=`X$BYT*mq$lv#DM8z#T=m~7ilPi zS%pAF`(DI2037d_uu&Dk_T9qG^rw4#Q<={vMdP9$kdsffgXYztR5^_J)FuC)^jx&gi6(NJ|pIX)_|f5 z1wa&vhM(2|Dw@NmQP~-Q64(d5`Q(Ea6CpFWG2f->{v4Y>lL zGPbfpKxTR7Q81Q0t6>4HX5Og+Lc7h(U$_@p#1h?|*=A{K=o- zqxWBeMU4@GqLnld02xFXLKz%Z#3|!Y1tkZR5+K6ZSRf^!W=7eRs7wqIdAWxev_wgo zA~@I0n!f5TcTFU0hs2L@>_@mzS4Tr&&EY(QHpK^2Uk~qI{q+)gWN*jk9ZpXe|{_tljhw+cN7uN*$U^Q4$!NyA4Rkb8-tEw8w}Rl~~P`n!K0|Ih zB#DUCWs{CiEuFZnr8-r#dcnj{!@THvRZap%N&zV)liLn_VRG3IdVyQ&-Qib7&!{35 znKFoq<(St7_(5IfDLGzJmiaW}FkLEn9#0C`N@#V6^*o@Kz99nh1UYJ}&9Kn+koC1u_T0lqeXo(LaB3LA0GJGIdI_86 zF%=jHAHcNTkA}WrXoUk&@kk53;rK(xTE=rhI#Ayan~gI!Bcyweh}>H|c#?;+Y#$+G zpbe_$b6ZDkDYoZ2!}D%z+Wd7V91mgUp5oAq6YaUL$Q$Z$&OdI?@shB>e$9`- z^Be&8=VJGoh^TW78V*cud@?Wa_j2`pfu25h7W&^lTg9SHdkFK+^E=!RwKl)vdEdr+ zvm2F+q|l94jB2EEut~I<*ChiKv?M73R4fI+;6)W>cJ=tb?)-AxZTfFh(6F(<8q>MVUC zS{IniMasbd@HAtd6Uw9lutuYys03sU#S$jOu`gejyG5NiQ=Cv-F zP^c;w8;}+;Ky=pU-M`ww(u0990ji}KOo?#ILhT{%es)#>;^Qvn30D(l%c0C$)*Nno zCJ{lnsP%~}Y7Gz&Vhqiz$HA?1S_ocBMy(m^CRjHBC$(NLiBO49trlLY6R0v`VW0q0 z@thR~MHQ@5te}et;AF%{6&1wfw6(mKCT;;Yl$5%0e94&HtD z9WXO~@CSYXa}25!TYi8*b7fyHH+cWW`*?AD0SOh68K>hB?|l1PxIZ0nb$EirGg3&l z=Od;$;__m`G-w zINqP|{P_!{bih0nRX!0Ah#Q~{q-h%{j5N)-zPd)5rdAg`#fTIqq%leL0mToolN;+aoH6xdZuxVKs_o^uf)@Za+3R?Z}I-J2aKFt^x75q-d0|8Ue`ns!t89YJN3~M?U zwN~U>kV{424P>S6HfKBqD~V(Xh;dSnZ<;a13(V627t7hbN4>$=Yo6G1v^r| z{k-e{l$g>(U40Eo(;e;Z55Dh!sEzFz$nMMD^BwIxrTyC2trsFxDz^XnDLfjN*a*l* z$@@xU8^JlOD=# z=Q{u~P_Oes!5o|x2G7h8D>+pQp_(G08^^-6WHaDrq(nuniP_p*E5H+jLITHx1R!z5 zL=h~638J;B5p@$6y?@rM3l!1vUfDwLb6HW!hHT(4XFU!KESuX{cYSISA;mJVMzck!0n40{OLFU6t{P`c>B|D z<8z<=EZ%tb3{%oNg8)$KhSPeFcRu(Q{_q=r0KEIBSn^Rlr|?kN1=rV4arxvDmlqc} z%roXGU`hdL3Sbtj%LzBP&++o(=Xn0{$9VDaOPuZ(M4oVU`2>fFzzIrPW2~-$H7r;| znb;IiGC~?v9>PQbB`vAIKrI#Px?x*@(^0|i@pxyfsRUwWqxZF5i=YN5-vB4IhQrsg zer{P7y!-CE*jC{E_ddilT`DmeC&UnNNC}6-1?Dts{uBpXUtQtyaDjQAjVOsMk8nmx zb0gGILB=NB2W|gsn?45gc0z3T8G7Zt_5z|So{t>Yc5wDXuw<-}bN{n@Tld&u({Kr54pW=V{&Ht|5?#o~L3H-+Y{Cg-;P_uh1D?A)>G$4$l zJpymw6|?i0D0hY1Ye$Wrqb3sUjF2|7=iZ7vq}z{|hTxCy5w=n^(q&t~+lH76LegB` zDnKc^#^!p76eBP*VhVaFuyP&*CKM|%quYR5+J`iQ%&7dGDP^K(N|Sr`5ual60T>39 zhTk=uPe-NHf{;Bda5RFbq0v*7#*`o(9~Iewy%u>?Qpcn^j#(ty!)q;VzEzhp!x)q} zF64qxvaJ)d>eq|{GpyNsaEJ&YA*BiPG~+NIFvS@$P6~jFD}J!DOnrXO0fBpThi0~a zULRYB-}jW}3I=m}xMy-SAOStkv*qVD{b#SRzv|}*5YIvFW2CD7Sr2*aoB`H#={nok z&fVp&(p*7Y9%{7l=sC>2zcz-NK{0Z%5b{;spC)pWM zrG<8qE5g7o4RHjz06KY;gJ=TCy@vi>B6vmP?`9Zr(5@+eZsf7*1MW4)04mRnc%xxt z{QI#8iDFzy&JbNemJ%p!KF{0sDr1k5-2ueh!j?q@#dt9o?qKP<_N(*)*ZCf-)#3Tt zKD04-bS&W!3s&N`s%KcLpi;H8306haqEE$bk|G1Ru$BJEf$7Hdc6OXKCH^1(@?V09 z@a+%2iFI9ZeSM7-6LJ-7IjiDt^^yKx8+DVcH_ly$L64>=+tAP|VP z3{FT|D>z1iL{=6=^N=QAu*nw0nlR4=c?Gt0MTW-7muw}LG9yFF#N?78MITCPY;9Iw zn}LUO?6U5BXV?C-W(C5;KnN9~R#mjw56w}z(!qCd$fOpc5H$QkjO?k3g;PbH(-?r5 zfHVQ~9B?p0f`*jqrd1_#RZkwF)neYOCm8)Z`>y(%-$j{fwKYczj&v1?(7#XUdvcf8 zJSrjr&GE9&H>PX@ivfD5f&t_T0i#r-JO|*`3~3f@4ISUCO$9(eMM&yVMi2$sF(7fo zfknx^tcEH|fK)<;ZsuH9RX8$GH>;191>2U9b5#IbpbU1~Jw7^q8_(;z2+)!l$;e2^ zP7q?Kw>#99q(Ka%NZ>HH5IZr~zYA~SUhaZyOxWh5nuaH}Thn|Fm}w9!XgNadZwt8} z$=05~yu%;;@i%aPzu@BP2`Fg!5|2zc-5v4rqZgRdjJH1d7D^y2tV$Ibz$isoe(%>6 zi+RQbPUggz<_S-pT;a{PUc>9Jzk$QyfRqwq&||39jMMQBFJ3&y#~*%xk3akfAAk4} zZg1|u2zc%3gzM`|JbU^KDX3i0l0Xq6f^{uePet?ls(@H?($pKAz-a;{^Zp{EY!%ZI zaEgRlH}Fw47PmU9Yg=<4RsL!?A__q)8lh367eFdu%>}39bG&?UL`v^~X#!DDB^883 zjCnfX>hcOtpFF{*-ufiwH0k`;3UJVn=Qtt7145Y0Q|KAgd#keUyOaXW3 z^SC2L4B@6Y}0-^1~KGnrDG2hQ*8R$}+| z)strf@nBTD%QKlSCm zi+}bT|EPWL%Rl`S0Dxcr`tM>DWwNBGXHrCJkyNeUXUfqlpZ&;u@4$>JYJTqS3?16` z^W#sf&kq+=pLO@vF>9G)fgnl(=M3b6x@KhFpwS3g`YLC=2Y~@TD1ltvAhLm3kS6D= z(Akx?|IEwQ&Z2$0$dPWJuKssBSA3fEvwP3Ta4y;JuK0^;#@41j?!HVLKR z-93U#)B%cl``l<$L=86_U~JlI5DE~4P!LM62$ujF_p%9gkIDlK44b^s-<3xo5J0se zbJdbEY#zehevk%6_q*Jr1W{|h0+WF;*^E!;z=Mcdh%3{>_14!`|GZz1t^F1eVqwO8 zy#qJ{!Tax-+!*qP-J5v6=f-OU6zwxMcb=E)FISNVyQ_OR(e_|3>DB>HwFo@rp^&~_ z0i4%S9y?XXMd*h-U?BBOjyP!GKC=)Q>7yFhM^9e|z`jRxO|+b2IM_QIL+b~ht*!P` zyld3tP3LkO$6Ei15V$EZ7Ghinz$kv_zFq`_0YYlSEaNlA&r17U+ck=a5uomdzX~$S zemztFsk#v!tgZ2HkFIU!`0oCy4~s}EA3GX)x(C}0SK3RDEc$LB{xPuK+t-2pgYTUg zY!x`0$C&o=q#I-Q&m+?LRJmyV_o#?kH3G=_0!nG#UIHPA3}qjO2r&sQ!eTeRwl7?# zd#vB_|N1}w73RYMl}}nCARPbzb3LY^ zQrJim6^w+zgNqiu+YeMhC))DxUjjI|V&Dg#lVjNl+zO`$O=LGEB2omPwB3>b%3UC` z9jY7xLP|(evam~_)C`~^XGUhVUW0lfyoWuX9Saz}B(J*q6shD^kD-Phbmdn+=aEa! zxb0)t0N3z1Clx14YxO*67qk%d8dK?EDMHoel2rOrhh%wgZsyQOg z679=Q&&oD1@raWP-uNEzS!=-cMu z@i`JeG?aK*Zg6+|99!NHqV3yU0p4&t9`XFSzSlwoqY)~Ug46LHcQ?;*^Wr1iytu*f z{saQ!>C^c>VQfm?!l-2g`|FmkoC}C*0nia5^d(7qcMEgu^A_aFGxX z5j3%~Yga*D31uO~SrB3c#foW;INqy4Nh1KVI&1OrHz8s|4nJKTED>*PVO6R*qZ&kJqIXm zNhj>2fb73NDv|q(&OU6fy2Z?`?XJMtb4$_O@pav>tqOvF@fW_hyT{Le`S0U&zqI@9 zyp9d9nw1-M5MUP0*4klxnJ3pj%;aeWo8tK8oJ&qZg;%oO}&C%M{ z1utGa$IpE2m+|#q?cvaX<^})SKmA=~$vV0gejF)1Aed?G8Gk1lhvK_lqbEvR=~q|! z+j{YL#=f?-<4VhUn@HDY=(1ZxfQ_-$s;;Mn~~QAo~22-Uf%$#^OQtZxlIb< z4Jkl~P*^lg$-(n*hN-+&BaoI&i|?*$K1MZA=CZ&{07Vm49gE}WJf7KyxJHvbK?jg+Vtsfj~U{sMMN}3k5r#85YvUN-R(>M48pL2OjqwqPDE5jRzTUG zZSg}(NjkY!YwNjT)4=cOiQJ9X_|x{t`I0&}!kimJ9z8i9IZt2p8VlN(kIxbjC0nzE zb7nR2yXUu`gMA-)4zKrjcQ1<|JO`pa`pyI$Oy?wW0LwdG4VPWJ^Op!?87c?GHiCM8 z6WE@|?gV1N4L5eF%fV!P+n0tb>@&KL*<=uz(G9)y;qbjCa9rlvf_66eNr_7m&wb|-Jx6*0Galxj?#5D+RT zL<1Cz07j(>l7dvD<_H6*%Zi*yYwA*M;h>_0^t2_TUgwJ>^n;8^<=MCq1ZW3de_=Pj z23DPrVyxlE&5Gk!6;ZDRVDspbsd4K&} zus+0~p`tOOjkAXhtMDJD3B51lPnUw#$O!!Y+#~tg>OI%X=ND^-jKI~)0#D0GcN{wbIX$| zr6N}a=kC$gbWlPHggGS~Qb6K>WT9XjG*pC>hQrYmk>&|;n!rJgGTWxlq;=IvV7+gQ zQKKSa04VAjsKA;tcm;rhl8uo%XPwU?t@PJ!PJOIue{T%m(^M)#E`of&0DNl1cOfMu zpA%q{jN|bhAAaj&$h&5BWCF2zz9SPN2OJ{fB1K%xmq?KzPtsUXCH zmutyQos1?%YqF2K{PYkc<8-;aOu^FN9o`rPO6Wq>Qi_WSr5GB4HuEwv=f z0Df&<|E*v6>%04Y`78eb$K%qJ;ZX?%+-uPf`u$_AO}jJ36#O$_(V1ZP3e0&Q_v7V5 zBj)+@&Y{VZ{k{Dj`rHr$M1XZ$@$vJI@Kay;Pw>xv{lDKm^Q%AmllZlN`a9UNiXOK4 z5w98RXRF9gma4294jcRXapOgAYn$G)&$V%a=YWfmtVrwA_$WHNw=YQrr$CAV-~b8{ zYt|aUC0F$bFB|G9<8*h#?elwl`2NTE&O0CC&%XIBy#M~6p_CPKDj?DFLd{UTZ!z4% z=<7nx+x3d8VV64mVSt#(fSfCC%q^uU1T)~9;kRlQBuqWi`n<67z@AmAV9Ny|XT%&( zQbwr(rAD1=QST*K6*oOY0~+xYvw~n_S%oM8Bb#NuTG_Q63QEapSgQq)4J0RRo2b!@ zWdgx+qd=&QHGfn(4d@v;pr+8%+2Fwu0>&-r@<+oI`_Ou!9kDgcHujZjBUWom$qw<`cv}?fX2zqi5?0#J*)pN<`+{mcff5Z5- z)DddWY7*7pQP8d^V? z*p{stteCj5y^kK_p|Nd#sFC#Uu}n9d?!zS?L$wxJ!3;j-FA&7;IaV1_ zTl$#3M+gRTX)vp~2cMgQFJQ}S=ONr3XZ>t)fQG*v9GK`UqIzHj5U;M4Bq5VB94=+W zx-OQ#wW4_Ll2l`7wn;|lOp&Fcmb_~Oxix_SW@)d%*twVu;E0NlDuTKetmgi#Yzk%| z)KnXQV;Gxo05DJ3%qug^895VZA{3z(?gC~dSn{Yi18+_i)$&&DZ}BnpzWDz*>rV@NN3B541*KGL-(9t z*}<8Hs7+JAG$muABxLh!=B#ehYW;H%*^I#BLCDmY_k7L8q-~GUJ)IU#Q>;d621*fR z^FXq-sS$Gdp@MEz^|5x3C6VbZ42ai7HUI~oOKWqA2CO5D08MKQyTEnzg+)V{QCM@M zHlS=3%Vr^)>#CmEtm~=)8T7Tmq}Hn`2BZ)%rGP0Vq!^IQ2*MT;9}+7W)0{9J4hYi( zA;P+DO0HxFRZIbC*15X8yhJ)oAQIiIRj_Uu_oox?@2lq2QAL%4k}I|i+K&wE$jE81 zi<>hoM$#N~dq=^phRP{x?*@?N*hYYYF@gp`E)}P;Ag@K|f*EA%9x)-r3De;M&z?NR z<>6q0QpwNOZN>fFEpBgaAyhFSG8jc`VDyo7gV4f#DdGZ9;Pp&XuOrQu9 zQgSM(q9k~0QL?3NL9SXlsuopX3o$BbO-vwY)i#fHc+N! zkSRrM-wCpXKL|(}+>3gDw~~8l5g|w=l%fEbD)8p(uj4QO*pK1g`M3WHe)#jB$CKAy z12H3uuGbVNq?i!cSz|{{-$Aa9>9~jddI)ldzjq&gEIh64z`n`P!LM0UG{tlXy(${T zuvxzEw&quW-y=#cX6f(BC%NYr9;xF%c$5?8kg&JETejV6+`;d;6~A|Rs26&sJoh^8 zri$?1gSJst95|}?U5f5I6pQ%LXc(3RMgn9-6+NGr7^ud0+j{2SNSoh5ZyX~thFyk{ zEmv{kaEQB%vNhF6pL`6PamUuP&nWd;q;0NVLD=JC(-wn8OZD~M@A1G`#R|-;b(Z{q z6lwX%`v*Prb`_h)YN5)?2(EgsJ3wd{67N5NP8MZ*sn-|ox|jF9^#QQ(*SXFIsI{%h`-f34^)vyCiVMzHpp9zeWDYUO zD#o<6%gt!usTckH=wRE|e_ty5&o%sGdw*Xh^`U%vl_8Tb7-5FXOAu+__o30^Mz*u7 z#dGZPqYR$S4VniiTE2-D%n+aR? z@KORr4VM)sg>t%foktzxv+$>#QFIt}H_|Z7D>-^0EmT@ror4vg53Te|4@OZC$td{l|j}RJMT{` zUcO}8Co7iKthyDb87QlQ;0AzgAe|lx0>sF8dUe2SuRp;&A3($i7IIrk#mkpBczN>z zYgQIM!K&=j(0t!&A$8?^H7+1fCF>K)irBf+!=#h-vC1T3UOu zwtTk0okTB$fLt~l*L!4UP}I6%W!;q#xzlcSr3BXBsOtE2ocV;=_{^#GikTC$LnGE>e=hBxX!^`LkMjr zj-OLOd*Zoe)Tv1g(-Su24T(r9@#}e`IRS=w9+a=K zJr6O=gSXtc+RmGH=5*y)j1^N^bDdDxU!aRlmNDB8gQk}m1FXK zZ2Cb}qYqc*6B*}6xJPes;Fem(M98M-Yh>F70wdB2rU;@*+iDd!NP-#Wqydfd+SvWM zFe8D11@cfs3w;OR{K3J*1RL>}m#gVNJ1FouRN-hK*{g{RtkGvQ11r03rVxbzmm z#`hrr<`H}k3xN!T%dn^RD}{FLu2oa9P^723Yzh!_&aFh2v{E?U2D_hoDH;GCz^ohZ zq_2B-I*9>Nf4}`RWr~?GO$mp?jEjo{(mW%jgcKPF8d<`IfEj3IoSON^*3h;%mn|CG;XLp0@zK->H$tYBMZ69Ao zN-%}TYxjP)Ycv>*z`Zn5uiA{Y-cOZl-z7Q-J#3m>GbR{50}5*@pNOE!BOPYYln_Ip7ILcYZ(V#*f`vp!_2^j$iCZ_w6ciuK zXkp6J9C0`taJaZo1$LTrqZmu-vMgBF6?IjsQn8v(A{Du0Y(d$cC7CBRvW6Lk!O|+0 zgF#x`iY)9|`CpX85a~GQN!5?VA8l>|@_LD8=SxB@_a*xUZ z&_j|-1t{xSQ!o;w05#wcp$dZvu$7D|8D$d`1HdArA;f0LiBVxA*+L;2tY8{&fDgZ8wRWg>cV#*1$ zk=BE*1jz*~tc=~2v2Df5^<=DhQ$x@Z2n1fU*~PJRE!Ndmj~eY=YIabY~XhUS9)LfZWIHf zdj&x~XI>Z1Nk2S1@S*bVc}|aoRPO%Xy;qwhTB=9ckSYEcl(qiNeNER6W_-XL7_E85 z^Ow&b1;JnY`M-`|{mtLOmX!=F1ie=X0q~G$eb~b@3E$f_DuC^~!`O5q0k!)!+u`{@ z4G-@3=!%fq{CWsA38}$Z0G5DA0f*@V*OyngzI=i?O$fZ;o8Qd1z5NKeXwGVD2Na#Q zbs_upF@gmQ?SAFew}XDaqNPN&h%_FQO%aH&gt_))>a8;DmhuV6|D$jWO1 zX)?n>m4h`0+bsmN?RR71g)5yNGVUM)J2I^np=SVs$k~raFrp+oYWty>jbC)Xtw1Kr_5?|4-=!1`i6>z}R#<xy+8K7evGgAEIQty$5G8flz}7yKh~3!NK(EW3 z!3^hXh(%Kn+M2h=2;lXxeck$)Xc_?qg?N13e1{^B2ns?w+iZTMg;c6>0B7O$yK}gX zz*c&Wyim^*f6F&yn4FEXKYpP`#T? zW)znj=jX!raJk{_{8D{K8rb*ORF-IZC{-~GW@KA-FN4H@>jM@Zj}U+qfGL7g0v{6M zJcAAsri&Tr@__l`0z42lj#mFY9w0Z*KGp)jb1jYger@ zAptR5;PPTdV)dMB<{D6I#zwkkV^o&;kSw%4XozAV4a?ffhIL!9t&6e_ZyDQGfvPeG zQn1z)OAg>nT3CGpYT6JaAkqXDhGfCIRrR(bTi93uf*=GfQ9?n(JxD_;^w=!w`OU?6 z5~?a~l?WvZAdJhy75geWig=;u42Y^gXpveAxfr8(h8~EL}4PX1}Pwt-k<*)o#xW8W% zSfVS?PL|^eiWAg~eehK^0-dG?ivKOGzpgBdT|WnVy$`0~cxY;~Fq(yPkcUmRX`VR? z#L;&1%SFXDgy`Z);xqUHpPmc0=Hk|e|kOW}A3e#h%o9t9^v z85Iis<*ZZKD|WkJJCU9SLx6{~y)s;{DZZ+di$INv0+3WN7=eK~%{a^#8qt+9Vif%8 zpA_8OJhun|N6pj}J_RYe9uChvZ^xs}+kd|SK{UnMUvqLt4FxTzOsG`B0&o>j0mzMK z%Kfh%@Hin(31NzQE@yyNMz{z_Jee#GmW!wob??vL=U<;I#kK4sQFcJRYT1zDsR%hE zg^Ut23Tue2*S4-h$m;Hyo(pJTwFSi+=cFgl7wJl_8(Z`_I$14* zSv+QL2)`bUS!eUggAw3-y!u+$f4>iJ*JBzpbOQ?G{knn6->>Ghk)rkCODW9*oO4Dl zrGek>0alr*{j^4~85({3&N?_oeRv0a%-lc#(iFUuqMl0*h^j_wm0A(R0kGeT+g#LA zj1xw~>BVXvdOm3gjCq=nQtE4_wZT32-hQ;T)QtyyZHv#r$YeaMoAx)XY+($T4wI$s z>A33}CuK9I($>fb@&rv(HBUSdlq88^Va*m@ATXu6b5XRhb%PNsCC8NT5%BtV><_qM z0A$G$9&vGYJqD&7cvg#&0?+{NcneWNlHGUD*UA{dL)LB@C@RQ2-5 z&zG_7`j`(B zro#-HlLFw`DuK)iah~*FNr&h{Hn(|Vm>4s4hKAW z@&wPGJ;Qu)(2(UVV_8%^o_h6QYI&^+ zEVi{`Sx(qiXYEx_p=(Q?bIP9E>XR1$;$CZzNyA)F4Fvnah<+&Q7tuVx0uM(nD8;?G zVv9K=7t7DIHO-=ny08|3E~R2PXBw#U++IKdu(Kt@`q3~KqvZvb<>y;7C@-S2Z{H;F2FeAZ#&Xi<{+HSuU@j5mfouInkEtZJR3K zjex^)U9y%p5?d>^D6(UYh>;LO(OfU6@{!AmS~CQ>kz6H?@RCO9pnE{`X$g)1^`M#Y z#9itvh%p#zo#ycp6Al-XhA<_;mXA1|GB{PF+4olf@gC#SdIm!yA8+t($<55 zUkAWO>cWf|5`=&kw>P+3kD3R*t=hj@a5^gam+#LaeIK;Qi}8#eBLwVBmjYzbL}d5= zR0eW!A`k(%f(s$A;CPIP#E_^YSW5g-8*vE-0!RHvK|rCRlBfYgG`BYw-Df##xVVO^ z>Kdw2QMZasHtj$zkfor86^w{T36Y~3`mzP}g$jy55MUxLO#%v<)-h|X%{V0s_w&#s zOB)e_fRT$}TPq?T@a7wz#1DM`590gY{tTX6T|;07M2-kCA%p~C4Sm&oDpM*R(fj;B z#(?wOIHmiUwKPz(YU>?bF?e_wcZGDEOb3Xs0$8Z91E} zG0aE^)ZH0LOsa;~hS_d5%>UP)Ud~BT!II1oK9fvk)sm*Qsh%@=pQO zz@Mub`%6nx6DM(Ug&tmx&H!0hk#odG0aYRhQRPbEM&6|7>ZyzZ9<9KedO#O-5ciZ z#jdVtb--A9S_YtCB1TX9i71}S+CJg1&Yx>WOF~Z_^fp!LV`4&H-2LgjYBy4A2(w14 zP1B@czyNw6f{^l@RISHja!JoA&H43^*4`HNBuTfHJ&Hd zzotK&ZB(*1X|z5GTCS$oG5^d44_iT0Jwy>}5K2Ljf~9Jkw8yVt^A2jc_=7&a2Mx2W>SStP}A$ zkg#Y9s6IEu(eHq-|4o+0qU()27>4e1|2UHZ-%!a22bKN45)|Y*J`3)x1cceh0#(rs zF@Tbi%Z9^*>EeKJc|e>e@T^gF2n-=8Sr-#F0BhZlS0FCSqG&r0fMd2*pANDX8-&`+jtb ztKL$NR`p&N@$?at0x)OXUEJgTc*1nt*wD#WD8kAperND;J`?M5hnx3tk(8YE4FRXoWoU#yw+7ftB&zz zC5oh4DjDg9D=cj-NHsDe%M&O2S+k%PfUses440%;jBtR(Sf3d&G18Q9aX8@m>H>#( zMw%Ii%Nf^CE^v8yfjD&{EF!3dD+a`->1J1Z-4SrxV*kJvJXL^WHr(!a7X~OT#|Z#&y)wC z*GaVh3#9*L2csU~J(shedE?>N5A0WY@*ZCM!?QZ!*Osj|cE;Df^4E5s`RdpHA@1+* zHE+z;0Q(|p0L=0p#rsL^_3_Z(Ekf#%GEHf8RkrEMT|tr20zW93IJ0bz;g0UPXwf{o z17nzvVLi7ovc8OAeSVdkaeH@*|L9AjzD7@gdt!R8hIajh&9ZSAz;8z>jUd_2bl4f|hVa8h!rO0u50$KbS!E$zqOy5_<9tN;V zQBtTHRN<@UWvmVOb^}ZYecJF^3rgOQiLjU_1r^{Bwbmxcekys_`0 znsYiR|6R@2-`P1{j1Z_=s4@-lnIl+Hn~EDNEv(hkvWETdo}du`dl{8Jr!su6x7{y~ z+5!M4#&Hnt)kdnA$w5RvBBM9Zo-q{91sIQH9+8V){LEkN5CQ4 z!rt4qEIPsJ8io)+rT`48>0X`=4Rm>gAA#y(*BQW@}{P2idq| zPzVVVA3@3W8La0a@h9#UFV zix|2=`?WO6U2gNkecs!e-bZYTJ(qp{1r1O?h+1f=PzH#JnsG$iz0bq+w1_sRI1AaX zwSo2T4u<)xuRT3eZ^SmXulPPY&ksL*ubt%#LV=n!&-Sqmi!h_Ia`pr(8N-1Qqw+wJ z>0w@3B^(Y)FngGg<{9BIfuef-s%f-pI8>tBWy@H%jFK~A$psROJuU{MDVl}KlHLn| z=sEn-W|eHPLyU;g!Wdae3YO)BbyHHSvRP97a>BYT0IDjute_wyLW}}VIx&?jEZ981 zQmHLMU35VOZOy24)B3GNJLKNhQWRubj{ey~)T;t+RA?4dfl*|`JgZ(-#{Z2sFacOM z^|Iz7U@9JAqCm_lJ2ZV&JpSL-QmIBzRMqor;H??LY`?n)c`%5!%}_BM>Vqc~P~hO$ z-@)%R15+YQlZU28y_*EJu2pKG*rimIO|wzdBdAJc@o{z_3Egs_zjr{g_t z?(T3r9l^Xo%Z_WlHQCr#=)BYda4X2&*8x{m&Z1epC^8}k1hbT95hbhIDuf7^mjPGT zm$lz!ZZKswvO}MI$y4D`%#q*7WSql!-NOSd7uU0^pR8 z!h{qrK!H$$g61q4ivUtHO5ISahN%^3?lhtrHc}#_!-U8a0vX#X1u!R#7OBSY{Qolc zroFZ-$#vL@%&gkeneO!F?#Cu&K>`f_1sf1#k>K3a(CUGczKAyDPloM(;!kRtkVum- zEQ_QFN-zZ2f5Cta!xY&~s+;}BJDg$fU6n)lLqud|?X%w_>*2h6?>@Dwva)iB6|rJP zDM%62p@bu}8=4h$I&;_AO1_8fB0c=7!UGDGWqZwnSZhqF& zd}0U!Xw)w1&oyIoc^5W|1E-&}sy(M#<|xL9U;fTdF3$V*cm7-4-aZKZtQz>N4hk#x z(&fWB!=t4d3GLbRdCg$d2$L8CZ6Rz=+ZpK0T~w8-;nGt-iCP&y>le1@O(|G(qXAoI zbj{LeqIyrTwaUPA7a1-E^E@G^h@bk!Z{v^uw|}|lH^~Y9L!_Llr+fgw7!bY$1pjqD zv#w!vYAwz&09gCrNU1d5=|kJt%_ReI*80d9DaV>mC&X1LJ?Y&Davsboyawst!X|Rng9FR3 zRY=&0avFHDaV3l*%PU3|!vbRg{2I;K-c4JRmhY?qp8A3bi#gj`h6+y3jn%fIRC2S9 zC92Ddfe2}LH&jmOtmb&LH6(*;nJZ_sI-t=t^++V9KWV2`)717!w!ZHgjb@*ct*J$m z)|K5>%WHL_U&d(hDp1z1gK~c-+9>wE9Ko?eaa{9L?fIcJQ-EW?VYE-_>WSAk!^BTOKFQQ+=n!K&S!&qtO?%`&~&~Gs_zU1h03iln+Wsmv^&YQoGItFWl-N-0@rzau&*SQE6HthV$b6^^_sp`lLc2a<51l_B31uD|amUbxaZ> zPh2pigrv1Mb86t188w}*23BmPu??~VnVR~5!a}Dt_12pFcy^@ep9N6XCycpMk3L%5 z&6Sd*JtA~f>ba#zPHR zmlA|loTO%8E`W1c1j%yH$gk8O3_c=d0ZLgH)e2V^m)LAJ82uXFc^p#2-QAtgo-?ClhvbiNq?8zaXGL+f z!E16>vI-amhxHgRgaKsR;q?2|p-ygFcipD`UJavdCD*f|VN1u#^ktZ>0`V(br$X+q77u0{)N!__gL zJLgLiFO||>p5O+L-Q@+IKYxa+nH|e4QnZDWB|C#;FOV4L`n`wGVcmZ zB!q#$@T0?OJz~4rVi-mRz5#$oN(qO<5%d0lISPpGjjoazJPWn?`r-<2zx5VgJbw$j z-GvI5NgG2LF@%*;pAG!_W`HjMXm7H~3HE#HHaY`~%tqd8N4;LR*_rXxopt8E?fw@1 zkTPNM3&HQN{OW&?yE}>eni1(VdQ-X-ng*;i`ci=}FPc?ZF-vn502bms2Au0!%BYd& z3S|1+GrNszebOj)sK#1<7#NcKm1a1f94)G{#8-|0xPllZNAvIf{6EIO`~ClU@!enj z_Rr#f`kj9xLVapt4*-BcoRuBuKY7i|hC>;Q!3wv(G=poc8T{mXk(mKoRiBD_tEt zCy#Jy%r6_QFZbkQ-P=%PPnix0`@@7eCQukLYwK5HJYlk#A2Ze&0Om;GwdzZX5o+MokrA3%=Bpp zwiXd&o$zPCZM~jzfR@y>Qc1Q3pGL0Qzgd;46_D0*+MAGTYb!bj+yX>92R1=WyRxkn z5c)6^Rb!qN#IWR(RVD$GrF6;O&sI^vp4ry-Zg`60O8ef{NyjEm+#bkma#9wP>6wI3 z!JaWeioJ3Gc0?!N=BYX%VN|mJ^r*pn~P3i>m4#5YoM$r7|C2|*R z@DLCjB&(RgYo|55gt8$N4h6}%pd=ALio_t_R07Rg1mKPIIo z6SOX@{D@&L^NbllQsAio)HXdZmf*MG@tC*GbFmPe{2r)#d-NOM001BWNkl*uwv&{Q&At$ zb#2x<&RHq0F=lub4Jjpyq06@Es}gl7D3OupMuTPssOTgN1oi~K9Gw$yaZr^0wzGCbj zfHDJv11@(SSC=bnH-oS+h5#amloO`o1jYe}sUR5>p&KvgepE9`-i78*I}e0`FpM64 z3<%?Z)p`I>a5y|@*{dw2hvtNmGV)=@v_D{;qt4B?VOl!VVu~=KByniXs=S;Mkm2D+ z!u`VlKYB!DgyayS1G|FxD5ZCDDMFEPuC_6Z11LDaL&j+a28tLE5R0s5?5NTK1!9Tg z0lt6+21cMb)=|KSIpLURJWK~n$GM7CNXZTc3So33E_RoA>&4r6`>l6yd2x;4MmUxT z`4C17!%9AL9;KE$dJH_N1G_aeQ9%vYv&p{CEz;5!CjEQe@Lc_FfAFJCy=__+`IQYN zVVb2R#wqyy)nEG`aDV@x#<@j-0E^n0?O*^=)_1Pp)r`R2b6-EVb2L)3q;fF~NSk5M z|K9qGmGZM3d%Q3Pq}>b^L9mkmpgxb(ap$gUsk>fzv=7zab`FSA3XaDke)1Q-iRZd$6cRR zaG=jyohn@)6GNz!EDRedHKAjc2qiI4GKd-1S6BG)ulwxWfpftV+8KQVo-o&NgLjqGqsdBmrR2T&Tju}iz>?8IX$!lfUq+1M;NM|`G3bsTf0EVFN zM-{F~?L>VoJ(!g5H?5S$$Y`~XmqvOUZ;lA8p-G2!4I&cl19i5YjQ|st|F&n-&pkD2 zt5HaoZ3ar|fOWsb+FnutBbsoF(;P@b%T41J*0C~?hWqR&*6(z3FMU>4^lAO=p!Jk% zWVD-y)Ln<$XEizuYJq|tblK@dO<}iN7whjT!0j4JRH@IMtG0qmd3pybT$RP;mw$cYO+6ZL3STgzw}P^-bOeqSrqXs-L7U9WE!Nlvd-ogo$Svg>JUA&THx?6D%(_1dtk z7j-b@?d6`={w&g0Mf#)Y{=LX0cKY4{5FGq4U|eso+itPi?6BQ!v087jTCd^9l{jyL zLkOV?=4NKZA{sC;MPc5>gqS6&n~PSS(STb?0tRYHG;Vzv-h1~w2^VX`WlAE3!?U7) zhe-OB9<7a z<{U`>M-^yVi$ONC8rj+|VNJsHZmiD}+Po#eXzb$EKm%X~Fu%xfsJqJP@B5wg+-B;! zzjq^3@=eheH;cekz}c>|0QLr6y3cLSR^Y1)oG=LR9S4g7%L!8CoZyS=l&J@$-s;75 zvvl>^n)4WJk;rn2mz-5{qZlYY>4cKp*368Qft0B_HO$+}-HRe!U!`8Gv~hnpps>R+ zMr?)|gAa(MV2%-Rq||$d90XXRWVk2*+7*W(IBYg6Y_=N=qj;6Z?GEeB2AhrK@;Xd# zRPf}3 zB1L=(lAbV%vR+sP_`!o*!v6Rg<-nLzL_B6p$AmOV;=C&)b}j=BzIn*KtOFwUAThmE z!~^R%!x0eY3_mGVKRFc2D4r3Kut_V7>i|EJ(1*1*&3eC*hWd_K}F8hS^J|fnmkwD!P3s{5*i_EE;Cr@Ne_W^?+;r@fe$DjQOQ$EOrg0Mv# zNJ`E1?LP%Pi?;TS>7Q-UF*0TVG2j4fw*#I%yTtY71y875BAl4VXAK$O6M zgLkSXuL3dE>~H`PqnVuYpkh>OL<9te2NeQH(tkWPN7Q0IbdH}zC-zPm8=EJ_cy*dQ zn&-`U5~l<`0yvM~X9onJ&qs6uLLQHWrQ@uB5UW>A6?~lgzN|AQ+}GA%Qsaf$0H{YX zBg~OH6Jce@bT)>20vpqrF(~FVCp{?LRZ~6J-~d#L@;N?IUrz$6``#~l=Wj)-$&0LXk*dUHfbJzH|{J_ z*;AWaYK?#eBhouY%`Xt_akEoA##(qV{%@Dfd&X)-Ke*2da{z zI&YM6d@>NwCYf^@0R}W#7j1%_%)LiP4_f<(FX8cZAnjoTyo9CLmPMXzo~e!d$d=O2 zNdNAf07z%5&khI!BWP)$QW(=DR4N=~vPd+OK^SF$;Q%m6eiI-ORJ$LMIz$LQXsxz^ zMbydLgOTP`cn}3_veVjlBft(hlTZ_4l-#E30XEnuKf~2_hwWyE z)wsfH7!irYcqs{odB*MiEpG2`kvYQ;9_&Syp9ksO!V--vDT=ok5y!(3x3~A$AMOoLZoeEp!9HqA4VUqi@Y(7rsrXvP|tP6e+DceJp&v7PMbb)r9x zXvpH;e|DaB)ko@#rqb3xyB~GuHsi=>&muAykyCjDegWXk?VCz}0*nZ&YPQtZYgFSA z&A_fLsRlC8MA$me%eGGSZPjP&pGG%t*#k)T4m@5wyZg3Ck{O56Nz3>0#YZ((6)ZBH z0D3#8m~kkLGOGXU*RSvk-}rU>>)-uu{m!rdqo2lifA^0B@Nk4;cyZ)7DHrjD$Cots zi|D0~tjUw}&;I)qT=UtF0RUG2)&MXOA(NCdDaotyG2!Ck5?}eshvFo1a{fo3eS|3< zQ8Zhk`-h`Mf)nF-IN;T*SGc{q#ql^HrieljZWU$nX@P2m6cX}28;6NY0M$h`NXji{pb@K(N5v2wA?2vZfrdq?e zf){lhaLetlxr=1^<^7ncPf{asB1U!stm=5umN*rp^17C~4p=ZWdfWAZAeANcx^|&P zO1o&T1Q8Szm2N;23*b^Qq{1ykQKtb+om= zd*>u;x$Bjz6%-RwrGtyeDYV|J0rKiaggK^|3?$0BX^}jOW^*^uTS?J=AvoP@+w=A( zojOXEY$BXpU&SFP{m}16#$p0mWcM_B-SVSbqh4oY1DYgJSwNz#HPxX0o)&Fq z=32^=nL9@p>e#3ZU*{`{VG()n=*^W9U2Tk9=Tu>CYmZ$MR3r361PUHB2KdzgzgfYp z2V@82k}%C#f|;xiz>*PXNgt9tUP&!HeZOr@AjP6;VKJJ3Ca7LF#HjUk&0Ewhbdop^ z00k+TQIv#xT}UUEbXLw;4PB^muNb#d(x){#r;He7u@BB6tb=x-gtModk+M*iQ)a}% zm}gaYEM%}rhqx<$I#M>;>-KTgM>?X~AVr;~s8 zpP!uH&5L#zi{P(uI8tFHj|zClQK$kTc)+N0kO*y!_}Tq+m96^&&)Od|0I2~D2n|L4 ziy-Gjyvzp-$RIaJ?yYkm%CdM7BM>l-E3DURgs|03cR{&g(s#DdIV5bbA%-Vg_bP@P5S87fi|h3jZmyr;`r-+8+bzPl zf)4{qaL8ape!%hgfKNVmh?6|~-Q6B#{*eG1Nzz4fa{iPjFekV{%JR&dG0hX^G9i_O zlJ`hyLg7gwotSa=aEn*BpX1@-9y!k#2Z!Bu1(X7Z5xg1@oY#4U`b^9KIgfEYAdG~o zYZB25IISr;sBqMPFfbzTQKD|J$;wyF@V+1ngvoV`YZz*6?ftHP`S%3>xB(aHR4z_W0XC>t0a0{BykaFGBl z2Vqou?;L`&vPnTV*#eAf1Q)Q~T;OW^1ed#O48sPF1~?ie^6S>{&LY18sKo|xUAx+% z@@3JF-Vmx3ICL8}15#4y6!Y<;t1$QXqV999rH)dJh;u?p8Q=N#WAOX)zwl3yQm*YV z z+er1;w%&FjboH0)cIY}DM z;UH|G`~5AB^8u+$D2MqGr6s|(gwExfd;+>ypigmP%TGP zC!}-Y7lm@`EWhW_ zT8r+_bLXNHmRs&mH9`w$1RmXa8vTVhuUa&=<@=US1-e&*X66>S>h9av6#aJ!JRCS{ z4!#4NDZP_x^SRGYcIsTRbwZs`?qm#3DPey+NUy3x^0kcX~Ct{?O@aD}PZ{FPD{ota9t)){uNb{JSm)t7JsnO^1fD2w~1A76#Aq0sATMiAO z6E%|u@jl@4VvQgB;3x36|K{Ju2RC2A#p(jPafkJ|#^42r6$j)}Fmu5)&v=*h!)jj_F_4hFy_Hdg4yXy;VuC~~0H}GSC8^oiV@(~aF2fVqz!+w5{JcE2d zDG^*IFh|6E#QyMr+x;6HjuRY!&Dz0JLGTX2%Ye-4Wa20kH)hFI7)Oa34#R-WW+Tpo zVSuLrB^Mm`6YlRHaDV>_Ic8C{X4x!2gqVeH>YUIE*_m;qRAJJ$TQtI%9l#Du+>CUM zrZP#+cghhi>B}krds%E!6cFrK=qO;QD2j5bnMA>KVsLgK_8>03E?qlx4(9~Knc6TJG$&wln;j>3jFSCOa zT2c|iaVkKW<=in0xVX5&#l;PtTs_6*<_2R}BhUtpMg%W;g2AnX4z5n68rQ53-hj#3 zC@#8*%G}PjcW4`h8JH(WrB9t%Px=Uq-G*7594X0KoO3w~et+@nzk!?!yjMmLinfnx z#IL860rt)$52aWxr-53Fobo9^J)th@#%qz}1!!$g@~HpJAn3e)+K)Y@t&1=jcsw<5 z${9+w8M*cYs*y1h`4Y;!p-ox<)Hz1XuU_IOzy2-!+kf@j^|HVIji13k|Ls3i)pAjh ztqQej81}=cr)8i1y=yEC(ss7EoJ-vZ>iVpn*X?c1AXM;6{d;J@=+QPvq&go#SRYiR zZ;GZ*g@EDm3jQk}3cc4!&F&w3{C(`F2kUx|QW zAnbN4TwGmZT&HZ0koopO;b2vukBNZviuKQj4xVn^S{?ctI6*UiP7?aYEL&b`!;U>V0B0 z$eWSg4_R8S_4XVrb4Smp^U$8(9AdrWs{+Yhp}zi(R9w+k2aPC_6KAG5*i7BM>x(L6 zSl9kW#}L^i(*}E9M@|T8i*eh=ME&68urf&Xdg^nw z>zD|ZBWfjIDK9Tl#CcmB11Z(HMy3Q^_iG5l&np+80_;-XHz4OQNlHa25+Eaz+PT3@nN(39Ei2=oXa=1@0@;YM*PXO46kO*r2r*_b3w1Ik z!aR$zaf(tN$GMh+Or9i%+-t7D7nJ^}%EIb;U9Z=8^5hvl{OVWn)?07mYJG#1Tfx%` zxi}=w;F2( zz6fv_$AI;E!1iK=)kexe^vMiEZg!9`J(97Dl8L=1?ak}*4Aw5w)65V-uEZ!akOGiBA;5!%0LNa7qiZz82RMu%NY1W}^P2Xg26y0q zkfg}FCnvyOCj%Eo$_YNX>M=zrD0xPTB+>3;#(ao~`x%Zrp4>de&E<3KHdnaV-e5gm zz+r&Hh#{;o_%*y=!C?ScX?ENjUj3iv!EXgBXT8_`#;XepFKvDMyay&rgR|@RVk{qt zOwF^TDSZ1||K+1|f8iH@LuhDfX!kTaquaIncWpFK$fXL2Ef?mlJqwR@X-3zn@u1IK zQ^csPV~hHwD3xy443wT4sL?Ce`nCaZi{>zTfWBx)_h*YXclX!(8PKrbv7VoD#_jDb z{@yQr8~^TqZDo@F$+vzMzxg|VD1vWEcwvPLf*%CjoHGJ({vDrhTL&JvMfDziTccOi z(bDgmaznkZjmz%0WG_fx5fR`$#2gx6ZlM%Y6&%}bxA@?_58%loxB&QqAO7e+;$eCK zW^Jp|p^L30i|0oJ9O(W$GtF#|_0Ay-;((1Q;r`(Pjz+9ULZCsS_|Q}!sL`pV2cnhN zh_i}&Cb4$|p)0pUB7RjJ2-K*#kKXg6>n;!J{*yfRA~~GJS^l6ruX9>52pawF z`T~GPO>64`7N(KBXT1_zADw_D>o{nn)Wo!yYw1V^gN;6IU+MtXg3{`}mS5Cpos)ge zsZ*tBRRrxwfYhO3xy*LmYMZ(G3Yj$4$--c;+T{$PnQ|eJGECVVg)s9%1l1ZP^8_Gv zuSv$SumX)8=%~+c@7`no{(!p10)XqmIr{TX_TX+`vHo9x&>Ass?d$JI>d>|KhDYZu zpAAl#9^4$S%v`k=ns}2rgtVVeoIJL_KW6^excGwoU(e4eqc{=;eD>x` zp?jit)YQ;z4pc`3A>7@+fkd6OKAb<{b$8%b6nI5=CT7V2-NX%u9LCL1qg9*j2D_b5 zVA(OIX~O;e8{FRBVTuulc?RW#!3}UhiW#pq8*Fx4Y=cI`bmBd^0-im6ft%|$_~heH zvDv)F%a^Zk`zGSBXT*$Jxc-q+GoO4`y3fP`u~3Ny>YAgY<>Y!_cKlW6ownt#x>nZ? z?$!o#hFU&z)>_3}7V8uia}nA{kms!V#e=&VgaWB#u_>6OR+wx_QfE&m6|+$E zSK|)PpS{4%%~K3v)KW`FaGGU;lE)kqUcG*ePd@ns561_1??7G`KPSq=hxmY(uU}yw zXTTF8G47@V4sVWlbG${)8Ta=O*dO+o<|8J}Uo%^a+yDR|07*naR4z_Efn^4lh{7{+ zNr+ivNQCL;Bj{KFx5ltykoO2Hk6|;w zuRQo5;4K~s<|utLj4N!nJ8U->00MHBay!n8O01j9;A zdYw8G8f zU+q)YpW;Bp!(|Vb0|Jj2Fe1RiL37=l!{7o2w}Mv@m&KIhf>fmBR?hO1Vp2f`>31np z1vnOAKdTd5N)+*{xgZ`Qjt?^qcSn?oadB~j)o_8U-7{Qno?;9;IIQ4kKyVubzlL{f zICy9+2nE5^azU%B`DCeBY?cjB*hBT3c{{J$*Q*!80uU>`*fa?UP!;kHlv77vqviX1J$}0Aft13o@(lv4l@#(k>t3~r9w429+w9?F-H1}*1vXS%M&BS^4RX~Zt-`1 z;T!n(|N3|9?|$u@Ka1bg5=o*Y%Jq8innqM}2>J#r4>N!O>TZ8J1KYX%!C&zC<9o<8 z&A_jqi5q~BQyjbxFi{kz`N2`kjDa0Cn+@K7?|lJ$9`NMxgCG3>4~GXZry8+R?*tm% zRvUcU2ewC2+b?^8TQSknyk z69CxNeqvQXw)LpBMc-YQuS}|dYx^ZZ9gW_DxhSo)E?^)Qx_s~*VAS`(4nQGzZ*`wp zwK%lkT=(7@oR$zzXstPaA_9(~p_r@Y1=W5ikdr3N{ z++uv4i{hVo!B|94ZLfd;&Kl{ov9)j*>#CyQmuw$3XU+-uTt;{at&B={FczS=?I*No z3xTR&Xg?ln+l-lE5q1TvHiy2@DSL9rI3qR3r1FoA!x|OuyOSZQ82WcvbGYv9=3oE- ztNm@Zf-x29ys&6LIZc5i_)$TyYtK<~shTawtj_xKs9`=30*!J#b(jeFb;^Y4*B3&F zX@+;QlGp%sP8J&hyj;CbqTC!Y&y3?NMopoD?Zp-$1Z*~I>@K#rxY%K}8R5LgtP!)@ z+dI5`^%A$QUSgUi1OhheH8NJZP{;#@)hM-RgEV*;*0{L1K$=B7sT5sI%PqJZfyjtO z0bWgT?Otx*M?C;;Hj9YC_Tco4;m|JFzW3;$FZo^n-7ZSKa3OtB#2E4%vN*{(r2lqC z^X@bQ>L#!E=*8R&`1T-p@wl{@(`tl@H>VJ4VO{&2JpjiTJ>b05++&icUyKuSauNZa zrS!-CFd@zi=YiG8fCA=P&dR9)3l#)$Mjf?wTEs*eI}8K7_to=Ll=hKx5ugRaG)H{; z`RDk*{_p<>|M7?4$2`xVzzBoKxCt1>0T?sf;4rKh<7$QI7{|i{riVRZo-iLL9QTKs z8X)3OL*1AN5n%D;6B`Xwb6l)ULUJgHkRuQYC~6=91j;~(1vw=(vI__qE;C}9F~uY1 z7_qxxtXAtv=Oy*(r&4g78Ha=9!e8tNZ@qYeci#OF>-7bQ2M`628vr<@l5sp9@#@t} z+`f4Y5M#I7VzXIe7z2FJNXXz(xZvTq$Nl~RhvObD&B(sMr-G4yi)WYk;N1`L_VahJ z8F%nBAb6?i#>L^2k3R#L@%r^^9QF_0IFx9ZG6;QV#=UtMk$j2I!_t# zkZ`=4kd7I<@e*%6eGBiu{S~};`VMyM8w48Qcm?lP2!5kE*FiRx{zo?e121Ny(_-F{ zA+3`|pff%h05uR)H>!T_vPCy#ldMaE-mq8LELt`orighKCds$XfZu=k5C0oXv*z0s z1G`0YU+r?XsA)u5=Y-ZM5vr;gA!LScw*>Wu$l|k(;@yL2*9@Fu`9YmAMqP^ttvrL8 z1q(w#ZrwIX*Ht3u`&Ewfd4s3@f9|_AQl#y$NC6lB39Ho_@4WM_=IMHP3i#mGvUQ&ceDa}=8ALc;Th*4=wDT@Xh$Rj3UTER%18C*1%o=I#CRZMg$ z+DFiQzD_Z=IaBH|dIS({jg~QB1EB|drKr;bpS$~>I~JhN zzzBD?hFb!#dbNckPeGu!8oWx01{wf{*$a@8PRyGBs{l*S7uskCl5~yZ!mUqDFlr%& z)yB51eX#@2ms=jfKzSt?02 zy8GgFReM3~y5gLazNE(y;OYqB$MBeK5rD0pw%)Zd*6PIeU{uBc!Ire8(XwDz^^FD^ z4YPhK4wXl3?y#1vp!IVtpVa5T%RZLt_iZmdH_GLGN$qC?jz;pcCL8t>hKYlfFIw0Q z(6!1h9aW?$uV$Am@2h{exuavi>I9QxK-27UcHkt{XwHH7z8!Xbqr^L-$}51kG&~FJ z+TYDtRtgY+q6@LpoZO*#)6~o9Tw3IG5hV~YhLNz|tZ{jHiL0v%TwY$_`uYmn?G|tu zhvO0VhdaEvdxMuRU*grPm$-ZL8uL71HF%^P5sRoHGDl3)1R8{58O8zY^#BN!85xa}n@wzMo>SmYC%?Dv)$eONdojNHyr=n5x}RF)w?1Z-0#SP^+H8C(RE#2Gjo3*sze%Te3Fa?TYB5Q!KTIYurHlvTwV%~&j8nM}Hw#29gV ze}{400Gl-&1{6pxLGV%*Cv(B={Vjg<(O=?t++(#HasA{P!^I_57X!j}gUxn@&85_x zozfon4|hoWf+>pfF{=WibEFg;(tg$j90Y>YQXBxK7O4{{lL)n;z+0yWQSo$jaRPEK zN&~b-Py~j;;1MH(5m1WI*QEX=Ya{}gXDO9*H~_&BE_OHg@T-3VPoBJhrxl0-KmiP= z`SrIL!(T|$G7z3TxyI$?l{gg!hhZEM#(+7_`1JEn5!0s%ehNxaHStW?Y%cKbyYJzv zAAE?-umu%~HWNJJT(EyQV(NDeDMC)aC!Lzj@CeN@NU&|el<#DIe8X!IWxs&>~J^vIv{{* zRM_{s+%4OnA)UG0?jJ8aZ7(9dRk!J;EP1H&jGPL-_07lN_wWCMf2K7{+xIN@2ddgl zW_>}Tt$=xkE!t7Q)YKb$ftP;KHOklGc}(=B=yjM|pV_*n=k;As4Qe*$8tGWmdpA3+ z8up9+Jp*DNgTvn5TmEiAM^k|uQX}BR##5tI`s;AmKcYhez(4uU&*Qtl^9P7IiZNxz zW?(Qi&~&ctt)1M4h?%g|-rC|@b)VytUpzkauC)bU3_03*PY|IUhU9vYfi(~k3yWs6 z-r~J?KY(`uqaU&ID}3*Ve~LE`uMp=fx&lKhu>m9$3s2OsfeKQ35Zpgg&Ww4Q@qh=I z)2c+mw4ZUgyT--l3Y+x~!ywucTx1N7!zf0bMr2Zsm~+6~Mc(ShjTWf{v>vNB5bV`h z)4Hx~o3@S{bM`2Bq#Cj`gVaE<*mWTU)zs*s9}G2wv$9cyDoE^*NC@RNm>F0ABmrpL z-fsm8ER;jPG=OEg_Qr%gyN%CwBCDYxOCZ$sIiqiVB~ z8k;bw}cwl%Q@HiB({TGQ_A~1zW!p5s(pN7T@WqWXXT7ee=NPC?SYT) z*FffDr%CUSTF$k8KebM5b08NfF_`pFJ4;>m29C_^FzYf!r^% zN6$s9OS@Lxq!p-EGuAa>g+fxYe$hNT(Z-nWxhhOrmn#Fttbo zkYcA8D9(uyQ$h%$O311Z9{hmS7!bk+MawRLBwCs{N*ym#Dj{G9l9MXDw15y4Oj|b< ziSBuay5SxU2fTXq67lFT3>$Ft$eBSLFikUF-@ifT1i$jwtuOHOt!upZ{=0bVz2~^P zxk6ZrP#X=B@A`1Og&PPMGQu$kC`}1DX7!FM9g1{eVtG-lT(3d^!yy+@NJk+Q3R3bT zdSD#j+zP`WRE?Y>k`ooqIVHp?A=P^^!sro`L*^0FER*?goG?cq6)zO?$T%K>{R6Pu z5Q5*~=JFYy-Mj^Iqnfz_f=dRx+hV_;;oJ(l%?8h(Kf~@~Cwal15C)-E-rnEi&20qA z1Je8;(eR@vdLuL9jevCl@LcnmQxdVRSD(Mc?d`3WRU@TgLsa6O^w$_fGaz`vFc7wz z5f>L1*sL}}<5CKrBqckgx69zmIU`0!p#(|=2nirY;e@$F9OHy(K46Lm#55!3xeD%x z(W*n;33K5%C3qJkH@X0n2>}BxFR$_T^Y`$zul^_a;DfK>>hd`V14;=X9}xT+!Hr7A zwgsTk%}Kpky*v<+!4EOE&mGL20or**VRP9)vl=%BtuuJZjIz#{RBEPy<)uBid^QK6g)L}lW;Zfmc~)F#*(M^m zTqM^G?fSCziFcS`_fx~HhDlB+aAf`7j8KUTxAyke`9cs)_RJQsx5(>qTd5Hu0QV2~ z_`5&<4gBxF|GVgqU;pOM;WvN#50JF*y&3vKb(Eho*!S$w-}@1T8))EdVT3jg1Qea?Bt&Y&ToH|L%Jj!+`a;h8rFJ?9cxUFYiB>G!7I{ zU|lB|K-MT*_l#z@1Fey|H)`q_Vk{_mLQEO^{Q<8&dyU=ZBivj)$BSogD5A_MH8!Vn*r2C3>p?MwsBv;i-;XL2Vy`PV4RAqoUcVJDOfus#la8@Ix*iuwWEK1cb?<|lgSjxObHpgV_P%=Hw_p); zA$Us*IX(LJ+9z;W0BdqiOL_IogQn@y#zAYl?2Ro~c5w%4PD43IgHol`GD%Ho`lP>3 z946B4>-8Sei5+i5!4xIsRk154f;G@^U&R+ z`6SK^vB#JhVYAywKa(X1hk6sqpCaX7XQY(j9BWif@^daOx7hABRjJk@axqQFB>_}0 zt~@TTw+Ji3#csgW)g{&|@q(u))Yy40NHJqh5oIozv&haf2jrX){2JqG#CB6eMLG&a zyUak&w{SUPo@|3qU{)l;v`~LO1;jo0)G_y^E*rBm>Z2bSE^q*RR|qojyZjyN7=5X~_n?GvU$!8|kO8JH&^ zPQdYya6BfY3>h%atE0o{AOS1b!SOTIWTOAeREp5yw4nf17ZB zoA7XmI8HMT`x%}Hceh7;`pHW;9^f!Y#578c-21x+{NOKsh>t)181p=9E~pIR-~qoT zY&L7$++69pFgB`R2yk%7vj8-q#keM()(dVF5^=DSz%e3m#GGfu95JOCbDA(GVVm^j zEF{{7nnU9#K^@-kB)P_;8*p{;1nhs2|osc|d%LBLT z$r`&X1z3Nl-;_1Dy*Jiz)O)(m(FvQe)c<0+5gCQh%0CdG+5`9a&wuLc_&@*nUoF1= zYv1}g{N}&>eMC;p-^q;NNm3&WXq_>(`op3ci_d^2u4B(o@6vy_8J6dw;>&(G`FD3O zkUAhpBc}ERA~+wLf%ZgGEe1d79Ey}{Mx6^1cLUGNYPlop+01{|K2k5Ndf8U#%hL8r)T5fA&*>v~jFT*q6kYm%RuJ=xr=42A1Mb>t%Q9A%<*C@*YYdNgS zP^oDe=4e^2PmA$rfV_fRbZrD$Dnz#qbpZA(5MWfBz^gKJom&P*c-aTmCwkHPxwC#` zM%Hu^);ZEv*>0_Z03O#l+Dsq8s=5?=pC?;TeGcPK*UQsmJ~b3bIoH0=3|B0Dq<5C~ z&)EOyTz95A-V9+|TWYk=`=uJXy#wyX6`_hrE#8f@TzLc6yil*V@48M4>GYivbi9K! zeYAaVvA1^{az7-fZztM*!C-jjE08x~zrxLNcy3)iJM21v$UbyVt}UEl2xYBeFzJP2J7#A$k5ujp*)h8|P{ zCFh;cjtI^LzyR=Sy@nVunk?@^RU0HnwT>^(5>mB-%Y*Y+4gacY8#P6Xq-tK|w>}4=5;Dg@h0Wgu!98 z9uVUSbDFT)&sZG?lv!&&K|pVTY-HIrp{PDJsEw90|L#F;Z>#dj-%r;8>b`sCs0OJ4 zUp{j_bs+QPyH!Yr@Wm>J-3DLR9BX=cyml>efxGk3eXm~AbzRZ{X#>Jirx|dLL5KiF z1fMYs6TCm_rkHipjbdy0@q>@PkH7rU55c8iSO*Mi5B3>{_<+~<1^e`%`7}x!8v_RKuv>32 zWZ;N3a*z!+IFG}AkI!#E#r|+FqBM>Hmz8E=3tI2>=i1MOP|IeN!s4J|*3W>X<$va> zU^+@ZZ(+bifJ;IyGr}lzp_n4_Q3RUi2bS|^phRGQKjV{+KgVaEy~OqPGmN9wPA)|R zw^*XJt8tBSTnYGG@02}}z)Z-Q5ECQL8S_*yA2Z@a$T5J^2v2|mC=axVgE;YBki_aU~bb z$Ar7v2bBAJlsT%wC5x_sWFH*J739LmsUUO0oRxu+BVti6w{En3PG?ciQgs}GK!reA z-dpevyQ@pQ{o*}*_5B~id+&S|m%Aq*9*_&cQ9$r30ly@Gy|WfjjU} zfAN!F$N%wfPeAaue;(ic7k?n?|7?A!6h*5qYL1I)jP-&S(t>l_Ni}G!&1{C+iLKWm zOMQKd@AvnyFD|;E{zKod)6y6AF%uG!u3L;S40!hJ1+1)vcOHNGy+6h0cb_1o8Su^6 zVUnD4XP)nVKL;uhZZoeN$yvu(%HWjo@NkFw``0+^pJI+jVJwi`qHRrg*4cXj`^GL2}_Gv^$N*GOcI_-iDLh2jY3;J`?!sMA@TM1ux6ILrE9 zRNT6QMX> zf=>Itt}7K9o3I#Kjqe3Bqn`2wjE3sC)99kvU*@oYFi46Hb`ese8p+p_7r@KD%Yf#+ zcBW(p7z}*(!^44ENhNpzwZ-PSsDV3@xzbnz@&~EISW#6QPYcjupUJcI`uqk?B>%Uq zP1eTRC*CzDE3?!M=B!cZ&S^oYW8OAi>!YG2wE)c#1=W6a74%SNTXoMtSgf(cP45Bq zIhz|-qQLrZYU{r1M7|7w+ww=uYD4>aE?~B^?TOu5e{N_!{%G+_E3@Q^^oQm9x25Yu z(?O%ZZ5%J}(C=rC+S+T^=$$;JWXb#2y%4TpfO8BCCK1Z>-aopZG0a*zgMpovw=7GQ z1Yg4-Y??4g`Oje(5W;|A2+cw02(F4IcJI^}3e+gjwJr9H)S}sTgmEwl4U4*r2%*Yq zfFQy=QU^03MUkuyp)at`NTw3&Z7>!oi!+QEHUqZaVHg6o7XiEN7EDK^DWVJo#amus zMv60HlF}+iVh{~r2J*;QtyT!b3ajl(sEWscVGI~n0rTF&`64RD+SMg@rkNLdZxzMr zZJhq^{n+V&@E6&l{Z8JEzlFzVX`e36?*Z$%>sE&hw@vZ%THX9!h(FZx{~Cv_Mb$p- z7GDr*@oMYa%6!p2DjA?6eJl!;axLc)h9M(_D0F3~Q6pF2U8&y(q0+EXfD#$mWki=` zKzpT{g#qI@qKt&qxWaC?#%4R>@@fMIkDQ$@t{&t9RvQ3x#GLOX%A5zJL&Ws@0T1yG z>-`3+^$O$Y5eARdYK5C{jjO9C*sj(Xo;e_km(u~$lu;-Hfopv{ zQztXhj3=r!PXWnuh;zbpIHE)ep_iC29}|xIh~pt)zb}|4$?esu1xPVtnkRTKIl?g| zl(`5C;sDGCt&);~hdbcUzyC2_JpX?Yr;IUdR8(UCD1bCt8G^^|Vuuh`QnH7DQk*y$ zVnWIcq7^Q7Pw@QNjLqgsYQv@(sYK*BW1fz9{ptaqfAR(~&I*9j|IgT)HA|9Y=V9M* z_lU^MyVb3&tGcVZ8khwbGm;OYOp=)-J`j*V5|{yHB0$azW`kZS8qM?o>ch7w$WoAUU`_aQW$K50Ets%m!>fW0fi-#}A&v%yZ zU>YaPqYz1@80&@w**N;X$3E}O`~UzT07*naRPoUIkc>qE?Kqdm(;Cv}Zf!ox_in$fMhdz$etLrS;=#K#eNa9$ zg;8(Brr3%H+c@1FlY(Ffj{pP1(Bt95M};*xIEO#~A>*@)Pcg+25|!hiCR0^lb>1HA zxzx0#1;p*%=>ViW;bwb@Pd@z^&N*CNUt{Rj@XiAyawa9lZrtJW>H^o-SJ;nx%yTSW zE%7oEtQ1yO=56t-7)``dE?_}DC(5|pg#p0} z=~!;Oxx|2j7!$yZ>_|OPOXa0Rbg1s4#gH^y(n8ml|L&S&bxlx{_GQ|Ic>(3HC?E6e zlDoY=MaexVg++Cq9kz>^g+E0Hy~tmn@S#c?uF6aWkM=I41_leZ=c0sb88z<;c!c$f zbFc{Unr?w&@GbRJ4+>Ws5G-@EyocO3J5tu<18*g1czyHEb`F!sPN(2jB7QYi9nJD) zu1xEu3)&~%?4D#I_UNSw5nC>nkP6gpI ztG!O3Oa}n^j>F!s?BVu2FOeix0?|Cc)ex|J7rF(`b^KKwaZZ@ZMXw*w4+C63pzFoC zTD`xn%>TwbQQBJDeEU0l*BTj84Zvn(EfyZ{wSI3V%?%LmNy<|AJ!$PQCJE#5K?oc| zAO!E=oo;GM>OfvgD+QqI0(|EXS-g8UyFJE9>Zn?Lf67Tp4`i_nxN#5L9Gw@XdA0JG z_wwuzLJfx?LJ~<1&&@PZaK)=eiUO*#z>q~5HUaB(KsT%~ ztX3F~juAo!!i;I$W4C>YaokH@4Oi9A#wcchVgh3ntCVv%J3YaJ`wy^QuhIDdeLvvd z$vK80AjUmnOqloLd7S5n-ENPISD%70qVEYYWyHA09Cw(q$2f1%jXnCIM?ZAv`wpvq zjX(~kn-kFL2%+D=!;2-8g=i^e!aQeT%bmpX&xw(|1I@DN;X9yMp;R$ZD<&ZMH~Za$ z+0P&VX^z-$x7coXxVeeg-Z1u~7#0ld1kV`vGsw+assq3b2}7TNI2Akvo`Dx1zQVu$ zKmH6q{=tVpCSk@#2l5^I)dri55Z66=^ayW1dxke2Kf!vlK}wQ`3?lf@;q>$#x^9KX z58fywNGV6eIAOor;^oUv@#&{8aCz|xH#gVv&Y97%guky>EeVw5qBvr7!6C+smoG1{ z-EPr!9$oL@l^iTM4^F@|MhUxN%a#=xBRMO%r&mIn`g`W$aQc^jvv_u;4qM+c$+?^g)EFS#c|iB45%Y&^|( zU@Bc#jq;`KS>k3|u2%q7Q}^~gUk{v3$;gaSzGaTmuLR(0U;V|!`M>__|3K>VvGlj> zgBn)&+B_006o3Wrm0y}@57A(ZOT{ecW&mi#Y`eh$D2(q!gw1AyCvQB$JMX-Mr%#{a z_~;1a2(#9c1vAJ6*(Zq5g$^l3jQ8##CISComJoYR`rP_FQ?_KjE#I*D&=KytT9t@8l?kun;`X@1Nsy z^m!q93J(9z_x~I(Eq3pyaix#)Q7>5Y!Vao<;R@S~#g1A&H^+gDBzftv(}OPcyDmVx~o{ z%_?@wd};54X025KT-RDNZA?hKcAf&&D^$Eww(bf6SmWtyl%ZPotYOPHV0H(&k*%HL zQEZ4YopZ$i&IXqB`R2uyW*IZG5torvkf3U8YeQelb=q$8^tz@WZPqd}m=geBWROH9 zh%rgLa+Q?NY4?)mH&=6UHOSi2=vMAsl>^Bl7;MZ6_^#t_hD`$0qip%7+47NIBTuqU zfwEzUhZOFXkx{J@x~A)#DCab}>jsFc$5P(f`Wbw;QJP!Dx7;H)zjI+zC#pICH|N*( zR8qI4p%q0TxBd67QeKNT;BIiMnRsR1vSU~dupPz%-2z}&3_EQ;JIe3NNP^ne^)p-i zxtwD}ab4G;3qhP)E79r0&?EFcx)9(M-!1OThiz~N#-C*x$zp#wI0^t3rBql0WdVDQ z3m2BSl)0J21n&qTNEsUO%=!YLGH0;F5K1mxaG>771&0LjBF8vkPDyj`fCLsGY@VL1 zFUek&TnVEYhECXZa{@!$j^r5>1RNSDlQ1atTr!ZI=F9k!M)8^%gu3$q;;nD{(%o?m zP|b#RP9q-<56f#KlFijO^29!8DEL8H>(%SpMw93>TyENCpXvPz@O33Jr`)sLN6!aI zKelamu+6UCr?c@7t}rr##kmfR-w&W+030Dt0+?RB-_&BYjUK4X zz}m(%3#jEtI6qC;tT%Z0@Bucf4f=k-&<#j=#EVZaaD8=y{mqEoc8_r%G44m~ZX&z` z9-NhU)d$#* zSIC$EBniPM0M0g*PK8OR7Bc5Rg|#^%rCF5>Mx1BtwmaNhPuSjMY;T0snNzjF%mm4U zZk37%3MI)~LT;Ap)O#?{b+NMsFZUZ<3RqFd~e z4i1zZkc7Z0C$XePBxDF{XJJl!^yyQao}NmcUCuz)T%%#6DJ5`92%*Et$%*8*>%Mn$bA$afA;uYPuAe-r zvQ{tN@IVn@?Icsy>+`K1rdte~M1iZ()|4Ydn>vroV=3N00kP9`HwgaL*M0@x{e$lz zYDqcd0A|ezKFBToH_e__Npswe{q5s*`&qg>H=3+ zH!5vBYW-TxLDLd-K8Pir9G85xtg5WT7FFHG;nOeHNdWqA=g+5n^yoLmOr zu90vs%fEr0wqFd)ngL~bGzv17A*goUQpT8EF=gKs5L(tE4A?C}PR?Rbkq}WT;K0J0 zmrip7PgNl-Uy=5mJ%_5d%1Eh7A2OpYfkUN*3^S5Q-DUwCthuyVO9hcCy$mHvQ@L{Y zXt2Hf;%WAqnmZO_ya4TLM5z~!$7D*0a0Zlb3*Z*^?>RzM+PU*RVvxo{Oga0EFzb8k-pw zB~bUs7Thy0b9LK2v$nUsa4WVA)0sXcrG>BvHMaB2Q~r8G6e`F*&=+j2nCCZyfUc9M z&aUgx_dR?+NMvv5N=dQSFl>hz??nEz5m)W_uuib{9bCC4SZKZ^6^GIwA(e?GmO3Z# z&PvFHFO<`L-=XVz@xEGqVNS>{il?|!WMl+s}lQOr? zGnhqT^Uh(noiL6h8Z$B~djHS?VuBn%tkk+$eMRsi~MR!r|W4!y@Fx7*Luc-t7= zZyinndJBF@_Gk$KR(LxQgB1i*b6!iL1<1WDJlTF8_Jdt#zl+tb0$?AcOwH-Z z2~JN>F$^no)FGyX{W!vTkK=o%I6684oI{*O%=0J;_`JjJ`WoZ7MU1oN!q)aJz`b`u zq>zCeBX%z?@pAPs+?=pouMqkkLoa1BrfJ4FPT)icf#EkDjy416ya&T!yBqQ1lTYyC zvrmvx#BMiYP6^4UGG|iC$cZ&qS`>reR`9-){;==?W_UkJh@qdsNQmH47D~o408Bx% zzNsPpT-*VIy6EHlC`8Rvv?KVi4c*zbU8FCJZ+3vD?BLRE~i0$-k>d86I`l1bzQ(_ zv%j>*j z05W6f1^`eZ1g+tw;{u8DD!Akp%Hku~IulE`fg>`- z9u8)6*HK0rx}__(*@RtH(E0EzEWsD*#-3BgJjVs$)i-|QmloImy|4a5Ow$CICxlF< zR_`pzbG1En#j3thmEB?qSJ#v&d!{fqt#0ls?~ti_C)$IY!@BEmetw3>Z#=?-hYzvY ztYr?w2y%pB7|?e;0AL8dv;^(mN5Yq z%8^3}IRvwm_b8hDLH?pCybA@r2^Tf}md!hil7Bc(BmTo*{0jcn|Mtg=zWLVIzKq}f z{Xa%bDpbk9qn3%#`FNLdbn9SKyc#9_r=9=PZ=-Y8+C)VWEsC_s&jSD=o?z>ux*>9u z+}hv+?%g}X&(P1x_;`o#gMb&GeTeL^79;gX8@xr$PKoH8M%xMv0zqS-p_zWW2TV4AtM?Rk3MoG z{vlEpYi>*i1{j;R+Zrq6fd`5nIoCYDj#VKhQ-GUcQ3PB7u(PrsIu@V;V`1Rh-m5&@ zyu(h`ltqcczHipYT}OEzKqoR)S(i0jogAE#n#YbbJlD2T1(XJYTOGDU*4VnSEvEs% zt>NM>*>xD9Qa$}#F{IsVti6Jh zD)42_sF82Q0lIk>@~|T9K(BvN7u>sHa?5_Xp7Iri<+P9 z(OzTT*8^?I^q#}t?I<2q1*xj56o8Wmr5-QPd{4LU#Vq&W=HBJq8i2_JC0^1<&nDct zyeif9wp}2=LGImm9X6W{j*dGboApM3rfx#c2}7WSnyGBjG>e=Q_8kK>V&V**X2c|sChU_9 ztj=|{aKcFOWnryW8$5dO20s6@KaZbz_X~J%{|$6*Ku!c8AoyPLrCkRg0EJXbH@5?& z$tDDuf>c60)oXN1un>s6ZhpCZc6g3z5w`%Z=)#R4VgbJ~3VZo9Nz?`30e*k|@BRbq z_Y=%ROH@6!vUw&{?@1eqMaAG!a$)sz+jL8-7s^vr9_n5uL~X?Yz+A)^LDFj0s{vy4Q+p#&^2;_VV3tt)rOp%ZX8QJ4VE!WVV;(sasxDQu`y^gH)|A^G6*s`>}id%4h8Re z$^z7|f-|sE@@#bLIC&`EoM8 zUO|N?f#w36GRP&VQ|T+zGVtsQK{fu@A2KUBka-JSV> ztwFDVmxFT-!%T~T=yf1iT8Cml(GEXkiI(ep`Ta0#6X4=>S+M2arT5uWZJ-F1MYvJQ zO?IL5U7gQBm1id97oek6=JmS5fsnJIl{k0dg-}5=8NLCB_KuEZ@5#(?nUN@KnLuHK$HD$qYFisu0cR;0c?e3h z%7aHkURK(r{qCHQUk!u&>pLlb)Z}942EYSc_OD6>P{X)w{*quhxAm_1^QN}wd3 zUXYY9v7JR+_7d~XUL1MkP$Kt;ijH%)gtEUEgL^OoizKVx6_4zlLUj4L8r-1z7?kC{ zmQQNhX&YiYnW{ioMxWfWL~(OX^LuM$<07C?1iZ06T0f0*#PxOyA}^r|5Nh$5XN=Q` z-FAoT>nmK`%ory|bU^5VRS$$9vG>J@r=i&)06hh4)*HO>=o#LA`#ByQKLCN?SwaB! ze2x9I$CxiM&3hm)x*_1~-U-g`-9zuifa4+MDUb(TU+>@tz;z7gfy^_;JtOV_>Hz9> zJ~;7i_X8pH%0lORSdLXn37DnsY*qt}$`!-|0Bk?WN!YT4ldwiXrfL|;D5bhml5pl| zdA%%)oLF<(Gm6I&Oh}P|QGn@N?>xg_{wseO&)VR`jk+V`tD*?FO4TFqR`&@hFygy^*(kx1%LFWLZD*wtz^;QanQyz%%AoZmmk z(a|xi1Pei;E4t7rE2S7eotIoAvK*u+7uymV@2& zP$Ot9LtX!BH~t3bx85n4L(M%FhzO$ent&z%T2{h2k9nH#@BhM=@#xVb{Lz2&+oet4 z`r4QA-9PvqQj(B9E3LtRvbWcb>DKmiu(#D{0-GEB+Ud7cU&{@OVq72C_8H3f)$eKX zz0DaH0s=J(&g_tq%xUL5&Q8wY-+mXJ*Xk4*c<-YhV>{jei9sC+VWHCv+BQ$Fk1pe9 zd!D{Ko06q$|K1aVGeuwKKPW0#ci@~5St93B&WJoArV%mCh*`m}cBNC1z={dX$n8Wg zm*^q$;G43~je?uGM9&p(5lk6Wl0ayALTC4`bu<~uJ;JC49j;?9yf30S5th2k>m<=F z52pR?buXiKLTKN@)_tpVs}rMHSSAn5AZ3%wlP#HpRvj3fT4EkE*pZHHc|4)aN%L5d zrr)^6i`)b`x58IKngMmjn9{lIH@S|Ru>uUN-4$)o8pz}(HKIf5)rxGW|7zriBVYO= zb1vXefVz-lS)QnUUeb(Od7lq-=2n*ll~QhK09{@7ZM0L<7tN%%$OF=Qm|@Y8)(LNT ze@eY*089=gXQSDJ1gKJZmbI2TNn3!#kGEiUoq#0~mZ&XP9G{kygEDJA9^M08=W(;W#LdkP(==hX-{WSx#nsgn#!*5R)_n%^P#T%C)bVu?>v>NO z9d}@#wFcg8hO!uwhOCa*?f2O4_t@{ZU{2_Jp}=O++Ej@#O(W*C$8MXj+b5(1coq<0 zRsf#M9FWPXVL1#ZwCZF@-!>T(*y&g;BAf5hJAaxp#?EyI=i4&~n(K)I&|96V<{nj& zB=(leqwUFZ?m;+vxkqVx`}+YvFVBQTgt4B(3f_RK6D;}wvav*c)*OL(nlVk6*j|r9 zQ?9vCMB*tLrwQXY17LW;#&9fQy>U`urSH^r3W^<}A2v8Sx{t>X-ojgNyo-nDkI;8L zf)D6JK=ND6al}5p!p-&)SG!9%Psp4Q(iT1(bcNNLadOt- zWa~jb0}kjq5&X_czIwkBDs~^tiwdMDf*?^u&NEWVNE$^TC?0`pa+{a)2tN#}MoqzY=!y9kBq2O2krMSmiFP`G` z=mf_{r})W-AK=qhuW+@!5jQh(F*0Qa`eA_gUGX@_m@)20#2Cf1*7b$0IkS`agsH9(FH9SG^M7#qlRrcht+C@^Yi<7^2TF4e*75gO*Qlc zFX=m>>q-sB7-IpGAp}z~#fYkTl%hxnne&?KYycxBVaY!1`MVVRQf`B#POB~Tg@s?w zdmUf^uux{ovrKTkd1L?pAOJ~3K~yI%N|FLbRRpJL!bcx{gkSzozkxsf?|-k{>sw#@ zGJgB_{-`SAnCpWAU<|B>9*E+-)n*j$)?!{S_np@rcZWwV(WX47l4)`K{%q^P6i*9> zrsi|$mlQ=AJ3czWv$vip@s&g+eDLA>*p63Hj%5H4YN%MNpo=1|)0FD-1t3a*DM4!7 z!{)0eWdk-S!yriA@|dzP>L=NsBFj2!B6SPDhNX3QZ{QS~a^gy^E+9&+8SgX12~mJ= zZjEiy*9?tDax5GYE`uC5#F)0vT84 zb}Q$k^Ovmb6%e)LMN6f&&dww+vz&4EE|xyB0KgT17)s;J6%5NXDFB$*!JC|;+TZqW z@_4zIRpl@u!Nq$v`dE>D#&+Aby^)X1%WD+%;qV{@hTeO4D^JAry{jj@=0F#vqZ$5o zEKSaf45RW~Gd9?p8A)!Nms>{u4tY?#&h{#e-rPEO%DB18s$E9CtYK5Q+c8=Ex7;gR z*>}(`W5;$a>o_e9v#k-B7Vdw0Us*4;u%^5;?_xa~_;R|!_e!oLh?`)itmNj9d2n+*Bva&LC5fS1XvBeIQfO($K z&2o-gJ8Wo;KttV7SV|qGB%a@Cnh@s^%t=|KI}92JPKugx2By)2*@4p)#z}G{$Ee}B z1{8EhDe{~f#Y8*Rz#dTZUk``o4x`)M$6~i`K0CZVH`uw=|CVb?ExjI<;-BC>P{Lfe zUVE#FjRs7<=wanZ3N(#++^#V>VbuIN!ASTD7_)nqd+7BO0n?Z;_FHtJ*#Mo~oLTC! znlU1yf$Stx)eYt(0(_b!|D1e> zZs_5I5H2x{*)SueS&6%%63tWqTWp#v`$#c-Xy2A@H^oIgzoj;HuGeasu6TYSVc~%Y zPU|yD9J}OX41>p;Z$8D(e(q=S`0-;5!=N5&DMJ=QkK^MrJbCgarf~vwJ^IxetBY5- zyu8BAeus;TOZ?#bKg7MW``8Rexc}fGhSi{?JEY)W7mMXACz&jqld{E&%m6zDvd5T{ z$1r#dLyxW_c*;^^5((f4?-^YP*sN9<`W{{AuvraQ4L!h&?RJOVG+|CcBoj0r$$RKJ zN#b1@foT%v%NQf(c?6Njq09tw33Hr~bJP&sB$GY?92pKCXGiz&{OP;+{JUSo)5p&+ zbVov1gMbiL=t2)i9UKQp+&oNs#KOC^812Kqxn5T0gMvv&IRm?*TK^A)jD1%jfPGel zyv*4-38Q|TqjD_7Tj2Lw-~LC~ZYAfnl;$vHkS&i)>i|>3Y+Nj}OJUZk6Pa`Mlr-)GCz50C?H(D|*VmYHTqupeawA@b;NjNit%7iC%V<0#c1zeDovS?5~lg z+$hQfAcH9vay)xKd#zmFQ8!3O082Vpc0!z3%i74Q%&crDoHTVHiu~b>T=6`V8xhJo z3g?x>!JD^Bh+={=vvTIbA`RU~lGc*XSz6Dw&zJj4|A@?#HpxE+MlE@1BheZ`=wR#% zkZ6>2%M*1}&9jRL2L(gssRMAJm|}4am;R>3dUHg@aB!$tx5{z*)7~Q+aDPqsfAPej z1;TB+tPgZf6xpc0PO9Ty1{b#9oA)Y}k~@cCu+B?lWnsO24Op~ugAd3qAvuSvEPrMk zYu~#ar$sZ{jzhEV7_|?Y_Z3-eb*)uh;VQol(^y;!$OsD~iIj>I<*Ae)LM7bgBxMgN z=VC-P2Ka)zUG?nR{Jgan=_1IgaNX9M4^T4IU&JV4Z{F^&?e$eo-tyL$DZr?NUQHwq zmhzlgA~+2EnIJMiD`^zVXAn6!D9M=+qKLuY#@dWWheNKY}PnhZ*a8PpkMWH-f7Lu2%aWP!NZLt$WfO_96MRpG#JUA2fqlTurgq$RlX}7H*qt=T=mgxbR zG=~UR!H0P{7e_TL%Bf48_4aWHcB$Uumd>kr$J{(8tHG`8FPdAiRHo}8;SR59O4akq z!ZV;{UBC)#Z7$e0V0uj1*D?x=Z~O_}$9VVo+j#i!O>8zt*z_kjIX=Pp*<&1SP6`ms0Jh^E)AS0jElVhBooM6=*VbymS&qquXW51tpx!q#FpODDQGnJhz zDv3?f{Hl~ z#CgPat2rBez%X>!ta^08i$D$;a~?5{JKStXj3WcNlM-v*7cw#DL|I8GmyJ1R@kXZv zAb03o0Jgr?T- zo${e>Hg_!H`b8sL*sSRX7ue?AGL|mC2Q)Ye=ApBDic*{r=ZI;ZF;C+8{q{lF^Ebcs zTiES(r4&*Dw`HMA7Lck$MJZiQh~;KzZ4;fNw!QTqwgAtmg}MMBw%jQ>$&*9Zcarn_ z_#qxYeu&evGYx5$Joc{ZC6A~Hp8}eVx+s&%q#UdjGL|!G2)iS6-GF}8qYHgO5m(n& zh$)snuDEZhbRG_qDMxfi*$NArt9_v{`D%BL+rrK%KGqsZ;?{b`5oC9m^{pxhh4 z!8wkcgwldQ=DF8#PH6_S7&P8}{x15i$IuN3y~leWyoXo2S4eXNfhC;JClR=f5?_95 z`xH6?mdXKuNXogf3kcMthRMLo+9CD4syuf|+FMBcJd_ww#?Yypvw7^vNE5xhBcp&2 zW{5`{Q0^36M^uKWd7BJE*1pn^!oxCDDx0h?i<~MzC)XV8yM_zEEg)cHjD{Siw5Wy_ zw;-Z5tXW<>bZp!F;(AW=(l7vLhDr4X0Rn0kid!4H*}PZj4l{CRq*Q^L83l!4N^^%j z0r1GlBiKGbHH|OnzieqFrEApC;XIOa=yC>o53kI(buQUJKTiGp{ zu*&gcfH!62IU>hd-i0%~%71bacaa@8I`C3fajr_e>CiRw_yC}mUu*P$wFx9EwS9Li5hEFHjZdv{LLxhKtRNm(^TaM0kQu48rS5}=?Yqn4 z+nyt7Oa}Vht!se_Mhhucb6RC*Zh%Ykyw+gC3OFqKMIw?z$vcPkxl`G9tFMz*C_$7F z@(C^n36(zp`Ia^za|Q_i=l}Jum2O%V!+yNPG)?f{W3^hL?*mRwPT)My_dVAAAYo=f z7H5o7E+bO}rdi6eBu3~R@;rm%00c&M8FP%-@3$Do5iw05VuV2G2a=FYC;yyx@LfRP z_aHdMEa4+Xz4=}I;{dH56cQ93vg{fE>R7&X^$d5bA6`0h5QhJT~hi^nQ)t z0|)_gOcEx)+hI3uF-{|<=@aaBSJ=%j5z~aEb%MtnF-;RLuXnh-y2iMZoN<>E90+~q z!8syLBfyNTE?UY`X|i(xDdb8pP&O{j`Aw+`pjIJ;Dl*ORn^H$;a*`DI8t6447_^^+ zSdKL0nc&#LqXJ(WHOeA{V~QBMfCmrmQ=3+(rMgs#_;5GLfD3KXTK2VhL_L>@#5nb+8C zdYqr1U^_m+ev)wYm?i)tm?vzv7x?s3NV{^>@N@B2A~VKWJkI-F!hV;)*&}#>e5YYg zLBeziLR4hN2! z%>p_Mu`@s)ywnHW93SD~!-sfq{{c=S}IMk=(8I7Zs#pakG6SOMY@+T&oZY>Np0G6n9I2IM4Pvd zO8#=r8CRE=_?!R9*YQ9755Hf>`!~Lf-~O-vSP0QlEd9d(yv}Qf+JCL*Z_!Bx{@Q+B zfDbG@xvvd>E9W%8gO=;(w)dhcrlODvtG?~$=8eR}niEVoJvl{qTXl;*z=sa`y&vN8 z<^pk=;8=XxM3R`wXgo#Bl+E(Kfar87C(IeL2~q+>BL_f8%J?qE5m6Q;y+9Rc&!Xo9 zhY%|GbxHtZf_7ZKpSZaQWx&|nAwyA=dmsT$H) z)HaeLXEEj&(GD9h)-d1<-12O)e$g^Q8`c)UrpC-{Mz&VruXD&iP&*D;K>+|HG{7AS zxB+BJ3;D8e`ZbNcrBv&lVj#1Cy)0hJsMSs;7SNa=hCB9?M2>lxJe&!c75p|ea&3}1 z1!<zK?-3zTRdL8h>pznt`U`ne`EB{fw2Znc5vB_0>|Fsg`MJ5w z`O=nVKRi6F%n?+!o0q&!O$Kw4N-;2_mqTI$oJJ;gH}JhZ)rIX{h9*OzZQHe1!{wI^ zMM;G_T(4OpL7l#^e3wg&VL*6c<|Ib??QV-1jIbX;p&Ede`j&bTt!}D)&Nf>5e68@| zRVZ4NhD9MbjqKzMgcmP9QlKjWIOmAI?*Ymxq%5;VLeY8^(3v!MFiAbhS;G~m*U172 zHRsaux~xB)LqpxK0@8$?f@a&O>^s9Hr02Ar;c}j}LxtGkS_Ug{Bk3QPxi&Ea$u;_q zf#CLE(_|xoV$Eaa3?Y`%8@dwHEB(zZ2KSUQuCBJYcy)>Wc|_+4a0xSIa8mlPj6iJm8CnZ3l^pk{`GdK~D z99&k$=ET69K-uAFbA-3ve12s`C$4FWF-G>e#^zg2OqX4V*X=Cvh^LWv6 ztt{%(-F4;RB9(g_de{!nZ#^hUNyw&I3_{a9-vYnC`JMj~yWNO1&uZAQ?L#+nW5{)k z5|RZ|b`%sAuVHOVQHUF*z}i>aTfa+u5Qar4yA6o2TCH$)c8Yrs?&HDz`#3#2Mc4I9 z@Y^4NUy^<f#lC>2H4(|Ll*NaOiJ- z1;6wA-;b#MzPh5^sl^(z&|_|}M9=SV@XYUF78is%45>16&QS;t!8f2e=vIR2b()Irq*rx{%5S8 z=RMXTpzk{PQg&35#u~#iV<^)NZ{faDXNVE&{p!@ zy-&40tn*KAQsx0ExfK}R5&F;ps{x*XKvY6I7e>_5m>L1H1eUh9C`fOd8w9F=9qlz} zz+Rg$vV4zh2AlSpyWW{JoZ8;m#+B&S+Bl4+IqXZ@-?`qr`OfChl0fS4xC;>1yb{RlT}l$G)wc&h=7x>j2Q zZ7o07>iG=QPno5>u0L_|=QYNC#>F*Zy;-3<6039O8^oC4I>s;z7={(N&+sX!a&3vs9*#tm z3;~FP!#sJ6s~*F?$IwrRlOhRLubCq_4l)q2QfTLr1EU^Kj|HgXvIy&fuvA=iBv;1d zgIRtn@4c0$t(#*hXA7Q51{zs_ssV62jIojP5@?aNt7&t4Sjxnrt#|zGo#a{*CsCYj zlXhB)$HJfuqzeXFdWa|e)d6z=TnF@PA-5tHoq|K{6IM{T-)HQue}eI5#wQ={ae8tO zoe#?7+GDdh!qL$YLI^lJJq0gfZV zZcH(;g!5$G5b}h~z@&oTYK7Wxi4wz7swk#n>9hVTo^I3a>}MP5Y;!DEWy*+8JORNu zbkrfZP=T*0@#<1;Ly@Cyp2tVWc=O3qJbw5HLq8y9QL=;Y;Jk!`dM718x~@YA0T~(N zG~(*&3YQm`*zI?)P@$9}w%Z%r++5@6_!#}L(m`{`PBzaBr_ApW^E@F&A-}r3{0#g3 z7F`dVoUF0h3{oyY!;Kk0&JM%_R>K+cI%CThxY>S&{eDD>5mt*Zr;HSxEC}CW#w?1a zBP8cAt5TEAf}OKi+B1QZlZj~MiP!;|6hH$U0Zty9^)cRl>lwcAg)idmXV0-&9|Kt} zhoML32RPp;@r>L{_X-i}3jl0Fd9eZ>dah-CnN;^5ZTA;Kf-RemrcPU8(>~n6pJpv;AF%KB0G_FgD!2jy+Qvp1;_;MLScd`;!Sx7 z1`zrVCnv{v^zb1bJ$a0i(-U-^7+}2j67t*yiC!w6-x}&H{U)BJsx$$nECWKIR@*|D zi8RH*qYph!PELgLq6_G|9-n;rDXy+AF-`kAHrn7@icB+Z1|Lg1APP&)xyc>1Z>o&o z^0S#kEl6zU*TP83glV4f$)}&4!`hNE zw!UbQSJupT{pkRZce;|=msPm>btkbn5++}$Vk%97e+@NWA+a0Jc5(=A}`)UF#vh33EPJHF6F|quQXV> zDS>12m^tg*(toAhT!B>Cq}@{1>9`!0*(&eS7;~A``$+(@l7hYFJUg6*dl!QQ@`B~L zHJHlzOU0lqdu6@bg6W^WH_MTkrEHPj!@zJ#d9hw=o6R_hVjyz*j!R>bfCUE$rMG-t zi+U(&Onr||ql~-G_I6*48>OF!(DGM^K|QNMFiXkD{U{~p=7{ZXD}=x|GG)N$vKJM> z0jL)hw$U`=nwG%5e5dVK1I|Jra~5mw#MAE7yXBm)0z1b@UI1*#m(HXDfV5^Uz!L;m zD7XMYLVQ8UT}D(TnH-Sk+BPFE%L$mKj352z1HAb7MizlG7p~VEJbm&MZ#{d4^Ye48 zRy{)S!fYE8#;l0!vMkYjxfC9FxfEU>V912@)%q$yM)O^X9G{gsm zyp0)ZAw>oKHg9yS7UQG+pPF$e-9w%J?ra=1)X9?*k|)SwC)P#pEFXu&+s^W?A#^x7 zJ;l9yQU}!zV}K^r#DbC;#F(Vq*lvp#pMHY(K6nrBzyCho|KL4bUS1&Q8PmMS#~*)) zt`E4nzQpm-iG-6lkKj7lh#-p8IE|9Z5H-wp+(}6DK!|aVVb@7HG;f}0$#?6*8u!jT zR=t!lySjdb{gjYn(s@iUBN($oiWwKRF<2ADMc0vT>vSt03yqy-4r$FHyYEk$mnl<<8Lgk`1Ut{3)`Em7%FqqcP!<+ zGSZRG+eVa!!k7Op{`vR* z+j5ux>>FRf@BG1^6bn2tfRI&SG2lta!0vhn+bgvh?dKJj-tOn+Jz6iaUC4Exw;)Qr!Xmzt!Uf2UX0#$Def zt0C8(d#D%4x)mX{4D+X3=Q>6cRRDO6Qg994v1@$;-0wOJ@Y-QK2v!lMJQJ>lcH3vp zV;BY;A0OlF>sRRdzEpT1_(kY6>vLJTa8gQ`rb&pKV+1gZ+@%RpXE~loSQ9?;m6sA>@JS^|MB-PJRh!AsDcIXLXjEHf@I7!ag zI7^;xBJmInQx-y^DPp}@V|DDXUab&1kFFDCmYLxT!>A0HhezM{*bFNK?~!JY>14!a z*n{U8`y0l*-(xO$z!DcvY6H$B%#H?L%5h)?w2i_H&~{2yN)LdrDSCE0VCkJb)V&UW z2MU0a+!zHlxq7Fae(x-L#@eav(o~`Xx{A@NndoAvsvhRnG8}^Z^hzS)oaDp_A7q60 zM*3hup9FBH4e5|l#<^TWo+z_NiGn*ywOf@;aBBE0l>@g8f44yo;-Pq_2w9GB5*8)03_>l(lFO?+~MNl0v~?-A%67ZAL1wP z{RA&xeTMCLjXBN;y+=wreDKi^@!6{n@%Y^cPx5qiap)q;a6(|k3V`8C3_iPn_3;tjeEOz%e&2ovoAr^(9FL&yBE)O*&Y(7D z#x{I=UbFMJVCxox9_iX;Rbbjp7%=a$Svj)_hriGvgeFp2P62R?_{MMi(ycRZZf-Oj zy?TNGAe#oGlbsjg9{SIy;%$zXd)T_Dg3&f`r|XCmG}sy_eONX`DqYoe9Zrsp@c7Xq zJbwHJ&d<-$4@1d0matJ}doCqImU8cw;&KqSvoJnTEf?abD`1NOAZn?uHIVZeQjQw^ zFyi9!QtQ%Fb01pV-!|&jYu1AEWoY;^Ti$ClsCgJth--jT)lHivm=Du}=9 z;1>T@CAr+BZA9x)(X*5V)!PR;7b6i;j7T|S7*=@lhXmr^#!-o|tT?a#=y zOkIjm(nM00iVZo-ewCo(SNA1Sa;*>?y3Q*o@-PCd%u&L5vy^orCNL-2q+QVUEOOJx za9W_VI2s1*I@XOmKwTH5erxj?oQ7Y&<{o8T0mTdGjOL-NmB!=THj`@pADCosu&^!b zFuRA!5-Ke6ZHx4GNAMwF$VzOc9GklP%)`EuGH{)jkorD&1SL)@od=ZrgCy;WnZQANUqNW_!oRaoZ+0qdpLQdCw(|$9 zyeP_$<%G8KK!&M?%e8A=@{Cc8HdgmKcrPSzPT0`BBh?Y8=%%Fw&Dv^1V$CQbA1#CQ z+vp$zvz#@&x`5r=AhLZY24FR4~_DmQdv)pH(vH zwwkFvgBE(nvYoXb4)#TLG?2Eb4UKM7mzIWQ1;CCL#xf#t>a_3Fg@DawgR|4q0)RsZ zprFncV@CIVS@%iPJ*G*+^XD1+?G`uNEv9iU{5K{<`_+K;(UG!Bi(x1PSu4HNly`{p zjB%D+y~MdJ1m6X$dQl4INRkVnKx3W-G|ZER;3O{jA}M9;Z!*#p5oZ?Q3}FxqeGgi# z(Dyz1en4;%c1GDkR8;6WlCmhB)CG3^fV5hJ(};`DF0k(Q*mXU|e#V3hMD1j+*Q;Ow zB}k!Ur};Q2ghWctyg008WrA+3D#%(Lsu&0lFRpX3Zt}Nv;re$Gicr9!iiJD4H`S0? za08-9H@r4aNHUKl_+<*KCtD}vOi4bYXmy(L4jGRa8rwK1#zQp_Qy@wzFGm#V6K`Zs(;KD5WutGv;Gw}TIFHSG zjfW2(;pvm7c>MSghSdrddLO(hK}r&XgZs4L(u{Y@&+j@{J_|m;=p%{}!cs@sv6Nvt zJ3B4!M&xjHeT8|NMD9_e1Zh87s9dWoEI{KzacR)yLHm|}>t@t=x@w3h%Ge1IlHAyw zGcGPJ@YjF&*YGd?^q(y5`>n73EqwP6|5Qk$77C;hLlKNb;!e+RbF|)!!?CrWua9VG zme;M#^Wbv=tTDC^vULjx<&?x%e1!8bOIg zj;gSx(vlWhIVsz?+F-p}m3@;~cq70G>~%l!N>;@LDa%I6bn0RCJMH#ab)XUksXQz5 zJR`*fPOM&K*{95SPB3q;fI}Aq{Dv-|3jv`MnJH`9fEtjrgbwLmXnhe{yRApGx4!hSSwaC_(YsLl;J;kZly_p%L6D#Z7 zEo&4yFEojhb%zJBwa1Ls!`rgdQc%Jw9oz;6Ss^e^XE-y=z?>KH0cPa>&9G4dMU8SlA z5up@~VmwIXVF9D4;s01F3ITBx1$P_!6 zVs(j0vue}=Ipr+5l3AXcrYwqc)|zM<+FAl6CxroELQ238XUwwzWjG=iiLzO1Q6i%7 z|3NfDi@A?rB$ANmK?k@Q25bic>JhVwJH7!z00#!5Y%&A2vY*=h&Gm%U>IQ7TeS2~f zL;F2@My~BS=UTq)Vye*yGhv}_g0k|{;Ju(DsS&X!*ye3$2d9y5XEmFf*cyd#M zwR}`T);zRMfer+!#$W|FBB)`6^x&rNKz?4;Vs5ndq zynYSb9t1=w=Ym>{>&l{yrDE8;g?kT1Jb1Xr#eRp)xWN#ku$){_OU9fh9F7OPdi`4R zjjvze`qig69A4vaxWT6{KE@|6KEhmXu-(d-Qyef366(%1AV(GjxQNFf#()%33x$dR zL4as-uEg$zc>MT@5@Rtgrk@g?fBFoEa-)2> z59JdYX~rO1gQ}k1oMBRGOQB(QBZR>F7;3Y6L8BS$NfCz?+1Nda65c0Xk0K@clrNib zAbYD*eiuI?M~SgeJp)_DX?VDD2Um|2C~ zK3~`F>sL9nEykv_o57P*!O(s(0~{8L7@&N)!?5W+`oZ^$tY=ja(CRd=?I%kskl{&< zW@uG}A&P;?Q{x;ANX;(lV1Si#F{N7t`~U$#{=Oa%N$4trlup=8y7Jzp-S-!FNyVfo zRZg92g<8To(ynx;TCHkn(4uLA?mMmo=BTon)>8#EgjzRG&-c(GJ1FY;>(ABEz*7{Ex%~&w!EJo=VMX?#S15m1j_KXqZMh>?L zF%g3^AwVs7%-~Q3ae2LYI`3%zdkunhvWFIu9@?4hL!nR4!0BaLuI=3nuqlnK^1S94 z8^A^&AZt0x7y+g#q2vT0S*S#mg)S8_a4T_CTTXDPKxPKj48#QY-xyOOIB-UVgheNq z0Ge@g`wGYD28CHI)S^rg5o#6Xi>M+c2nbftvOvZ&eSR2{JWOiA4j6*ujS`6$J7+jIlrm$=6OQu{x5p!HZf|jOdySjh*O;aQYRxG1h+1c) z!H_B&M172!FwByp%`Cahn{k72NSYHQ<{F?9y-(swe1oju(XW#>>4=XR*Pr#mOJi%zi-LB z8H`d`3>?#}5jYv&y-WE$9#`dbt?Y0D8|7hae|Sqk0Qz)cWa zTa8^|i4hkU7kK*gDc*kj3wYy=r?|Md@YEFZ{0h> z547K>O4HEzNmJ}(Zw_$)GzuexfRYR5XTl3(tw_Tlf|v^JO1WLA5@Fhi(Mo9qG~B-l z`;zC_uNyiArR@h<3LBqEF!KHY0l6wULrzd)`T zoNaypAT@Sv&s;J2?!-DJ3Q5a~FhLrN5-UQF%xFb0 zZ?-+Sj_feh=cd%a1@fhEZpMBS_RZtk3H3S$!PAWhtjcB3v9`Lp$~)BXV7a%oSLeE; zY94Sv&VN5U=F~BY)_aD{NMSOC8+`i1$IW-xY;EiZBTx_;&Jlqv0jANWr8i!TLQLja zl+K$TW#PI6`~39On$3hr@{rj8QOK0l=K7J^(>S3yK_lL5?o39JVX??@9eTE{qw@jZ zQw*~Ptzr&*{k`Kh18c)xM~a#xaL2vpt^fpXVfX8O+K=0K@G{bd7Lg z)Ao2}=wi6%ckwZ|sElS%YFDWOoMqVXF3VP+mV(3W0WUuJ6vsJZ97bfoOL0l$3u}ok zJ;P@3O_ClvZUiigG=x9`%{3}#q!d&cU<_jtq_R3HY9c_H1pN;HVn&HY2!*-e0HF`d#Nc%J}gmV80|+CZX?W@ z0V>7Orz_M#uK6?-y5AuC%yn2>N1HSA==vdm8v(ek`q2NIx}WYdixPDssLo?AoOC*i z5>dHd!X!m*R7NSH z9C1~UsmO>&0&Ya83u+i*l5;E|0#%F;A&9`I1Cg`-3Lk#(H~94V2Z%`6V8kYj8eS6A zP*Rau5aFSQnOtYgc|tB)cb1BVFsq=Zd2U%ln;YPu?5PkV#%;oGGh&Ql7I z$Vnl`xtJj$A`Jmo_x5=7_yMl2t`JkitO7=i1LB~{ujTxjvZ4p8DO$@@L3Rl5x)@*% z3kG=Bp$FWpBfEmoGele0f;<-oygHZj`^~Ta100Xjg0`Etkcl0s)Wgp7jZJr??!8M- zrG<#K5-N?btcBl&RoLfFy%izga({t0p1y&1-gyUaz4az8E-wI*$e)xF;xM}B*8p$& zd0}n>;bJORsL3a4f`_Org=Pu~sT;ff&ROPhGi>nS{sRC|58aIC&z~VntQKNyim0`3 z!h#!=(C-IRDj6p^V6+m;Tqx^UJv#|)qf|lA^3J1{bDHOjSFf(|@BE!FTW*q9O&N;oa6gWg=97_g3X2g*73Tq z+Y{r($)!cqF^e)>n{jn@JlkA$KT=-D zl!CUW97R0^q!cA5E+#}u!vCu&hZag;mwCWNh^U}u12d&=rKBuEfYAg{01MBjez|zo z|J~)xg5jV-z5)ETr|Z9Hr~A6rinU^5{|;(^5v`US72h2tYTzX8n}abatuqu~i|n#U zf(oOt%k$%kIJa>yg?4_se!0l1vO-`h>%<;bMyiy`d2M5}eA&ezBealf1Px%)GBpuB zsJHaBwmr@ueV5VT_AaAYhMz;-SS@1C%PE>d=Xu#;JZPX{EeG8MtL8Bm;i!>OF?!qB z)=?=fa)}x$IKk1Eea`?=RRV3jdV@iW7;5)h@wp|{~iyoWM$ipL|-oTg969#TZ}6cGmjzhw2M$(bY+D5#(DTa$alTGQr{ zMfOMn5=&awO!Jju@Z6KCg6y1U2fZqa{Om=fHDp!kg;XFZ-7Kh5Tqc0CS;itZgLsZ= zIik*t!?ED@HlyZ@S}Kk_YTr)})k8NcJC}C1-Z6HP<#%3I_9S01Nz#OpKjM(o+3@Jb}xD}vd zLgfjd0ty8on6f8=>;7_!`w#Eo;_3o15^5~~3v#OgB1oBt;0%q;oPHuyHH-2&fveqR zQ{k(v4E)>%ySts9z8IqvkC1>~%?kE*PWk=qZ~g&}he=AN^ofE>1Wx<696+yli0oz$ zt-UdD=IE{2dG46}$sCcSZ0vSByz%5I-hKBSy!qyvxV*fO{?&qzq5@V7j`rM_wtyKX zT%My7p`*8=pLin{6WmP)2q7dSQ|$dxP(>cF-9$XRucbP~Dh`tSm z>4$DT4;tpRGIqGoXM&pxlR~G<*>Tb7xL^Wf#4r%1X~L^lukmmH`@eyI{!jmMF(=>u z-LK$}{`eAC;-Sn&8WGc%q<7g)3v&^DIzQ?5ct$lqbjCw zE{tFHtnmjfs5J;^D4@}H1gb(0NgWb!WMf+#d0#*ij-7AWEr!Gk^&EGK*IGEX93ozw zIrDh+q10sb)OH$)VZ#lVE2A6G0`wO9toz$MRejEL2tiUCxVE~b7PSH6SIWnAo+Z>> z6gQjf3d3?}bk=1aQ-EPy#qz<~`{f&37pR4o%9$pDcv8WhgGy+I^c6)!w|JWSP5uoi zF6Ns%rHK@XhBVqMRA7miZ3cZ+jysUP#W>AdNj5B2xz-HgVqh^5*!F9;f^7^=xXIWbq@Jn5ex#74n!3`GuJ#9|UHyk>&e=}IPk*I1N?<_{Z<8i{F z2#|6vs>o_Il+TfR&#I1vnVjB<*lh_9q-<7=K~UL1`EC@^77+pIa5&)h_7?Ljxu8}^ zfCk-6*@p}(nr>bx3CR`3$94!+A0<6J~q8n^Z^>;5`^d{h*)QF4Fdh!7Gyhs=~cS8I&X-A(A*=j%9OL&(hYJI^yFO*#0^xBr8a-u(7AeqWSdwFFs6nF(Rl%v01hJNMkt&!P!GUGE6p zbL}kqJ%okgW*;tuJeG5?+ivmn$rHTu?mKwvt+#M>xfce-_1-HN9@orJm01($`};^aNUzK++i$}C$wj@;YC^6Ew5boHn&Ifs z6cX-T-p8-J`<~z)WTEdLeEb1kO`oFX3MxR@7+|FILVbG@aoL?4d8c}Vqo6RyL85dl zk|V{6Ko#H#VhNtWc|ryOJZYp-UGh2S8(1p89jQ_M-y^01;VOZ~K(5IhdKe%FjHhN8A=gP=*_A^#~DD zfYH;Y?w$T)FX-e&C4&~LAqG#QjdG9GPB)&S4R}lF_87YFD;XJW^t`{vcSuEi`C(03i>&IXNDujGD2Y4 z2hkmR&o24rZJzovWv0+B-bI9fx)`VLwN5l(b4Y}Q4FyDsS`xN-aP4_h`?J$rHSPF( z#pRft_Q<}Bkg`rv5m!@#o;`bxo152QW{l$~$cW>hM3qoOL4(0J?_%}ZyMYK*0>}Gz zy7$nCaVbE_gpvubUma0Cy2iLU0&~Uf%`K+e8FQ}SEa62wiI7pJ33;A@oHZ{-=P(W; zSdry{Ss~hX=*(ME75&k!7)5#XyihbNYrkbeXi8OEeXRG@YT@%@bbU?+yF6 zDo%@c+21{3$})~pbi=R!0?9!tnwu^8vyK?KdOtHfZ#!CexQ#=92+*)pQpRh-G%Mns z+*qq9P2%yCkh_qiY(U%uq;Zg8X;~W%70iMx&Wapj%rwU6c^(Xi5ro9XQ&oUA>rNjP zrR5u&5?YsIR=zCb3T=O~-MgOab8D^Z=`_4sKc}y?`yBud+MQs8xD^bK6ulm>0GDVz zLQ`0sCbtkuVQfKw>Ow>e$=AXDV?eBBP}E6u9X7$mfz9;aMnhES7TLUlA)#5JYDt1I zVb~-LTk$Gc$SP_@C2rZP0YcfX)_9r~qE z=E8urq|5^LX~!%5ZN5KG0VC{c_3pCg+kg98zjo4_-}>5rir23vd7lXi%7_9J7KQ%M zGvSqDRU2`1L4(Zm&?z7*X6~X)XZ`bgP3{Q5W*qVG!2`VY)?0Y za6AoCYq2o%>LHx2^kF&gjwc{rh$2IEaewQdEQAS~P5AECQ75iyXrmb@QjD0HadUHX zrziM_Kl*djS~2GdtmOp(==lq(0^c=v=#787zZhf_OlOuitF1KD3bu2&_JL_AgwUb$#o0S zS>z=Ne@-c37)L>wS9Il4gcgD)iI}NJ)ErQhM^sE6O(C?w&YZU24ZkBH3mKzi2GI;F zBW7)|h5;7w!PWW)!Lzt zdN^&jOGIBYN@A-vgmvY_!adQ>%&feb~=IA0plFkzR=tqheIOB5u}a$9Xa*LnV)qm7ey0O%^cXh=J&@lK6AVP&l8z1D5q zD%jfG;`Ci6|5UD?2W+4B-viJHorD-!q(o+9ZqWx|sMnWKG?MZJ3`~*MJsPcB8&iM- zDe5_kCpbNS{!GA%0#NG~TWq!VR`kiLMUb>Y2&e&|+UmJQ5`ZKEJWr*T_M0rE7h;i| z55TJz2fRLH^>nFnGXu;4oGWT2)FX@Xc93H4lvNneJW`I@XA&WURKSG-N7M>&v$N$W zo7KjMVf!ilp5^vAv!*4$`mZS|jFt=BF{7Z1Lj8g2+Uj24u2nnTE?NFw-&X<5G9M+1 zhdpP>2^40eH9_Yh3bL+==Ueq-wpZ2G-=Om>Q3uWV;htkwCAieKIRhiG3j3?~RVg5l=4m@)Xf^aC0$0jNRA*R91Xi@E7i5^>09Z>&q#G0I8tPBgXDR`_3R^!b z+YvmMImWhEYH91hHm{~sYe+PcrUL*7u?h9k?lPRjy-?bDCurIUh6(_l7ugIE%#2c{ zCR(8)XEu^B7f5GBM&c>c*JxIG>q5mQ|lp(-LiM`*Nd8B%uYL0Nm3T-YM(zwNi>-fZo3AuA+? zqFf4Iy?Tv*>sS9C{_lVGzb>Bp-nV}fKm5^8kV}g`vH6G*04)WjlgsDvJaaqoNP#pe zMd?^~?@}4)gd8;f+V+D@knoRA+*3Xv$jsgw0-)veVjS`C;bTFh-)ykiZV^(%Pk-^R zaDDqJkgK33$EpT9Jx4vvzbQOAZYfi!bZpolP(-c51HlX~11M!sN#GPvBZ(3WqrodH zZiO3EVG(S)Eqj1QksB55mnRikRq;@z78FpC5y_0Eq`9qC73M6)M~bQ#%l?fWv#bir zL4e>!=%R>BM2*Mm`uOioISt*v*@UIghy7#WWs;*_x@oZpp3bPJ{ac))(CDHI^OfDm z)O&y{Du~s91);;H2zt9d;ca;qG_li4{W`<{;<|lfWTDEYgC#MzlG$nOy^*4iAUZLgoUHZod--X(pr(}emzVmXb{=eB zGK+_kYxU@%!nJGLm7j$SK6+ENJ3L(j~f;~h)^R#F`* zkgl(QBGKv|Ja2(3EAY?hD;v>l<-G0AW(RAV91Agzht5{XVChk<4?6Qr0NW1yc|p zu?oo(%vtLG=At}B#}WH?t()$=z|qioqvU3K{Jxf9vC>N5&?U%8}Si7Py(Xz^27l@xm)!D@?&71s!k=HQSNiw`j% zLTX;dBm`j2KrUHAposxhcta8e7#gBUK?FKV;!(9w{t7ry7?I@K6H5r;kRsA1AZ&md zD{`#jLk$(+f)ENKNqC=FTLn)*%6U`?&xVAfkmh#gQox6bJWn_tZt*(ZNba1LM%s*0 zlYF}!u-#}a*r={`5Yiw8(|4OoJbdsNj~={%i~W71v_Yf|V%lODb{NtYiAD%KY;pzA z{l0wWV4Sstv{U2HoJq1dQIt&pw12?%h6?>16OeW9l;5M2p39}+2jBmVMYF&4TmKmj zH%GSsgACAuS9HyoyX4E52c*w;a^SH(MB2nK?u0RKvJ(if7S2QgCYHT5jw7Btd4hLT z`MtWjl5@z_Lq*dtAa+20Z4FN6*A+hQ=GtCeO;%eehIa@8=l*u@jVrzYFoHmswe3;@ zhGB#I_wP$|L<$HY;iKmt;cz@E*qE+rXa>LjS_lqC+xmIz#(JVSs(@Klmb_TI+>`{dz=6KiO&16q$vI>vTZK%aW z1k$p3r0*g$!FcU8Ga)r};24X&t;~KQhq*AkIs=G}s;UCJJhS#?xx;wbDIT>p5}~1v z7Jf-;G_d?uLGNv2v3Xp37}uV)HJkD6+x3Tt9I(rjM_0ydud|fJsYTb#fzL|Y^Fh|5 z)|Mk|DS^^fQ)HG(7%w`=CV&x?ulrz~AJ{%Hxr?1P8*h;{l+=Fr1Irn-eE&1+vzi?k zQE-Ldx?=t2#xYpm$KBej+gz+yw+8)ddj)UNvjvY5Ic{Co*9{3q=a&FG{p0NkZmBbD zz%yswZC&zwdsl*$_v$`c@RF_$a0QEgc5Yl%l;C!C23(-?>-PO=vP-{@oDOvP{(Ze) zFCS+=1g}B^EXAw-K7y7065TDl^A&VFQT4%ed;1!>WW*r)KdFne)B)o-YL1C` zerlAYWm4_2S&bwoG=z#|VYHfGn+9M^K#Bx#0_TVtqr%5q9%)o~{se*T4JefaR47Sk z4hIt&O55)&MBeHb1EjeWy+F|{PgNBXTYEb@7DB81?Br?|=Jvg1r5SX%T^3!ytDQls zKYTHHeFL1iEts0!*SD)Xph`-m)FPxAB}g80siOSORtwh%Uy^aGH~k{~S=+BrK{&AI zidIzj@GEv20<+X64())rr7CA|VXZeP-eA(QOY-lE8UElZ*7Xe5G7=mbnsq6sTfMDv}uu|zC5}&`t~G*Sc!-#(J>HGWR!tWGfQNfdVqtr z6X4rb6qKS0NvIYyqe2Afnvfe#gs^q@SQvB+7>5y;ms?z3?hyx;ka4ZSR5em#%12D| z5xLA#vWOu992Fs0MKVMkNl&?kcok(1Q(~l{BBlZwx&e_A(h8KBP>296>%p8c=Od0& zMy){wDv8=4L|B?diiDIRhE$MZ!jNXc<;8tGc<>Mp z?mxzEcZCo(AdEbKm^!Kfuk6gyb3>Td@-VVHZ}Km75fR39O(KTwO76 zA?HNo)L!-i$VwTq?^wgOw&RFLj~?Kicg*v91ykrm`CS5Dc^e3K&pU+wxb)QvK?q&f z2)wF+w-)@*H{LVR;B+4gK~X-6affl(V7J?1v)v($5g&j247Z0{;Zgc7WBip)U)&2c z{bho1QwI3tInx7sreZmHYsJ$&ZzSg}XU5_77XRk2{yn_))?4`TfB%Qx_TT@`SMkFi z{Y2`mX9lqf98`eV1TXJ4-z_Yz=N3S7g0&5II(|0{t;m9~JV=C&sHT|Fst(|%0QKTPI(45_Fu0>{I z7l1t_Xt69RAgKYmvIq`LRh$tJtQE;2mOi-$nMlKl$q~rqy-S5^VPwKeUbF9g4|Ph3 zKfmnpVm?&S6t8m=-lSbsxx!KeHb>-em9w4CxaeQ(Ygc>Cb$YjScw6l&a3{WNvK_+qWR+*_ts*!%5R z8qrrnkDo1GybRE>E0h%i1L=6om@^PUMyao*Y|4DZX1B#=vq2iv5?{35Zz;(0jCmF? z1&c|i%B{w$ddQ$&vP~ikVGEQ2c_!IvwIIbP`Cc(;2&9xdVpJdp6q199(L6ms!2z{a zOqz%6G?*o%I%<+|3uCB?YHij%4Fy(EuIe64JKSgYjsJViECMa>S?}*&(KVXG+?f6e zFYj|l*Ei7WZ|irJv1E-1%1UHPk@8b@g1Ea0s1YEk)&WPJ2Tr2dm_@m@&?GAqZ=Q7K z2686d)c>fq+IKJyE2DA|Ljx7mnh*#`L29`sPP&d2u`mj0S)mS1-1(sHDMn{((8!*C z{fy`Y5@mI>A#65;-MGPayG0sCFf%6guFcb|z)A)4EcL9-f^Ia=gb5c!JECU53^4@6 zBp%b6st7)XJ)hTfoESuL6%V9y~OS9EsnFIychk+q8PJES|KE)Az?@fLkt*_ zD8ON0&`=SQ)@w!uQB@)&A-E|7AQNJZU?N46*KlYhNJPMp62>t}z1Ju?mRuP%S4?G= z8km`IAixmZqoLA*Fr*O=A3Vjy#Xa1=_Xzv_J*2cnqzzKsAjK_W+#rMz684;Qj#)IVmC@H#;ZzdmBe|WV-{1n6oy>k?dQoAGlw#1-)X-8I1YID@FCv) z;urDmyYJxg@)8y%mePPh%i=|?>DT70o56)5cl!NO@L8`Dmf$Yb3k7)e=mE_mX{eDPD2rUiC7JXy?onV*_~kNtJpz@#T+s+s+I-3ytu*_ z-~AN~!+_mxi|uBMpMUVL@ae1Pn6gG(BoXBqS@j_arFHNJL@-AP>SjWqLA<~*A|Rqx zMy8Cw1S*g;uw0}fMx9YhM&+!=$lCHfLz6j7*$rlx)%_i#L@&e$BuzzfP$ZjEKW^>Z zarGDx2nK|NGm;uFgJOSJ`6oxxUH#Wzy%N#y1q0OT*LeNCuO+S4R^vcVsIm)eCUj{y zXm_UjaM%91Ug=gln))M*z8L@4F;<+6)mRGY*xVcCW9r7B2ZU^_CUbRkC?GnGU9%Mm zr)Pqz5)y7zCIDUY9w1ER2(Nn%LZ~uedsE+U^Xe)4hQ$Ug=cN6%>F>+(7^tRl9v=t? zTCN+}^F~uvG@)adCLcNScr|%V&-8-eVzI{3R7EiQ5`%l|PZdsT@1(BOPN#_XbGA^( z&(Q5Y%B7J(k&A*x%6SDBlbe)|`ySG$%3sFlXlvK^lZ*A z7R_DcidqktrWxaO#BRIAFiH(TC~S3^kI3_^d8LBjW!84r#(YB5V-zlI13n8ab0)3$SIn&;WgsE46DXVQ< zS*j{XXEU5AYm^d-wzD2D(9KDfLlYQIfNTy~ms@GJ3R9#?poX?qDYMlqi{i!4MGi+$ zOMLWj-ilBFL#cNwtp1N##zWn@0bR&$SNE5aL?G;Ugp2)v{eFkt?gAJ43k=&WYGoX5 zkGQ?P#o=(k;dsRHa6qlO8BCOJMo3t*I33v!r+A{3SnC0f6hJA6f*zsDh0d`mxRErU zHVjB1=}%NuD zlQ!70gxuvB*lzdO-OQM0nU7K>TyryQvDuCS{sl(KQsOD+S(&KZhX{nK)>^6v6fuk= zt}gH6$&)wn^vPSecl8KE+#}EyDef?)9fq_Mv}Z~pgo3(FC5O$FgvKy|mM>}l3ugrR zU-oJtV=h>9{|Cd3MqEVzo+b%-o+bgk`oRyrylC<3U;oc>dvjC)Lp(HoFi2K|J8PT$ z+Y!ZGDA5B0?u>MDxa?jLc$xwS^upq)P-_>3fbC|$$yq{Nm z`bx@PF~m|_5hS-31g>IeBP0oXrU8)#q%b0dLGq|I`lYa>34t}#vC3iv2tZhkUb%}QLi&#ftf8$`S&oNU9A( zfhr9o&dQW2PYwtR`e1u??Fnt(Hl2EB^vY+s(Mtes0J57|2fv_CUAyMRW>(a4qZ@#i zh`P(*C7(6LF({RA&o5N=34oWJaiLM^ks4{&@iT3=a|3F_DIIN*8q4?k_ZktmR<5in z1J#uwVlC*ILI<0N=KWmv!J_)E zC)Ty^o(_@P9z^e@wzXbX5NJr>>}!M7{_W?&Xxry0oaZikW>FD99d}jNz~zxZZmcBI zxzq7h>i0Z1zD=j^Gex)GLxzfcZVVv=pT8DGd+LD>o~qPx&f)W}WuN*|M(%YZbR~w` zcWC>B08l(NQgu(9onMb4v42B(Y_(n0&RU8I2w6dt<`z;smmAE}jA0bTlx&k}Iigy% z%#OyuE@84YOf&(*utiE65E8f&$|L|iIUcat42W?L-fn%;*+K_MyaRJSO7ilk`C*iN zQW?OU8Kq9hQ`Q_%nbg1qwN&*~v(Q0RLaHiJ*4JKk!udu303ZNKL_t&uHU-i>qc(%< zsXsIKrr7oh?)ttp=7F_;l0L|*-*o0XBYxqOruAc5fI_K~Z(EO}DD~#C_h+kZ93WIk z35dpbT*)SVwuK>Au|`KlGe$(v&~pm|v<+@vWn)U@D9DTwo7~r5c9d!}PA`oKHtzu# z60qL`_pSyPM#pihXy+T`QcyKS*U_D0a2678I zh$R13y-$Xk9VsG)AiyX=Lf(i-L8+(_Uj`y4Fo~ytip*Ig0p^L3kWv6epwf(&ha+yE zy#`%Zgai%smYl8_1BOBBLZ?l^eu&uc29*abUz9P;6Xu-7+8-p;IHrUlCS6Zil*(CG zLya39+;)fpYcC$%5iumx9FWE>HrtAMsvgqIMT(NwoRQh`ghlDArD7N)6=Q#~!Db_E zN{C)S8b(}PT;b89r+EA6yLkBE4UFj$s3Rh6Fr+<(v_lL+f5Zc0q0e&YgwHf)%RtLT zy7T(H?@uq`VSKuwyC#jvmm)QO=UIMgt@z&ee|>TL?|k#W!0VeMP>VAT7Xs8PV}`$` zfEa`C$coV_QpUuxmKE@H67x{BanMRpWmN#%;UiVGhH=27M-TDdzxFG5@4a8aqel-B zQ$U_GLJR_cHjZL2GeNNjSQ@U*Yyv!=Jfh>?V+4EwtMh?0xb(5`hua`_+V}J~Z-Ne~C1OVL>3f zHk3iw(gOi0K*FJq2YmF=hxpRhzJ# z!L=;{<1T>(==Wn|p6fMPFZ!Lr=Q& zsUWWS*#`lyZeC)pM-*mAPH}{YjtPVTfd&ELi=+I61S@+7P=}3Rpq27>DMdmR2||Cv zfP?^0h6hP#zjEQBJ`^KRaiZe079^e*bz~4 zP9;)A5usyOzn(>yzsvjU>tLUCLiu9vddMeSuirQj}`5)F+8}B(~u$zRXQs-x0{(TBqbV{G3WMRt86Y#9x&GX#Pp}hxPw|m9h#(eUZ zBEBxYmh9iLBTVTyR^iTaA1~hBK(B1R&wG2DmtMWrXr9+rStps9~FApP6nae{<_M8Got^e!~m}m6EwyhCO#(_FQOQeCDGI?QEFB++W5Y zKUW$%LtFa!^JpCV(2Zk28U{jEgk|#>G7DYIc}6X2yXfBC z^l%|CS=)xhjeh^t<#QS8(Uz1*(WkYI+AEg&K0{9?w6!Ndy&-U~h$yq9UQ78+HEOtn z&PQmLMlLJ}(jg$mfD#LmTWj<;wIP_&Yo)8Op3evjqbR?ZmjkY@E^v8yh3$5WK!Plr zi{yG0wWQftoPe}n4GG){9To-?(`$;~#0WKawR}lyx&?nnh@>D-B7705ATuXXRLMet z0Z}CkNx86wZZyC#na_fZjN?2@=qzP$sECQw;8rjU5tsV`R~K7swh7~ABcZ|(3W_3t zFJdhfYh=z6jPN0gb7XUXw)Xnz&N1oSRz zy>E%!7{-LliwoSlx`+LKgK-o{`BG;P2JH8jc=+Hco<4aC4<03jym z5V60!!2JjJvA^6SB*}8G*0!R?3dozPk}HO4if8l6o?*DXCEHP+R}8TebWb1e-f@QG zE`?+XBoR0YD;}7wrul^4H>c{_`Klg+0d<}o}CqF^1 z88vfDF^Ysl5aR&%uU;~eX4B}`mAmin5UkJe=(Vw+zrU|--77z58z8CKo2=Ne5CUY% z;t8gT?PiBJp1uJh#*hN``yD>~_yb(uzQoKEI4~#y6y--!M})?vxIxgG=783DXP|0I zS)OMt*~pEzlJJZalYo}?xKQxGu3l%j+)t_&oVB~r)eMXdtk6)1{V zTD?vZRU-39Fw|%X`4XT?!>Q)wbP_E=ez4rr{lELQSv(V#Ox-yIa6d~)3xzZb$V91_3E$lUdhkCto?q@ z7_}?Iwd`N7w(B$1z_8f&y51PGozGm_o%w0HJRozqs|)D!;G1axH&K=0=rE{h!Eu3AQPF(gyZoRhv|r$!x1;H z#gn%k3(8QCAR*aO`&6x;n1EU^9|0V+Psj)qRJewq6|WRKuBPnXXI2NdTc?ErOaQVd@O`~wlY^OCn6uqqfaYyB zVMKXOn_CM%U>L}TmGVg`bwXWJfNM|!;DS82#j!D)GRT0Xx4_o5KVvFY~cubH2#1hkp>@Y}P^LDpE zOi>iWX+o_PyWIx+-F-ZK@CNQ(KEaSKfx1D!fE2f?*pCP_fDk)w+a2(QrqhK8p+B={ zlwN(57HxH3E3-Xin1K3J+A}2g)+&(*dCrQlFeBH3?|%31F539!*Z%=tzdE?$3)b`w zSX7K4fl9mT{p}?nG>h=EZ|v>40D{iDc!yG0YH#&6VaTbPA7M3j+sKVK^iBtj903 z8kpx9&z?QUm%jQf{MC<}C;0onE9lU!nAk{&fCNSHCO2yMxIA>X6YLj%+gW(d=sL&^)Xoo$zodY~5ljgI0^S%Rq)Z(uYRxDmBA0-i zXU+ZR7M)iWRocrPnP8x3#N5IYrNl`Upi@eSEa^7Y_8J#d2%TrLFzhI}9#zv;2zqXN zg^d>q(cMC;Dh0hKa)pv>(F&n61XWEfYWtxHYi(B;4O|JzvA!7d?1gsT$XU_d+3AzMW^_O!CW>GZjvuvZS#s~X;a>x0*{n;ZMH^uWz z*Q|%#`g(Llr<{GBZoJ-SYt-oWxy)kelwUWr*#9kJP}}W8t54o*QJ4KYAR&&y`z}rk z1Iud0mD9eRnxf^Is;M0PnP*z^C$bu(-5&1^RVPLxsFxb*{6W`t*FSS;1T=bdeli$I z6qN>`ppgL!MW>X87;N6Ig(q7Ng@+C6087c33X7Fo70*Kj$`J@VcnF--9hUp&dBU6p z@TJTw`N;&#r8o$I*DwMQ5Rqs=;(%CZlo^h?TRMwT;pP=B1+F+XYb!o?(*jMwxBVKp zeFiLZg9Dm}*!e846yIO+y{!Y?-we;~bvZPwzQ5};rMFyw5?Xk(;l%W^a972{t*6wj z`QlzM3Kv8sL5x%i#cIKk{C7rFh0;8uArL5u01{)w6eom9N+Ut%(PVlGT8^qN$6{BC zz-9z?`zA%8B#m5q7M>J1jap^|~BrLp z%WpcNCQD!?wul4 zgIM810YxE3bImx+VwgJI-XPC2q`ZR&y%Yh2>ZN<;W5GOC$sMfAO&1ZS*m}xXD!kHzKz$AxyD;aU=;5UjOlp9JQw6#P%>khCcM0UiTB@sAAkF|Kf^~Ke}sbqUx~ZOa6M07 zMzjp`>J?H~;#gNv2y!V!Pyyz7!n0@3@E?BVcksXe zq9c}D0%F0vN8-5#6Gh^zZoc>C?Q@apyz4)XzX$(WIGd%VRbFJIur%NIE2qc{jG zH`w|Gf*3b7O-RF{jTZ{QVL+lNI#-gq=S&3>aRE&`ssdVAi(+7?5iLrsp&F0G*x)B=gg{bx>_5H_H)G- z?Y#DiYcra#(-(C6({v*42vvWNpEOf=y3hLeXfvHc)b>UIbtK33F)f~72=pDTaaySI zovAE_P|dBw?R-Gx>ji)C4YNF7CRciB_n86t903xtF7NIQBIeceIo5~zxs>-2xM3cLH!zw$q zn@{%oM#*k2MIwf z6)^;CHyiA>JN2e+Fl@C(cA0TJ9&kvvI2;d%aYhUiCKMD%Cxvu11XpH8=B#}bL@#1s zpa`x>!|^2_El@y6P=kR2nE;Zj#e&$#i6yjt7U3=-BBc=*7du?t-(tTXF>V;!&47!G zi0w9EGXfMVGLB;Dm!wab*UBiBB&-t>LM`-E&Ri}ThvS54lF-f=0>S{qL_nx0EXv$8 zNmNFjfHJ89%o#%x0uw_3Yu;T-BCu7K99SoSrJ!UjeZ~>H-6ftpegj{4>sRpf$vfEZ z?j!OBq@Ld~?vTPp!5IR)z<0-W7y49x=u9ZE^X5$KM2y4Tmy`1q6YPX8Bd}0fR;nt$ z6Xr=m^S}GMOXc^w-~F#~{c>6;&ER@MCeBEldhYb_Gf=ViaGEmP1h00#aOSlKwkMw^ zT!zK7a&Imf*VnIbJRWg4+(>A5`2rq3e28%zfdJ%Mz;o9d4wCCl=jMJrymKMNy+8`A z73Xu$e;xw`mY&~fnjL&`&K1|!ukrr-@8f4b{V6_r_92ePqZ$YUY~K42=3d!sxDd;+ zxbR_n7wviZLsf_~&-CN#pYb{6rA%$JX5p0D9Z{fAT?ziRFMk97_%HrPZ~uGW7F6;d z{^-v!mz5|L7(kTr8odEUH_tCK=ORiIa$4kg)4xF5+nq$azwCow6aOm z5P2m>SjMza8dT9WY>R$PMB%do(KaFj>V53zhFl?O$n>_g2$fWEqR>3{0KlbTjM(@) zW6atMO(gl)+}%$^>Rkgo?ZP6l^z8NCHrYo;Z{hC}@1S#AQU?6N)|9DsO_{rT0^(U6SkaFsJ{hNQ3sG>%FwhGq7)t+#%-62M?{D-79nn(z^g#^S1MQQ9NgW)Ba zN{0THP-p5wf2)N6S2zN*8g%6_epW6nItBl;Ww6Dy&J7N#u%S~H*X!n9Wfz22jT*1k zbz0oB-i1+qYz=L!6<8DlZ-RjQu<+EDE6xx^<+{3`+G93{tj|>fYLSu-l`3WqYD8e^ zQ;ce1CfCJNP`_NTdbR^X3WC@R@tYiK_R##=88#TJ`B25*%0FGdI$)X#Vw4Ut3sD?~ z=7AhHf5MlvS#as(QQ8Yl7+%VZE8Y*icc|*j=TMz~iB`_1h&8_4H zQvgK;PpUIY=Qrg+8ytGNr+Bs!l9zY!a65 zIUDQJV#}RSKyIDx-_-#xH*H3p{)N z2@Zz?%*(c>_v_F|GxSQ=mfwkPa7G|;2F{D|oGQEPxmX+ooH3s)`=eakU zChFf~VOSzzFXl(Kiwc85jB-tg17>2ONxp9aB+?|JmVlfy^2Fd05ottdEVxbmx@QjsH=A_|fS5s@GUN{hN^3adB`SR&hW?}k_~q*-~cp4lK=SMI4zyjuv> zLJtCx@N?rcT5`{YYm#WLWS(m_fJCJYQ9vF8mQe-1g!(_1$w-X7#C@tj+k@B z4DI?38rScewUMamkuQb4I>Z7PjmTwn1Jqmd8CuP?D6Q?ob9wqiCbMI)mjQrQ9>MjP znAttU=f>HqzoO)d!N>s4jCR>sVXZY@yXXZsDy`lxGPYv8tfqQxeCYd;rpX!;r73kX zC=r%`Lx!(H5QCuhMUbt zDicap04sg}9D(C;f}(C?I#%^EG3Fy9XQ{UuB$5+G5+qC%UAR_D(~@JsUL zvrLyy!rT2F>oW>SKd7Cp2Cik)b8V(u|J@N$ug6SHA-7QF8i6t|$Ehg*9{%p{?Ui3f zQ?~y<(%!wj^ zPIq-xR#jI1@@Z{D+~ytslyxFCB!Ez0SNLg_ z5hlVkMTx~VH#Gmf$WN#bcE66Pu4>Uzf2^#$gcK_u~E6c{Bh zIFu^MRD#S$M8Fi1y1YTFaF|mqgM+wdPw4{b-i(J2D;_+2h{OJXyjH2#n-4e~_c*M# zsB3pKknGrfy-N%>)atp4drXWXz*LPoQ&&J#M$QGyga_A`c;We1@cQeY!^`QD3Rg9w%oTHtDdYc!iMLc1!mj#*bDl;mqXFAjxXzi zRXrWP^^Fnye)X%riw{3M=zf!RFoG%ulQ}{6S(6Y96XzB1)T;Yn>p-O~iIgS#djqc8 zySO^RfYlRdbh_>!N;f(rPWiAb`0?XLBB3=*cvf_9Y>u;?Ud1X9%_Dn3lZ@-QA-+v#=anbtT z1W;EVFh+sSzjrtX(1j>!_uOG+Vei`h@z>T$+?8_UJ^eEiLghQNN|loF;}1W?-~HuZ z$G`p;|73W_Z-3*9_`^T_E99C{*eOnkB=wUMpqmhLmWlu57waM*A~cKQUH6(c#P6|z48=F+s_<9KHw%uZ6TQlvdUihNZIcKnx_G^NKpU16IaRf4e;hZfa zr&gK=4QZPYKY}$6cDj-Tjqfy&2HQ8(#^k}5?5*a&Y>TcNyW41Ozi*OB+5STZ0@l*G zeKG8qn`g}WS7H0a&rR>sc3k$J!LG-4ZV5cL zdjLIC8V@mw+WFVtN$wf{e0vLZx!T6zIPXAD(mA(v*jAw%TThVHt?5fRu)y@s)VPR#9tgl=g4Gnbi;HrE=H?FA8a_ud`{`yH3m#v0< z7=f|S(v?5CcVl?d0PFm>J$U!X#&L^rg_5dGU496`?&Y; z8u#x%z}16*-EPLAJkhk-tZtSS%K|J4*76F}BFSL@fJ>12c}GZTr4>z)6ao-xgnG{- zQ3VG^(eImb=*;2gL9Yj_cVzlL4}Q;F&FXCL(VsqE-843KPJg0oLz|yHPU(TG=3*4pOYqse&=mqkNX0w`ve*{6bG_c}2)o^c>+4HgUhObnOh~iDo|am1ToxSm2i!b+ zhW+gga+dYB-)9^b2E~e$AoZuI$hwag2ysG8S`V!PVNFP>q82IdBbyzdP@Tq@G$B^N zG*1XSwRV~NcC`{01;{c`Qz#Kg0cn!tTuk5+F{!&D2hsbM3@pS5p@L~eSr+7FkFp+t zSTXMsF0LnBU{fxLhUpxSj zfZrHqOw%Q%=@Nk^brUinN*Ux<6?&pQkxejYP_ey5=D;7wO{lU~+x=Uh+`)DiJ{A1t zRkLhYeDkgUYFOf5{q^6)&CQK0Z*uX<3OvWd+*k(p1K9z&aco;lSr>MQiz+!ciG&nn zcLC20Tn_|RmDYHP*Fs>?qVErTeDI?WT9)ftD_(rzWn5id0Ynnd*f_U>gpf`SViOAG z)mt~jejwVs+<90#KHCKeV`w%{;?jRSYE5QMqIYw1i${+h;RiqX0Ukeo7susRVm)Jz zgOsI5gC*UBxF$e-42<;_;_di|=)^U$4{H=a2O*UE`W^0r;SW+?>YmeD?V=DU`0&FI z@n8PZSMmS+)&DiT_gi28CH%pke5aKUBG;C=;|?IkAByLuheoh+N}Ev#`lPGhNBz8O zhi<0>gPZlT#g6G?G6cD+A|UdFxdMd)at&B=!L+WJ@`?gRtyzRolGrR;*Jg1s_uUvH zYD!3=`bA*@mW9<*q-5m0V97@u*Q10?tWvYr!h`Hzt-!iggt!0(hM)ik4hTq^={?45#@jz@KNPclwRiuQ z7nm>aOG%UGp2PLMd)Qq}n0Gsb-9Zz-6mczEBztVuy2Oi=y2N@A%jNN)fLkXiFH%;; zX9E@xto=~etExJy2BVZRb|#RczX!fD(Ifx)NkQ*_%+=nh?-=6|;m?PDfLFk(HyGFh zR3laNQQhxDSuWoE^X=n~zuo7wc^}XZU{f}LHuNO*GO#|PqEc43&d?SqK{uER1}Rlc z6JvqQ_0Zolct#aU2n#57Nsb`z$QL|jUu8BU2%43MiZU(_=p#;S*4LLwVa)Io;CvM$GhKov{^ zf>Y81B#@MTiU~1J;_@Dn&b_XkTw7i5``1@^>BZOa+0XtgUVHVkxPSc+s0p)wO~yVLfJ2@9u-aPze7Kkk;_bzLQKS>Y4#`}Mc} z7d(Bsptx$RYgH>&XjU^19ECTG!dWX|Z*8bB8aA#m^5>a^ zR8B~+c1tO^xw*lzYB{_r87E(S@g)JlK?JXif`AnOAw>ekI9OUhqA;<)w+9;=1Hc{A zqD1o+-+o|Q43>BxWLJ|}as*V|+}z;N<9G4)+i&CX<9D&&@7223`=F!~yL=Ojdkj_U z%9;K(iIx0#uX!qoBaY6C#U7L6CCW2M-4-jG zk~Sa=^P|ae>Y3=$CZr0pKaGD^A-{V5VF~~G+yyr|As8qn_{4kyfC<1DG9p0UuM-6@ z7W?k|3IPoqY|lDiZ$Jd@osQo+ZaU0QYu*8K136>@RNMFc-t$&#M|Bf`TVI^gtqRS# z-#pON+VgozwzbAt=hVl#RvV`#F2|ZLt7_#-NH81y8fJu}F#xD#2+jBP5MmL*O+P=Qa1N~g>wBF9!_8%bIr?P}x z__NvkyhyhTbCoa$2mHKM7|bAT!xRR#R?e;=vh`r@|Kr(mZVYzaWij?%XLfcKI|E3{ zTMi&>OHJybP_hnj8vg0&x%o^i-~HUND*@2Dy}%SDG1cYeB`z8$U<0_in1PYIPCHC<|90P_7sQP8ys%; zIPS&eH6LUl6w=tvqX4J`0j9M`=3WCuQCC3_6f8-CA}Qm}viLD#N&o{x^`LJ1^W!eR zMjAErvlfJI`<2G`p1NE1cDyVnH)EW9e|R%AYvafp3=|Ftu)O4a?(*$+z6I#n<`o3Y zGByrq*^fm-rCqM#l5FQ<&^Tp|kjbM}7I_l4=~~Iv4JO1WK$clzmCe=bM0j-L3K5uR z;PR4i|NaG@d-wp?_wHeyXR*>yMXnVEMPgtHxVT72=^A`}4X%v!xZvj5Gu-a?Adpx< zFLt=Nzr)qNOU#!uLLih(;+;?#$72Mg2sHN;Qq7yvix@F>jk_H_m8FzX);Qy;nVvy} zG)a5~B}o`I&k^$+B~xo4n0=5`a5A@8>4U~&%`*aBiDD~O%yYyv&xmmbA%bfZ;ccxr z9xC?x70*6e@Zpc2;@Pts0EDaSE8Kr@4-fA>hs%pADR;us_ZTClG$E!*a{(09oXYYM zk_1FbQUf`~mh4E@g~U{rT)`Z0d3lYOUw#8`zWMWbeiM8p3ws!AEdo~CSZC%R2TXK43D2q=hA+STvSe)6SiBVhpxiXsZTtJM?- z!XSnIcbwd?F;e5%CKOb^j&z2%LdXCZq2NOMLZE?Ho&~@5oxVr1;0{DyCvtXZ<2*_DH|bxO?$BLcYO zTY)MQ2|?qJ-RJ6l=B=V8tOID)bfZ0+TjS<)tD|8`C?b-wPJRynT~SU_yB>iwM*AvBA)m0+sFn&|C#UIEA+u+6ju=6$tzp$P*IYxiuPHOs8uiA3YR-^y(L zod#4*-eY~f&xby6($|wdx&CbLYkh3(N}CMxmT*eS)7INr;zro$bpo;1=IPK}f886%ys>E9Bc_m2OS>Oy)pN4lN1a*{ zLSf_f^R#gfr*X~sHSK|FS9-Xx2MUNT@fm>Ad>NbT0@O z47HF3|7Ldgp9ShVe-(^0B>@UanP;sT%X$Fq8OstI^II1YR%$JcQN$p^HBkgO!8A_H zjI8BY7z=K1Zjfuhx@H`f74y79P?yma&u}~*@a*;j+}_?`IqY#f790+e$f#-@uuOo& zfUZH}TmwO~O^fg)0$At#fe45}lIW1Q)e^IXrjOJ@U(+4{pSwPWrtSBi_G<68_O|=W z|2@jYfB{={@Hu>kGxxVs^R5n^c}`zoJbLl^W)b%`Ad0 z@rn>6yEmhN0wX38t7@M)^=~GbvMPPR^W4cJVm=oqXfnq>Oa#-ahW11q?DArjM>ioY>DT|~5 zz)}*X}lt`6QKrM`QsW==M`*FPZf^<>w-x()6_>kPje!U92ucx)8-Z|jc@M9={2D&@Ge3*hU;7O1-~SW> zO{iHkhAHll;tqi(5XCOwz!-5CQpQES*`&ig-JQk`lh$_=CK#P}j87_7=|E!uV0x%p zmhr3^#=o%vzW{J^bJH^6kHE2jUG8%){FrtW=w}GI;h9)vho8{MmC4~M_H){RgV2j3 zbz!X^%#H7<0CLWvXLDmhITLC2HRFD9uGrAMW(R=t5SjT78!VtAgNCL^*YHbBo819^nTX^LsoVv~&|dG|o-4YMc># z?dN$At3sF)__kW@fqiq2g=S&;%usu&x_8+Dgcrwz7#Ltn{8*4n z!dw!jH6bkr#A8ATQprH-iO4^qrPTnoxF@1!ycIyLmcK!0F16RJuNul0-5S#S3IkLt z3b_y^BB@JS3IcRqLu$#g01eCWb7E_Z{klREwze+&){jAGuYDZkGK*U%M34D(!Z#pg zRGbAua&Ux}9IT?ilE6w|JdZH|()X6tQ3i|k_uM`Xt?$Zr-MTw>wf(H$2j#8JYRGV7 zqYmB&@MH9~bHLRZwl{boggVuSer-YSMp@Q7ZKZ)!nWc&1y4$)cz1nxW5=h6TlSv>1 zhzFdvNO#Ieo8)NGyPzP-k`wXR#<|2z6e5^ve?O5+HmY%}o;RpGBOcOsc&u0~wf97kYQM3ZkGy%l@EKa3whD`3m;LP5$k+#Oi173!^mSuAgt;P3YKgOK z%e7W4%c2RXpfM~3b(Jibbu~>@Xq9!i#R@>~Ed^W`0EGP^Nlwy#@@u^+JS1G}Hw z&)exEzcXnWTb6O8q>P$IT6v`zGr$UZ&2lVrR5bb3s)^L1mj2mcN(ob%k)|W&B_kIg zX8}y5@{lZTP-rycpSYbaIU}x1bE^(fgpe2sX$qL;h>KkkjeJfhYr)C|H7__GZg6|M zN3I3a6fxf>+xcJnd36a2v&1z=AS6i|VhO_Rs!A&pCPlkmK_zRfM@G)2W%UFk zGxU^Z%=1ow@5PLHo)A+|1(XVMcKAe+1a(>kh}1cQRLBquj0tqI$5^dYl^G>7)`hVg z7{>#UmxRFA*iEyzi60ps<$}ZQGwkLA(nOdhLQF}sZOh^eVUnbGoFHyEBr)NTe#;yr z<&6SO1awH9-%o$~Wqj^uejcCw%;)f_2cJejLe320gei#SH#N(37t+ni$__SJfBirf z25G{8-y|KBjEe|u6LyB%-J<%TzTI%fe4%_%Ex*p~`K>eH_e)>;2Ur&sSColVcM6Yy z!7_|{0iV&bD(YjT8?7toMuE)^J-gqYwPN!D#$tlHMZ07Q)-w|j+&hL#*S<;y0wP#y zm_B><438c^Zo=HlFTH}x%PT~P^=DZX3~~Uc)YgyC_uK(^hmbiO&SRns6Qr1{T7Fk7 ztAs{yl`QZ#H@A4_ok#fYcfW`CfAl_<z*e;~Ve0IU5* zKj*$}OC-{SLnq9c8|%Q^L+1^n6>Ho>_L(132!xy~o<4nwzx4}W#=rYlqb2ya-ueRm z=-Yp#<;}9Tp=%jZQ?{>ZcX;XfVoHl<(H`jO{@(PheMtT&JAc^m9qXmvHoA%e5|^G* z=Ut3|iVQYuhh^+nKv>nvxYkt!d38f0%dm`oKr#YSB*Yp(F@nMbPy)2BIdK9ZAy7gH zx5#BdWwEj|S-n>4I-}%@g4zHIiv;YlM%!6Q4IDOLDuY1Ptjf%cN(^F&1T0hqm^v>H zQcyFvpu<^fJ!!SCW435+{MIarRjt^jzzZjP03Gbq9@?gFMhyz~sKS)70}phJNve ztkEt*>W{J}Vb%K_@)d=z%T3b+sBL%p+@1T}e)rx@0qP=ea*Uf>uOMz`r2zt?4vn%~ zTdN-j#Nd}dHSl|G4-x}ungsZ!2uvv=O{rzEG;MfMbWuxfmN!C`xZ7r(wc5N{4%n*N zN6v^bW61)bk4r|32~0s_;cl_63vSm1Srb_?qq#KO+BP>G15C-llcPl-Acd$D2pH>p z1zr4A<6O+;r4vKi2*clym8;X!~THVXE%6y`vlK!KEjhHE7k&BUIJGsAkK{GGGg8Zq!2-b zp){B$m1R+9QkVV;5w0NucZJopwpb0RPaKhug4Ib*8dskrjy6gBZ<|+*$;!2YGmx3E z=7e-yFa>e*Z3&d@01c1~-3Z!8ssCHoh+0G$aR2H8S3Ab>xZw77kHdbC!_5(CinzEW z>@Hk9^pue184n)JxVpLrE+o952>;+VKHa-4he$4BX$v9Yxrfi=jn_YeH(viNKK1a^ z2w_4g03jiTos0X8x*^G=Wi%5AsIBSKYa?cucGe%hPB0inW+zJ1=%(4*c7T|9wH`j ze^w5&?rudi(na4cEN2T&oS>#SR)k&>CXjQ+M<0FEvqDzj<(FTD?e>jT!zOVCJ z9p(MP(?xQZFl>pe1|DhmF#vr|>Vwk;Lg@GCYcsfcBg>WsZgsD>0BN9!`$=@VfktOD zYV~R*DcG~K?$F=-+ArY`{`6mfOKvfBmdqrj)N7MEVbF`ggGFM~*G>XDnQq?P+we=5 zrKEMG&$;DtGGDf|f|Tk@0L=Z2DFC@xzC5uiNwNlg2jRHvQELXFz-DdOqq?z(A|ePW z03|R|ESQpbA=Jr2fVjyxrHY4$SXrc>mN2%1IX4#P$tBsGB_Bmf;*}Gk))3Y#&!kps zZtqq41aAFc4#S>mmKPJy4QS|^9wy4N7gM*I+TR}d7~qMTkg%}JUTyao*loNR+W!qN zck6r`XKXE)YiiT0>0TWG&KY5^?-GS*LUt7|I&-kp7(KASVy zz#l2GDp#i@aQO-JJQdNvD>r0TnzftyniwZ=DEENttOS-ji4%6_gDAf}0|n%gku;C^CI@e4fOeQw zVb07d;41*BRbqE@S+TB+aC6Yq{2D6&32w=X{A}B?mcOH**1gcyZJX2(#PUl7jY}el z`BfomAPlRUk1&&)xB$6-n+u?LNY-w zYeqgAP+eQ?NIzD|t_)xmi--YOHIOz1I#ZFjW--?@xE3%=t;=<>Y`wrV2h=K)8z>;9NlHjv zP6!H6OJU?SYtj{qfz29H!N{w`3a60p@WJ!=>>F?5vv0hKPd)rJVwk~&5D+oN87a<) zVFDq7I5a*YYiks$ytTK_g98@2u;twM8$&;D+l95g@tOWX2QRF`od|Mb;WW$dx@6>1 z@YW{b6##tY%l`w4(oqh&3aicA4>`Zt-R85zFD@C2NYQq?*&$}6wp>gr0ocPeAaS!fHWF^n`J zmmZ3qank8}*kHE-m@{*W_gxmr%*|TIZol8-{r9BK?~gzD0PDI)=s^I)?O8(^EQXT( zJg7j`lo{vTanZo@NqPtBRwako6vU1K*SYzjEyLY@Hr&6l&M}%$Z1S@S?4E`x1uz>3 zzQN!A#V_OEZb0yFef^j5zyIMsM__g0S4PKRq$nlaNHfgdb-u!lS*5%-o~?q%|K0^O zG}@igfI+Q{0!E;4vj3znqAWMJr_y*R_m{}u?Y)HC+lY1Dqm%_!rbOCvdxZf;P+1|m ze+fit`K8$Y#Sn!LTCA%I<;*=KiqMY5VH*Uf92H6PG9*kXA*NYs2y4}WP?ay#J|+U1 z_g|$7B1w=HS}jf`j_dDxf(+Ih~ z(djxGx5pg`gmC&Co0ehoUGI}?bEp|8G;2KJ%)U4evV>RIGXo$qFz!H*Jzm>;&(D$H zZ~Yv#wSK;T=laQ2j1BE*>k}_OT3)*-1Y{K9&iKkWzswNtqif| zR$$F}s3%Tjoe&FjR50cN6UkN;cRIQ`5f!mdCvHna5FGm(UrK55qQ4n1Vs8R1==$$i$nn}pU|H{II* zuDps0rAi;W@imiA?Vas=7f%4nt^p|r5H%0f`=Dm%-V1A zL^Im!Lu=0X@WT()N-pKYUVY_NTwmP-R6&)Cff85>M*vY{=3IZy2&Y?jE$f(gUP#>U zvMg%(72)M@*yG*z-op>y`5}JvqYrRgmR9DdYqBktpOwBF0l3W*?zp=31w2}d`rNv4 zu(}1`*`6PGdj$X*mhh?IY-_560)I~+b0?FAyT>xC@FaEAZ*HF9Z~wxt;Ki3-!k_)g zKWfkax8M2|{N5k^h0<~-byJ3OjE)%&6p-px=wLINC`mf?zdHyX-u%BgB7BXE+~zu za_IcxR4~%_8=umFR}~5x&(MA|Icr?wUEI7yNCgdw%5zvsS#49ezIFFxv_0fl47^9DAB&OAqC~56 z1C&xdPQbQx;pVEf;Q_v8MsK*^WC6FPxpu{7Yu;y==2KqQ_!k^lG#T0PTRS(*Q>K@+ z>ho<1!)i$vEeYKAotw)8bAQ&fD~z6P%n+kx%aX31Mby`kf3`hmGKGE;b?h~`v4+rp zH=wTIOt46oEQZ9v%pY_9NnEsG^XfkBi_4U8i3pmIM%-V_kK8iw0>a?dwIFApEZUd? zsQ_W@E#oLlVg+-dZ8E26W$bUA^cXY)bs%B7QEOCbtOiX{i5Rpz(u$nL+9$EW(%*n?zLm+%vmCf;(ao`EM4dJIZd ziytzVc~cSEM)l@;%`oodhyD-acfOxy^f3+cognzkfXu4t)^0oCO?D}SmNlAK{$&E< zT#>-y;!Z%}jAOn9FDo)9M2g_bI35d@^%kY9Dny|JYrEXRAA*$6nr6Z@6XqRZcR@%y z22l}Z4>1Bs!n8O=OuH*Q{M41iAjgUn3A-s`o+p&3acMDX9pL~*LS7ilvcq~{9Ciy1 z(~6W9tVYkO^Jo2Ybc4p@2L-?nt}pQLQ}=Ow{|eJ3AxxnWRpLA=xJqKWqDfX-?Y;`I zCbTMr5fD%%_l%U4NfSbd5{u78;+=EGx@s2Yl7Je(IcoiHu}ELW8M~Q5p&(8`npk3h zV?vBGQW6154x(<&lRA^a+`>c<%ZX&1-lYp%K6ei*M07{%{m(DF}f7!zSq^ko46Clj`yXLHlgMx3KaeMyi zSN=yVOV$Hz9Euza!bpkwIC_of5pbGt2#lcC12y^SUEhosbU;74G@#);^19;5lPAj9gdnfH@*1wMuO-{M#x+C#A=&n77s$`ME}C$O z;eG@4Tg`scfZshxn8<1EjH2x*?B8WE^}x@6-{_|jBC8-k6oeO+iksUT@VoEg*S`Mu z@n?VfzqRLo=bK-`@BhhPDhQU(LKA#9Zfi!2GvITe^M(*x>p*|53$;z;_QGqUhkQ>M z^MrW%49XNh^B;@=*aR*KJK+X^Qw-P#V1Hm7^NLcsMO8Ob1BmtpqJT(}Wna8QDnevT zl~H*@L6XeVHKUY_Qdf29U)4ho8=9!wa}WjQJntlfe~gl>Fic2c0w}73gMz8Xq@3## zEL@JYE~#W#ZQgu1z2fF?%egD7R6{u&M)GT-HmeqmT;6~&`m?8Nh8q|qsCP?qbKWSg z+-KhHb36ZI`)~w<;rD0l>}MlFcFov^^el?GO~>H7`}tM2OrHV;KmCV~QoBlKS)iHN zZGKy~$o&igN~R!jyRibiN<1V;4wPw%;_?^+LWsyQtEuNj8pCx z9>$4Vv}l$3{@eD^1LZBoAj06%Ozs&b9h)(K?_PaI3tdBhjtEG(_I3k6K{8zCQbANu zNHfT;1#3Qlk+ptd&q&P*CJl(k2wYtO_pcK!FB0a7Fek!p3P_U>$}IchN*@ptVM;q( zU0&k)`Vw=}_*rJ;yy9j#V#!vjC^x2+5@DVbcDo7lE@>TM>hs;tr?Yd#sz8{gfXj;+ z_wMcR;JFLTR}mC}Tq_R810maQEDL+j}b}0BKz+0 z@*1za^g2HC`seWC^RHqzT>~|OI3lGTrnEzhGbGczE*7>}u`U9cv*IUNgtmh3xyfMO z2+k*;8N=RgF3X!xTJ6|c8Q=K&DfoTsYyUG22X5L`HqEuU*jR53&=_CVG1{?UpmfyD&q5wNyWWH5p0^!zYE#QMnY^K%x%AIxEDUw14Vq z)-6Y4Mo&?~T7n^QhrYeN!Q;mjU;d5X!Jq#hzt?X4?YF*&-}~c#-m;<>E9;R690DR@ zQ&O|z%?-DH;??gLQgk8T{^X&tjc`Q%)6P$}3WL$3ARt6WasXqXq$b^zcw1J!Sx^rd zs7sSI+V1OYP4-0yTJml}OhBrHQX&dRFs~>aQA$QGaxUbOkjsivLMtQW=UikV$z2gs z#55(u6x%r=8T%86CN%fZ;jEWZ)k@KDA=j4s;zYnV7h2y>asZS8pXu3k z4*pDT7TnD~9Nx8|w*afns0Y-9w$6-}ro^=Nwre%?4(eHTD!82}+aP<@Xx^2js_5N3 z+qy>7j98@caFvTLZXXV1Mz*b|P^XUv!Ax3xqL!vOvbF3JR&7i3wRP#TKyTx3?PmZQ zI2Ka!&`$eFx~Ccji)Vqowb5k=9lFnaZiEB0M)xV8+RjZIm-{T;h3QOis?dL$P{<6! ziJ^&1Do}Cj!L9($;G-SLZ;ONmAwqwOkblScsPsE~YD_on@Dm_G_)k*)rKe zEK4AiYL4wy7d3$bgR*SW>Vs^7P6T7VRW=3(Zpi^cttTM(C%K4J!%1gcmC+ft#Q`&; zX{IVhph)h1qaQcrgKUPuRr!R=q47;G7qvbyng!V_DC`~fy8+*zii;38AYSk1(4R4o z&AJv$)@uqYvULDaG@qf9Wqc%{%_|^o%V`GYHJ}v95L~%pm5^10)cZNjz{Le{ahVW8 z1&{&Ch_PatqHatP2qKB_6(X?PMNRM|Yf?(}tjJhUS+(s|2EhnmCWIJ}rhqg_oNh|} zz+|Jf=cE24*6)RO1-OK3n0MdQUL{g*n! zU;LOEs>8DfDX94 zxWo%DyolFd`wU)q;brX7rML%hK#Ds|@e)(mA#j4kxp|^>;t{%Laa=>4X$~|$+0t7P zU;|Dz*EycR*wp!5R+L)t_22k~lY77R8~+oI%L-P|$*A3}ukAatF!Hc>b=v$}VF1~f zK#Ti@C^)JEK;+h(2n5(X-@h9Ua0dX)4ZFqe5k{+TyRQqD=dE(>W`ITU8Pv<;*|TSO z=bd*nl&0eK*WbXs>ub@g)QarZ0ztwe1fbp_G`BuM!B=0K>zW%VdUkV*x8Hsn-~I0Q z@!osyVOjPn_(B8|WEGgYt4$x9jhUp>2Ekxl?~5JW)SvZMr6x>s|9%k8aL2m7I_V1l2Ykn$`iIOwwV1L1YL?(zl*fb`Kn7dOBe>eQTiOiDKZ~zq@Ga zwx%3U*T7vFbLioqy?KqiQMib~xQECM^jkFh%;kH=PJ zt2<1Hal&r5!=8-GE$y&#HPR5 zI@`4AvEDR-`Ae9XFd?oQvcGX7I(Kd7)(&w4fa4+CLGVv=8NfDqfLJZTp4fEyj0viw zJRlI7+wCA+Yd>9%0WhOkT2ty}vzjnqKo@|vQB+0>GBAOHvr@QV9#1(EnH zmMYeZm52jJ#bB%v-#F5mw>)ln^52w>gfb_H@RHYm0Xn* z=lb$rfAx29*snvpF1L4bdnapFZ_yt2F>teJ^~0$NXbrH);Wl`>U_5ApJERTN+Q^#g z*5=?IaDWFE>@2=E>J5Olj*uhaRu~XXIH3}^y1S1a{ZM0qf!AJr6%QXg00pVxIbnzfz+&$ynN^XKv8-zORVin`Kj6_jkMZyS{de)`(IYI&ij;yT_AwA)XX5rO zkk6_IgnG7aW0ZY=h)5Gdj;n>-J=lO?N5X#p$GpSO-Bv(7>C2hVKTa9sJJf452JuuX z1^dGu@4f#%KL3@s@YnzJPulIj`L!?L5B~HoQECC1=N2HAU;q?jkKb#8oe4UP5uCxr zCOD1b8t%|@)2=RP^C0Mw9 zNh2)LU~J&Gtq-Utn&yX*(n%f2oe11;U}(E$u;C+38R4?e4imfqs@SY!8h`dREpyIw zbQ5jAw@kMkFj-yU(CR7jpt~MlI9@?{kFWX4)hT5_U`sGYXo4fTes!zXINqjMpf31} z4B&es5b4~0_G2HEZs`4hf}e91G}wI`W@Tr>IazvpG0Z)=D?8kmZF`gb?`Y(OXxodQ z?Db{cv^LNHqqH4b%xFMQ8fvt$3e=yda2#Y@7prSL*qwLwlimF?yp2L65KslE7UN}2 zDKoxLClP=e--dAuA`4_Ol;>O#l`mFZ>(zO_X`SI3Feqm{?(;Fh{=BiiNut)ROmUVg zY!I4jl=?m5VK83jRUu>B*1I$%(cZPMG$z8_M1 z5OV-(UO@qfJOMy+k@oL5I^Ibh8Z`Iv?QAZ z1haGw!l}L|N=EXOCV-@L1~jol)Bc8lDNIPjTEZ(J&A?$USXZs1t4vd@DI)OFS^-+X zs%1Pb2dOI>6Xto=49=2hN(Nt1xFQ6}+Z4mb@a}MueoX?v=&jt#yzY5LXq=?u=sbS%5&tB0#FjJgvC^ zLBL}rpp>e~uSDxt3rlPC$)DHLB2YQO{)bZ2q3t0e$jP}Yj$alvxTSeK0T zxZrp=0t{STT;tvgpT>)yeid)L_Bp)x!YkON`{0s5oDjo|lr9j%4uK|FII5v11?NUI zJ0LqDwm+R=>ZxF3 z;MWOro|eW)^ncBxWh)-1HF{)_kT-Ix8w1xw~u!VA#SIzjR|Y_;rC zj!G@RMY3{>(vESs-Q&^Y$N2vDzmIp{eGkXuQ4&MOXtUqIjEUic;OLe_zqenWURywF zI_^P8f)n&;^E<}V;4V;W^Ma;CIe(ueRcm^Rw#Hq&vzyb+$l4DPNIGB+LA<{X%Mm~N z-~)XA*S>+j{S0gnu|}wM5^t!IH4$P_FQuySr>B6%T$Z6gFSIPv0)WAmS_qPykKLf1 zmCQa9e-z_G6XB9KB;xj*sJYpVUevZ3(-ox|`fW zIHf%#zMdVg?AFk}XZ&L(OW5yG=f$$*drz;{F9Yg29=lG~wk2%?^(1GFF8yq>(0s4p z>2b!R#qPwT%AI4rAKn;XpQUMzl?JO~dP z8dbSxyZJl=%$!k6)*6TA+7uCqF{Oz4B4OHHV7{2JTN2hIV_mZ*N)u~v%@r%JU@j;b zSdmd7*2&x3&}ty=c024YB(vsjH{pUW0G?#sBZE1MaFJK6MPn+F5JJQ}5mK5|5wN22 ziVFKzyLPb~|u4;dT` z3QCd%QyEyJBwZ-AqO28MB#U%j8PLQmR*zeREVKknjEa~Dr34UFOtaJ+4v_#V$ZN%M zS#dlpINTm_dvn14<^bY|>4p2afBhm}dHHAY!l&QBZn^?WLSU)$JEcp+I3a}8gfN&! zP>LA0L%}n)@v!!X4dc9~$-tNi8T}i_UUkj-38Z!hk$TCLio8ml-&`avdJBGk<%|Cv z4u>-2Sr9o)1r2j$ZVcR=rq*9rU%J2&++S^EP7pB-w7KF|ZPP$7VNCL3Z=!*Q-3`$0 zx65Mgyuf#t6~Ow>XTBTy4&y(vKA$~%h9Ca$ZP>iN{@Uw!aQ{J9z|{iq+S*7lX%dg# zrj_8zS!#)AJG>aUy}iZbcizSKzV|(KdtNjdkbn;9WA(EDi|b?+&MM4`YinaO_Kkqd zP2lNPr>&6GXtJS`cqm~I(zYOY3n09(H?*SwS8vsO+`E0&*X>-nXGqUwZepmNn-P_z z)YXrE^dtPeUwsSz_dn~F;D7L&zlz`glfM80WKJ|W7DcsN#CQUw?y~s!u@6+_&I8U{ zq*`}}Ari)&)#V09Z@ojT-`oV>7)4-|02x9cNp^?8pu$?hgqy5I`o04s&qVcO&^fA_ z^sq_>P*GyX2topLK#2iK!*jSj<1)w&6N{GUrYRXYKtS&#e>b$R)NsEWu&K;Ik<~Ap zucDPtqK&+z^s?I5M#r91O+jaH`$(kj79vvHxU3ACkw}GPa@M1k;L6r9w>IVM@Xw>| z1KCfZ$Cc`LK3Qo?_yn{$^y?&q0Ji)NO^6e^8xL+k+>HSWSR{k71DiYw_S7G0bKCj@ zv_yg9LwD^QoeP+vna(6mbKq>VS=fa9b1k3YXRRH##!Z>h)|75aQeY?Xs7jxWb$U2o zv_*3-A22y$D=t_oL1cKcp89`v=)_PSbyd_K}X zW>etU`Dj-8Fx=}11~?gH9D^sB%5TI-L?p2vmIc~ew$v@gHgb#+(^R_)sf)rt&-H?kdL_C-(p>hw5is`Ay2}8 z#AOy?5Dh}zmVh6(iMQ7|@av5@*3`fg^%v9peOx_Z-+p_KbLA6^b@ zW7HskV)q1&vA-{+5h%{n3<^;#l3DA@0wH7&RbWwXfSzYyU z3~p;Ng$VGBc}kd*fY!^49l)Zb$ZN&2EI1x24u>OXsmMi31r?yKj9OQ$I?xy)*5Xl^4{SvE~JNU2#}e&EA_ZPZKUK3g&4>UI^}Oepa1|M07*naRCFi^F#{oDVkz^LC<-_v0#|e0A_Of9R9Dqua+S=WrJ@v} zCr=3x7QavxoHJ_HQb&uHDB+;xkZf6*pk_iw)^!n4bCkH(WtHKCin=n&l97)Y$HNi( zXGbiDg8NtZ@#*JY!|N}94lh0b1}@Tla3+A&?Kxf|#+}40qx;yCQ@uO(>;z#45`PMQ z(AVG=LJoI15G;(@c!CI|RqMwtQs1~TzWI%@+|jT8%72gj;V67{)WLT_mCb_74Hz4g z0J<#G!G*!sJ5N425O}1Rx!g4cXS>}USlq4245NCdLrcH~I3V4rNWe+bjCO-Q;~Bu{ zil<5i9kV1=D!9Gf00K%bc_F!%GpLlx(9kofK@dpv&U5x)D~@8jKfA7j72)lx?~nwHGUgzp~v8;D@#$4^8{HX&gYV$O-6qg8V} z*qh)$qs7SZZwJ!n!JP@&fkxr0gJ14_>WItDu(jcZqdqSAEHrZYRZALc6Jf~<7yS6c z5Acg${u=(}pMSgc@weal68`xA{OhjF$o480E)aTRrIB#GJ12@1?L|8V$%DB~Gb(VK zun0%fEk7aR&EGEcU?{sGv9c6X+jmXjVJnI!@O&X&cQ9@jaKIkCu3FMaJbj9R-zteA zQKkNFkYeuw{6YY6)Z8K_TszN@4c$bzm4k^{<*EWOYYqsrWazyn*qa^4%7r!1p~@nn z*uaFjSZ@g4Xd(ix3q@m`>=)wBuZGZ(9!THU9D*&K244C)wc#_s9sr*L4O7;09(jcC*xqTBO8*dff;S9g##X zlMhPHc>3%q%I%@K1OY&15mK@dDKK&_I4pat%Ze(YUjVcZ+O8x(pq5E8)Y!B@Uc1-E z;da?w8}^gH?_HXgPrC1?{Tt|G?z7rsOIkv#wyOKBR`bu=G-1L7SHfn2g9iX@St#du z!ZatX7Z?#^QXr&?k{l7^5kyA-73{Smh}vYxK4CR|@vOw$aMh`egNGBIK##2|^^N;Ia7&O>cZOetYu21=mH zK+cR*08a8S1qn+a5GYs(0wGe8c*PLJqOXfZT(Cu=Bz3u~sK`b4dP@jYq^$}t>+fw1 zX#_Dz+%G7Cw6q5*qvnEq%<9g>-~!|oSeA<8KBHvd`syLxeDmk=H~zD~i8nv{bGUc) zoC;oq7*XoBlo_#31{nJ5N?!3 z*MY|8gw<|K8$ducP}KL<7?RQt8}IgbDo{Yyp&mZEYn(Dg+6jR)>}0_QAAEqn`-NY} zzy8iYY3+RDzxg}>;19q39pq~3juBbh+CkA}7v`Q&N5|0CpF98hdX>LTC_ZOt>7w2l zFl~I0Mm|BhVF+h{1&Pp(07R0cUd`2=x&Y3z@hyp|mB1C@{bd!ItjpV8V0R_aLQ#CL z?#`-Et1j-w3=RaK^8(?u(9jy)J*b6rUpI?x#l6;r=tcBB&>VBQmTWdmM&no5gGv%@{Zvk7MTY0>v5-^b&bV(pB)chj%_K;Lqf%xbu2 zq%F06sX)g-4QTGq`tp-L1PiaJwXLyXkH9@jBT(#gp_b!jJfBHI-AYk@-1pht%84;4 zmJUTO2LOY5=QN?nw-IdpoN3=#jk_g%U&i3&@JcZIw9YTP;5mHxJ&ZQ9diwy#_=8t|$NsBu>v_UKv1) z1pyT)C9FxTjv*A}yx<5ztp&?bVo;BVD%NDGm}V`n5daFYyKk3_!Wqj_kV`>0E|`vz zY-+b2#Ur5>sjpbXf^@rQ-0o#u66<@5-L4?;r0%eqnH-D|wFdDd>!w!cGGp=dNjxNC z&=_md--Eb$1rnAYA|WP13X-R@sJ4tKVBTHe-u+8lU0q?fld=}3d9SFgR`9wkc(&i; zW`B#rascuQt}Mb$s6gaii6^KPz(8bMG?E2c3}u9}R4lxL78w(9z;Y-!JX^3HDz0}A z@Y&D&4F2Zd_|Ng5eC|KR!~35CAwjY|i|ez*{3e0g>=vgiP>f}d^q&facPgov+D7OW zT%p&AbYO?)2DJ4*J9sqhY}SNV>$08&zrX&~-^F2n1W`Z?CX|qDN_8=;th^Fcz^^Lw z+FpQX<6U((XH{lB_uO-cQF#7ZBp!xHvg#5@V}A>(CMF{Q`~5B6dFK(n z_q`wB@#DwX@As&+suH#~YXP-Hi3%ii{%u>>JhgFH)>9j|2lwcQdptwVkp>vXeNHg) z)(Nl37_fs*%m5JC39z;vHhmp0Q`U501=y|$`%I`N%?ZPAf*K@j<9IyagAZ2xozH&- z|K_j%>F}m+eeDbQ!*72_tZJ)(Fak+flv?yf2I|1W1mP0}fXx@0Sl$H40WkQ5zY(UY zE2BtuP10oCuXhZL}wwYA9*UIOp(CX6B z2~7<2y9~KPhtL2(r>mPo7WYeGnkGq*iv!m-1Guo)+F zp+N0%s~bS&t!G_n+U3L`!pi9St8JTQdFW~b0^`{f+}QhgX*di5+dOT~QllC9WKW|4 zvnBEJ3E|q@j4`buQ|WxNDsff8F()&q)9M8B+q%nzJrSi=VPYH{!~d7m2kMw-}7I33Xr9DhYyE7mms=Cv{&t z5dqPz7i0>c8bDPUTqNVSFxVhVIQ;{r@<7(?h7v~Qx5l>v-e*9u-4kcxi_mDpNdzRdG9&<>~XF2TcbXV`XOtawg+57 z@l=!8q5Xch0qiDF5NY-~4Jb`H!DkP4Rje>(Ktu>3U>E|HWkCq)avY7Iqtayi+d=C0 z>Kutin#$MKuav4s&*B+Fj93-`rnhFXYA(xyc}m#rGL~7M9|pqcC2o1M*}xAY0AMj! z>E#l$wih+Y$heuXxtig;XuWfma$qR|OB5I7%Ge?}dtm@6AukS5YrujuJRtNkCs5<6 zeUJoW&I7>{0?AJ|cnq7Man}w*Ai2+pi*?9qDJ5VWq<-))5W+z4!NL=y44BJM*Eo+c z4Ty0-%264Wl-fukYf>y-dp3c`6@n~;HdjDE0B46dGqSmh#)Nq{W4=n*hGRT`_8z|f z`+g9gdjETI=hj`YDW-hD;5P_r`L%ah;;p^S3?p0 z5;_36RgktNKq_oig#aRyawct?O%5@Dg=S{`uEPNt5Y_{%|!rb zBIK0t>eVa!^4bRaS=udeVnAN&pe>tFs?eDF8l z#P#(x0I0iIQh`W#gvB^lAyMg`3ASyC7H56zJrjDto(sJ~a}OE@zP6m%m09v}SWIWf zBgsOSRv?0^BEx{W679Y9>DIsmNNAF=@2L0T4t6N6nU-W!<{GA9MUQRO7z z(^)GKkb@@8(!`a{BY@yM7m!fK>73*i$+F)}IJHh02)4CwT1rXEAXUpU*c5rq9HL;A z)x0-<>pFGM*|{>1(#VPh{Ai*_d(m29C&F_}DFNr-kmPNsv|_c_dKv(A zwKm0%oXygQZZ9`@g;B?lSwlAJb9;)phQ34ji(nisU>rJ!RA`%eASwN-wV_Qm10;^S z_q;-8P`3TlxEgoZg*7J+7wepEEo3!LGRgOjp&pZfDC~9K3!l{ATPV>gd>SL02q4WI zHKd5hiPBS7GB@p*EZ3T=_l%f2k40Ru_POqruHcU%0G#oC$+tCc+hL_tWU z!A5ujN+Ju(3f-=UZI%pZVl74@FKw3z%9`z0+*+Mx<;_klj#*ryE$@j#fTb`O&}Z6E zAg7FKZr^uUmn2YqDr6668I!i(D+1%HFld7H4a%NMy!YO2^LOA2$ozUDq?@z}hc4S8 zqL+Y$d@c}6t`EA-4ZrVXWLMP#Ucbv3Vjb1;BQazUX8~1SwesY&h8qc>8U~~^i}lu{ zSndIIib-<7;DPM`9Bl?{kGAk$1ih5ZY9p6(wHy<(ByBPVVKr*!Iboh9kyKjrJz#jB z;atEtZZU2~fCxiKDzGkyIb*lWxVn;OhXEKj4Chlhn5^`{&IL2DOhB9?cGn4>WPXsH z)YgrFg$xp*Bn7iIxAEA&5JX5CoFw^jqemFLfLRZaPpW{?_?+wnm@}}XYg{jH5MKL| zaLj~0BN(g}QOQ~?LKLxNWcOZ@2jwDA084J4T9goxd6bG#2eM>XmeNCsx4@HN-FST z-N5DfMi6N>d1bi9bX#GR%0_JgCSdeTOX$qA0N|ML<*)pB*P}0g@qfkT)lR`>72Yfn zi-F$^v*QT9aVkcF@txQ?%utf}X}f;tndOxUW^-X*-yuC-Kk zkCaih*c2DmMqpSg1&b!PtPu*xagK`hDCdL^Kl)JWSEq#cnQ`ylJq$s-Kseg7q70Qh zh=i-l9lrkcuj4QN;xF)xZ+w8us~re(?i6z?qpfjM68GIIF53ArD_`Ajt+JC2tk)+A zck6k`DM@DhFo2n{Fe4_0^G*~h0I#8pD?YKLO`hjewt@WFM>dn;4?l<;<09iK*W$ze$FiWic?KD1Dl0q>s z18I>O_I5Tb$yF|3SCu0L<(GjK9%efW}T-pECqFhSJS;Du5{+g19i!!Vq>l!>6 z=xX=k`fA5sDGL2SfXJq#)h0IG%9@Evs2T?X|mGDN{oBx(w{EQ+W-!`^0U`xx0qzH;akOO4R3{i{rm>X>~37B;f1KZ#X`4@mN0Go|iFntg=M$0O_34#N7TB>>LL{lmZrS}x2X$(m>_WUzW^tpIR|=_fl|EDtH2^AW|1S7HY>7MH~wZdyGl zW2B2u%`PMqrY<#orS4Nf9D7By`TCt&hFj^*ds9{<~JNk%&!Z2KFt-Y zXBUO27kbh%Wmk!pF3cw?l&BRk>}r@u3q;v^QLV`-XQUW0s|)TDBfk9Q75M$q|Ax!U zD=hPZV&%&MsEYeo_h0QtD-8B@XT?BuFVv6thUY5N@CH6}2CGs{tchi3ck|@bMawj& z;2zikRk&Q!tj;>19d0e*oVYNd)=~*>cYuAS!eId+@_WvVd7kjCZ+w7dp1~<&nkF0_ z9U-TT94&jX0Ak7_biH|VfxrB#zr@$R_H|tEt|jK&*EKHIRhRW_s!gH9Q?4&A<7=;~ z6mDir_p;52eP1kpTwNNC-Xdpgw_DshJHs%J@)-kul+tbExIs`QWJ(FIUcV}3oKnsh z0!b-9tcB|K-1KY6<#X=l-u^DFG!~-Twh3w0u304PY?7{_30xU(-n_xz|3^QK|NI~R zpqs-l{KDt(&wuBSr0rUW`OQ>=gw-|Ube3tSGv^FFr)eM9#OWqmIk$gPMyW3ed_1k?zDXc1)|i3GaC6*sJ751?DO z(w5#MBB;_m8^%hJ*eQgalsrsH_Y2VMS5u-AN`qu0tbFCBvEFo5&3D6wJY!(X@T3B#AqmL*}{O}M_k z#=Mi*JJzx`AayV5X;Z|$Zv`YlZ7EQGw29Q$% zJFya4RD{&>4GK7CcQ=o-u{S**Q-_X4PgVZ>(KVH_BflO#@4lr}mgK`ZB}tT&NbaJ7#?&yOc` z*7o)OxAib91=0vnOZc+HnPrC0 z4scRBNn%lzad{8#2Otk{BVz~-n!v^Q?Jj3^Y=Ck;o@A@?E-ns{556%vO2KcZ+2qU~3gxIojeXfF$ZD8BR?FK(A zB-m&B8eM>zFtMA7V?8kafnsO|@hC3#X8HZnmwNE~D_{QKad~-#7-JEE2(}icneJ6i z%EC~~?d*?reaSdX+j>|SY6W*%ea;ZeqA3pLbD>{8h*gou$=T-W?$$DH0F6bL%ib%0 zuli8?+R(=$W2w+WH5-2g2UMObbXtWpVqn@$c=^$X_}aLE^A0D+ClY=T6F>y-f+j{3 zOX=H-OI%)FVxDJ-`5nB@v5Bm?{9Qingu(SZ8|bL6&}FRMe3$@%Vy#%uO?z2smF+m< z@uNq0_uY4K_wFg27r`ZHt#lV^a;RyV@QrVN1I)m(%(%L`E+FEjs}+##s(gx+KJ?$! z{YR(@3TZ?>ts-IXVo1&B_EQv|uV25$5B=~@;m`l<54-+-`ImnZzwz6DAl@O7!92+O z9ZRVsZWJqM_LaUzfJOx_-|1B?oOOK+te8>9g#Lp97gd3pP+c-j$n)O#tpiaKFc0cV zycBY!061n*yv=!%WQ_)-NZpQ&cA1<&ka%HJc0u-^B;3oO%#d)F4ASIV(Dp#e zX`AEbU#)#z#!|uyY|rnnd!>=`pCb?Q6#;3F8F%~6 zMuE`M>N4)tIM@BC^sJ}DYq^8>e$g?u1GJng+|G%GUAfZNb|2bXL~f(XXG`B&kX30& zQL%7KhpF#08GT{YkhNUoQ5%r#Z3Dbjan{aLO>DKl?~5lx0pyLMputAw;jw=m;;qtF zhOMz3^1AO1@s?K6(qgXm{MZ%54O!!dR9JUf`o^Z+LESHHFE&4mSk0g823LfCSM~@1 zU{Ev_yk-%0Vp$se24N8M-8?Ud(+<-#VK+@!V!|>lqT$vUPtq7=%N}YL+F+Z@+2V^U zXXzg~aF)7t>oQ2@f8SoMHm6>$fM5U}5dPalnjM_tn(kNzHk4j z_gn{l?KR?RtoL}c>iXis(Dt+F+(;8+grJ}Nlcw;P9( z?LvlEsSZ7@Gh2Y z-kwa5miwJck}S(N77<Zk1KYbTJ_yd0zpZ?VM;oj+eFg#LZc;^xP zh!8e#egshfvI?o1?8cacZg`jwyE-XoEyL|+H(dvGQhQf@+(5PxRZW(*ELhq#yZ`_o z07*naRI}9jjTvA1;*WLD{!jnIujAt48Zim*GT^`ld4%NGPr?Ir zR&3*k*~ZohQ8Jh!d}_PiOBploy_W6}R}e>%U@fTP(R+{G?iz33zAee2Y9CO>l8bd* zV{DuE8w2kcQ*ndq$J#0`_LYrtWess@*Mzf`MiXnAbHF%AK8Og>a&I@s7{?L84Un4O zBd)HlFi$fsE-p&4I;#&^iGB<8+C5Ui)>@FV=b8^2VYCXR>r2L5Z!?SDxY^**qepoE z{rB+Rd+#^NzH02Km1fB~W1c63VJH@}Z+%NF!7X@bk3j_^C~dCCDk7Q*g(jfovc7=2 z%r%0Xy{)wz*D*E&h4C9kiWzU-zQy1B;h(~PS%KhR`NB`*pa1S3YxsdCKl7mqUh0nB zSq}}(87MlqRtF}fj9t!V8wbn`lu`zIZn=B75op^5ZSN|_liK~bEjz$8K= ztBkAVyz-2g7I8y#9&m%sZBp8j%6l_N!;hq#QYP^R5#vC0f7TAbR@o^-%9`x3BsYS^ zZbAV}l?&`LOL8l867`vW+kI6hWq%#k7Xw8J);@Pgk)*{QIsx5+Nvto2Uu!~C%{@@~ z4WT9qvbJgUsL2eDYBqebT|g>pNg_)ItCg%tYScBT!km)C!re84FcGyROI=j^K3ig@ zZ0NVFU){^~>Xojd{Is(wZm&lBA7gPp-wV~^0 zbb61FvGu(2(<&d@wd+N-{ZYbOnt7fW_D+961prkteCG$Lb(jA;ULVr;gPxUYZ(s6#Aa&N&Q2#yE0`JIlIVm?2p_ z88z8k3y4jAY?zUj!7NG%b3ZQ%2%vaDIF)7WoH(O(`uw7$zbquoIR(NxZh~Y81vhZY z+Hzu%cN!-+c!zNuuo@~|0jbbN%PJIC0bY(Ye7F_1VGLXfPXju7*Vbe#~Fgv*Nw zFJHdFN8kJiZ(hB@Kpsz@yo1mFogcvWe)sp{?Cw1fJ6*eg5Vr7P19Bq>n(P` z1JDwmXBJ+KO;PEQ_1qZqtlDku`C7wF)q+|`LOFJa6#!1NjuH`$j*oHw-aXv8dq?&I z)kHSI2ZTXFPf|+w_~Vc9^}qQ#VvI;>r|qzz%?6JjJ;Har z{~n&5Kf~R-x3SrdBE)CQiVh$%5@&FdWPrC$PH_J08G`p1#}VK9=C^Qld0FObtqGF# z%gvsm?mHM?E9dGE@YB0hu&l}fTiY5NX7{#Z7X^lZ_{+-+{LnxAY5e(r?A@Wi{7XN9 z-~PQn5wC=#Zkkj#gj4USO8lyjRflvaW|;QxFZ0r_uZ?lde;c8wdC!_H0_ZCsl;_0@ zX|Ky9;0XkfM=29&)|%iw=19oAAiD)(;YpGR3$~^*@3|z!Qd*-JnaIIu#f$_N55yYBh$)aAeqmpdp0~9kn^gyf;7XWjuDRTxj;!1uJ{5)hqXL=Ly3YaO96Ljw6O3ZfszOB}T;EHR3X1nr6)N zf@zMW#xU#oBnQn*wuZH;0VGT2B%K!l#e|!iCs(qhns#V^0uK>yBb-zg*ccEuNwc`j zqw#RdptfF6r<<|Rc~%152w(P`Gv>*w-ZspqkrxUOXEwsEijZblY->sYtG_``i#c>I;0FZKVk@5gkcNk20&wX`_e{hVY5zp5kB|8ZGZJ_ zq8H>%sZ*H$0kGS(#g==(K$-Q|gi#G4 zu+MZ%X8Et6>L%AQ8=<)w(VhmjfE+?$N&v9kZt>v31H5?t9FHGA!qJf^I*KcrhMy1! zOI&br>lVmKlC_sFUy3CWZMg%PP-X_4FU-+O;-yB25b(<@#$9)GtDtbI%`APVT-LN* zHRl|THyb>-e;?0ZyukDGcX9vzJ)9gJgNU#!Qu@fltJRb=GyRBh7_c3-7{(F)YhS}h zAAgMH>Z-_}!mmV?eW;Q^-{AK|;d`@8V`**R|C zz6}PjEQ^E*c@JMKZduB-DL)L(*!aGpi7TXx;P6^=3=fyIoWi&ELT;1j6CI0?D`p5Xs|KZSDV8Q607-L#cp(8rLZ)h#tOJn7I%&5v?G;>Tk!j*+k>MYl_ zu?ZIWw*on5RtB3#z0p(@MvvMW&FjlN9fiMeMb`(emX0$Tpa+OMd!q<&j<8mkNu>cu zk}Ny(I_E_ppzRmQh#R@!fUMHaQR|7snq=6*bew}IlN65>Uc?M&2_(wGgEb&d6Rwh2 zr^(g5S;32Bk8bz{h^mV`>v+-212&#~K-pC2_b1TL_F9AdPrRBv5Dff!r$m_SkY*9| zoml4*dZAz2DL}yk#T^qsk?75}y0s{`&j;rbyvJr^$vg)55DI~E#m%D@O>O~Gv9Kv% zcgEjK=3OHy6=LuzEj2lJV={q$-dZArK5^Dzg%OCn5|OOkYKe&gTn5Nj;?-(p+IxEo zbo&`VBrTJ9%MeOvfc>*4omv&Ue(L&I!X<)QVhLLG+T5NY9YzLoL}m}y_A4m^D#7~< z=Lo|fHGm>VL}E#3qWjC_WRu$g0f(M6o>%vefl0|oE&I|z?i(Bsg2ONj2t$C=ESr>A zvMLV&L=j^ULNJUT+oLVQu+b!DN$L?NE}*asqL8=RbMarf>W+&w+Q$*nEI zKma94I^r1Y9ei-$Fe4&W%`+viexG8(ykuNoMeME?T)w@+>yIyS@%jQD4o{vw#b-bL zS$yB8K7+H3h1#%sux`8#61Rrf1 z{c8)Wfr({~ny zgmg@s2q4M6&L(^w7_|tDbu8mB;NIC8o;`a9=jZR>^z;-VXpDYN$jRc9p{~phXLrwJ zKPHBE0WV*^!aPq+pOem`RR(QCOHfKX)Pz{7kyv!Qb>E>E-uK3$W3{pv`sLo-^cNqz zjUe@D$uS})TwJ`x-}~X8z<>F(Kkn}P(l34vzxg|Vs8&sAVhN>>-odd`g?s~o^(?i* zWf`;mO;j6d?%5v=S3qI+lo;gZ|KFMH*7JKu;GmP^qWmo=M-)`SPPKMd-G?{=Da{JF zQ~>1~>zkTHJ^N#kEYc#dnw(|Yg}U!J+gVcj1S(Sos!IGa-Ka`DZh%lb=61dfT;^6; zV&73+r<(*^ZYI5)Pd2J!=TqO;0Zx?(jfdBTv5qN^JAlkH zri}`O8@aK0sw619@#2FHDD7OW=hW7rr%<%|DOa|{fX!LpvhJ(7viWZAv-h_=?%?{a zJ}Q=6eT^w!B#()CDo~9l=h~fh`yF5`?`lTh)OI9XimN-kx%G>pN8gzn>vy35 zEgh}nHTh<})b+gwK5s=JYTMescde`v45kVN74?XLaJ2CV!+;@-l7Tm~Y6=&mlo8{s zF-DEWN;?t;AdrG*uP@Fd@tJz)f_2&w64mu6Ad-lXa#jJ7;Zp+0i8T(8!tYegyM_T!6jjt1GtNThDBLex-mTSLGR_N39&)&1FL%ln)p1YZ*rCCE0N8FgW&l ze|6pNHaa9hRtRbV;so}r47zEx@}}x?-0l_aLe2ty7X`r1Fp!hYD6uhAVsPLApB)GR zZUjcnEVe?!R zr&P!99I)90+_`gtsmwSqf!XH^$fCuLp6(POh2u-Ohc zIv#Lxd&HePTMQc!G!rqH7)jEp0F)42YW9~flbjjLGGjMITwhPPx|s3$^;^7odkw(h z$>XQ^{!f2DzV}m~#=X-AAU7aI31u+w8~g}Rs2aZ_#o6|whQr7i`$VR=Vz5R~_pQ6= z+A_v)qaeiqb1s?4r&+=-)(NkE^?&?zyn6W>^Rj5CGfc}_vTZg%wmp9U)Y+*{g`5?X z18IVjxt`guGAq+tb$ZW|p$u#sN1UCW;px*Sc>L%QZr#2GB0|*Qd8-YY6HE4FmU0B% zdEB{m8}B@MDvC+B|+N0MO@a$7~MfvCRUn( zgrn^-?%%(Mr%&I(v-5MDot~xg(|3 za)x(K5|j-Cg7=y+AF$flYRE^7QYYDw!}0M6o;-O1$#y^B8y|cFZ{EJaJWt4+i?zNg zHF|4l+s8gUh)QBi<9B7BgATg-HY;A*C{GkOKlQ$WWca_hc#Hq$AN)8TK752f`2F83 zEqvvde+s|#FTV-~l}zR$Mg|ErfmeaFzOJ4vbYt#%My5Eb<8Fmgn zfM1m}C=_8@08FS1gMjUZ)ty!viNuc+LsH+vQ)(C+gr%ag=w?TON%R%u~& z!0d#Mx5^K4ROK9^YSm|vb{Gt|s!xpav-gy$*r@-z{k>CYHdj?n$pLhlI59jpdx8)G z{3taBr=2F3%2(hVJIhx~?>zyVK{T!aiaSGwe@OoG>f8iPW{LuV_s(D1qfk* z_alOrk|-(n3ois;e)kZNFb2Xf4Deh{&deEkVZ;LN( z*#(uxUDgbiUWlEiqGv&S2#85*Sz0Glqpa3ytFmDIYx6ic0$iv-(Ja6@RnP-M0e#*H z^N*Z#Or)+i8Gw`lawZh03q(i~kD3?={tC_su#7XnGc+Bz&W#741|kEnjf`IA()!Bw z&uEP`WzV`Y&06LO*laycPL6Qr?j78^b*seh=9I9zz6LK5DK2nMTr|N{+|3<1kY|KZ zl6q~AMr^ku#?iyM491KE2j(PhqB$XQMB-eMWRzrQEU^+C9hPO05>i=8Va1d%3&u>zWft=_r8Ap2D@nzA;cMR*6@lVU{nTk=q$IQ zMbWw2v!&iDLwrX_8OIHW+?X&);vV9RaWmrV>=f@jdq?6(Pw#-pAx24WK4{D@5sCLh zOh^=^c6Uw)VZhnxeeuk30nP`!di60bE-x`h(M0=3&{=C<>%3Nm_DPrS2$X%%xKx-X zdb>Ts{rmTDetwRpPu>yB?=TbvQ3wHE|2bEMctR~%7h^0UibwN)jTZI)WqM_N`L{H)0$l>pK4CYk2wcC6Zb5y;}Y>_N``ItxtN;49%ky9Q z#n0hi{NA66(k5xmY!%89J9tyhw8VMUorC+a1<8l{-6-mas3~#NE1~)(4+HPD5J#qY zE=sVV{EdJp_l`qG<`dzK4khv7<+Z~!3w;=MlD)@m0mg5oZHoSJJ1M-do4BJwK7l(dX(-t-fx$9rLrM3nY2ylH4voFszHL9 zkbpWj`|FoXRs?WpG(^<5R=nv$kZL24>$uSoj~31|5Bc;0(yDhzJwnkhALoJi3}Y< z!`XUoo9r&$daVo@Sc11B>Ge^ti6krG&7K3DV z3{D3^bI`wwSKlAH*4_*NYGSiy_U*55w7mmBgr9ktF--~6l#sG8(3DZExt4T?Na8Iw zo3XsG{LIvBzWPQ_Vy$JhP=TE!hshC3WGs2XX0yT3QGgEvh&%#3d=@voY0(k^x>*Po zBdIZ_YJzj@q%4xpa(GR5+h|Oi)E)%)3zZA_&yX5gk|?RyzO?0( zEMZnc677guQ{8Iu*4AV@jE99w8=rnwY5svetMJk6O{!I5^q{0)x?$} z>e&lGgB^^T5W@}}kz^?j9Kf8AQiM0xW(KmlvbEgI+~>W~QjHrncj96_b&#yPL|{i6 z7gOV}6K6#2J4FHoj{vDxOd391El zrSZzG5~8%z$UNi#KSGs2!1dJ?=6TX2MGoF+f(FXiY({K0UgjiAW^7iy8j+L~8^(am z7_ixT3>yb_jNLLJ%@NbI!`rJ%Twd?6nkW{S-d^U7x{&v&Zl}BF_ZEAZ3oiMq+-MbRVE!V6<9aKmx0Y+# zoc4^OYznkzv0CKpUirQeA{y|!EDM%t!LNK}AN>CO=l^F+yGg;WBqWlo&uRs3wH?j7 z?0u#sF5@9P2lko9y=rh$ZVqJ;^xJu)`j@?G2mz<3r+DYtGdzF(9QW_tD{jw{>`meb zgJ#nu$HkKXfC|3}YFY4a-Z#ywP2N1L$*EI z;{N^nI6ptf`LlD}y?YlS46@oJ%Fqx7sb6g%(Gi$jsR-b-BwmaW1Yo<_;=%m~nk5}@ zF5}~mKf-Q`NUAX>J=|>q#Y4=tu7OBg>wUSu4_LwP5gtE&fcM{jALr-iI6FJTFo;q* znB_MFgkjLS*;J-g*3MxFqtIQ7r8iPD*x}a6ZE+8F9t=i|39nv#jI7>PD5ZoN%VRgT z1HxJ1F^#KP12}F1gk8I39EPf7Z%bUCJeM+KcYTcyzx5$L_cLF>SN}}~!C(COAH{F{ z&L7G9gvnOE<~%@t#aF9{zrKnbv-*7RPO3kxP|kWEtjFETNZ;-%d=ddh8w_)kq8TCy zjS1c%1Szv4JVcl%u~>5%%5M=w!GUTOOF08sg>Vr^Vds#wyb`jx`%^O!HE|7T%#_gu z(-PVKw6oI!$J)w)v(b_?(B9;?7Q%L|3Qce3uzjlR)AH^f%$iH>A>On0>OeC#d*>Rw zwQ>xBx}g_$?tZY1e7k;^t*t&qJ$)3OUtYFop>Y6q&!k-}P9(uk#g)b$_KD7ujoQ3i+c3Pk&!O^7#W4nY8}tA%Oo}J3&|$6>Nmw7!+$PPY zY(fsq+oR4)Ha^JGRxOoO=gr2`mVm3@>D-#qWt9NTlFWTO+FBK%^|K(^AsI0)l4L3_ zNHKv)w8KSoR7-9kDKWFzY((o$J>f_xVVP&dIZ3wWvS=1RoC<@DDIsh2-_Zl(IO62w z7~Aa@oACtBd0g(q9c`K>b;FB@xp=#ljF<&%C9zzjoWLB>9z7U9*F{xW}l79w_ zRpKd6S?pof_{QRP4n{RaeckR<<$jp&KO3I+qZAw^zI36-#$U`x5cF; zIn28SS635u*AsU0j3q^h%TEM`gCCqEz8V9_XDn&Kv`lz=d4Z2UeuS{r;Sg;Ng!?i$8XnQ0ztE0L;N6Y{L{(YXN^C6t}t}V60^Uv>!2;Q`N#+JTO;)Z!S+lCR?{?eI5YkTr*Z` zKZ<}y0&Y+5+`&8Vyo2-eXSjd=UIA22zaJDR7GO(qo+}m+0V$<~;AQ_YKSs`s7&Br{ zxW2wFAovjd%#9_cUzc7el=-V`q4JmrVG4fDT6_NN98aHW9PW70r$@C>A@5p_3Bl|^=^llV+HyR;5!87*IM+}(y+FY+jmFXEgn96 zi1*%m4=-N4DDm0MTH;B;uT)6Tn#D##+V?sum#2a)dw>^lO$A}QJ;tMlj|(3l0$#s* zg(WTpu$Vi0(Mxt{OkhMXW@HwbDCb;2 zSg}4a1C+%>h#|37OhS*@`qU^FijZ3^LFP8;?QD<<&HJL0fnpQFi)-qh;-#*c+#tWG zb9be|w$~c;(!!qgnJZT7ToXREfVHkM1KFfClrgf(L&mt{2CiWv{h+g9*7LxUKC0pA4jI7M*i)hAcLb*Rr|E z7xfi3=Ve5sJeG2q=Z;2b$U)nuy*b*usLI{t+$pwL(PLN6-s+5GfE{;x5zR=75;%+7 zGq`#Rl}a3>-;;jFwF&#oEa$}vZfC#AaBlso7I0OP>#&3`_3O1(TI|hG$-qtsuU@|v z%a6r**v3{wp)a8E6i+32sC00Tg*cgVa$nEhgr0kF{L8ZPq zHcOl|=OPcolF%hP>*_X~6)QS5l-rQp>I{qGL##taXdE2Ox}LHEOBPGUk_1S&#&w2B z;)vmenR7E==!CfXudJJ3B1w9sdnhMhQLvU=1(n5JNDoL%2}??d4d6%_Ad)>JuD?oHM2!}&_@}GXDq6OAa#xNfe?a&A3Q=3 z#++itqAtwLvX(h9QdIkKCPWY@C*);8PJ|picnqMCFoppqCuey4@EtsR`abU7egwjZ z6g@l-1^imfZ?%}|8j(znFfEhj(JcDm>mY+t#!(3#t^SsqZf0tFo^q1?GDpmF#1a#} z^rau&ySrF^!75#sfuU$PiYqJ^npfO;+K#gc1C_w{TKY2ZDqzV3$X-@3D{e+vyjmC- zgU6jackt}lIbOVYf%^|0VjKs}IY3hGCOCk(->>$9)5 zu#M?AjGsJ}deaevB}Swek#fcm0`8rjA@d^4F%Vw8dWp-c3(WH@r?F+s%@VCYUz71Q zU`|;S9LGmTc<}H(-hKC7S*!c^;e9~Pse<|t;0N)F0=ddVHSdLi2qEYW9u5N&JZCsK z%)B6}%lpyx2u~kB#o$Hx@z?IJ@#^)*Se8Ze71S);Y+h1ilD6_TqqFOA+wV7&5NQDj z${d;HquJxDgiS<}1v%x6-EN1EKKu|r@>9QnfB%R7s@(G{zw}f1t>6E50D#Czd7y~R zk{#NTw$%3;fR}e3>~gtGc(;z#wXFO0I}xDQSEm%wvC8pMPdAdh4hAaC69Ggi!1 z9d_m=>_|d_su#~ECuyRxcZ<9PsurWw9O)n0E-Dyhb$Mm|qIsX!I4|a^1P1`t1a}53 z+oXJ*MM;hsd{fS(0tui!=~Y>>21C^|&jhS}F;CrRHG^;&!fL;*zpy#5d)7*}3d7JS zn4|}7iKNnM0a|5%I;K`;tKlf%s-ShYH&O57rd^vZDSfyvTNi+jx=!owN?WQlF)$;t zHN%-3c#+lXeD@ypDx=fk^D1;giNy{3wr2&oYo_Y^`m z^@pm0s|j?zlEfcDE-=40X$^1q8EYWiOxg_(&As{pVI!-DqcLA$RRs z_X=c&dXskZnZem<2J&8(*qfi#o?tM-_3lD9r&l*i)iBd2Gwqg={E8Wf3nL;S?^4Os z>l`o)!mLB^D$Hs2+9d9ADRC)Z1PC1n0oa~waQE~Sk4_)q)~(wZha)&=^;@&l`el#7 zZ*j752!113K8cW3h)*$Ut=3*pWpJZ;mUMX6K|pyb%@$iM`STk`D;y zt>y$-07o~$g;2UGOqBJY^4?Ymv_qO3p}4#MhKooNTBMxN$e4P-QIan~fmzl(QC8-S z(9pXwK9smP=VAfDg;;}-lf-K0M2Jg5iWxBiNLhpsXSJmrNUhy#^3P2ll-3qOC3ByI zinHvYr1RtfB;Bggmc;q4i3I5!T6u?3l11bEyz>}0BfQh3QJZ6&oZQ0gle@UQyu!4b z5tk^juS*p0oRZWe&H~C)MoE0t#`*&4Ttep3O-1`w0KYO}LQ)}uFpL9+5!fCLxOe{+ zo;R=7&Z<^7?C$9S#UR72R{7ievpu^e zJ+=urWQ?J#KKhwDw72OKzi(Ff#_#I+S!uN)%7z#dmSx7Y2u=Co7k^~0m0$Sze}>&| z5}C+K8JG+70g!D%h-pU&)E_csvWI}LdC3%nQySeLwg|-zNCKK}o!rLLCr@$y{2UJ+ zJSgB7fY$nzBuY-LN#(r^Fw`33EoXwz@`V?0%J6=`Z3V%ye;x9-KETD>w}?3_{Z}4> z3NYmN4Cktnv1om}Sj~pRYoCX4kR)F3JjJtT&v5VFy$XKSsv8EW9$=Q=S`*sF)tp7= zAl{`z-2)om?!3d@+jpg$7%?1)%djMbj15g)t;>ORCyg_q)pz2m#yC3K;^Cu*c>er3 zo;`bp)6=^c2B}p{q~*yp>6KTvlVTC-_Q~pRM+gB5{QzbH!6D@ZnKQQAV?2KJL}J!l zK=``Ht5+{^J?)CJLdIDWuR-@hpWUijF+Kt1bV5wmPd4CLr2Mk_t#!!+cjrXln&t@~ zzkG=w{)x}y&;I!LOPgQ%{Ey+c{`H@NGh<1y?5}|(M~S(_1GdXl0mXHYYkph%e&g`= z=l}ojeQf)xnPxT%tAa`c8I%6A75 zy9mm}X6+Cqw|E;c97$*!7*aDhi>H#!V;MWASX01qBuY=`>uHz+N*cdu^yoLBuc_)y07ZI=HKjVBep2*y{;B341dx*ztpLl0Kg zU{;dex0BI)uYXk_grYDkmcu3_Y3;S3FYMZLE&UeafTndEtgj54MeET1T($Gsod+oF zQCi!3v>-BqXsM+Kdd#J8yd?%@waUN zs3=fcp5H7n+x*n=*$txCcIc{pYO>`XBuEHPmSgzYv+%-^`xn`d!nj@L+0 zEFwA8A!8V3jHAR40#NtUgt!2UTJbom>+%R39c}UG^bwvseToNXk8rd- z24O^I#_oDSO0O}vh|y`7Ok(-QZOD~ zTpTBL(MCj$2?Bna#bgvsm-DWITlB;atG``4(aj|riHe(~LYD&I)&;kV&`i}Hwomw+ zXu5ztD>N6HBUVIbL{0YxK>(U|n5{#a1>G!^j>NSp3?9QE?vgIBCVMiC4T%5+kDMJi z5#j>u2mohHQS15YI8&4?Ql72kNJh+3a;PnXQ~1PCQ4zjYl=Nos{IA;RYX@*Zvo7@b2HHyFnwjN2pZcGsAu8Ot^cnrgUVJpJ)vMk6~5fKxXG+~J%{CG#$Y`1_L5kf?q3CzBn z2S*ZCFlX_+*xot8{dw`_G6-|M~S)rc79qgS2xqDn;;g#fIGKu8nmRp~kep;6StFWU64$w5Xq1?i z=~m*~@7_HH2=L?qrxy1Ms~avc)HexFb!632W^QIdZ#Gsba)2M-=f9tDzf_TkG9F)uSr zh_skaD<#O?JK97u_PO2P$1-*+Y#>he#v$Rp`@NY@(#2y2mSx84*RSvofAaJAkAKvF z;Gg|b{O14tC(2`#QFsYEU><6cz=q#*qf}U*#s1}WW!G2B`wv;vKIx)v&!W(WvJRT3 zq+~Eg5Ww0HzuqDyvCjkoO&L1|GA|nMyC5gY_mHC029}sT2S+t?Hfe@v$4PQ(XxN{F z$}$H2xTR?s3|EwG?Nqr25#fyTI$qJ~PX(#3iqU0_SQO zhXVlnP+Z+!YVy7J9$?d4H-G_QW=SlWGY}X+07#7@-dSB;k74u}Hm0deLZn%eM46?K zasac(v;{6NcewHi*VkO)b!Sd+3b>e2Kx2xlbB~Uum+a7%A=(m2NhdWHI7)J+Wl3-@ zBdTyOvEW8Tq;>m`Vea!1^BH5r;-h8|Bxo^4P;eNw0YqDPN0>DGGdo#NT67*G5Eqn; z(Oo}vVB`RbB7A#|B`&`Y89rnsd|pBBeMxLroLOb7!b<`LuIr7cIuv&Y5TD_mXe zWc-k%Qzkq+CmR20N}$Myn2~r9(VPfj9N-6n9~dD-ECayVNv7=>u}l+UTrl`8ZXe&l z>Fo!2^57ZHP9I|&k3ngKqY=SxF@!A~ZDb?qp5vB@c6_3S3Q)sQD%q>9O*aV>MSxW{ zUR{;-Txg8X~t0M@HHUFY1UpS6ZhT;_&q zHsc0&Pw(Q%<0p7_{tOQvKETnDC}_<+Sdv}^v?VuC_T2uO*LRBo40!>2 z#H*ZN53>*u`hC0xzb4d{emDYqSF(Id3r_0*1LH8_{@EFbqk1kfUcG*eX_*kM7&>^Fb!t4LYghqCh+oV39VxptktK3V?;qc9R6a;)B&dVF`0? zSc;nc8ZaTrDiD-5+WXP3YrBR9C?zCJ`fKjgb$uK8jj4>w=tO5!Awo5oV3mYb_N^7C z@aEa3p^WRk*}Pf;Au(pOIT;wO3~Dn@H+*0ApSBC_J9X#PT57=L3jTIy<)-su&rzMn zvZh4k4b7X%PXn3-^b{JhuXH|ip6zEVhj$j)62IC#SoVo2$4!YtiXrx>jqU4hPV{Y5 z6-_0PDA{+^@Bc==Ajlp{o#0=`Yo3OMcM_L>q#cm**hbUp+HmXVyT;#3Ah4MS`dZ+@0<({1Q!Nm9}vkSI15$@c%h0SIIA7t|{(}b(5D_mbY_{)qK7ddRrz6=f+yoV=?Ka{w{qP21X+o4a&N6XXT!s)9V2D7}4H8>G zDO!?449ph2Cc1K6+;4kdpXtrO;_9A8Sa(E7+$X&9_2zy7S8c891GgX@C_KAWObKP1 zA?17+$b(pmU9OC)#Eu3=2*40zyo@BmZ5Br1UBnOqhT!1bfX(RP1Brz?U*noHmI%yq z?TiWiS-lCM?`+EfmF>dll1CLFZ@+3%tZ4$s&4^L8QZNEU$cYs}L*jj%)WD?};k+wJ zk3dtOK!?>*?-*_XJUfgC$Q+S)5a2v7SbVCbkPKJY5*dHhaoG1})XR{+If-mTfl3Tj zW(LQEWdW8*nCBV(IwL0q$egiUG2Xtp!tNr1nXnlHKv~_@1&E|LAjY1qJi&|SFU0M67>jV{f*0_siQe|hLaETg zMw@j1Idfj}3WFscafvfhOz=dwb$o(Hj~;`WF^mBpfBX_}F5XD?VJOI@+|jJ^KK-72 zohxRsdJp5E8LZ#IvuEdc`0xRakB?vrU%~GHN4_S};kvuX;$>A>0Jkfm=Tvz`5sVyR zS!7}SxW(OJgby+&pp4)@!o}5vfXI9xUKnm~j2GncI9aO3wvXHGUp>^$B0lMd#1&B0Cj5jbPs*>-&2>2=t8 z-0=B^e~WvfZ%PdM?RoArkqKHn?GAg8VD=?+LW!t(k&TMyQAyS|9pJ6l=J z=(NOcwT6vWCbaGp1dCRe$1Pu5`Nv#U1j)t{{7sXm*Cc?dQzvv)*{Xwci&-%DxxEssXG| z;GP%HTG_$1Z-KeGHP6e0X__#M4nx==1P=#Evp@KN;DwP3KynCSfVdVV5R0WD42kPB?ohLoxxo>m4qx#FD!#Q9h3ga!R1L z5ounqOj`lqI=IXcF)jeISk`o)X_>(^Bhxk5&7gq*C;C=#S(Ug^;;kfk%BTRhBrcGj ztq{2eoX%CjRqC?s6OeWj5RoP>sT#CHSG(jlZLsxwx~nBNtjwt}1;8Ol z0uu59s5nc#MNy=Pd!}<4AxJ!#4-UiVu-%FvIVWIVfMw}jow@0YC0GN1MtNPjU5TcC z-pCy(N!z#vVq%Fmc3gn7S$`=Dzzm)dLV{1g1`c7U2S25TtTfD5^dpjtikT3S!w?8* z4B#|^c><87ZlzkKOa7SL^t~CUWsWulUWpAZ+WfjtYQ|vFbHj+sjCq-{TruWp2FPPG zY$SvFW{coO>$JofSGy}r^Cdux;mBiiyuqk(z9y9BMBwZ+CPcNZ3=Dq6$?X%oc=joL z_q*SRr;lIYWP1wa0n8qwKf>sbFt{x|Ea4UPi&R#!|Emx#QwUKNF6xGswrXqpG32eF zxVOKWW^@K6<~L`|F=1X7#AP{nZhrBX{u$oBonh8HD(ld75UqC4w9|bu2NWT^XinQe z@xG_4_Urg817e%_#5uz4J174iY46r#S#q6+eJeBfKIhb>t8dfY)t6}iGc-+7wnYiP z(6U6+RN%spWQznq5CFpw4%-p3Lu7yB zV6|EyYc7BS6ib%#D%5mL0B8=JMgVdo33xyn1ElUpELr@WcQ`&i!Gi}6)dR>&MS<-O zQ4={4`OY2O+^*_~tA#k{1n(S9Pfu}v{s?cs{Wcyvc!14jqi2l(egnVa(rU4;Ht!3e zv*RK?dCd|$jAN7UVAeTG@Z@oJ>z3T?6NYiX2OoZbR~Ijlwy_g%+qqIoYQJP`<7$Qb z3VxqHd4k(_?jQuO0<44g0pqA+a<01S+WhQoj$Y`fN`=P#574-42dRNB=QLr$93h~5 zy}`Zv_u&SmgLB9~cptCRYjw$1AB#PKrln&e%Ps_8^W;D|_xkh8Kv=!My0~!}H}x)d zBx^tCjNP=u^uvh1{BxhjKmFZrb$$HmFMSrj@mt>p>v}EXB>{ngob?^UAasIgJFsr- zDn=hTi|xCQyY@lv{&)IE5pJ0^R0$rTs#x?}+1k!II4zkqtfU+rz=(6gc6*7G2=mO6 z*ip9yaYiOaav6yoGQ1>;a^h{`9m9bo%QO?)nw*=xW;8SYZE^-od1vy2{WPx*d04hsjo~y) zE_cQpE_2(`*c5&?f5k<<0V_5Rs*SZ1g+rH}w}r=co+!-t>^Y2|1rX9gAdn22ie z0pk~i{s+cN6|h&@?BlBd2>4~vEW1jCKpACcI6MFVAOJ~3K~&^@0lJ&@3B321V?>;1 ziAUVcnBr^rO9wy9lB^@BmT~|_c=%xeb4HA7vEoh=ZwL06FkA8S9WtCXU zT5!}l!7(63aq+`ABD<{aJHRwWTwU#ul7Ke3qPY8T1Uq5aIc31l$Y}zF8J-yA7(PQv z2qXZ}tA)-sFLkcay^!NN#@jRD2K>I^GQWDO4{RX#rpsEZi*Mg$8qgRW=CVUFEp9NW z$k*Rpmi{;>NDPuan4AjojzLyznYE&Ie87S#KyAv>)09S zdR|le_wlkrccldIB$i-!O+uxy#aTW1z#4n*fpG*@8vqnBj5Bf`6$EC?d6om+HT;_a zN8%nP|1v-cuf#jd55b__cs!mZVN`j@V5*Tz1R z-8oJ3K;B{S4ntmH@N0~>S9tXBF+TO|$8rAf8BW)C#N9my1V3U3Yxpq2K@(mTE>?lC z?47Drte3gpxO!kTT7oJ_dLgQvSO>0N&}fC&M(0h{{XWjZ$Kotm>c95Y&vfm5>6ia5 zE-x=TrfDv$OMqp4wM>guD3F74&y9}Fg=@*Q4-0+udl{uuG7u3?PEPRT@e_RF`Exvc z@DSr@@v&mr9LG`WIBT72*?>mJ!|ys2df~i-gT+p^M{mMvAo$Z;Qjgtv6%q)S*O#c4 z?;6Ks!dIOwAnE?|&g0hE3C_vo!CZ8-07dU^`DhvIJS2q{Hur(KEJZRghB?V#>%1gutT+`E6L zWP84Q_b!IjP+Zi#ukPH{GAaA1dbHfQG*EA7gd3^=Qrd7uppZ3~grBp=dVPd@-oyK$ ztbz1?#?|GOoWsaUo91;5_crU+A(zpmzkwa=K+;lTxzdo7uNOms@nR}YxJ6XxT-poZH;cTr zqY)%FasY*QSo^hj5_Pn)&lGPLnPu76?#!h|300IBEWp2zy`4j$hilq1o@79h0F?UU zP2UVu!Qw@oD`y_KpFaV_lB}(rQ`T(aEzJt>;sg71v6jl()E?!$e-BFk>%HtmVJ^mm zUP)FS|2V!-_Chlz5;;AWN|L6`;{L|dMv@_2d(6{} zH0ORJcaxftxLF{2^`O|5QZ_Zt<8U_ULso?4!D(MhPMkM^Yh&W6fXssH%M04UEEjAA zeWC>wWdV~4sRn$l3{i>AS3xjuF--~6M2IO1P+qKIA_1fAxMahkSRRe%wa=JtqVVHp zC|Tofvu0uDS^h=>ECY4|K%pvpoX-g3grN1Toz?<$jsUk(S}K#F3<4vk88Jy*Y)Ug? zikcY7V;DTb+95czwn;Bj&PY?%5<3ZT&f*CHXuOrUm=9sV7zS+CYn+@M;q>$r>kVOC z1+0%GQJo(E&Ji(7Mruj{o(6at;VB?7iCgcq11Mq41CEY22rJ3V8-@|Xu!3_zW2;3g zPcCQz1aZ9_{2HrajXNjz@$~WAc>Lfwj@Gw8QT*kDTS>ViH^RFBWL?L+U?Tm@*F|UG zw;V4A?rsHuA4NLddmdm|0y<&DIc3B-ise@m0xiMsFaF}+!Rw3bPKi~m@a9^D4hS+> zlPG0z33CKXC?e;JF%wauv{o{c&pvL9g?f6ZZ;m%OfBXo~pFhW24<2CD%*aG)`3==d zN<>oHvz4=G2?*<4tcsV`-EmNtXy-hp zX@{61Lhv{~J_Z29oUq$X*iI8(zkZFB=klJtIU~YqHR8_QyLk5ODW1LkHtyfQht+x| zpwc;sGxok(el1hB329AV>w8*IfMyRBSkc`B==r2==a3P202pcsW~{~)?%lbo6>miN z_<%mZ<<+IskTr#{?S-Y#g}SCpfF)*R0|<*v{w7SgT$im7!zN|v>%G=$OgZ85@)Do^ z`Cq{A|IfeOwfEI8DhSS5l4C)4GD9n0P&s?vC^W)`-5#ii`~N0o*2mqu1Wu&=EqMk= zdgDO47r0Ehon=wWcdUkEoNR7mK91O4U*W=EBF7h)wmXo|Qo&=;6+{Us5@r(Rk|RmZ z$P{(Hs5zSnih}p#l)5z9FcIbX%m-zdLrRF&lZL@Xt}?;+AcYH0t-xfto+>}Dm&D;$ z-oy)qjwJmoXc47mc2UlvfR=Vlt+Ar?h5GM%`41gG0vZr}h-TF9_6}g{|M$3o_Oqi= z?$0HZ78XimpsExtS!1*3tKxdU)RNg0SrN0X-xOIzPrguY6LgJ4a^WLc1nZCaSh zk{&JEKDvl*WloO35{@*x5p zxZ1U|H?Ho|^-iu}I(v3`mxM{`c&)EqZgjA-L!Qlxxv}>bXYNDb_hb8t0}9Q3{z^LU zVeerl03s!EB_;|0A~;=x2uLYoo@dNS>L)Tu0w*65KvHW>>dPghm`cJBsJli=C|V0Z z5(%Z01ev56lp}};BP1p&XGV+(lu6#P!W-)-pIk;*6LR=4pqSXUuU%%2(p@ z$k)h};Rj$G2b_dsjN=MxY(zNP9pUoo3YRYuUcbHs=cz8x#no!6g_sqowL-fihwP*l zBj>t$m+daWZ?#0!D-*=^+Zf3r{*0`a-+?vZ8XjV=E-Z=xQtK?M)l}+20~QZJc3`Lr z`y4CK)Vv}k86wAsc><;#W17@DTXqBr`0ao%SCGt5W#3`NZ7b# zfI)K4JOkM2dwfF5ml(oUY3rqysN2GY02jo4GD#CgJYyT!DdG3_FzYf0wCoG}i- z7}gk9V$CtD3p0==V4fu7w8b2!6v0{=Dg?FujsZu<8@%=4J{~@JfYY-zhQYxF8BEGs z%<~R&nnfVsQL;YM3ItK!TwiaIQWVdPqYYM@Q6L%vS$wTQ2vVOqNtR6KB$1GWF$_3a zo#FKO3~$|jjC*J2SP!S56ae;cZbS%c3_;!v)_SCN%r4?_5AUL?%s6;Jm3!KQc=>z< z()CS?#iH$7-OCsgrfJ5kF_2$fWPJXcf8#&L#jCBZQ!-AeDW^>EuL6J^lr<3+>t@Kg z5ey1#P!74a)}(<}5iFg8kKBA$-OREk(%T#z;o-xFc>eqoc<}HcR^uq(o1jWdEe&Mx z>?HGIvU^M0LdOO??zu8q|4HIX(O}?6qF5kLI6XN9lk_=+0pZ0*z{N{kUtM*3T-wd$ z-61%f93SEFlRK;(Zuy0c!Ai;z>HI*Gzck}--RGS5 z7=RM<4Mfa|;k?Ju(J}7cy@!;9AAH~gF0L*x&ogRr8yQ;$V;l$Ey?Y05zx_nSpUw;r`wG z@Fe8}eeihy{r7QsDapTDVYQ@3g~e^z9Mts-18+JG1CKX>%srq0piKg!jmFy#&YPpLsp6QxkIn7 z2d9o3q>`p@Sfrdg;#KPq+<=qKEfqjBrftOa)ivf_!Zg1YuI*r|JpdVw5~5ECE+JDw zq6j#Y3JT@GZ~WF;e#NW_wYc_)Y^}6(kO#|JDb~UUcbFp5e1yz36j*o{unKg-`VY>oZZUF4CG%L+8>VSN&qC zMIA>&e4RU4Lu}fDrh_8a0B|*%HQlrjZoKySk~$yvowd8k!l2q`6$fdR6;m3ud5NSM zCmsMgcA2N%AlUY!knskfd*g`c%@h!01pvzX066P9o96`PE#^rMeos5Jn>g{cyv$2E zmI};7Kodb<63s9(kmXe(XxEJn&3+jvDI$+x0F&+(P8#e8Gdz)@U@Q@UoX!x^~n>CrXwft7ERlQL@;{?nTz?Z-@B@kKC9(4mB zy_5x8j~Ip#$!BCvh|`2=H(}Z)Op}8AC~?w0IE!X##;4*7QWd;U`sd6D8xd4Jga31SngOj6MxP5jXw{P9UdN`I40eA#IB7_wNFWIIE zp&r0WUPoFYrW`N~?(J`|lZ3f4`QjUY@T#XyZ}qDu)AC6<@MJ%vBqeO-c~<2^+Oz!r zt-twS;PUdSQ_!{DHO~b5rQL7B&@CBBvkzfIY7PtdDW~_MMX5KIeoqN5q|gtRiM>+?)3frzfX4fAkQaeEuBgkIsv=m6;3p^*(g- zLMn_F9&9ePOJT1C`X(5`9Iz_r$W6P>dkiMwK@~{wpdeOiuZi@+Fu;Eh@aokoY`0gE z8D8HX29L9|+c55dnrxUo9pItX|-wh zgb9CO6-c}XVFZzfzz&Bw?IZzN2)J{08<|r%livIOdwBKwl~jhX^S%+bsJ=*)rOSZ; z0xsJ%wYZk+^N=NfdA1oQloOheH7@w_@)CdfXFrF3`VaR(@YjFyTj0zB=u_S6&RPGe z<7ic~2?OZ*v;eG!_ScVc9RkShRX}C)x8MqGLi3d&@iKE2zn)1j%9_4cAvgU5cEnoo(EsJ6VWw*71D?p4?iBSO% z_747~k{~zt8Hl!L>%PyWnW})XkPKS1-Fp30OS6R`ly8l`24V?vu9CEy^`2#IRO5;5 zSW3rSzlQ8wDO;b_V{0Kh>Sjac@6dg#?b_eQE1UzuN+EDE{00FBF^MIRaIKvjAQmF+ zmD|BNQtM(ug1N|wkQQ?;C1_FtK(n||dnW=pIk8wUgH@Z}uZ2na;bOatb)#df>J_4O8UH(`!5B3}t3@>>8v7=YC};N;{4w@z|atGRu~msF@-ZgL_4OQsa7C7H4^ z9$99VY0z8OXCF=}M^m zAqR}Bgp?+Ug-aO(@oJcN6Xq!+&9Y~_2i9xC(Po8Pr>8hRK1LV@AWIDHG$r+N$i=b_ z2*`HMgP}l&r1L2y>~>qcdifIGIb2*iIG2&~7CFz5LM<5?S%EXd`-CkeFcZ?85a%S! zRh21T3!i2N0vs}vDn(MM{V3iP0pqa7$?+NPoV|s6x8K6)<_-qhfDjP;AeLXhg7c#a z&PrT{T4gM$%;MCjs}~iF$>a%B>XU68dXCEk+kMTxyn(M;;W;hV@SPRQUy*#RAnZCk+ep<_Z}xlCpdp}j!%B#ZJa-TT);0N39qDlQz%NB zI^P!V(SxvBhq#FcQ@-0gtaD~FicUCiL}2m=fx$eKds9jvNAM>S_!fMS7;69@&O7Y3 zI{=L1<73>tdmB%lKEczcPsQ@PUcpvX@Bv!UJfTwh<|(|_$V`2BzMovyvFed+V~`fvU=m@`s}Qu--eg`=|J!dL=ZR! zfEer5fYA>aoX6-#jNcD<@#;hD(rZxC!_UB7uF4D|!1>DY&D+NXC+DaF2~Mqhv$_;x46^^wsWJ5Q3ah6v)u7JH19##P*xJD?L&bm zh4y;CDnP2ys%e-Nw5j-86)E*ywpVSxT7oOfk>FZ-zv0qZ-s2&yH5jRS`?P0(NhAgu z!R@-TpZy$B9YVPb=vO5my6pUg{)>JK%`KNsvxXYWZszJ~#$KpRo>QS9I)H&u)Abzr)$iakq}FUy|S@#?#c}q@hcye$tKrt$X1JJ_t_%0#o`ui zTEx1`BHBkz-vx6rS&Q(+-MpAs$D!EKxG1@pQD3=5j#vQODfm*YVWv+IU zlpLC_1pqSxApr9L3`1=%X93cses3dtvVNag*H~+*CA1g^Y@ZbZF85 zoPi7p1Bg+waHit%(PqLmEqX@EQ2}$r<>hOPYhV~Xd`Oa+dqoJrOWYe2MWLoIHxO6oUWljZ7coSgg-cDsAXIRFa=QGuQbgVtWeIQ{@vSI_YWfAHTTPqz-!1XWmMCpDA-!3Og@ zBS!}NfaBv+2|ow{DP>$=U*qa(3+D;9Z=d1m)2Dd*`P+E#;665+4UDk`-&nN0Ypg`t zUF&a?1-jK_8}PJo_AZ?JfUKJ~A~b9V9!*_n?O#-Ht09cIbNjC3NKj?W_rK@x>hhKH z7@&Jq(P*|pb>D$MtA(_;YF7YUez$vU?A(lBLGWMvnV-Y|^?SeDwfnU%{Q~~p|L`p- zB^Ras`@jJRb~b43<%-7iEK<L0f@dy15`JWP6=c6sU~w}| z8965me#F_y89V?_9)tJzURdL!iyvT`uaSAHoVt3n86CXS@GN*xb|84T6p#}mX@*%# zZBZ*e5K7kimJkLQ2qoFaA%JUq-8Fo%12qLSbCGo0c_VHO2;8(^=Vedfg8FU)zfQ|a zS$pP|U-Lk;?NsFusU&8{qjPRADG(J!LDNH<)4I7}ULWO5v9B7%UcXx!T6X7arG4-2 zUlmy)_l0nT#|XqCLZxyP>sE8;BJdwUrA#=330zL9dIZe3!XkmuDJ&(pw_Y z%xUe%zU%n1J5=UYyf2#17d3(ln6bM7pNT={#`uXklx+?iEL(2Opa(R-^(@GhA|nP_IrkohKtu9yi8eHmHvkxU@$@fEKNo^ z11%-#Y142fl=3Z}fU#*%77@X$k%qj90CJ(YPDxEcbKlCyh+sCYy>`w7(UcLh#2e?F z5Rb2 z2rIZe!qW;qtl-_C#W!UC?oZAV+zDlu2h_eY@XZI`9uVuEsfS80hl}NRjtSEoOWo67 z{aWw#{N*qII$pneEm<4Y@@vWK4E$zWpe9{6!kLY;9&Yyj{W14rDc=+TOhmHh%Yi2R zk8{RqHR9o;NBGnyKdIn%4Rhfeh5_T)#Qa*{>i^z&Sx82?y;$SzFm1qe18(Fy)+C2j zC}TBcSZuqMt6`0=dGX=}rYT~*Ug5!m2YCDKXL$7J5jF~bIcIU@R`6?i9zwXlU-+s2 z4)^c=6F3)v(~lk6!RzSgPw6hc<|O+TEAF$w^`{$Nipp6F_<7F!uC=r)LV-8#W5K}zrU8+ z{Th=ck2pA~jmx2Aw-qIigd2q+h!{^E!4G)v{qNz`#Vb){F!Y>ighm4)HwY@+t)c$2 zJz5YcSlK63ak zo!~YT@0=UZ2d%$Lz_m+yGgzD3=~oUGc}ii0aTlF zf{cT7u$~;)wbs41KeWH2i%et^N;7VI&Mg#vx;B=^7y+C%PA+l19X%U*6sDgU=oAV2 zvaXeYvPtFAbVEy(IcxLA%MS10nCG+r03ZNKL_t)KL+>($hY|OXLb|Cron)JK`z)t&S7I;;fYZJ>1`~A47{L31` z!7yuek&?Q0oX)?=PA22B_E7Pqn$PHjzhV!(Fiee>JIm!NI4XG%=U(b=^ z1z~&Sz?$9n1Q5e)w-=k_qjrVs>-t9(-YPNnyvDqM;NSqSR=;5oE1*-5!C;URFl2G8 zAQjj-%D|ihWdmTpf1oTF=a%qrrn2GqNtnHLVWXkUubWfU&L#* z+L48Z!-TNI=6(H)OaKrdV!`BXsSyBD^O5_BFU&#P(V@aIK(T(6W*~R>0UMqdIhH{H~!;i?b(J0ckt@W=)s1x@Y}u+crMc{HqP>ZQ5o{ z(_dquS!vTLlQiduWo@l)mr^I0)dj*fdE$&YNerrGfEJ^Q2w9nG%6{)9Zi2xe@8AN# zXNLs9QGoX=NzemvGqKFzF-GtlMUj&M?*g2r?l%`TiDUCfiLl#7Twm_sC}22VMSro7Ea-g$P3s%Wnu;6SoyRs0f0sFwts?yMF0< z#iGB~W}B>}un%&YM94{P^|Ha7CQ|a?%utRY1-lF z_!z+x?!R>(ckbN5dcCe~dj}V!(}{V;)>_DgFq-uv#rm_2#G zX9O079}zS;B`~-Fx6f{i>$i6p28TcWQ-_aUe2Cp7o>t|UCo1e5i$1pJ-JyQpC|v7; zldshegZ4v%iqK-p1A-{)h%rwye)6aPef+^c|KGc|fAveB$Jf94JHj7x1fqfy5C&i` z8RelqQ!{Ue#&dZ8-~9QHasgPSxhwfVs@?wE>n$#@L!W)AdaC&qKy3ZK=fMGRa zJ+ATLOOLDTSJGBi*P+~GdZsL;`vAok`Wb1`K(8+7xv~+mvjO&y{ItE*0^nk;EXkG* zyTw-`qCW(bi5IbTxkfrVN*;{zx2xV3$+AqFJYX^hqe;Tl%s>MMDhD<`T>cc9fv6gI z%v5e*ps!Pyzys7*yRA4_s_0z8RA6m8Gho zG1|dISaXN3=W0d^0;wr&$K^?KPHXM9Nv(Pzr_>up&&S*HSG^*lF@B)m4>jw(Z6nr- z8Fp_w53Y>ItiEP^YYhO!^Fd|4&QrtQ(e;BHncFPp+$^T%YQXQIvt(}#Q~PMMfeXlC zgjvq7E>RLUb8j@T7*bCXPa8&Hy^()IAoyVIRNr>z0jqAC8!o_^ktrdI;|wxM*6Dek z!6_rfj5LV_(HN-#(1CzqV7TDRh6rK65CX;!K&0q;$=Dbel8)U$0B}?~sBD^a-^n1 z1YigdpjzU3oiJU?oT!N&N|r=>kun~#7)CO;O@&m8d6Kw#56&KmJrX-0iz`(IBXdHU zXK~M*q#PMDBxYBwc@_r>Cm{$aI>ea3+2i>13=iLWj3rZV_zi}z zf_JjF$N+2Urdcj+e;i)J%d0%Q_xT~^Pk-98$xte6xAbDpNI6SMvsq$)IcI$3SAM>G z&zHaa>jnJUJ1lgdyqoMW1Hg@@Ru4T1%gP$}SX~_2L%U_lZN0v>p0_HqtW4&J2I=_RI1@a+?5(ajd=}OW)&;#ob2&)TR4%lW5 zmzD@{?BGMFE@4E7F~T|E_;`bq?tqaot_DogjN7+w;r#p&Hk+d&C7OlQ>in9OfI&!k z1@X83^IaeO;IHEU{a61P=G_@8qo};b1c(yLs$+NFBQ*CRGE#~F2uDX7Jbd^NXSZ*I zh_Tshq$V><%~Iz*TyO|p_fZFCTgkCrtwpG_{4#g@os9s4FHOVkf@P6R)_S*lP7eD)7+uxlr_p%Sv zRo^?Lobhjb`mf>6-Mjcl-}xWQGhh4SXYm`~{0>ZU2F%*eLFmy4=m*EqfE6N}p92%I zcy4(a*$&afcx$f^>G>qVyulRwI|9hVQ3jL7mGQ7+1Bral^MK*Hfe3$v}6p8kKmW-~B)anEicyrlXgen{tiF`q~<=N1V z-3tLK?YVibLBvAZ!~3OEX1IQ@Aluo1vbH;!ugL6KW!--Lwr8b-2sR>5?1Rr%PQYR; zt(;ijS=7)v-b1dl<l1#dzolWzBe@pD9epS6XW>rXHBKz|*TIfm7v4mHEIBi)?N(OxJkY#nsA7 z#>d*V-0Wk5z6U7Emdq%%j&p|OIcqG-*#oo&;s~UeE67*PU*eh(v8)g0K;FZTz#!C? zHRX(%M+HT~KD}3WmQs2uV>d_8E+S?JkXPoAkW-YH<9PPlO! zi8Yy%(`A1%9UFN_#*uZzivz{@X3OUc5L-M^;Rqxy{Q;WkUjadk8O{Z4Hb=O37dSpX z0&~V@v%=BQaT&k&9^*Ln<(nF9RdCmEn$!>g{>8uiHT=;Z|5DlCc5l%_H=hB}1Yd-l ztnT+=erq7E(2rH?O|m9@Ls!mXnI6K3Tc@{haw0jN1;`74citm-59d`;K~>mpxane^ zsJKZk-JrWWsg7?6j@qAl31w|G-!`;CC%l*SNfodZ1s>Ts zM{-su$fSWma7a9Z83>MXygt_0Uda~`e85K+9@pE~i1SwHn4>5;IU}hB*uleR5qwFr zJ=>aQZnNA{>8-6i2CH16Rwo52Wc#q93i&z}C6lp{o=Xk`U31n8-siV~dbgNK ztohEqPps~4T)AomGA6sBzK^Oxm~~91D9Oa){Rm4kcGyFYLE!Y}{j~S~H)w?Q^jh+IQ`|NSIk2 zd&y9(a>LTAV5wALuGV-eYsCI;mKycrlogkC4L0kp+qY2nbgF=?A(G$_OO#~>D3r6- z_LsENuLYq^>1laqJ!@KW8^G+(n9gH>#H(*vm-^6EDp(Yty>Fd8sPJ#z+bVtahI$`k z|NFx|fyi`Rlyd#Rs~lF!AlW=veOCj6U?DQN0u!szDsF}h(jw^wN^DJf55NO11EfF; z3W`&*7(L1G91~-jGCY9IW{uN(XE-}M!|~=GR;x8U2E;gH`&yD-rTH4y*H^gSy_T{x z(O*8jwClt3(*a*avVjgwU<>|>WrpxmF}tW42? zwY-EeN=7O!wnF<{Tx0|U^`N>FZm4lCVwQS{Y|b!sv!=a(dKEhD@CB)iUkAd;Hn6MO zow}p7cA)$VTJU~iu|7t%-dfBpnN^pJM(C9+<-k_g`Jq~|0R_83Ez1T-+o9M$1K6!4 z*m!WWa|9Eb)j~n9-IoE(0MDq|q*;IJUMR868sD5UFek~*oN`3eTC+*(fdb+NADjS| zKoVn?AxW!Ja_VLqg|=!<5rafRb_8}argRPGXPFb{0GGr994F)~>&P1$RJUjmx`WIC zWw6U|2sql@!oxdH@X4p|;?e!b*o?=ZBr(3;8Tb{r4mM3NE&kR0&U&~o8uux=qgl6l zQ0j!s{;+K4{rc{isDZPEq+`Do@GIG#W0dUMzp|+F`=u}bU0l4plF|Xn=)1U^^3Ebw zXu_Xd1w8rDd;`aRX*;AYx9Tx#H_yOZM zVi=@$v$^gO_JMCX7^$5v+i>+@X4KibN$6ZEG25}q_tmA)K$Xl{MhF?e3LylXoJg#% z^HsrVb+E^Agb$Y3ss|a~PjFP-pRcy($SI)9YE1;o++TIrO;%_eI>;O54K!hCz3U)g zR{YSnK^ehkFa~vR)C6f7o)dyt#-+Sn>m5)i-h(}E#!hIUSR+&w1!n*J-rVJWK5o3Y z$g=S2c5YS%28$Aq2*C}wJ&Xupgj2V#IZk-_>Sb{oZ8mZzz}y68_l5snV3K`T4+F9e zx0?RN7!7QcwX5JhrHpCX;e!u9#LxUke*?ewzx+?-nXi2DGx+*9e+PgFpmUOvjPMMG zWr%Lv5{>5eM%({(=(Hq%gQn2VJ$s;^LM?+*Mzy~e8={o&I$lb0hQo_IU_OV;jF?2w zUxf{B-@1!TQgfR;;lq#K$E)jvX`X?c;YiM<;2nZxoGuw$dv{_1!1eGo{=;o&$*J%S zw7}9h*dfKw(gMuP>d6L`A#}Xl0)@IBEuOe=cjaSdoTSBGG=;>zMG#ne1?n)G_7`sY zZ0k~gnm~GBTd+0OohOy29#(KM^74FSlu8I)`!)sTWzH zZNZBvU>2a0oBP^!y88|EG(#=?p?k>sW-jTvM-?oip`-n0W932zD9=S5uYu-9rtWCD zci#5DTUcjDCpNI!T55&PR!yfUElhqW?^97%lhkFdJfai3TKe6Kd#FC%(a7RmYQa?r#( zuxb%mF6stY<|IX_ZToRX0h$FYFp6hEYAmyMCUu8W;SP(>m$cOK zKrltG&3ByP*91t90NOpO;e zGM6M%b4uzRVWKx9Ws>*I08_#)PO#Ej&XXn`lTu+s8KGG5Sr0KOl_Vb}5P)HDI6d0n z!M%rg{^VVpKX`_t@s41d6q>9EZ;x`JxfRmb58+ zt0Q>wB|EOQY4klL;O>o^(FxM+K5R~gy55veGa)hK`ua7%6PQieWN!Svme9&-DRLSc zNUlqWNsB~QMkhzy$TG@vy)Pi6Qw#y!eh?B@Ue(G)<{6jFV+nGGI4$#Jd!yFzt$AgN zunm!i>%7!CZSU{B0GGU<%5x>;z=^Wb6qgd>gzlMoRxZNns0ucq})pspY;>lCn9)cu8M@*3;Jx95G!rT17uLs$E=1Iq`tceP+1 zdQQ0|HRIw+TeRzl7wuA=MH>ge;{Di9Z+EgT`CL(sE#+$Jr6>zqu+807j-hJnvD?gJ zVi|7>X0WU01`*YLRM_mk=Sl&|2Dp{4N*fuTNWEekA_3q%qnhzDJ^!fR>n&Zne~UG~ z6!Z2H{VvYuy)#;+=X##i&JnfN>|6oxq3ci#c@zT`VwO@dWL9C{l$g;lNa?e^API9! z5(mqfkWxZSglWf^b`nec_~8S*`^g`}`CHF$dU}e}-mh7_s?5D;(PjkXcZ*>Da(Q8kU+%9wqV&K&IFE{^&Bi9-bWBIJY{(2kV#@-b4m)h1bB0r zk>(7CHO|g9IJ5UZRVBwPR)FWc|>Lgi3j zCWast!dd~=4&Vx67J?h<-&S5GX_o5sdW}ct=lIm8K7}Vw6#TNlU+=||=rlQ$D+k|A z3)^+?(%$VUF`9siayZxi9zHbp=+liGMc56&gJ=-p+hVpzm7-(^rSY`@W6-3Z!vUiQ{7&+*V?%?f$9M8J!t)H0I9r}%f7PLfk?S_4^~-ua`6V!8s?6G7!zK-y21w^ z{16|0_yU(#*OE`b_9YIxZ7=(0om(m%Drh$W)Oy#CP5#OLI#eSb(6f5crny7MlyGrz zfq&;e{5<~8|MgqtnXi1|Gx)~e{|=mjleiF)L2@RR{kNdq;c?!4{V0}kX&2Rn3ViVU zatt=YZxIOOBJF?KL;B|4`9defDx#2`5A8gfjI_U~ElE+aTx;lHDfyQr??ujX z4(7y=yckl+BPn@i4ZUJi#RCDw(ivE3#x>Na1!e8ko(~;=UG5v3Pi>^o&Glza*Dh*5 z>$s&4To-V8zS3TQ8b2zavr%$b=JG~%WTH~-CTqWBorv5{%%DaFaA@|~4FLEcH)!8! zxgBf`3Q|P@_7>x7=LT!88E2lPmgfZ}`Cp}BE7u(2DOEnHd#mL0bWcC7FrATC5)4t2NnatTEM66q(WPo)QFa z)~iNCL3>)4T(m3R`=(E=kcUD5OEPAfmdp&V!U>VNf2kFd)Jm=#lZarI4M-U$=UkYF zm1P1q@~ZmLn-q+%A`=RXrwBO&L+yM&&GrS`kuQu(RxM9PiC`z)f zWz!Hw^@MP4i#bj3!GXMFD^H0_ePICbK8fI~+%l^L-jf0n601Eq(Y!n5dzrM}E{R1y z=8TlG(9vZCpCl=l1E6yr=ZJX{D>RZrPJ}cwI03hg*0}xf4&HwF2|Ro79Je-if$YKA z!Mg!NSi}1fjz(Cdmw`NLgw-3#+D^v;+}fdCLBJt_-Gtg+v)6)2fJ)){tnOX&EOEan zC470A@ajvyju$U3kWvPDaXT*wh0N{PN+0Q>X?xZ(>B5Ii@cNO2UIU^)yMS%~rX+Qr zSF1s?J^$E`;n}liI6jt`-<-KxNrPDCE3ZM>G`--puNm!$ZFF6H+zOn{cS~?`=sM&U z?VOZB;t(3;f&oN($s1@`C3>vaKd2w)0Vzp&q0S}EHgcJx{pJcFQsJQ3Q;i97LkDZ( z1_8p6g9}xeC;+$@6l@U8CiYSJyStIezaY~q{gcv2H;_~%1-h2N&{Hs6uL;T5~eh(LyuccD~b#ynJfhH8&8ZF~&czO%c zC0w4nIWg<99V%5es_!v@&Q=#|!W6Lv18@NzqAa|)xWK>rbH9N9<9C0%JpYwn`V7AD zTi*s8Y5B#<2LP5D-E4DGJA4z!-{*t-d+Nr$Wn(KcO5av#2hEb_^1n`bAYKYq-pG1J zAc{aDFflgX!>tB&b9V?~z{S;oH19xemb@UExF(bMtFgMuHX>Cw7xj{TXUYQ;qPwx{ zdBY#0NHGg4?ES4=pud}?(yAjbX-JDUTY8z2D=mPiGr+Iw*DdC}mje&2hXz={!YcNt z2C&;(6ZVprcJPee*lLx5(?aaJI#<@}WAMwR7fXQ!QcoauP=_aOt02_ZMRHn?9) zhm>whTHbWo%*lEbWs)UzwU?QN-r{##K)tMkbrdq53w3Aib;7*I zPaXFA-M&6&$xFpd2qkGPHT`ccuZN4Bz1hwlMoFU$0Ep`TqVbXf90fGAV3<^+?|c9} zu%-cnAK{NTc=F^K&L2F*om=;Cvc82O3?Q#%BzRY}HuF4Vnk4QwWfsAG7!l`$l()zv zfy@S20QIWX{t}7x+6YpByIQkZWi%#vFlEVrm^p#6#*wI|z<@B)VJ*u|41)Ei1H{Vb zGMxIp%SMuVaVd*!_okHY#j0!;-bG>Ox(xc~nWgS2+Kq~8(eCf945+w)C}YfQLX9vN z?{r}s&@=8QXu&f803ZNKL_t)l0z{3o6|H4%m`{6pmV{JhnK!HNq1a#Z3OY=px*nT< zS>3~n7PO5=hO7e*iIH|hNGytpIZ0BgOwz}BlJQS5fz*{*Xr|Ku+dCP-t7{Sxn8gDE zE_d!;U`a6Jt-K6bT&I^hzZ@$=03hXMl+h&yrG$Bk*zF>w9V5*NX$BApCr3wkc<%|` zdH&;g_V|-HJ-Q3x0nAQg6-W3m7Uh&By=rhCT9+p4bHxai5#0=a+sV7>;^uH&-e(6F zgL6Vm88PM}1S~DT0C0VMB|?x_T5=noCWEuuzg0kL`(p7p^7;(u0yQDK9k-3QFY4}<_j^c8yJ^Xc77Ko<08L6O7!R;M64vVv%3ESQLP|#m#&h8B zCg6>z3a(wR3$SX0JQFOS9v2H56s>l%R{9Q5|9QD@@p)MrRGvHZuA&$^FxKVO&aHuc zTE5qgiUx!-vwE;d&GKnV$TN_&Y}(6L7x=;Z@8ggE_>b`?-~VI0x_BiShC}rtI7Hjp zC&1L6(gj_sb&7iWsDM`11XrtXI~0qotRT1Ui_S%rSzQRx@B;zCOLyq6eBpEW`fq(( z`M+4xazi^i8^pT6XqZMj`n_dgG%3owB2yiv8-SV+tqg0Q&Np59nic|xuokNQ!{|nd z;W!KbKW53%5;MGaxW0Ogn67HAc_E|L0Y-7<70}g^yq;HC1SSB*C zU!HCoFa60#F(GR8hn<4nd73dzJM5-OszPY&uYsUh<)zt4GOldBSH9>}bQ?5^&3^8U zt(k-6RX?leHNgtKSA*jk>+^nfn=Asn1MD2Lur#BAiY_$e-`hTT3)frMrF)p{M=OE=s#c1 zEmM<>ukg!5GLM8^f-=HpMTk)rlUb{ZJVN_C-9bSuP-k3uKj%I+levQ5_7aQYpzbg$ z5D@}4n64-MKmX!i;=T9Y$L-BqI6gVS`sf(z^$Hn;X`00<>@z~}I6gYY?X%kmKEPc@ zaLSmo$2{-9x5bYJtSs&sI+o6*T@?f7`<`+JOC}JZN#0)&9h268F9ABzIH?d0pe#D% z3W8bvdfRp^b~wLbT@jgMGs=Wz2Q;7Ryi|eH-VrP&*VxHoSjD28HOiNJL6FEc49Z3k zLDva*C$*eHfJ!MDmCNw!dUN$>b7smCTgr@8F0MD_=Cf9|*STc}MB#J@SzTv~@S*Ep zF_3rSlD`UT1V12?0MmyDgBm;;C_Kv%=fw&+%{l#82ZV z-~9`?d-ed1JTg0YKOp!OLKxuPAal<3;4*S9!Ec?1#+~T~hSRL5au6(5TJxrMqT5L> zjf&;BNqBV=`2COn)_;i@lQ3H+iN<7UNWa=K?O9WxYeT*&D1LQoE zF;h9O+L+aP&=fWrfA4*K_q*T4_rL#ryuP{=!E6{r!9l5b0W9BH6}5T* z*bY-*2GVZncj6AKypMC)uXZuFa9$WZtG9|NfR<#D`^4?B>}e;UEXIhJFJI!P|H@y- zKmW)7pgi-nFMJLF@QuI!JK}*871%H^Fd=w}tu++e&B@YC)zHHF*7J#*=TsBNcW3ya ztMaUdKeTOWJ7#(F>I7&2ScIL3oPpp+9Ia0fZ$&sq82k#?*CTe*HFCNJmjsUj$a2a^ zQPz-@RMQvk@ph3DszReVS6U?rEy1eN#=c8EEkv)ObC6qbT$em?w`%m5YiV7dVXDdV zQ23#QB~jw;iDf+Gp7IJ-E>Asx)VkZ2#w%H~brNq#fy6)6_to@SeN|2~JkAbz^ zop%W1P`nj$7G*w1Mw}Dk95Kz};g#Dp)6QSJKa3|dpDozlqTli_J4v*f0Ys{Mh=8IT zAZ^R(KhMjCTNPg&eCvU*yvlb(Sf1<|sFfea5yN_gfd>p=cn)B4l3xcs->7re@4oi@ zU@%+;l3JIf7I9U!Lfdo-Q&TJNaBaidHM!)^0)+Qy(e3*~>mOCY1H&Q#+GcndPBkt=A=M@B;#&F z1ZLIo6}6NQJ2Gn-Bwj31(=wV1b8kJd-;0ZKv!UAsQ-132mJJ##uCpG(x?77%n>EwQ zCE4$7fc>GXxR`N(bCtPgTZ}B)-IRcslaw%mfJ`->2`@FTYF`(w_~a#f0OQ(wdz^GZ*YY5YK5cCF~%^0N$TeA<{iA>f~GBYQ!TNDSu}<}l1X$MSK z!1gtecED!k@Z_y?{KcRAY5df`{%_*mo%Q#W@w=d&un>06zEG{}k6(xhS0qv*uhi-;ID{ zi-*+BKe0K9$;oGoz3rtWj93Dj21wr^(B>quTB~uuqX!T1WAA(l&z?QS@$rf7+YAqn z;Dab8{Ll$YVmYe^zw9~V19}j#317P3_1@N^VG0;(1e-c{==jx-eyCCDL(i*jYRiPq zA|AmsU}m#&E@2#Blqcr-6nF0YGdz0q4{-nf?_st20LzQnA(6}{Qm#;I~_&8@=Kq^*MIZd;1VuD1q%=Y`WoLlhK6^x^HtBzItNQ2yu8}Eya^OR z$GBj*H(mmI#S&})SaMzvQUtuq7>5;(H&Xg4xDmk(aCn7j%1CJj=cvk8vC`$F-Zj>p zqNua@zJ@ z)cxMvZ=p41{ns`aZ6d^)<###8V%aYJ?)zuwSWzD6Ke51Pq?pxWnh|qU8MFdC5RjA8 z95G5qV>5PUB$L;uIiaae;2tnp^7FiRPxW3=PeUd+O+v~Unnhm5CShbc2F>r0VnR%* zt7yUixO+7h`k3r3Yl*w=7+)xVtBje63jpr&`T)gU-|6qBEO5Ey?DhZ4t@p9#r!%FI zS%RoE;+#XwNsLe$A4lGUeC4)X_{{?N$={niu;s3L~GpzR*iI8tnsL0@6rnSvtS(5d$Zk}!)+RUtLLjWhl?eBav{rG(Zg-8@&?*<% zUEE+ZKpH>nRMU`{#nr30ylc`SXxSNC98Gp;n?wVm0MxJF>Eck~j;OdnYt#GMPwp25 zFU;G88Mm@zH$S;+&-wj8^^(1mTp5$aCKQdav#h30-H9yOf+E&z3|TrsOrY$5luJyu z2_NiGaI0BNwcKXS^If`SuN3mS)AOqNp8_-G)=$O~ojJe8vF1$`MVT&d) z7U36~kRpMQrGJ=PsxXg|sy`sJM8^jT$RVj_KIr)E5LTB!K>`HM1mXy!fbk$Bt$>{n zaQ5__c=$aJQ+#n>lm57 zY*6jPN)nDL0E<#7=YW(Fu3f&47hik{&pr1XUViyyT)%!D01$^-)7UJo1Zpz2_H?UV zO9zX}TymCDa#oYI2(PvRjliPx6PBn5rJ9Flq`X4ImQw_z!to;n$y%J5aqapweCP)r z$G3i`6@q`}b5G!Z`{n-=qzODXdfpj~0Rv*;L*|r!&8nBaWk|gc-0#1eZhxyoHudbF zwh<0tzSYwqK$4>@6i%};MVxm4W&{EvMGPTg5eHnm#yB{*j&U<8?bm7!iu0FG~p$)Dx|48#5VayrWj9{#!R(y1oBG^1qGEy3g@SAgjDX@%mG|f7CV|dBb-P3V% z^HG+Kicp=Yn~9>-lC9j9MDJT>b+{Gq{g!Z#=2FHJKrO*z4N{>;SuH}A@T^xJmNVhr zuVXMihc#K6{Hu9`xKuEZ{)%}(aYGqtb8Z4d;*u-03oa$22SML$V|wdi%6r**C}E|F z_q!UtyHkBXy5w5@U$8L! zy9>hZ?k;wBk7I}n5DikN6DvuqvDp_ZNXX!nfRT~X1`8S_ZXp9{9kAMLuzzqF-+S|W zc=4qL2FpIEgBr&XtJMnE53b{2Ut)qKOPV0F#UQmMLl|@sC5CuI5o9$b{W)-!U~|Q_ zGFjf-UpAy?jx4)bNBFG~0kVv2f$fcUr2>Gwn;S+9FeJ|~p`iM#t)Fp@_FeuzF76H4vJ2-Om2#)L=#bU7l6A;z`nHggmF>E4&1-xg} zTEUuMLZGeqwjwVXYW3bVUSq)Kno1RE*8VGlse*)f!8c1%BYYK!BBeA z2^#b36fa;a!=zATW~&*RSuMpV4|sy&FG1eb^?B3;A9KR*PyYDNVZGr_$s@{#N;o{g zw18BZQ`MLnbKjhmiiEA~&xGLDWhw;Sl6EbZOWbwWX}taIZ^yawlJVX$yVtTn8uQy& z3aN54rb%)_m7Lp3a7>xe;1I|4ObHCRkl8IvGmMw)1+uD?vu0c2%&0Oc!{HSR)VvQj z4*(eAK8E3X`5wXwA*{BJufK-j8iwH-?z`{H*x$c^7cTy!8|yY#sTn4^4Bv5J4#CKJ zGd}tF$F`2;si%Ke+m`Q!r$eW9?k&WJDkN0de##l5R zLm<_^bxe4}$N=RD{T_%wLoDa>%9Sg4|3`lqfAV|3)vVWl{N$(cPPX@agL*DXf0tVhj@j^ zx;a-o`CK^mj(4wPwY9gkf`irWS?+1#+=8^f6wgjnp2GL%;y(0D)JX{zmU;RFVMJ6D zJrQ;Am>YQWLb-j)nU#OqfEnW6Y$g0`#q>R=N1f2cpyx-<<@6MnDj6j|QK;qULZ~ts zlJXLezq&NS=mN|&Tw+d9WjyIN!MBdr_@WFm91T~m?7`BcCykQ~Dr^w70q};nCbfcL z0pdb{mP_E+k=t$Y!eXDN*MlejWv(p^@xMLYlvjbfDn@m ziAhWxFm6WBMq*2$f`bHy4;o`SVx3o_Enxy_dfb%FT~wHjG>R2Co8f1U$1$ahA~a*A z?R!AYNS0hF9!QM2>JLfP*m2pv ziOWOOn!zC;E(a_I4ZwHpiq@XB{;XI;OIm$KsY|QJAEYiXYoL~(QkUqQ>YM9sZa{&|ALyzhuNvEWnG!fSu(MyE{8r?k=zx7D70QFy@4?ic%toHYn7? zZ=B&X6^t#;IF}6MjDU=h5+X~Yv$T;+t7(+DVq(oOu62~dLX#j25(`ojXsB2!m<^PG z$Pu^f9>M85?!=?-{}A5)@cVK1T_XIZ5g>@$vy?kp2(WXkVl=D!nOmTlBhtVMOfb6< z&uyw(BjEOq+ehVDn#Ii7lJlfu`ThJCro!(}eEMgx*^F{V$uzDmlO-69@N2?50n`A6 zIZru{2JoaboOhF}#K*gh8PUlldCbo45^uZvZanz*ci^6T&g0mz<8r35c$G-D=K(Pe z;^yS*XtYBt!nNFL2>|K9ro!)Z{5NyWF`YNM2txRbA!`^8>f7=ft~y?3#_sORO$}ga zBVx6>1Ap_q$8hP=k0SFDoE8v-nQ`l_{~mXp{yJ{C_roTzdHu_V!HpCCOIrGn)H$6)?T< zJ0}DeYrD}4bNf*yU7DVj#ISk7;JpDyF7H=is4|#U_-q9y8&3>EWHy@-SFc>b!yo=Z z{MjG;cC&w9`s@?<Ddr05o7>i|5)4Az~P!tWh4p2|&)+&wJS910;+fB=yRx{9+HMt*)@TBX%Qh zj*pN?z0XO90|m5pISSV*%^*SP~g zYO?OO^JwmJwW2oj+BTs^&{4t1^0YKR&b(O8)LXlVNclTY-y9P#>8kF{wz)L>2Y@{s zQLj)k97|;m6}$9%&+QZq&v6~{bO|~-V(#%39XTGWn-BvfGdQU{QVeL-0A-31o4b9t z@?^g4-ZN*^IC5sK`D#|2>|n;9K{uBkznM^O6SOmJ-lBtsSrqS4svd=A3~Q88q{i6V zV_`A-tKnN`_?vRiSWU%A8I0lJU@fjIKoNkA$d^PuRIJlgFwa07AW41#Dbu#V&dxFH z?Cf9>k72o7VrO|w29lFzu@&Jhh6o;5YvKaQN*5_J5h1aw85<$g0MeL%jU-v(9NU-) z&F(ky=!kp5W@AKZqr#dnn(I+qu?^VDg6TYqN2_j*#fnzIkQig4NhK-G8d(9QAR-O% ztkxnya{_t3zR61s3Z<%KBGrYKx$H#>!%us=~!IoQ+{v8Nk-1 zr7{s_`IXGHo2|m{r+@4pW3?XLFwFJ2CcUu%7tN_+M2Sgh30BaO-*X!3r zI*fTMiU?#(zjBFE%|QJ}-!0bzZCMk$_w-Z0hsU4z=;U|1o_^*Vg#nW_LW}GwJ8lh6`t-tM9YCjn zvvC*t($24*DajbSSxYVI%)qs)*YVPeFXQ>=p2I7bUcuhpzLbWG0i>QUqPaJl8tXY? zMM@Q$c*blVmSkw8uI21#rZKb)o^fkdgkw9O4lglN$1v5{%8AhB#v1}*hymj`V*mOz zJo4Bl@PGf|ziGz&E|MFLU6NI2{g;dVOfLIe_xyF0pvsjKNd*8#q{+ksPZ~iJv zg)aWF{3WHc0g(pvkgEL$QVMO=XSrn@M~6>c7J7W ztVSronC<9jQL)H=Mn7n3<|X|KG~9+Ubzuw^X51b7*OSFAG)PwWhd*<*J<4v#3)fuHbcZjqcBGafRLjo5gUZBdMhuyKM92Ux$aCM}#Tm8oH%8#g9tL zsa3^R?vfK*#SBkNsxlcEk|u&OYn<0Fc>#C`!n_k{VyOYxSrT@3j^N0Vqd0m@EWW!t zw}P3mURixkNvyG2tubyg5;BM)hQ%N;L?(r@3cyLqxumoaw@@0Ds78dS3?(x#j-~WV zart0IPA!4iY$SG|WT;lH*2V;<9+a4Y~@B9uY=ZhG8Y@rd7#| zOpK`W&J>WH^IO#N^zQfKkw-p&yYD`$ z!Y@D=#OfO@+jE4uJsaG%j5#&;#4=n^IjWV)k$1)0HTxo!#eZwen=vHfoidK2l;p_s z!tdYv)IY|0J-P%t62B{T4i#9ut7gHgt)&-W%nj2c;#>rFuFM+uxf=lrc28UZc6JuH zrFELf001BWNkl-1^dci#n^KYtd-j~ywBG}Drr+p`H z4re%Kz*^`T(jLzgMiQP8#DpoaP>p(SEAfH#RmRzdZFp@zGRWpF*S)yBMYRY2Ko`@8ilYST8&t&bFbwZ$)Q^_mreXPyBtYX#gsKo9S2 zaZJd)x^6M`L^wWVprl#Re>R@KU*7)+Gh2Sx`};BC$U*XOh5 z1hRPG%o$k|reWe`AeY@0Z&9oEBA)>i87S*oQVigr#v~1+q-gnrf+#vY{xvIWDOE;= zcGw)MN2^l;G-uhn;&)*P4o?{WHq-~&zvaH=W#T$M02m^0 zM~))IBRE*CaIkkB>y-!)>$Rk5w?PSkkrEaGqcZZkIV)i_M7vxw?y(BUWW~WLAagu< zElCnHfseHkA-?}OBdT>yFCG5)^bJ+92|^Tgaa(%0+9ynqznXc3(Te7v+Vz3sOO>~uvC>w z20zBoT6SxOx_vXiBWl?$2XmlWp2^A)h&O>Ev6Qh{k62${A&nV#oxBt8dhlI%_@PH| z=B_hX47=bA1R4;-qWmK)Ac@&z;i`qRYTfERBN`oY*rtZvaurLE`)*fnp|am|${001 zF^>jc?e$YX@t4hnRZ zsHSBqX?t5`e-6L6B!;MK0C?un+Bf7(Qtl$;k~POOdR5pVE zyIA07p7{ohB`Z7Vm`Kmy&oNVT&&@KNGu#-1i^8&Gdmbg*vseZ)u3g*1%P(ER#pf^L zl~-QD>fk`Fz63x+K9E%T?4BU1FKLhl6Sb_X22r+Lmhy>uy*C1d52!@EU}zvBZ{4AdZl9nE|Zz=hJ3| z&A6%kb>)HlVKMI|6eSjFdB}dQCg8ffDYjO|(3dsPw%Gk%`kcXI=Em+5g$jdTae8%k zt)DA?65?*k8o6a3#BJFti`&?K9lyWh-Zde`&v!DHZRf80La2O4`8x&2LmI14Xy~PU zn&6r`uD2qumiM;^(Ki~W4ATom&iYOO@mwOR=Iu@~a5MakgU6Y>b)9BknOxo@%XApM z5G)znsb+l!8k#xfW&E0w8Upp1!sBVew255Q-VmOmwH{K7XjSOdgt;{ZjXPF~MkRsMTDODL8XVqNFd_oXcTN8*y zU{0DEUTStxmPPRhp%;8>p=lJR-}*31EfI?F8)7JZn(!OKfN1W}JunhUw(Ok25?orM z_!8QKX@4a_Qcwaa_Qzxj341=Ec+HxteUlkpg$rNGXf{K18SL~{$_cm5aJHvutW?y2o%BQ@_ZA5jVz(T zqK?**UGf8stU* zMu7|&nD9-exGSqw+affuM5eK~IZg0!3#);=w~yrn*!C`*U|%iH`49o%M%Q63&hmg? zFF%7R3sJ`H&gl)?_wWBLgwq-25D-___YjD5oa#@m>*? zwoLeX6)p?hsd5d5X9z{Wt+2tULbxGf9|Jh0J8lNe0HPnkmRjw znU#ZBg_|VGq~Ck3OlK8 z%=H{~&zvHu{#E$Px(UppsA=|8&mF12T)3RV5q0-&bg>AoV+Ib8z`TdFNs{?G4wB4= z2x%OV(i+Sx*-#zRAn{;a=hdx&;TM~GiMb(}M{yi8n5K5ld4$BdlVn5QTw|m);qBtRy07hHG{IZj z2->#GGO=!yNzX~n%4a_NgUxe4^%MUIRtKBXM`o_DZUSu?OBK3=X%L3qaJSdcT3t{- zCmWZ=6O%}1<#)-H>GxOWuoxD&{r1~&@4ffp{Q2{^?Y5H`hM}DQI1Gr3CBiUB++edG zTQ25uHX1>o5RUHb!ZLw6=FSO)N;|c0K6HPJM!E09y9eb;VET7Gez5}Hf}5x?jZKZg zritwwizmXxp2GG{EN|@XoyWzCpTRrdDOTWP$DYORkr#3O+C8rQd10ZJtk>9VR3IKlT)lD?FTL~1+uvyYtel=hpQy_vh+HU0|mHuS!T7URMFN zz;?H8)DEvQkBwqZEWtzpDQ6t45Ag6uK7l{`xBsRY=@&oq1it*MPYFMi#v;&3lj6qI z)*p+gI8vB-1Yob zrqFPg@Z0K%7Ah_Yr6zhuyU6jN($z*KESyk-I{ja3!GZJa^#21SGz ziwm@^fnPJCK2O8+@@LH}v9?|PGZhA8K|J^l$BrEpVwlI`o@xh_2yL<5~*c7AY_S^w)k4JipYkv5MMW;CZw7lGdm<2 zK$MjbNx*FK3=`E@UK4)35Y0+(Ob`Zu=-i%7xb+FLfa+>(wMcvIeh2|M5JC=W!J1|& zwatFkg^3<0;TZQ1wmRG9xj!b2=##1IBCaZtn%2w`u)Y6Xm= zme!hhNuVeW?Xs~<6Vg?rH)V+D=4>yEE4K;N?g_Wf9WMakwff|wMS$n7B#)zU)Ge~r z3ihMq^8bo&TZN_Y9wnKat(7JTG9_=FYZZp5SmwJJ>}KYe8IS%pfsxrJ4!ySFsl$Jp zDqjCKg0G=aqobus0-9YYJRg_Old;-Q?l<+*yrC*{?(#Hk_P+gOXAG^|a|msjHObM$ zllE%q)Wb(O3GZn~G4q1Xy6}!v#~M^9R!>rjmP2UToKsEG-1;4j#}A_^o*Mg_V@O&Sxddmlm?9}N?P(mI~qhA5F%l* zSYUT&KwJb2aR-ZG0SYVRaYW7=B#mjbLeCOE*AmrcF9J$US@uSSnX7o{^JIT+tgsLM4n$zh2vuAv^xdd2gx)oKLL@>! z$o)cW6H=-GESkysn<2BDl4iF54X!!)pyVb|y9gkt;6&Mwdh zoF&Ga+isa9DHW5(m4}Vi?}ci%NU}jM2E>KAW@e-@U`!VCo;1CZ#-4L~rkWvkyjsw? zknz?!JxUTcJgxvvggZ|i$0P532p@jz`*8n-2e4cm(K^Bl3~_170naetgCx(RTXagyfx_9h^FK8_u6UkMrlwGzB!h|H2bsg%fSBL84SaIxpmLIzm9Kz`{#kQE6kIhThBOkLp2793S%%8 zegQP4k)HY5@7Hmn6&M?#1ogg+y>RO`wthpY(gLt$C{9}EcZ1D(EsEkS$^PDa<4wHy z;!Ak$x##fOtAB&lY9%hMk&xBZnMPUVoPOh(HL)oUuMw;q}*F$M^ltL3?{)) zs|=h9&MjW@_w?AOw~j%vqcRv?;q3wgoJe)3kTT=2Lx=4g={N-qT0vHM5cRleax zRo&9S&0D+;E}@1ZnxV>Be+$l2ZyaAGqOfpW*Jg%(bA~3xZRybbIt3k{g&VkW zYSk3d7+*6ARpH&AC-HVAQswl`k##q=T>3UT+4Gb2Sq=RRj?pNBe88|+1W;IDNIN2M zVS}6#hNMhsmIPH<6G)M6{Fp{yrIs=Z7`436IA)DC(!NG28@5<3!MwyGEilG_^_oFJ z;wi^8BBc>DssNo5M$JxbW%B&K81Mz<-E$4ga|_^i&jUrbs=d|F*2=A^&D&^CMKs^3@P&^9^hOj5gh?^{Hb^viM0$!!IsIr)P7u!E+YxiiDF4q{v)hM~ljnr3)PJgK=~kxKnt zkj>%lWPXZp%Sjja=9o1^e{+G zZBtfZPWZjiWqae7aZVtz`=}QE=CXNkWp<~JOb17b2xqOMBn)d{Ej=aLcVCFcYKpj;9NHu%GEt%ekMVapU@E%T%Jq##1?mS#A|a#oNkAlSiy z&!-_g${gHEe}IRx$=K}~&T7$^S$*=KML9r}F^(I&`Q{t=z8`!XzyI4$muJ5CnaAJgHm0+#iOtvSPptx_;w3Pu0$K?ynLsexOV=mRfP1gJVh}4%DYYVWo~HCD^Kt?##M7+c z!7gt@QB<<)!zB=Ht%1}g{vm)V7a_Oc`d+~4F3zspUP+E>7IPU7S(DEWg!c}Ua(w@*a6@H5%-^L)x_+W6) zbKy;M98tGSZY`_uTc_*sgScsHP9drppHUKf7UEed)cAAN^ykJ}l^nK@j7YKYr2aV~ zxJn(e28^m$EBKc(1_}hqF4iKS~_xs+b=7F?-IY+9-XLSW=vV~+u786+SCMqtT0 zowFWM&*Qqdd^z;8$C1>ED(6|}Y>aqiQUco{srZJKcPi(&L5h0*d~!51Hv*!kPVM61hu?$8KJ*yg ze&GQe**&JEjv|I(iN&ykAubVV0IAzEcZfo?gOZe|j=3H1oMx@wpK)8lOah#)jR`}= zR+CO#G)INc&wut4O*^0Y2mb`ut{n)Y6sn6pkehWkoGSaz4Z(LwMxmUc3Kf+=P@z`y zM8S`{p4)^mjTnXjCr_Thx$|dn{`|Qj`~swPR0sJt42WS`LtMEpcYXzL^c+{AzpO0r zL~2E0G~0T?aAR*C$CL^ie&`e?FycDHh}d|_lbEf)X++#li!-;e#KyyRLd)#c52FCU z9A_2U#AYPtH*e97H5LN57DjwO`NU%YfTy4O{qoLX!tm42d~+7EsGBDn^Xk%qHjbRU zeGf8cq>V(dKAJguF(ym0I1XJe^ztlvlxT!DRu z_Zneh%Tbc)xdn3LFv~AMLKh<=as-)=Q_f&sfESjG>8SJ@L;;Y-HP)-OhP1FK`rVXD zd^n7Lc+0sB$qhVbIj;rTvq$ws0IvIsA^-y}hf7&lPfu*#QJd$P%($)}R9et1GQ*X= zaqCW+Mc18o+pdNt8Z9PFj4D>frU@Z|;Lt++JbY36SM?%AkTONd|6A8v5`OQA-HH=#Ou&^Q>bJ0u@Kk ztwBR~CgjAD=DN8QeA>;?3Bj;T&pM=Xy109fUB5=~bzao1X#gRWjPJROz2+^FHzkit zC#<{kZi?|CC#?qsMO>*Sk+JeN)-VwYKFW$vz#9+|Miq#166F$&LF%qm;(lEMB>;_!bk0)BX2O(v0mmFbX)XaleP^@#nOQ1|HoTQ>U<~SNP}6C7MoJKV6&Q1NL_%Y41M1h27_E8`x!+?H1h)v1c~lrA({cmEA|N6FCr|C*z3+TCzVE{y#ycN)CypJx z1!*md6b8xmJj5l2xX}0~&*Y&D#2CObeP*rmJ9DuJQieFZAk$wrA~YUJGfRf^jn?@c zlUNMC*ttD_=I{UKxOVNjBwRC>U%>UFj2LkfSC$%P(2c2!oiT40Pl%XnUV?T`73NtJ zkfbCqaO%`;IDgMM+;h))+;PV#EEWrGSA^eT7_e9j&idOktd4*+YlZ?dAQgN{+@J|U zHW_V`TE?c;98U$7hD197$A9Cp*|J&v}Fl8+K z9OwIR37_2Wb7ET453{;GYr?C|2IFQFyfr3Vy?Pxly!ZmX`<-X;lB2{q001BWNkl5W8^QTvg@YKJ^&v5p8nRB-mIzj7Q`G18OV=Nu)de=JA z2t7S2dM120L)&*zK>Dvn6T0=RO6&TIo!@aB@y45P;`@K-$MDU6U4`H;eg0GUSHJRA zM2bk98by7KrZ7ekka~;PM7V8#o$xtx&-wGl+Gv?4wq#W``1kA5KSgTPAjSYHWeUwG z8-ob>R>Dg1I%F}LBrA5WtvlS;&Z#|%-m49EPG=Uu3%@-bsxYQd+W-SfIVIu4tM$GQ z9rEkiUyUGbY8!>wmV!Y0bbIXKK-=lcTUQ<{8{b&lF9;K8&Vnf>CkWBdbwxt6b9$@S z|DOb3f6bkb+2_#WfN4ARIZ`H)QO^?-HJirvaDT=pcTj1ndqo6GU!|q;Z^pBfJ{&!% zCAHMh!PF$EWjJ`!xKgWM@6R4Hmn6O>c#8q53hUnbOU`q_-YL*;8K*;yk@x-7weh&m zl)+hWjqw>}nWu)u3Ex&Wt)819c-4oz6E;84`4>$yj8KQ&wn&-m} z*?ZL5&x@Hc3jq_lu%xTiCf`=5OLv2yq6r&RE5&dqdz z3fkdmZ26?8If3NRXWC1IU&dyWuvxD$jvL8J51~C*uU^N+ix=_icb>(iOP8=-t&1{7 z5~?sHRX>!;@K%PbYg}nqtMIt-SiRe;bzunFTvJDM!at z&#)!NBFlV8a7wNIk_ii=d-(b6t#8b>zV(_b0o4m=L-Up`zfN=Kcye|LMY&PNQWWD=p;EjIgT+{iv8XWq=opd7PPCU7!0o%y`yvQ$ zyC#DD%_&-@{m(yh)3oI+2;yaaZ&7&v4;9jl{(Ai3E&7w^x3@IgHdC#8UH>_Ll4x%G zfjTM$IpvtRg9UH>D*|e-?CjGWDCPHt?n5>^%D2jn^T)j*={?Q0%0bJ0rK_nb45_9xc83?4_VkI2nli%&iw zM8=?Ao?)Q?>jq^;Asd?U#qC(C@M6NRC7w!S2eVG1@d9*opN;7@Yoc%0E{T7)zo`+P z${0|1HDCsQh*SX9q*{x`QiUWv%Q@lKmX^?JwHw673`ySrWR~PS>$Sv( z<(wzN?-!r^MO?kQhq3q&auxna7*oseTz)5pX*{!KebzM)cOD~Lo>6qJ<~sf|FFl9b z=Df39;+9*Fs?DA*JvKtZe!teB1W18&2 zu8q=&?Tvr$=B}Q>uH(BgLotB|a5ElIWn>L*34{-S_-AqC$R+&6U;H9oef38wb6)1< z9Q>)h-!H=H)8D{iaTx%xUZ2DZ7k^Te3fsodgik*4AppQLPybud7wQJXK@r8@{_Fw%qUU}se92^{|w~5u1l#+g2GMdY| zs^`OE9B;hO^EK})gC%E51v)Aeul%)~8unh+=+KHoSUifT;+(psF5B>AF>4%Hi?ZV!+55Fec1kgD= zSjI?xkDOOg<5CDPCx)*(bJ~p)%G(gi_DG%{T4n$PKRlaN!r_40{UmR$HwyMa7L%>#izg0)b);-yyVT zxZEv!WUl_k6G(^Fu4I)?2tmRcgBOA!rCsF}J!5(fydW;W>zN4w2<=$OeK*<7w<+W7 zVAcU3DdX%*zRoG2{P)7j))otm^!JE>f!Qp!b+UdyWwC>LsAl^;Na>N$l3$G~0GWHV zyqB`X1JkIQIm&KR#otx>Oc=)mid2xN9X&x-GPZ#tVhl(LNNL1+HDbNlG^ZjH%+P3a zZBGrM2)66>3e1dktU~sfEKUVQ5Stt+Wn8SADzDi_RROdxd|g?GM$^b90L%BJfy|@~ zYldV|%;mjS7_F`svA7DGGQ$h5fe2Zdaxk~C!&?xCX*DgPB@t09pP#8YCqv&3?-#A2}&W+`Q)aSa|5jvqOS2kyTgkA2`V zy!*j-;^eX06`=%#Fi5hiC<3r(^z5H4m>WpJUhO`bpl9nkM@a0gsaP@35KJrwB=N|W z?b#T0&Qr_p7e4o2;`+6HjN>RUUx;{en!^nC<&8>zj=5oWOm@XhetLes*_8?N4|>K~ z$}S}=hKO5ky%p!royC3k-h;bNpT^G4PKkdHA!1>c-!K%>w7J-DT|4gf8MpEzM5l2j zm|QinOFK_)UZDmKW|$Lgpx@I98yz9?nkv^~Ppn!-&WMcB2JKmWwLbQ-&*Ipz=K%ok zdCz}`?|tv17{{Y!EdH-&aEp?_^?UT_MVvkR>*e0{>-S-Q|NLZ(HonI{C4%qMU;UP= zQ`|0kozIpt6R0^b9!8Ck>RRlcYx~j<)))YV*_?3Q$ldRwUf1}6KO^X1F%_Zty_nVH=JDcd1@YL*Atcf4p!$l zNDhk-kW2uM0XZ+QSPUZ2LKMZ}Dr4{Z9uAaQwD2#o8th!lNHzT%a5yARAeRuUdZGza z@5Wnjf)^mG*9~!2;n(17ex0@nSpIC<8L7W1KN#y=<}!9q7I+WqoZg~W6ZxG-Edcg+c4_1?VI zyS>=`|8I9GMs2rN_tcbPL@3Fmig2mCxG7Wml`y&|;6TkYf~$g-ES1kuU1AwfW1d_A zZH|(t<6@{mR5QI7BbmtwhCS?Fuuvwy=BV&tf4l7XRpw}E%XURr70zovek~N@nTwn- zaAr+fmDPIJZmA&Fn1BQ$ z!Y%O$T0$hofHVdWqSg~05otsS;=Y`M6M%rqfP}i{V*+>utT$^(6Vxo6zS||(vgWdW zj=Bz67n?YPSYo0B0Z{|7eRfYT_|{r;YB5dXDjZ|o@SNLB%L1gSNf?vS39u~t+AB1y z9Rt=70){UBw*pRGcdHi+Kw^K~Wx}&1Z7`SWoHLRWie!BVA?rcT67LEEIA+lpMO$CV zJjzbU>=A_*JS|hWF_Sq9%t8$L6$2Reg(+Prv_@%53_uJLA01*)K|oxR$DENe7uS0> z#ZNCw7>)DznP5rrL}?bpeOWvu7FusvT))zovAesA`|rJg4?OY#yyO0N;+EsL0Xa%` z>aZ&%#p145ey!Azl?!1*vYxG>LQtkWmOjT*;_NRf%*G5uz-DXpOsbx7NJzstjvAY| zK}rcve*QQoO7@1;5A7~oy zl@bKS+W>k-sW2l{tz>>B8)aU>M>@hXIfEPaHu>pA)OzhGgWBM*ASGvBdg;gUzytpr zA#6aDar^CG$E8c3Y{t=F?fB|-=bgWcW5+I*?^mz93(N~W`!c^zKJjSz{pqiMtG3xE z>6&z^%(I5|7$Ya+aOZJGIPVrm|L~T@L$eP;!$*vx*7|jp-<&h9UcH9rpL-sE{ny{d zE3dqQ^?IcYi@}EG?@*zGLK_2Su9-3q0B94VnMJ8EW{rZx&q>dzja!ANN}TIj8Nw{W z3~CMx0L3-1tid5nYdzIeVAEWhOO{kngF8H4n^^dOR`uj>(y&l@#x2X6o2%M zuQg-&;%A?jA0&XMp8gj6iU`Bu&fx620>=2wja7b~hqP8dQ1KreGYPJ%XKhV-SL+VN zfIx%dQ>CRNX&vBv?+NcYTG>ktxr4!Eg?~{LrHc3Ld^buKW!l)E z4?kf5PDw)U4AfPsUItv?yl=>_;WnUiR&6rabTr1(D!-^Y_H06-#@|y{PSeH)YR|%C zZvbo=xqD*U&pK|;7tTMeKeqftHSTN?%C)^h$4a;6g`o^t_kQ`*GwhuZJhvu?DivY8 z8cmun?;g4UZ|#~>q*}k;%32JD`nxD7>WVesW3b8$=7^#gArzjwsK8Y2GC9D!Sj$|s zRFO?u&a^6W^nJm3;_58&T!)8PjC!_q%+_88a%^2YXL!kmZ`}stGs15#%arxhwt|Lf z3@NdcF3JfhOKfdzq&gOouB-jFRM+KUAjB{r1ZepZfK+JAnvg1`1m>jKrXinWKpX}P zL)2smVvhI2E-f?4T+8g4rKgoJ`qr86%O{SSWe5H*DTL7 zYp-&vxM^o^`BZ@|L=QU6hRtVo_AU^bZJD*SPOgHsjDKncw)=p@RtBz?ShLO=V2TnU zma<9xSPTirl2uycmA2%`XXe5H7*Y!%lvywJUPcm^?jVQL4jzKki!O9XvsW?6S{~+7 zUdQ0*luvp_?LWs~HSd-+WKn9z2rL#+tapp05<^+TOg4(ZE{t|(8&ip2h9eWnTa2*dl^xxvjm4~pm zcXlfiQCj3`$vJW2kMZDx|9$iOwd?mQE+G8q;~xZ2h2A3U%rL5rLUTfFO(=sf8OED= z#@&ePAq-U!nh&{5fjy21<0fG@v@mJy_<8sH=&h}l0jmm{R_O6ofwB)=+wGMP z4bzP|xO5}oiZlIKOetk$&2rATcI_%Y_|YH1zjK!0!!Aki7fV)HTZ?94Zt^;84giWO zqMmVOjLAO%6hg^WF{XFRz0#i&xELZ3t5PE8ETM3VC60#^*j*mQ?#>QkkhA*LFJ&YQQTTRc8yjUyfg=~+O!h9fh)mzlX5lbJgOyVxKcMWLCH4UTL!1YIeZ`8uxESXB5*okYg;3{9eanl^9?tCYky{cjmlTU zhVK)V*K&K}*gTkorOg+4Bx7EIS;v%NnW^iZd8>2)A%ImNE{dF7;aT2u`D8k;Sl?%b zW9q)!^77>Q$-7F6h$L~aB_0GM5#f+jC^Bo7=5hcnLDIfzk`I|+;mgl#G%nSUe@ZN| zmKnue+W5%8D4Dx50hDvmyb+oEt;EOVyixZ;Lpq=bLf??KRxkUPHl0iA) zH*`Qj3I=%@&b&Y05Yw7jN2fzg1QaUM=voXEMl2b)27EA2z?jjBv zoJ^vrj$=fKBLZ!(*{rbv7v+gZHkHY&V=$PiG)3CXDIg2s z!@J(`E}Xpe1dt-q2m~Gw;|^kwTEAem{La9t5R&Z#u|YC0>tOqS`D;upTIPI;z(Q#g zEJ~u}gx~dAtW>?*^OK+d1zf&-MckepTr!(bk)2Ruj3`%PV?^DJ8-T_F+gWdssAapK zvxwSX0<@lGLLkDeCvL^Lb7yhk!Udc;a|TC_9s#r+OLjG=lF1OiX<}!uZIqI0!U%8C z@&Bi~Ewg>x3}fG47CvFPq7X))tub!@nvw+5^`9G0t7zetIYcFto6QNl_S(mB?AWsa zfEZW!$VYw#&pr2#aOvewVgKNCT??uumjEDygp()#7!N$~&vEkPpEl!o_Sv7odmj2{ zcn|&=0N`uSe5)qj!c>rg``%=(-pWwPxnj<<=g+TG%M7FJ;i1A~r|ecfNzyUVRP;EBvClZ-0p_i@$ho zUB7-EANc+s!XJP0U(c*idnHX)QA3hE?{VX^%N^WKe)lciK;SogRVe<<9v7jv-T)y0 z#Gn`vm=OcO(e@;Qmb(BLi{%oGfYoM$gM&3T<4WPhLdRNIG}2~#&FmFwj+Bz+8Ysf= z9F%&RHeIC2gjt6Wy4asNplWRnF)$L6>%#arD2NRkrdS z_H2^~7dBlv7(RtX#j}-`75-n76i*a}fr`PbxM7xboF+`RJct)GE%P&l2&(~X;cljc z3`EX~?7haSuu4QlzL7S9>m%y9n1_|gc+>!A-y>P29D7z{fB{KX1=K`7rQp5NFv-ST zzgu}3QVrThvnIzt7zROLTWF9@(vs1*&0$7j$)4*IQ6{sjnL8_LTUH_`W!4(RGLBvV zRu9%XriQq?ymqr?)i|k-@*TN$*^LKvvIyD*V0$M4NF8)_GcWMzPvDPge$}foLOD4N&S5r z03|~9%vjD9*%JfEND6<3L;Y&xV3~`W>LMq5hqBBt% z<&=?%G9p!6Z|xbc<;Fy0ZqG6HIxfJDfGExMC%wFn_L8}O2C;>wDIPKZp@y~HYzQ(OiEH; z_ajG-@Rs{8-ZxAsb7ULgoQYoFQaSSJ-n6am{X{kmD)Rzv`l#DzSryG#n0f}x&H&ha18*k zSnT2c`~N4LJNFfQ?|UD?%P&8HG#)eV9yv2^yX{YL`t)z(mRtS`!?4$mo`4JZSNPg9 z&c(TmnI;VIl-DPenydQV3&j2SdyD)wONBARhn+@KPNbAH<~L!pR@Y~Z{k?ka8lHdt z1$^h*-^S~&yoU99Ej1*GkTt&q7dMS8``n#tKVJQ&3=%8T%8kx(+k6`(#|;=xJL6t> zE^QQk!5*$-Hc)KwLw!sHzA9kZFIL;u2*_lQ(e6=IzRmPg=$kQkf-|mNyME}L?b@Uf z3{A$USw!O@&sSKoc^koL7pUWf0sq9D&|&km#xcLgUJ58!swiPKze|viD9L{iK*21+ z3kls>2yHE;Q%tef#7B5k(<)Wmm%9Ei5M|AvX;^n=7Urs4X5=hdrbq>=*NnJx8e?4q zJan)!SyLx1g_-epp&$W1zE_3g?Dtd*4SmAerpKOPnz@>@cq2KmJGTWsZsr~8JZZK( z>(}$GTyr}+hlA%XuauJ;GxwSoFyS)^^Us&_!+gW#1wjo=M)NC!O2LG~{w1-#WrUeL z5-9hqwE|N0o5Hwx=$XO7`~7;@HshAerYP#nNM>H8dY)sGd&o+AIvnZB9kzn2{!aG1 z@~RX{GTsnE30pIoE$@4QyebpC031Sfi5|RWHiUp=HK1GuxX%w$he2B2=$g?Z)ryOlr+DD*=n zPgT$;K+-cfm_K{WY8BUh>^U#v7?g1~!IUuahyeqb69S9ta0sz5Nm3T72P|FN5J6OH z0#`iZ1&u1$8qmm4qGqMkVX3dJ3Bas~lbz5jeM~c}S?9+5muDT~Eu{%q#t>QJwC%UR zlEtxTVM0UB1NwZsqJ`VI3uLEBwI$df9OX(aHCb0 zS5-8+cJ(SY;|O!nX&Lg$c+X#scr-*x-fI~av-(njKcM0+o4Y5-mbm7~(IdF~ZKrYX zz31_^x804S$BqF2au&<5C`<+o>zJ{cxZz2OvqOk98G&jRYx1=;;iWWY&6^9yklFrb zU8c5eZ=I;{g2^);HY#Jom<$e{ag{HJu_RvE&|e1!Z^Jjf@hf=r(SL&D$Dait*4^FR zS8(RcZ{WE}~gaBEjAsWZ=Q6E}1i zk{LH=iJ>1iSZ_wGH*2g`Yphl)T)TQ5FTM0Ko_+Sac=gp+vC&dTrJsh_F(mnzA7>o~ znKGamYejO~5+}k55TeZ|<>5OH()AaLhf%GgZheL@*H7giJpJmG4W*yVV5(sfmEI{H zm{IEWdt;2#_KV8DsL9VZoAqHYlq+*mWmu>@QR%Zg8@3;Sa=4WVwCAYc7cO|Fj@_T( zLnpL-n%0uT)8JZ&ujbyN1hGu3>L)ALD2=wXW?{xj*f<{k;mm zHmJh<7bQm>XC3$4`KvGsXw0RS?VI7(3T4K$4wa!nz895 z7Q;6tNB~q5CNX2oQvSwVl$|kV_F}~kfyLTu{E5+i>u(!8o0u<(ONj}VjYxU)iqFg=h1l>uv$nxpH}!TgG0}A z6C{H))%e}w?(Pg~rGBtqEZ2@LMd{YXD3A&mnI+rmW|WMpX~P&(>!Hwez$h{2G1&MB z!w?ZkEHdj=!Z-rEI|I&~IfF+YegqFb_%570d56UIjsb)PV%)`IA+FCM4C1!p23*{| zocjqHxzQFdbcV^03&a0n#g-f5TYaDOI zU;WiT#r^mH3miG}0*Epei)%NSvo$Dxo`3F1eD}Lg0tasVXoZX_{5scM10oebwC!8B{q?`W z{@%VQW;D?uGZ(xnN>-o{_2OQo8u&0M`@nC*k%k(*$mJ*?040H`Mz5g`(g!xmuaE=vX)T((y@;jPlbDzs1; zzn?>$tJfJ4*}7MpQ{HDs1|9CRYoaVejUz1WC~W2=c|JCqq)M6*<61(6*6S7a_V#e) z>i2N@@|(DF^$J!8E98`wc6Hg8D*!elI!swsluJc1=a+3t--?o_Z)0wM)jQ3SwgNs= zdBwnF=yP(8tCH1C%=auqFQ~`_vkrIXiVL!3&~60%iqpu(QQ!$E4%$7rDSYmhGetcl zz_mI5{Oo5KZ+&xTw->lepY4>lzw=gpbL)Sji??^bMJ2qgQ`;}&n^A>As{gz~p}yLE z=gI@Q=9_-X03p^{3)O_d1Q`t$KGEb2lQl$;Rj<-Pt+Fvna=RgF6(7$tN|>uWXBqFO z0lF?GXhDh$PgnU4eIMH4X)Q~Ft2K?Cyams zySu=#V>{U0-Nnw%0&y6yUazsgzlXj34fgjF)~ot_=+2PMm)T_*rs`G=pd|FNcZ1Nk zA{YZA&Sv|^Vs#iG*^3yXOK?S!$y>+T9Iz52Y=9L-QQ%yZC}{fz%%Ml}C;~x3 z77JP4$h#`2Gem$K4T!ZI67@0xqh@xt<^zDJg5^*x{>?u3``%rZX^{ODjWr{UBgW09 zXujkgBaKpe?!bvOYliA^iL-ellv#pU^MmKJyq@|z3uKsr)%PVE2 z7I^KokK*;$KZaqrf)gkH0(am26mGx$_p!6{`lP*_BQ9Tl2&Yc{DZc*oU&G(|_-F9U z*ZwQ(OohR1^J$Zc6{1QgXJh+Xv}@aO@#w8vZ}qBHKt(ESntdn?2P_s#9Npc;=3s>} zjmRk%xX(b{7R9~7@LOUO#TO>T7kP;rnAkR7W^1#?g?Ex#ZP(+ZqPVJS>n*=NPTyRY zJ=|^cTIt7T!fUp5bGZ}daG!6tzTfX{*PqKPuv{MI$Xu^s5bqI*AvVDUjlen~F@`hB z?_3ubUV!?4SbNuROOC5f@V6r(&%L)^s*-G3l4WC7gY5>I=>eNhz1Fy=u_W`Qy9XK? zx~Kaun-4TJ#@J@eFoUHsG<=xH8f5db4F+aSV@YLMDygdO`<%>(*z;lU9goaBx5^A@ zm+rmiWM;f}?AX8kMAz5#i@UkB`$^kr?`wY;sN}3+L7Ko(V$&r)ecJ7?-EMJlae=e5 zQyiZ>#Odj=)&m|9vl&WQg;p+LKUK7AYEZOZoWr*&jJ9>`rmxNHV=C(ziZ=L8z!UK`zkqI zB~)G^r^x~T7?hNgRC(%P76_&@_}noe{3tty!Wh(dEVNv@#+younvxh}h6wDeB% znm8?|1I&wyS%u-JMX+JppC`CnR8N&v}pdSwtsG+%ss;> z435N|u*3jcoGF8SrKf`f;Le@fc>0-JxOVLt4v#he*#3(8vmCbWWTH4h}qSUb~KK*RCN*wJhYAad~lx-FB>5IhiF5IcduA z)NV#80VUR2r!JJW4wuY>S(P0KqMh-LUw!NPWwo6RKnTAT0<}2BHUXB+hozAqC04ey z<|Kz(wf;Jk1ZL_Y?3^#a(=@@YMxB8Y9AA=m>A_=kCpTAeTfK~wOfq)@e5*G=zrI8$ zp-HaF5@qe}vKrO^RLKzm-pW{VhW8#BS|_@=kZYGr7S(6hvQTppW+REpNNGv{^tB_0 zkA3W;`01beG=B1*{3Jg3%yV$$ktc$~fWaSV%L{|05ejY6l@F_HiPWjMqrXY z&)w78LrVTOA*US&ci+15==#jd+Q<>sJXv@Gcl)rwS*~t#s|t@IfT12zSgx%J4JNLb zW;Ub0Z{M|cV69u;G(iv%a(W8yzyC9M|NWoAX7dP}&G+E_2-^!eJEU|S|LmXrBJSS( z1}-js2(R6J9WTA~DZF;~^~D(GmcJ+N7ti)i;|AT*lJSat!jb`w{jyZ0ZKqWiLOC8p z_{mwqF>c?!4bB;Z_Xs}V!Gi~w;skL|@~Fj8q24j}_iVkChZL3p75*1nZlzZC^pBR9>-#gt)lokN{ZQ>CqsrUfiSz_JCoi>(psr@H0mByv}b zNnG>Ch;cVzx836W{0yh3XE-@I#_8D!E-x=IP9svDkXd8f$o7fkh;iKT@m6CpUt=Pm z$;8a+4p`6Ue$U$aw&fjLS5}VFcXx<3b={$?FuBo3{x>$K?wye&xbu2q^ z2K1Rxz2kI`<=hJyWWtd4sXPB$T=WEFTxq3${BeM;YtF{SyuZmA4etZGEmr8-02*v^ zHTeBOKVJ)puuVy8{b>7-X20&aD)_biN%gaOac`C`Y0(mbkE9&xGT%B8YQ=sfCIKU5LC5?%Z zFD|u{!nAXik|o7zSORzFt9F%rx5 z(Y0&1as9ej=ZG-vA|^cqsL8t4g3ZTW286|;+Y1#2%8+6a2JAD5y)m%dYLFZPISgLw zlB!mqSj&LoO3i=}q1K;EDN5~Q1%4Tjk_5VWEe-&v7G!b`tQN9d-d7V1kt4V)Oxux& z%g!zNb2(>Qd8YxoK1e+J+*(}reZx?=IYU#f?(WDv?MJBVzn1EWF^R^^TfOEeaiPk9 zyvmiuJG48zzfekhyV7U{!{$KPy8gFefD_-cYru$5CVp9h#?%o zy8+NrM@G|GH@!2h!OBTvYj1+ZKH0DpI$L40^ffD!=?>?$_f;X-u4$Uq8*Sgu)%Dp1 zW9vmQiO$xq0=p`hRC*Mk;5tQ+S@l@!R2ATFdx~0(bSt1c9BjnXWHW5k6Cg>9xH6=A z*r~u$ersn1rQPnDfnW3VC>qd}%LI&iz{%QCX}AK~-kMbp&zx#$sRDo-0MeF9192xr z7R3nAfTHI6?zdU_A3PqQ%oPIdXLHyyj!$E^yR&%5%P)TlckjNAR{8qc-PiH*OP|K8 zul{kpv8DAZjI(Qf=7ug8{a<{p0yC;`)Pdzz*k2_c6rg5F`N#x|<{F$>f3F=KVY3l> zegDDx7)Md&kyj50GH(i_lYXp>9td{Kr4v+nAy_Zxs^Jr@f@kG0bk6uyyAQP;vp* zbDW-@;_U1U+wB%Hs@1o}X=Pj@({#LWu@-eM>Y5fJ+ply|Ik00S=+}{n)H|YjNK^%l z&aAF?F+iZc$DT1hZSMt(Vz7*tnt5G(PttFHO zDjn9ds(P<^s?S01p-KkLJ1ZEJpXS=EF2N4fit9u??i&{X z?}|dmk>w?-9deo&uULvLuAZ8z6Kxn}GaLdH@LP;Ey>N&U=d9xm-Xo~RI3vT91Hl$6 zwE&AVxEA0CX6YkjPMF3m zm?OxEOX_YsM@qZO92ERG5=-s1qnij}=!8RY(b-~}rqWIT!Fi9t4e+W3aYW$Am|{d4 zrGUFw&oeI0&k?5yUdtaL0o&~kY0}!IxA1^SjNk0Jzm8kCR1&WP2?vsYF(!=T zgx$EqcDuvn#U;*9&vABkhV%0?>~>q^Y^5wEQ?z3_%$;k`shapn+M7xBr9aIYXk0rf z|0cLjaaXKtz`}ia@xC&_7R|1GYcfHX$!VUkbI>xotX-~|#9{$M&nu-;M(I`g!LeGZ zuYz*(aWHeSEdPUD?bvD0DZlpl3g7G$22TLES=)a6o#+)oE9<*&R_2PeC%yju&jGe8 z9~UaKz8fBYIkn(=SMh-x8aMb5(w^mlRu@($TNNcE`7B@v%ka2+)OmZ*5ANLw`~ z7(id%sI?52pZ!=JYFVVxFa0S=gblc&ygzeBnkMYV5mS@|k|9o0iMJ!F0(4tH)dc~( zJ^(`iHk*LKi}{?h7q=I+QbtZiLseF(4BCS<^Q{k(G{y%dmL|E90O6kLrsDn~@tM2r z4v!u^#1zjo^O$UiUA(}QV<${91H%TmediXQx$``RVNf>}(ORCLpX22Cp=dDG)ir2r z?Is-HU~_=$*N)(wM;bGByIs+4j+a~Pb~~J&o(l8Mx}e6n^ry=ebOM0y(&1Ov9qE@m zlad2bYP1>pN_96f;Xf&Wvkha`U5WFRtZ5~BU71-wUrB_cmf!+P zs2)THx_$2H&w#DHMHNp1fZY@G$nuP32~QcNTvl%5c3Y1JTNzxRaD$t}X$^pkLVe=C@MShWISp)|oP|k#d%>fP$4&nU(umfiWKTd+1Epb{Ej7*%X zZVNtw{^Ni6+8Yf&{UgD!4`6xd4 z><4gocmU^s7^B48`=GASzP8>9jxZ9V0?Nv|*u8{ua7ad2UJ!bni>t5h0M>bF!S8O| zVcbb#nrW0!jbRAbYz}~pWcAMgmhWXMz55tpvnqp4!>)A9>+?`EhS%@J zo5}Wow4F&~*F%7N_F46K7R~ql`|o0$E|GGAH}58xOXdu)13&?~Y^JL6uRULvii!UG zZpU#I{q}uW-qBg&oM`gROUwFVK(#*8zoPCfPXx9Fk zm=GjoGOIjUTu!n69@kPy*lta zYrjeZS3KW7OI7N+>Ku5yqR(2N_p#Ey$;swjNh+agRcmjqBmP#{^(J(0hi0N*eGn?Zn~#iw#~ zU`=Qw7KFy~s{f=erXI+HX7UPzAq*fVF4Hlo_E6oi(PRWR3Sn0FQU=C}f%6OG41`U9 z_rjWOc5V0-B7YGK{5l@X1fR`o4w{7VUEtuDF*Q7Kxz#?Js{80Pr97 zw6hrk#%Tm|A2(h~`B=Ma(rmFd>4DW)}okOpQYypJz!TMOoAkPu?Lhk$^Zw2G|xau5gd?+(GCjq~D zDC8({{oBhO9zA-5-EN2L*RSE34?KfIe<&djDT1b|XmQ?`-{pv0SD@5&nvL@bMVvJt z(tYNrBs*&@Ip!w;12-p1Bad zZ@(50?3`9kka+XNlf($7j3ErTefzd3cR9in;r_#SB)Mc}ac?7NvZdwwB@vb+FDOD6 z2n<)N3KWHrt+mO*MMUovqNe=d{>(Au$Q-ckyE0eLBP{lC10-Q!w+eErbf|o_Q0@x& z?K_ag^M*-1E3$&$rQ7otzVbV;eebNkd>FJmRl_4@>u$<|mIlPSNvp`d%tEvOYzo%F z?fl$t_v!kcHNKitMpnTx#e_IXRfOGc#CW;I<;4ZgFV1j!c8c@!GhA*jFvU^AM^wOL z^mTY;w;Jc&f311Epyf=q{8afNvxM+iz14>G?%8)MYktM&-4!Z3h`B8x~X2IguKD$TsCGLch0ytZ5WYtDD2 zv)(zCp$(`yISU$#aO;K**uEhJxUSGR!`?&UKHcC2$=Ok>!`NJq*E+riU{Qg!S%slq z76lmFvqZ(nz&RtTC$2=Y<^pyvE-r9!ae?i2TV$S5GttLsL{14ICY16l!7pdgOF!U) zSaF6hzy}XUL9CEY++;HWQ0=;J+-ZIA7{VaW4g=sdyRl{%%NT(uRFojXXUVENCzvLV zGbLam26jNm6DU+VCjt%*0UroC0h__$`n6j)Jo1>*Id)URxD%irN5;j)g=U*>hy@JTekIHia(DTI;Ij zq!GxS(`?aj#kCngsi9REAafyB1HT0fH$=?2#y~pfOY(=3Wm6@fcH^>^II<1mokM8* zNGhyT-LL?p_HT}hI8YlSbn80jG|7d7Lx3RF1P~*8$2rbMX+BcX}A>sWL zQ8dy|dg$5pzx=QN6MpV<{}C}-Ts6slXR#3EoL1?n>6vtvw0CTO8q)><%MRKcNMr=Y z_CsR7bY4twN;zYUTg3O?Lre*~X++EkFTC&q4v(%$n>m3dU6+B>rLXp`SSPS@IFeeB zOrR!6&B?_)u7NqX`gy${V3y=GlP0D~F{y$r;q>$r?|lCqoSdHG=B*o`;ITP4z~Rv$ zm{}4i>0AY%WOT2*Vjb+QDJxo+Oup*g`6$+epqX#yE1&x`Uj6FplEBVU&1hF1(03WB z%s{ZYIWOj%EqLEv($IcJsaRnBEP%Zk-@b7eNXP8nc7Ih%_WC>*p#{QoBBNw}2Fba7 z`_3HzQijfN2>0*b$Hnd(42D;_vl{KD4*&ol07*naRJ~jJs%JW@gh!asESuXrFZR6g z`F6OAd*s6+#u->Knyt6?b1uhT)6c?~d+=-40gI5RYg3oA1KX;_6Iap332qLAYr`dU zAhReNzWI&+Yq3V3|Lw2H8K7}*ZESr%A9kiUv}4~~b@>UTlg%uVO#^lJm%Fb}Altl9`?Gdt^|>dyX78Hg^*OJZ zD;&xmu-|7gPOIeZ?~}iK{@b+0&AXLP%sXl4*_ASoE}hBFtxG&LpPQWR+VW_vf~Smw zQ6;dtZ*9FRUO;CXU!$?y%iS!eO)e3LlaXjA@!AfiKj!!l|rv5SM0$ zF!)k-r!B?fnnf-3o6u+hAzr@TOZs}RWk96XsTM}|9-GYpf)BOEuT2JfWHpyM=fISU zyK5&~&E-|SQYy5lrI}Wa<`r<>V%vnab-qpK9Kr@BF!?A9rzT4D=&$m{0v-XUNEP{hEJUAefoQf1esWy?i_ zWK6Ig>P(W*D(l8KfN8+BSghNUsZtcz?JIRQ}%m{jd zn#I~_pJM~2k%5bM68`-4ZzD|`#6Teso8M~WF^i~xBMC5camy2Y1Q7@e5& zt#}a_C|z`^Gyna6v)Xn)<PkHdolaLSlsQlZmHZ8Y?y&DvMD?JmB5jO@?~eD#1^3M)B@hfhkW2&gg2ArfQ6 z+1VN1d+&X`{r1~ZM53hkqGSPqV*$>FLm=V(mnxrk^8?G#i2?VR)u9g)X+%{1{eqahO_Uw!qD@yaVdv#{JB zEbwfk9l&h++RjyHz1RO3P_xN%u8oCP*RZBvRQi%v+p;~<(p*iLV?3_5XTKS5>*xoj z__b*@<(Skj|Ms8$-;0^}^)LQ5nAI4dS-DNnTPOpTv$&!Ncrskk3iidaNtnH_d+TB@ zssP>eNx^T75phcTZ^AT=hz5So&vANkg5%?3oSvSD+p}7JbDk6&s;p7mute^2>bjLx zsgas;LX8Z)IHC=#8ep9RXEe{5CD_*3&G#?nKvLl$0j52(Z>&zL-PX!q)~{lPWi(m3 zwXLM3A#5;&lK88Pi@Avft_mCD`E&j=zl?_Eys`eQTR9iBA)8?N?gsQ)*VkUQkBjeB z3X-X;m-n{oQ|5Jc#`K_^7JH|@v+^h#L3@7gJ%2j+u;HqCDW`$p|tszwzyanOT;(<$>Qs=iwXM`r?G?aIS*i8#fMc^VW4-zkVG6VS5>I ze0+&ryuju59A_sCsnR433XT&2BBczZN&3SM2b&|@y7@G2-n=QyEhpT(b_2{A7Z<0v zyu3slx2g?Juynvx3!}-v7zGSw%fQ)KFGYco z*MM1ZXBVP#&S8o>rBN`kct@D})o(8ZdI3##@ z!~`wl0wl})2xx)sUY1lPj*Q8YTQ%MRSq;fuz2G??ngflF<2Jv$`p-aY0sCb9zb0X_ zOvc&vMssL)%uRWx3jiNVf4A>3{_@Yh15X1SAL0`q|1ms$>uLDlfh2CW2?;JxO~O&S zydFPOEgXA9EM}M$zr3sb&L|0F77TsuvwlLE8GrZ(e^&TJN=e*@HBkyP@Qc6n-*r9u z{Xh6ky!6>$Mz*?;WQ$k9j3u~}byyje2`U8LfC=-M^+mr;h|YWV8c;$OQqDLzImW$v z_psT>{`uesKZt{a0}!B!ocbgc!ofmZ@PJE3Zh2q_&R+ z+FKx0`dn(E?-TPLf0=@54%XXtdiiiB3^Mn8MZK;7lyYm(WQD^JFl;s;FKd{Q@%H!M z#&&m(oKsO=b4#b~uWX=9=A(t|BltG(A5WsxT^EHwT*yzV#yoWDE!g;u#9VA!g8m?kVf10p8%t z-`3xLoy|L`x-i3luX+p1P7oO)#)KFZ;Ep547$r1zoG?yOO6~IUQbH_7u>i*y!RpPH zG;vfL8fE=y6KS<)XE;3EAPkc6Q*O>m3|UIwOctLjnohAO*fy`s$vMFLpxJnaxcWR!lE+ZiTfjq(xFboHxK`@J&x}K6#(CnpL(!`ev;$-R*C!`z^ z(}fTKCxAvc7lrYfR~vK9j!fcinbbm(bH)_KZ(Qb9;+Ea!5P<@2KXn@qZ{Ec5@iBH` zkhuXV07^33YKd&=!T?fRq`d{gdj&#AGH=Si8mLSAYPo&OVc!wZa zULo!P!{m{265`Y3KBVoIcerYuCe8v_xpmEPmH7~X)P`ti#Mrd~XYU_j%6Faoc>_4g6{xyd#T8W{rQ!NJ@t(vF?+Em@<;a z8iN3Gnz##{=SL^pB>;Q@T)cmQZ~xi1K)gZDj358_Kf%+tpFs!#If*+eGh^ck@S(V) zc3JD@!)%1)=0kBmw>2{1qs)2jq**>zg>!wE{Y^yOL0qQN5lp*f0%VK{zx9Pb!Y}^P zXS#due(m%4+$+C=aoRO>)wIdRr%=|-Ji-f;*Tclhc9~Q;cM&Tst}f5hG;=MN(lmm(Yc}`15_PV$tl7lKCwW?X{CLZTN!7nY4UY z#yC!x#tA8@VkRY=ot@#GcizRld-rhvz4tKgc5u!irG!V19-;soW<2|$58?3e5S%3g zzI1m0QLx4BvHe0j-&X|gEE2QN+sk4^mjXq-r-EPo-t{23o##I5>(U1D>Z{@oefRFy z%Ul;Xu$BJJ1#E5d$>41M;=FnVGzs1YTs=C^mV#hP+o<=re7;SWFIh|-(&Aw@ zVoC|3#q2HDf~m}DrLmT`_v_1bc?#dKu~^^iUMN^58@v9~O}Fezzmy7Q_Vl~`yJy;% zZI-pSuU?M@%8%i1i~F^GU2UDex@V|Nj6I<8DFem5bai&9|IK&?dLG-J!_+>|tkL5@ zusyUsGnH=p_Lt|2ZI%ucH<#?&ncOpzI~T;u8tpa9B*tcptQo4F-4#MCM; z0aTDpR7%Mb>wZ)PG)Gm+r-<$47TfJs0Pq+UbEXpKn^MFy3E(aCu6W2&XTcQTEq~EY z$u_Y>b3hR7K*BhVIs}Qgo2G~u#q@0TKXYpLfYq55nhGGK%&6YgmepAV67P}%V5!N( z*~r&oMb!=3ER$it(a{lZ-h4{jm^B!D2nw9zB`z*5krnuIiWtWUF$+L&KEgW(&K@o} z;QUOq zn?!_R7?5(3#8Nryp_$-xic7)(Og16X40uYdr#yE-+X3?fD(MkFAg0cY=@ zFf-vfygsenWTgBUZu@SFby%&8>G0)Vf+`WyJ{XMX|H6g3`xE*Q6rtj0_T zgKGqhMhG&m1(bXGxnQl=ZG&ku6dK$lA~=>kK8_>afB!v+OVPeP_uO;1cI_Gf!juyb zC)hsmzTel2`PTm0nzSxo#S&@#Z^luD0ey!hgNO-noWxoa6Jkn8DdYU?0`DsLefQmW zaejUdhJ>szGNx(7qel;`Q0X0>efC)#931o@Sf806)>Y`-FVtKGfR>;4ywE`19Q>Ah z=5=5CZvia7H=2CywQu01mwy^}@BRs@h4%@Cv)LY8y`@tOxEUy)_eWdr6ijnDv>A`l zy(4(?>T0Gfxg@0@rifwK;F+hN2Aq0xImY+D|9zZaoFZwcg;yR`L8uAx?Pt~}2X3tU zwq7kLnU7;W#&%ro_x8B~pTdt=t!C)uIm>kc>iK{xnn&(dXd#>$PuM4#Hgn>=Url)R zo4@_LMJV&$HQ=`@k*gh0!LZJ)jm_Azt?$}AV!;jO7MOOv*J-}rbIbdfSrlhEA;zq( z&#{8vor2%;OzJWXQw9^cb7;hf)PQ~x~@a%svfwd)KOjDD$rB)s*)aZ`HsOI zPcJU~T$5cDo@9+Xs8<`Qa9(M*Rf5}jDr?n%Q47OD6V}qqC+T}U5g4u}8SN~P&2*#b zryiXqus2YnA#&3BsqbS2wcWd)lxOX^=1QNI($=V{RX(hJ{@C`O00h@_roW0Zk?QX~ z%~QiCR%m=*dwV{uyzuJtZQ(Iwtb^rt|vy@lzl9f1T z@z+nu4sWl*m6JMw3AL7$(JaK#%zFo72SS#3Nzx=h#Knc%gt_c0O#(t=MKM$LC|C1; zn*H8bW$ky%er}=K=EZ96dMPoOCB3>0D8?+7;3)gYG}EQOjX>nQ%uk9L9up=cI55Tp zX&QsRss|Kv~N_O081^WtKgp|KSXzLj*_p%tKMT7TNd)nQtAd#*We z^)NQ@*WBN=Q<)B-k?Cd=?=(?Db&r=U%Yet{f8+P@%fIroVs=2KlyH1}jJMu;3xF{67hZS)*REd&SdtOR z8e}kwhLvX87O@D;de&;3sjgwW&TC`LEO`QAOp@_%nlQzr<&P3hPEPRdyZ7@O#yBCHvO0FYP5D_@@8>cfa=a#o;;c>)Q9SKX~!I_OcP8)~`7*X%Fsw zf?_9RfhA+Nf(_^NY)Bd4fWw0UANattk`Qqt9$@#r_ZH62&Jd>vLg+GruC0#<5z82a zxiGx%dHE@>_U(N=T>w@kfh?;!=em96!8+_c^C<7+W^LMW7&xi|_8b&b=?fR|`)7ar zzjtl@>gT_R&1RzlVg%6W`wdL+X$=?&iv>Y`?4~oh~kg}L(GLWFwEay%5Zd^>L)c|Wp75L3H zkd`6LCQO8rT!dU7EaA+A^RqK-FE7OtRb4*4_sBdV#*CaCVq&C;kdp&vaXpR`Fm5GL zO&k-*dF1RRYbR~s+#scs*q5YCL{7(I+u>q6VYdS?$+(6AxPJWr2Sd=r zQf39pFw22+9_*5s{_Ox(V)4yf<)l{HlmX6=+P^*ctyR^jq#>8ZZED?xAeQxs zxDoXLc9MY!Vr?hy^>-7}&DF^?FakD6vwbs0#O&Z*25|sWkPL7vap0Idm_@Tq(5{fc z6ic9$$@SJYXaX130`e&pdP>@5XO>`~C=v?&Gip*R1H$#yv)#~qX1_bkm}YISWbtjj z1Do}kK`9m9qoLy^(=-9ad(~xtIe~Q^g4VVo%4JMBCxnf|#2I|SID7vg{_{!>{0HfA;4k)}!=wMfiJ?v(^qTKoxLTxTosD#zj=% zg|*HSp#i|@=?UI?>#cI&J^%a*xPJWx0K$|kxf~!hKxcwCD(LNm2{Z?I+jpw=1R1&z za%PD?mQ0A^Diot=hd47XE-rEZ-S_a;TW{h1JMZHB>`dx&7uUlY%g)RgcRRfQ-~pzb ziigQ_&pn63!)pL@7wc@L+Ptszm)8WKwS%9C_C_gmYoganFa0#`-u(tzfzsTauWI*k z7KZkE?X_C`yw@m|VS3J9Ne=j7|_Nj6IYu{sKCCu|g?$3x?qTs+E z-~%7{pw={(v-PdF-on}0F~%{%Z@ktSUUqk_pOt>s^A4WTJV02!NcRXr?>hjTa)w!UxumaCz^o>m)jM@Q&bU2eR@!IzQ7CL5RpXVDO~@9h(3e(upVd&Mm-!>PvjNall0dcD zV_E5=kfo!Nl&26~5qcazV!cHH_mxP^vKyxfvF&UC~prLP>yFNbGp*v&CJuUFa3cAa_$v}>Pg*=s93#19$l3L1@;fVE?kex$v z1H30>t;3xF@WeQ~IKkikKi|Q%gF|dWz>of;PvEIrPid@U(nM|y4uB6slQ@V`l}~fV z`ec_WuCkTTVsmxxC)p0=_F7u{s<2Q%um^}XWzGfU5`O*HzKVbUKYp&f>-T^E%XsRYKjq4^DpJB;P(Re@88G0dj@{b%eu;W#wsZFW1Xf6 z4<9^`1Z+uMm7ah8c^n;G0{~3L!VQGL079_@J6?`sjaF>D`vk9+mJIyP6J)h+&ufC$ z4+4JM>$SVDq=T|n^sotA9N#<08zmNjftZwes7j%G9x|U~s?15L?r-kCG{NCRSpb;+R zDsFI$Zl4&hlMm4CO}N@ltDIlb2m>`z$>hFcF4{h=0lBs2I(}pQwyoI$?bY#B7yhEGC^$>8Lg_=-NLBP{{A?jN zwq7wL+(5lD70g)-uY@700&5yErLo2bgHgg1sLmJ>N|LLx0G*;ixqUNjHoqM@u{9|? zjG=j=C1w|5!7clsae21bVe=G{X=r%{6?ve~nyvF{Nw_r6QvtvZ2$rB}80vvzAlOFN z;;h~cn&3AB!l3bOnt((G5%s5P+nS_V%u-gvGa+gMEOD2XxV4EUDJ26SPg1|qCS!0O ze82z&bwSM7?Iz6%#z?u&aqtl?)C5MYz?-A>%dD^xqwMv2=NLXX@Zcq(6?*^?kpRwu zp`@I#LsJH_E+AOrKXg*NfXM&=AOJ~3K~&NR@Z=DjEr!-58@V1f)1U!?s^2t-WGLjSlpe}NG*au?uJ!>sFgfwfvIhf z?sxk)1HRp+ZNYEHlzMt+aPg2RpqEkOk1YY0S?ryBmk5{$a6Tb~h?E?hQ{ksDLrqTR z9l~J%9eOxsY%k96H-Gb&@G8vx$Upi~+`jcRoR&yRaYANb01yfYuCWMnp57ilr0J-y zlCc+HtU3Ij1ZWf?5>@ags5Z_4M4MJz1`**me&bdA%CEdqK7H-A-@<1;^Di-uqsG$_ zK&~W1DDtBTDL@C3mX`<>b0OFcnR1Knt=6U64l5h44LQb$hsTdFrikq{VT=(ke)vV) zym12rhnN$15}FwXu@KoimdEn?rDq+;x=CXBl^FCSz;{#tJWWV3;qr2eci(*%fA?Si z4&VFU_i%A`4zmi(B_URUupZRF7$>~<-~o0?-pkB*;e{7)baVtFLdr=uYz^ILX0w^f z{VUOb*9dzJV0roFPpRd%LaZWqHupcNAU9V&*z@Hbnt0$U5L{)hwSCZ9^{m(ZxT>{p zUD0w?pO@Esek~kD+`dBa0EP-arijdp;0HYQ)NR%D%btAWO~&!b3C7)oFk~%#)%U&j zwV8;nk3Az6`J%3;U2E3=c7M&sPhcz(uh=|y@!vhL>fg~{2Beza+6IFFtqkWJ{^IL> zw&!2_!j}<-LH4hL-_H802Z=2|TPvm%(0*1iePzw1(& z|I+fS*565D^tP8>^jXA`VpS!i{SB^$Z@?AMyj zb(hL&l$omIshR(}5x#;V1FF%Q5 z(tzXIN!}`>ZJ)HBA=JGCt9yay>NzV)Hv1dB(#_gkKC{xG_OtfeWKHV+b^X$d!RmUi ze>Z1D?L%Wd22e_?=>2W=7E!q5>TO|0%mzHlIA;CWvu>q&p5cr#2CAQxq^%7PW;+|I zX9iSZ(|X;NWokfg0lvzw4ZpOm+%~74oC0K(Q-~3qgO*1K>cV3Q4;XQp5K|UQ7i2A^ zv{F`yAD}2nt^CHp`v7QN+LVJ@8X26j0-rh%=Nu3K=Qrw`9ua&fmR)kDU1x!YY@drT zniIs@F(vGF3FDM8j@23m2zVI=1;8F~WK2;Ii)b2AmB4QZB?~68IBpb(Z^Y05vH1*xhOTPb}oy1aMA=n&Nb}B?kx-fU|$b;M^ut7 zI2PAvv$!%__SWjQnK_q2%A5&N6NlON%nTPYhK+~YSVAnZnkPT%CKBYA)h!p4Ab>X_ zaRy@p2EoyxYI+mX-csQ@fzJJ%!LC_AjGk5x2Yar0evLsFfnH@6OOo}tLr&Z? z8ABLA4D7&|qPV+!;R|>1OTY9|x%ZF$=y&j$&-_b?=hybhIn}^7Z5ZveeY28Eod7-; zHarp_WnxIKq@n=DKcM+61gQ zuv@N5Gxx|yS-|f&PLd2zh1ZKqaeIE_yWhpVH{Zh9*;zR#>}eBB%d6X#oYWkj;)LVl zW4uYCNzI(`;pa8h*#VKG5V*cbEMKl1rnwai+fk^X&;d{MG-lxUwb#Dh2z*>TVA{F5 z%9Xk{Y!boJ3cvO@P(kqBuYJ9v>Aeadmc!e*Rtb64KA>)IcJIQnfAf1}9xd)-Cde0M zm+)C2fHxAhMAL+vnVKrMF5mQ&f$$WzKcf>A4yCwRSzN1eBAx-H6d0NKJ4$+ zxsn0&G;abu&%`f#U#ag1P+K*CD{!dPK-w=Z^l5d>_gSavL86vINBHJ9dhq+}U-&Y7 z2mk}*Nq}z%V)<3@yO<|70lJ-tD%1hAnnl0eD>|{O%B3e!{*cBXz_YPA8Qi#Bdh6@$(r zIM>J3J2U!e+aAcNdMYuiTXs1Hr5_H}STvWDoOewh>fRBsY~!x-Vi*oLxPI+A4v#ik z3Q4lrPM1=9X&gs&t4oq>NC9Sq04nkcLwg8o;wDQ<%7*6m(>P{Kx#H8O_U0Sb} zWKu>fR%OT45}I-rV49N(d?ThUFsXF~ki$L*9!D7DbLXK4E5JDlpyyG37JNR!kyvY; zbAY-Kl9tzLk`9XX4+-oXa!%^bEQ{{cwK%KLFe!&-vP{i7CvnizNbaYZ@M771W$aD1 zLTJ6;Bre;|d&OX>WH&6#D>G^?;!3zueo6={X9i_LqFReshzUZ3l;9`>BnfdQ?2wU= zDOJ!A#4R@`2K$J_N$NB+0SRCxP}->FQ-#muK-s}1OBCWEFxdb*IsgnpiL31eBXkzt z62se^J9ge19_k*i=hynBZe>NZGNtYs0G?m!T9*iL5r|Xj0eO|>6nLpClWC@dLt=4D z{LWv08;K_n7@z#aCvoS_a|j0;aFk?YE=CXm!An`QHDRh3o~aRNTmK=q(2hnCF& zE#LR|x$NMzxMopK_1Z(m)4h%+6C7jIP{=>YbpE+n)mO8S_LQ3Ys z?p~o~F^|RsmKj~wuGj9qj+b8gQ~|;Bcb9!NixsbXs5D%k$u-;N{C)G!_6eiQ`%A)z zz7G(E5r+Uzzy`u!rYH&0$PunzyM_;a=y?!%1n=;7?z?#S@S%DNRSzM3Yd@Igk~3ZQ zM61kLj={ViRs{XoJ3G2)UEXKlmq7jdjensR^n1Fo@z@*+eK-KY1^n5p)Y0d^_}g${ zD5bhesiVE%w{3%TZcu2Si%?cU#FB2!_GIs^{GmvoPjIcRTCoU~Qb%I(6&Y~CwB6xy zyT$40IgTGb#G^-#aCvcooT36>b#+!H3~8xJDlIlb>5P2Z{;-ZUQA(2UZNfnLjJ)AohEFWoQ>D{@VHw$7A%fYzU$@AK+1 zYkYskU8KLxXuhwbkue-f4!bdCzLUdSz>G3~4?0 z0CeXSpnz16sT$C{x^s(6ZTly;? zTmKdhk5=B1{T;4fyN;VTZ{qN1BV{mHvWI#&_~0;vpaNB_1<+%H<32-V%{Ep|>)d=s zPBf&O15FyGI4_&uH>Q%{inGK6lVf-b=#jRv9uUNr`?HW{U;E}a{WcFG6k!1SS@@(%dF4uMvl;mO}+U0Wh` zO%Ig@pli=;N(*RgSiQ%-CqgM?FTk~0$4coj^D?Nsr838TJeDD@&<=Rz;Te(eACX^YSp3^O9BQu*J3mq8=C)t8e8zh#YdtI6W1x z7-K{nCw%lHKZK`lKPCG!N)0b&#xP_A7XYe)a|?jG`E3BAmEM{(sf8s9BLKVI4)4GJ z9^QE44cxnT4;N==AW-o_F~Q2lT;`(inv9anPqnp7KuQTGr^m=|=8{9<#TPy-mS8~Y zR42)JZQb`JmAbBVGrqZyIVZuFUi#?;_-*5EyUddYism5L4o6VecKNzdCbWHNAGho7 z*S?OIKKrRfcIdUMN%Y$&k1EZPj>UAIq(XIn&h#{}W~u4=n%i-q@Dw70nxZB52mn~U zmlzW!yY)vDs{}IT+xa$KTO^#rqE)2uKdLS6y=^&imN@Q*FDBDufZPK7{^#HN62h>lH030Vwj{jrUG3=koS1#e z;(ks3H4#tZ@Jy3y54P{?_ee*_b@FBqxf6F~%p_^4nCt%U>invVB{9Df&Mz);e0+>Y z4bg~|`UJ+FZ-SSP5iKrxbnqLcV zgSNdr_b;h;IX4x&W})S_zH-|ZDt+l6O80Xsa7!n3Y!!?x&%(8fXY{|m<~?;4`RH+N zG;)UBPrRg=)wdK-vi2<%zGMCDt6n2*Xf2?1(T;)#_?53xNQaz)l5tWCUv%1P)@^+iU_34hHz3 zrtd6qt>g#{E5)JpYolfdWQ&snVv?A)DMsveBgPS!Mggy+vCO4>jc;g9FOv-n{MNK28aa7rZmalev*wy32+kQOb+l-l7_g{CVN25n(YAZ34R#hy#oV?gD7Qc zeQN2yb8X#ZE;W|T>TA5lJ4-y!x;)DzvE=eh$;Pe!DJyNfvx&3Vd#TKqlhCY;FCkLa z15}fRk?GSalXK8E29KN*PEH=-um9>V5y->k4L+q~^G-KrGT_^hv0oCfS4A~Cm<{hrFM72Vc*YaQ&XXkk9t$UJ@IWvA3 zAH!3(Zh^=lat2#X-9QMzm6wqA&osNe5Uidsss!APBc@3eOdyP7#DfP9@#dRv;@-V` zI6XZTua+P#Fs1IL9gOXeO(=%RD!s5o5TJj4eulT+dIMQ`@<%@M5!|?OLoCHyUGk;x zp@x5;(IB^iaADLHq<;3ZKZUz@zcH6X%QSQ#XeM}dJgsE0set(^EAirQ>V+Hw!EH>i z0E*_h<{7I^JGcC_ZM6zXht>@YS6=P8Q16w!TWQlGF}VnFvL0T}O$DhIwluf{Y&M6I zsb1ZSi3krLJ(RL~j^PP%cA(Np?Mtg@qZuf#0*&>5{vA=Z$j?Epy-VoQz|YllBo9=9 zZmH;Cv>sFTKyZHH_WWy~|0108NSupXpZ9~7wzK^!=WsnMj23MV+rBfJbvn-`bIb=- zm6Y9(TGnMW0O3zeYd}W5RLWnKx79koN$Q8ktmV`qF1MFBesqlY-n);74<6v`^b~0t zRo+soFU%#%GDFH3asj|L=Sv~nXj9f7;?nL+7&lN^K}y^2IswfnXY!0?R^EHHJh0h| zuA|M4S(X0G+v@h?ya`=bDgBjtK&y;itjbrPqvg5Tc)K}(S&g6kKqjItpUqX5&66oD z9(S)@4(Nc0wJUp2zg+YSxN?)v&ZiFi&Oqz>!{%4<1dOCTd)AZ%3JSRS`^vW#AW4c> zX5e@B{vu;E-|e0KqBv2$*_9kpS}e~~E%Alrc{uM+%_r0V-r^16O02KRFrp{{a;{!< z07_n?7R=W5)(|2FBu5bd!zS}S(X!7)2{1cHZJq%}2wqB(SjNJX>&EoX1DWBR!)9}c zgM$NbCR|=#V7uLFra(!h?KWAmM0Bon^ORToQLxp z1V0GTstY@l2te6Mat)`h=NUkX3`&yu+IzqULWmC0x#B?}3{2-f1PlioY&IL23(Ha& zqte03;mR2a3B+nC)I4I&0h^7(;n4xEU%Q6QMoh-yR=>k`J7Tw+kYd*H+xvv3L1M{e zLUGC7>jupzG0GNp4K0`C9K(5upCT;zC{`NPKv&6vu z*e3{2-+2Zh97ru!=Mt=D~z;Fx?o~RLwoZV&ps0EaAm^v zxt7Ll<4V$J8wk;9cj18;~n>F5}YVgzdB# zfOC?3?Ck7J+@X^wAU^WqM{)D!P1zecgEhgPT%puMonNHuVA;_#b5rVQdCe^m1|0TT zNB3#HA9vN~dintr1h*xUW&<)SetFkye^u@Da__A5c|PVNjuP#EUP!s0p+JzWd$p;=zLlnBoX9;KGt`EG;fn@-UQp8$rt?uy*fAWrju> zWb-i-oY5=~X(mzmzb1=mUHMypxHflOWd&9blyCmYA9wfs`WL=f%0dxoS-%iUc}4*? z3RZQWnQ)2nHvues)izh{PUS@eDGOPZc5@J{pUu{m8gMqBD4x$B?A*_oqQ?A2&GxQt z(3ck%c=X^Q-hKC7y!YOHoSmK^P9vOpCINO%S@y>yt*gtco#Aa?Du7dWbtnK}0g_Uc@9_&8b!);$-?^Q)Yn(sxb0HRp5f#PCq;GtCn zS$$QIC{CzRQd2=Fyt;mSFM9D?&g2LZ=xSDF7+@UhY*lJm#r_8;PE6>TO*wES<* z3+MfpU)njrLT*{yZ|~Ky)9ju_dyDx;*H7UkwD_#hK3GctX=N1yBUq4b?Y#A`k+)U> zq5|+vaf^zT)~?#;-u>VD!<@m1%bv`8=HFbS%^lb+l#tDM^mo^Eu8ya-KFRdto)0R6 zxABS$NCT(^thYz8YnF>^W?{mJI85sDL-^JB{Ims9%(F%{_ z7MUZqm@tkRqn_!~FAs)Ts{;iDH)#2T2#^zxE-lJ#0rZymj2t1;gzN#oVT3G}R3Q9GEjM zw->+#3%F$hHp7g6dBiAI@Nv|P(CSgZGbK1=*h+Z%&s_hLY+L65m&6s?I|h>msw*RE zHEHAsLvXl$?HYEw3FjB*_?y4^j+EVi!;k#PkK&o9pTiI~V6ELs903M~5Q>+8f!Vom zG8eqX8dYheXLLRIEy=IA`JC(bO)INH=-dkCT>uSw&om)M0ePSQ{O{qHfBEOibFY5& zi}=~k{%cHTR)_EvOSrPI!Yyd+M{F?P-{gSxGSzcaT;O%$bh701h`QnFP#Ely_0ET3} zmTAIf12{L-bzZ?ScD3MlX({NhmWF>2uv?UgMR=+-*wW&@-+?|cR;$pNTZKyB3F;}@ zf8Ms6b&jtZ^S(>uW>T;HClN>?=LHqDE(i`2sXM=OxPJX6o`3$ss*sU<6YstEE~aS$ zLp*)jade8PGA9*$TEp$ISZkHG{o0oastBp&;eL+HGE-b_XAe~2((bqEmQWOhO8DlV z&cW|*!TTUQ(L0Uz4W;A}nPP{P!x;b24v>2G6ml(qcn(Ng3ygr^Dxew&t|US>VJ6^V z-x-fG?o#@M#qyhyT74%io%a86_U2EPB*%H+=Mj;ws=BA=zHklZzyOkV&DKm3Me)!< zE&-4djYdga4!|Y3wzfa4+5S~B62u$;DUl+HbC)_uN<6h9C`!g9G1EODI6d7p-Ca}1 zdzlg8`-8j3k(sZ$fgG#ps`oM@JYhxFU$e5%b*%U`j=%B5yGu!PxfU|yf_WOsr-`RkW%$o9i6dwNF zUbco0+5{UBV10Y-wYnYsMoh7}oo_#}8FTvNvQP_n|wj0(fmM z0f175b4}u2@~D2kTHy!fXu)^%+o|FgTrf z9~=_16g;O0PzGa%n8y-}nscmL0#87ex=Y0sM*oQ^!83!r+;8>gau%jMjv3R$$m1jy z+K5u>2&e!!Xt|@N9B*^D$@`oapiE9IBAd+y*REZ|LsuU{7=liY0PTyj3%vK<9h}^` zi|uv`X3d0Y+7HtPCUZq5DM z26mADBwMs2^un>r#yY08hn<6G zM)q=$dk@WEsh0SXj0NSub3_;dAq*bQNlC7_l^Dw1PP`j33s61?YLVAcRt^JVN^s{6 zzz%T~t69>YhL83P+6)@iuu<1wwjS-l4%R~z>aOiQ2G7`pL+o}Vw%ZH*yJlJoV($*n~qQT( zoCW;8`|d5g_11NK>+Nsh-pL6#vxF5iahJVSQ-v^@t-YjSS4i;+#y8snuh^BNPa^PzjkDA8fQ zmhBj-z`bxhY})N7k5&;x1;DzK3qQ#4j_@Zl%kM9|`g#c&^3EZI0e%RLw+0m)*auhk z{UjR*Oh9B+s*#OeMqzsuSV0%u37YeE*RK}v%a}#R5?&Hjp*Cu!=W!fyetL$xckki$ zt=l-heT>u7GsF~|cO@>Wsa zwScOt5#G>JYdw-16_ggGNi)j@yrL)%%52Wgmu?@^3{;xD*c~O}Cd$lk#K;b6^)&?; zz_fJ9wf52Q2s;<*QAKr*8vr%Gs4mUETkd-q4S%QC4707@b3ar~Gf)E~o0ak3_Z=+= zH1CmqPOP?ePiu3USoVF{hkA~-inz4_u1M=MP-CC2pBb6CRH9hKD%+DYP+YCdng;}o zHc4cwTqyOg%RZS^&WE_$_BDaq zF_1nK%tB@i$^<$~W<^9GZ-6VnYZ9X=k|xKR1g!E_?p14JN~0vDLP7{0o-Fy5wE;=2 zHSIt|7&hW+oswlU&6pxEO^k~RAnw%4W;qtfVmJl-hM-xCb5iS_F$cN7%Loi$iV>%0 z=ZNtZ&d<&;Yz`F^ABw;TN#5c&0WSJdx6TecD>1~*vQG;m&PiNjC(Rhmv&AW=z4j|+ z0HHFZkfeBgBFlyrktkts8z4w|5$7ES?={<+mR*8a((U~9P5oe*FIK^)H;;TnbG8{4!rYv-kdBP?GgO~DJL}GoibUK+Gh?8W)c8na7 zTHYrJoCY?YfFZ!ggv1Q7B1?iakrxcqidNP^0J$rh%LJQT4*INK1EmPI4{(kUb40p` z$ayQtgrbxHBNC4SKLDG-)jGkd{BD5Wv5dzz zVji&yUfxTLxYG3yJa$vU+1dN}^FROZNHHQt0RT@w^#N>#0|CLDF=?!62-VGmNc-PN z5A6Xmr<0DcvoW6DLe{onzgO@j>(+XitQ~Z%P}BlW%#W4tzVhW? z#*hE_Pvi9B46HHvW{DERPA`lW&Au*}9eQ@C7wtG#1`id^mYUQR5Mn~Le&>{LZg*S! z)n9#EEG;?Vr58Vj#~yneL{bwy^HloDAxPXl39pT@Ca4j`h8z^*xW%no$9VJ2>v;Rd z+c-HnLFSC$Ew4k;`L|irAGP8*l36epWT%IN#otpmK5FJxXga2ZdnflWO(VwL7IBJr z{`u!|?bq0_)LbAELbbNC?yT6GMZH-1se_6yK|w{?)))iuEB6~<fi=`@drWwVy49x)PI+N%Zc5VzPVj~LSq)1+mLoYt*XP?8xU^rQ(POzlkcO-dF%9A9QNRrSc zMIh?WG)dwhju7`!b$vDfY_Z3V2-%S&hGGTGK+#6jNfiJwO%u*e@8bCQE`s+6L%`AD zRU9537BEhlgeoht%!DFX3L_zez=#SIp>e}Gqm%@xt2X;ve|Ox_v}0tFq!P@Gq}c;K zGAK*NG^sBsZrBocTm=dXNH;?D+OTsfd_V-z40Gqn$jrzw3JCL50@DGMG7kdD0P(GN zAehU#Y=G#*bs8jYkM6)>P%U|J8KMmKA~2Y6%^@RmLV^Hd?+KKF!|0?Ib&|4Ltl3K2 zZDKsVRoG;W3%0T_0t&N*B*8nvFa(5+7t4DR*Xb$lFijbnoVUc3ixqr?`A~7z#9MZl zvDU_(yFXL&Q#PRJ(o9iKBx^6U>vj3vLV$CQ5WE0jNAkU7=ym`ch=GfXbG-T1n=l3l z&UogTXR#TMkdwsL^CX9|32*>9gGH~oHUcFyrkm2YHI3(G4DLY>)OsEo(2{zu6b9KR zU`$csg6AOk*MI#D{Li2K3G8+wfLxS1d)}mcp`odjKCWA-+uxT~iTT*&-dqH+i|qye z`rCi4nW=%7UiugwdE^ldSI81$S&Fr5w%weI>$CA@B8M0!93S7t_3Llp?Hh07-pM@x zP-SCvwd-7lWcY<2v`mTFY~Q_GT{~xzIZ1?e344&Tc;}~Q_^at#VD;Si==0Cx;cE|r z9UTnq3j(BN!>v&Q+%*7!1dYd+k6aIteN^0Lhh7K> znRUObFyodq*$dZo3=eX!FYnVe*BDZVem**pnaz?%$Rr*n0YMUxsjxLo8O{Y9930^2 z@CYFUnK$Qf^X5%#cUw?mIXjxM73C}I8mU5IO?mX4>_Z#sgYuQ-e7C~32z~^{fBi2r z@cZf;TB}`XH4H;3b>zH<)^4c03Mxp>89!?5uYJDejRlRlH=wqr93h*4J$%W&G6hN< zuX-w_YW1}Y&*L~^+>Y38w>UdH$KAX4aOci@xOew1&QH%IvwPtq30ae3ie52^5uJ)d8Mml<;<^8kos_V53(IO02%Uz)n z0g9a1^5OY>c$5TSc9t~j*X?gp8et(O%sSrRVa=JPdGW0BfHl|TwQB|6bo;R%W&M7B zf7b!@YqIa`HKh|{4}Y9*zX!b5*0KF#X%zU*-%-xc=AHAu#nZulSFcBn11!pmwvUWv ze`*M$hGp^|t7#nsz{s;?W?U3ktTIMl8sBUoKXi3nM>yTbelyWI}sm@thA;~2%l z<}yMc91I>(LokDfTwH-OWd)Q1h%%E}fG5P1fUU%XrkJIUa1!vFqJoPCSP-c@vp3gg ziA@q=!xC)Oq*hIwbv-Iagea#d4^wC63@ifB{n9F)ott*@Gxm?Sg~2I4>v_ z^SnIjK2-lD0?2XEpo)b?VuL9&B7lGZM0M{iRt$&iJbYjbPU;hyyS8`g!d?Kd9Avhc zJds*?0b(mbq%KWP7&Ku6=MtPt@SNZ^P8bTH?cmM{U{BrV71>(>bx8r6!AJ^z#UhLV zILI8Q#Ndg+ku*`309MgbC5=5JWKIQ$*w`uvo-`&HB{7;05-aV<72q!=9~jeA-Rn(| z;5@G>R_jX@j2dCgPEnnN{`1*lm|$yrPVcoW$QRo! z-nn_R#OOcw+;e#Nkw-wF;+bRfVBR#J{M6sYSHAX#Dx59ntJ2moMt$vCT_3dGFjV+3 zH9UIJc6(4m=+I*J)?Uzp;KkPpg4g=FHjX^A5 z8%gi+-eI%ZKoPnq61~T_-}!5dn(%A^*0cizNrp1FXd5k&F2rR#;eo6?v&TDETNp2{ zyep>+0^`sAWX86DoK=PTOl5dCT6$3tFuPUd4|e9>oJ(^99jH13IH~-sU?@C*MupZdYZAhB}bBX zz`jxTKkvnS4%d_~^9Ok4-m*TIwB0_l(rkCn;_Th`)NBnd;}vDE(R|)6#ZratmVNCX z+ArVqG~T|y?K3GoT1IfI+yavksY&S8g>7*&zNT*^p%%IIoaz*!CKI6htY%MFZ!`7_ zdhg!E%Q4O`!vkcA5UJ9*@l{LW+sP!E7mHKGQ(k}9k_I$^SOJniI6b|PGI}{DE^;}E@a9Mk%9O;~ z5z`JavRKiyybtFZ!yCt%Fv{pW48RZ!{7T?7v($_d4QB&>q2Onb+OSd|mSE+T0&OHq zu6G#103QZ;O&leRIKgKEvW#2eEs}r|17QRKia|0iI|h6f@XjWOqK={c*E|}C8URd? zgM?V?HOgEhW*}umM37lQN@61hX-RO7P6?j)IbyJ)qo;>X^O_KB~n%jC7ux!5%9+D@90C29#8NI)_x;JY( z2fo%H&Hzi86s%ZyjqR=ilhdCr3%DZ$=ViQE6(9;?2O^}HaC&+VfBDTn*KD2FZe_RA_(?YhBTA0#Y$b10sYwgTSOpOWto!|Z{{?QNp7^XCV*{lOq2$3FG-`fOHHAc-e;tw#WRROsDy&bFf z4)C%E<22#s&39Dcmhj>WFX8bgo)8P0YEn|p0v@t}S&P%(Znt>nopIAp$&WrXQa1ZRe|3Q^AmgtRV_w5xL0Ie155LiMkVv45zz?CZx z;RDYOIM{69T|nlHTeohDrI1D8VsGoluWqI?yXC>TCUyMohJ9Cgm;THZI;+Y{ z!k!6kZ`lKC_Uu8jXK1C<)VRd%VR3cOuYK2bVEsFNuK~ukzw*;tOYIg@c&xk$XcR~L zu5La`oOUMxpvpIMe!V&fm`iReGnO^Y;t}du%VRoM2)3Zt3Kb z!E!?~1ObkF7PATc?V6m=rOCK7n}72fGH;4vBU8RX-TtWaG;4hEuBrg5>mk1b;=|z) zwp(Dg%b@KJ&g}$<`0AER1UOIdPThYrBXP=BlUEpF1TZ>aion4^QmZB*C8zGpqb5nI zuFX7~EEZX}#O(qK7#a#zqhuLx)LQ|z|vzV062IL z?>A*pi~%}Qwx2UNDj~UyoTa{T3mk0DyaU*y)Uq}HJKqGrGmAAHKvvgd=R6QRJlnyaI>v6lQ*pH*b+N9SOx)oDn6trgwck1sY7!y4 zgvXr0b^isIJdMRjHPnC|sAp%nN>VnI`1~rS zs5VaoAQX-*v?ufDiQvpKOh9&IIXuKGffC4zyZGtpJ$&<+w zT}5_c3Fa695+zbw+M^1V##pH`O&g3cX;ksd*->yGfxKlzCXB9qU;AUi3se!~fH0Ij z!@NUE8Lz$m>-fwoKVI7Tcfa)|0Kh-|;eS&1W>0=i@9Q^ZUlfsOt$(vCSNAn;N)*fm z9Q)hcOEUx0G~(vFH??sY)RRv>iOpsZaBhbw5#T+Df!(;pt=qTp=9_Qgt+(F7y?gh- z%o>`}&LQha`Z56qAR4hi`!`b%G>1wq$^qH^C_JRb`B@x00F0vmbc1n%>oNnHZHzAwX;xMlfPs`X3qbpxcCGVl z-8)Nr!~>``quT1}x|0 z9$k)66Y3H0XEV3wUwZwQ)iXx2v4=qcu;$#TZBh5b3xLt^6o$e4P5@x;@2ln_}I}^hHkRnR~UB zA)2j6X6_Om32-nCJ^;-Xlk-X)0HaR^Ou1@SWR!Du$!C}a5M{lu<>hNu%@*`DpSHrq zyk{r|lR2$*x32S?`mNDMy|448x=%CI3ia4?u3p*;TFiONhxfHn_=+iB?#DdW-h3Y| zMFGVtyx*R${iwX5q`{MpbqW`v3};}Xgdui~7MX_FyjZ1;lrwV5NI8`XDf$Zieg7O7 z{wZL3WggZnuxpBmC9kVp@8+b)W+-CJf`iW(M(^>_%X39eW#NUAMO*F(*#M?xDOQ=Z zb&iyY6pM?|cnBsu>pj}poTRi5dmxk6n42K+l@pLgi488wMWC9yxcRq?v>9ge9kYNC zL-WiUi)nR%HOGnzn#gD~APfVBK@uQwHh{Q+cdleowrr1_36v9Dtdq%^G3A7ufC;(N z)MTwgn*azw_r9C+-?^EKEE=%XEvAC6EM=3J0pcj2B8%zK>w%dy*RqwL5GGoSNavgp z0eF33fUGV11g{yH3-J_QZtfJC$SRAQsbp)FIZ1YNQqZf1tyhBJEM5a;Q?Zs`vR4s{ z&`*q{dR>NTFa15BpfWx#W-Vas0T1(H>~I!L%8+e_ z0fP?+6ly#O07SORTZJ}R6(h{R-Me>je*WL^{@pE3?!J%z@qhTA@ci>H;L4SU0Mb%l zjU}#vU>yi*(xDFgu3S}6s$;+G-hF4z8dzQ&b42QSF*L%zgj2l!`fuWuSN=(N`@jEx zeiQ%TAOBb>>msxyizCx#0@h5JU@lq9AMCQ{sL-|XrTST&PqCPYqG=jOymRxNA|Rfh zpX2E8uz1l}Oi#{?9Fx@Fz40x4^P6wt&Ye2~e$_Rz0s|XMA+}Dj0R_fOA)p~DQ?|?j zg}p%A5;c=8k0>^n#S(n;<~wjsylXzd&*JLUtH1#K{LlV4KL6U6F^&U7j2fCUU1-L! z6p~ggm$T$j07`N#n~=);=0aruoTEy0t>tR|?%MXUowX84Yke;Q2GFcUf1np7Witlb zM{|I<6p-t9iK^mbANcM12B*9z!(v#OAr$~v&PYivsQdzRnpxxT^y0;(MOo zzr5-WoPAc-O+k@N0-Ary`>YJ0l{zX(uVTbl!0#FEot)tAoqM=wnoJ&3pGe@j&gaKY9PwjaLw=jNJCM+%;RLdodNBhD7q5 zBS`sNQukwy8hd8h232dAC5SmEmiocjKF>uM^-$q8Cpl!qFG1xO{oP^(Waxk_U+4%+*M{ z==89)jJ1~CnpBv#z7HGmTb@Rl;7P%+c?h(mW%Z;jrrbC6q;0=T0ufo)q<|Q#uGOKT zRj%t_V%Kv+CL}{+3+LbrbNeO`JW1T@fgf-XHrNaULKqMzG=i^;J#z*pfRkwWauP*= zgEV>X&Rv||{cpH?=LBbGTcpf*@r9Rg<;sy-1T0Wpu4>^h2D!Y5D?qS&zSHAzO~~DQ zUy+mQLBbICx?vbl0UINwY2gkH0RQ3NehJ_AgP#Paq}f~5)t^PolCku{jU}yWlloi+ z8rH0d1(YQt=f*%Y#+xF<1~u*MP~dT|NB3~zx>5t z1@mSBQsjN#ooKQKf?M!t`Qg?M?0weW`FEGTe|B$Y3BJ$OT7DOxVGqrjfOEe-*?bx; z&)eT8z~>}Z-;}b1IVFw7%;JK7`}TYI_P1~1_VIgCD$uO#r~>J{FCAAgK+RQ|{28BR`4aQE(A+`D%V=V#}b z#!0>E1n7$9R_n<_orP6#*On!+jPgsnT+?H!U}~<=u?Z>bZvd7WFlix7V3=uk?&{hf zNOG^!e;LN^mfk&eo@cY!Ot1m>5}!N!zFpr6XsG0$u}^e(%{E--m^Lp?K?2vr!8I2o?F?!w%&CPq>Tj#?3%eu%2=%C;xp^pcY3l^ zh5h_Y=s)Wp;xZ3&C29LvTQ+EMlg>vSw}vt_G{UoWtx@E&C7;nY^WL6!?RC#}=QKAx zoIOVM{jTxAGP%574|c}2-?#h&0NUy6pP$Jxn5{+gdoY7Y*JuMCt#)oHH{=hn*=#g( ztwYLE#)tw-+>kf;Wk_0t^tcnt@8JMkyXtXxcm-h?H2Dv3dcMWU$tku9P@*QkveJX4 ze`b|i*=OyB@(t55H-OMhq#bImxa|Q;KXkEv6H-n{T4E_$Hfm_?*Y-?jd#=uB3x2Dq zM1FE}jv6Mk#2U;B#F+tj@%?uWY>9wWJDF03(tF9GLi#EFfvCtpN$j{b5zZ=9L{SS zfrupQ9Z(!SSiuh*01r^EOjxpB{+>I%9{B*BWcMd0kcWVl8KuObUn|{?&8Mv9X7)O9=>)BhX)%x^USk2 zI6P3=skA!`y<2h%(kl3=;Fz2H3NO;RS+_*l=hS`HUUnGnyV`a~@~4Nj~bSwAK^>jq{PyoCe>6yV+foTjys3@Yc0 zJ9qBj`1lUuI3cG5(&F%70qo9sgfNsj3Lz|n4BN~7`|O8QpG%A07J;s4hcyug>bi9b z5}vP@++*(^h5?T}@(4csp%38$&pwNXAAT7B*Z=uh{L5eb*BHWpVG}TfSv^%$9(tL@ zci&Y&a03`R!Ljion)97CxAzAHzg;`cGhhAMAKn)Pw}6{9q0qd4ZTsKJ)hPggF1c3I zDmtMdTOvWR8jhp5%t|~xu-jeW)~(yPe&a2?_2zZlzIBXo8Z}Wq!7LJ_jB=mi$SiNn zxtzf*;F&AR_5t5o9t(R|hw{yw;GD;w{=f5>-!H# zUEI5K4`-+6n5Lb8UrTs}<^WUwbyDCWBwG2)LXmUR^_{OY^Kz)95hs9 zJ!{iE#6)qfGp+26oBOOSF~sCf$>f_i%KEyVe5iM8Z!Jm$Xb4NSs*!UgKSRrV?Efp& zzXYqfa%uVATqA9+8=gL=1lP*6O~28!Z(v$!rsIQ3pi6$&6JQ11T>deoz;c8#7jt>Q zc2m2Z_ic^6aztsTDoRWaAadn|YujgPK3fIDz1wbCJwl;LH1FI8f){hxj`6aB%@#?1X7vJp>+o>|s3l*i*QA^$Lz2I)e8eXWI+OK6vj8r>AE) zKfA!imNAVIhe>KtBkE&-$uHN_73?i>duo9*?VHYEI zagzF*leoU7SeJ4Y{5J9?n{00P%@Xex0A**Odb-47O^#ZIDJlWDqBO88E8uOl#Z@bw z%IDrO0EggRDJf(?z@a8Q3&8`Lpvf}GN_}Hv8gf`T2*@PQ;5-QUiViU|c2hJot&FVhSW==01h5k~U~#!35c$THScI1XfUQ)7lZ7W%wCTmNO?p};W+|c0A~ZedF5#W5sznn()+}vnf6qZfD+IUN#~P<) z_c?ga00vZbpp<2M{q^6#E3fpH;6M0JzlFc|z5iIU;O;4rR1c0;aJXd54P!Uaplg@< zzuR$@IiflT(-cMNW*!|)%o*wPF(!ycRT5&fV7I<%mhg%6(1y4^la|k72z_RlAj@c( zTkG2F8X}*AY&0SVv((3YF+sC+Z<88ck{hPRX^RKbp zogoAd?~VC2iHl@I6v19jASnN=@u19g|Fp#o+C8{7FE-(JKCJCER)wK+4uAG1f7Cts zi?4p6c)ob=F>JKXaif$WohaKcROp||I6L94*+K>Il|GdRnsrc@aupc%Su@tgY#hjB zjT-B#@xD{kA1QaVy|}>Xses@2-n%2AGH2(AQv`DpoJ3{?wxm}II!%dY;1;&dw)WCH zi#060b-Y@~w!QRcZPdAJp=Hl6sVGp&!`!s-0D!2R4Z3DlFM58?N(H#t+0p#YD}OKVvM<}d^&o71 zo1MG5p}Ut8sK`h5yn|(XuE5vm&x~=V)F{7`)BV9}1gm>UaImd+!|P41S>>Pei<)-U z$EqXVKWFXt)N+dD{SN|!>mH+$6ssh!4O11&T45A4e^L+HzKK`kTc+N1=cwN2LtffW5DyzJ%i^y`WzmA>=7Iu9bz~* zKnMZnyDgr0;u_w&dxqP$k8yk~2^lWVC+v3O9_^d}iMe~~eE!S@+WDF(+G2a9^i2Zu zR_8+#N|7YB0y`u}qV?7?0pmDgni66J#-zy=^u0dxYi)Qeqq=H0yrF<2SsVdLrrBlhidnv1AN&!NCX7yaP^ZQG;L- zEORWew&L=h;Cz-+5PFd0l#vok?2@{QN~xlR6eDtqWn)zqS! z8PIIkE^)cf5?vX+!B&9*O)d-~vGRLuH+Wz(1RRC~Y=Z2k;5{~O(2S$NG^tq4XZ~U!K;Mos64Its<B#CIMf2MWUTm|4@1OjOA z;5NpPjh-B;>u57y*~};v*i=`uUW#GW%B_h$RU18v{bh51Tndflttz#8=kV~u595XB zpT{RY{xY6<<{A9#XMX~(fAPy;9z^joNKS^}LiO@^zU;jgV`cr=wU-|kU7VjbkI+yKzZLA3`m(9|Y&B*({YotXY1AkEn%sE{L)I zTmm>)C-8FmxBL$_tE4ui&w-<^!Qe|6Nw>}}2S0GoGzdMt9D>Zb^N*bfNR>}I^jkDfTluz7dnYQ`L3tDK; zj_L)`x{@~ufgo!-OHEhw#h2!}AT@O~XRhtD-s0Q%e9Sf?b$_AEm(4qs7V7`&lk0u! z&sMv;@;u{j(v{v8Tz3q0&F?!8xP8eg(5vIfv;OZ32e2L$Iid8~_?RnqxgwZ0Zzt+{ z!mY(^&Npnn_sAP^%Sw#xVz_J1-tP?M=HI2XVdu`80@wOAmk~SKnwSN%5^ zDhR_Mmb+f~cQ`mW!mt^{Rc#pHJ%Kr5iVmDJrkp@p7m$c>D9MxIIf6OEC)MtG#<1C7 zb8UmCo_Y$;efU{C@#K>@I8;+80n8JI!QtvdN66$5(+<;=kaL8i3lNQ%pc#49Lh4=B z5?kN9IUtnS3t=n?DLWu$(Q>oI(rKC~5CjaQAd4|g8ap#hh|`2=s&3ikod&dR5=wS4azu?GSgnyxJ;o!8(!eE~Px;)r1TJo31ahni$Vk>EQ)i7ZX3C_QbG2lS zxez(7JE|=Y0qBNeC6W@@%mVC97GNPGg80z896%Z}lu`m)-O@CbeMunXpjoOZOHJM* zf~Ns+gJj!uK{A1pT8I;ATzW1O;<5vgu(D*C?joe@PqqXt`b;BWTD|3Rz@m<&Fr)%z ztHwzcZB@u`))6Fg5~#9l``p^|O0U5a4nx4fW+MQ2kP=+Mc>%x9BlrV&9{}e&@I(-e z5^IpY#Dt3HLW~n)%moa`D9W1<0zUA;XYn`x*5AO#UVaHzA9_ejI88Wt|3s7x&f)Oz z5JV0!Cm<2n5jG?W61GgUMt6<&wdcY`f+{pPzZOh(1|0TXqVeU@hk1Kuy^-ZnMx>VD zH{SS7{Pf%%`ggyMANavfRp8hy>ay*+-aV6*y;KkH>JZs7^SSWGMG!0p-s~br6+CF& zta2YWf|k8Q!70?EMJ!4tlvVddz}(jxP(&uc%irRTZ-Sgz=&Ci-+OYjW(3o&$WKIYn z;E_ij#z&re4j=p2i+J*>C-JkN{Rw>j^?w6qiLDe52cdW2|Gj{^?^;!)T=HEDST7TB z>LJ{}YYlX^pBV7H?3woZ%Gdu8pZ*a6!Hcmus-^AF3*2*Mk$tupZ<7`JG7GXP)pD+u zD9fH}{9_zP#0g+!l;aq2`}Q5YedAkr`}z&sdiP!Il*jmx6(pz+=ge5PH}Xz-jGI~4 zI&FRtBTbOA-)keXF0EBd=SQuf-n&JqqhEaO3*vfD1aI-a!K)&e`uST)TE!|Ma{0aP z{mvrS%|rcvd%n!3q};V{CvfdRH(mp(IZ279JVoSjLK;V;?GDrV7Ss6_m5HHK@ro zN&>*;leT~Z=>w_EMVj$?*`CQVi)2z|FSRGxjFxqJmb|w<*WFw0>$<&%zNy>e52C2FGM~jl zSUSA~ehVJa&}*-l=+A$8fWAm>6sk1YfiL^42?ZdO5Towm*1N;{SOsrVP)h0@6*=52c$owwF-I^MLkKuHH~`TVgy3=YNaAK(7FU~L z8l^8A#?h54IC^-%L)Wh1+O;G2FydmXmenYLY0OSsj<<{$cj6{`FqHV7i#!5jjhWST zMsOOlO4Y(EgIA!H0q0C;6w9bst|f*t=Sfrk3kV5*f+NC|7}GR~<}^y}*OV$zQz76M zXlwZ+vdKrykjf~)xPT;G)64>RnNcji2IA)BEbnW9DjGonu+B@2ZZPnhlay4-RI>`N zfC{si8!>z51+^1l(o9lWnQu;-;X6s0p_n4lI7#A-G@;u}l*Ofc0Ej*O;Nb@WzTR)( z`~XTBF-6JpJ&G${Vy#2z61@2-gHhsiQk4maNHRr}lvYWJKuOC#*;-J|1Z}as%$nsH zVxgEONfMQmR;GzDMyOzj0-T*xtC6-%0aE&+uGbC-gU7+J!Qtirhv7i#PHUF!!TAyk zX+P2*D#>NC&2>updqUQt*PJHV)F~pS2=9T%9(xooyzm^Jf8ir|;>kw=IP7-f(s+Jx zhAB>%rU_3x@g%NZy(-r39Dzxe-51Y^3U*AOS!Q9>&o4P7T7|+st8jae*XK~yZqYo; zu`5g-7{UftPAEPWkFA%z5SNc-?-=F5W(2If zNL_E|O*TSfd7_E+wgcVpthny=4Uu}rFxTW9m#~R4w)Q}1M_?8b%20PBt_BXxIN#z` zi#zw;87+ogba&-}L_c#*Zb)L&b+xdwvUezplmdTW*4W9`(l$=YQWFdU;K zOWN&rh%ri{MG$t|3Ab(?3o|LRWKUk`;qP0Wzyz z9z}qm+2;UN-=xKJcE7|{w{s-_=FAFy1^Dt9!MhRI?tqIe_VKNKT2bR>agBF1>)0rzdS!veUpL^lc(}FleWw7L z&wu3+P3Lr3L?|m&%c}(kG^0~q?34B} z0+rbG!p_^zAK+T=AFl`qdZsk$tohe#dtzVb?S5K(-t+Iv=Fh->_qT%L%lOx&G7iuv zSDLjb-!>O>7njWXw<)u7c5oI?VT^k|f7I|I7#(r>ue#LNci6kvrn?2d`_7R5-d1?( zz0F$s-AgB>&-<@Au${M86xe!iRq&IRJ!)jAX2{HpAlW$?)60e1SS zX3pv=D+D*v1V;+o*@yBXxFT@ zC1&yg;wq@|%k83DgSnut`Jq~4_pIF0{K_epm|*giX*iPH%0v?DYvW6t;5bM!tC&lY zlxdnu-On5)n`E{_%`Wwnb0h+BfJdM~vu`^|n3fpR$k=To;x1y`MMRdu(PZVVe5%Nb+$=vDTWljRBE3}q10Dzn)t#>T_iBLsF5`eqojOaAJNE4rpTE;6)ef%#cfQ=rS zP3C#>fBa!=4uZxJ2QV=%wmY2OJ;BN8J#42fKKQ{8;o7x_K-r7%%ZxBE22cUx zSkqQEmkHjND{0oBn_qn!^MhpGKovIIa!ztank9JY4*k2o^EG_$-~SE=RjD(T2|WK0}O$E z$*pR8^D$I8h>N>ywfu?_jkCu%jyQhzJzRhDI&NIQj^o?Mn5I$AB99_;d^eZLU-R|p z)`og9x8*NpA#MQ^0I-7J5Ip{L=Jx#B7k@>{AZk0odjzfVyR?uPsAz@1=Fl-ODpM)| zMOnuUJd>(3A+spWu(2|Ok6I04%ce6d45-yvV@fNg}I5<+GK zW(3Yi$e2o*BLTiewon1wTt?N#)eFx>=w6Otc@`{pSqp9*d?UU~A52-&FegY37b-%x z(_}zp+Z5rvo(+q$X?C9Vz`gZ!Y3IBSy7J$aZsx+j0hD$zWgxBBUH!ce_1U+#THfFO z)Ek=pwc3JwNouVz-uWF>{+l;u;EaqK>UYvLF6ZJBOfJv(^|8;!Nj?3Pk5>TFYOiPg zAkeJu`>(aRva_?ku0fyniP8o`&QK;QR$cRcsB14qp1mR!S)WC5-C{+C8ckS3;2nbZ@C1-k%PXoD*1Vj{>bF7l3Jjd9E?%AhjoO9~A5S(lRDUTB{XgMn|N%@D7#B!RYtcUU&sKQTfWp!a6HPg4P z2Wsu#q6{&sF-afnY!t-|AvjSu5Q$}XqoD*x{s5aWVB|H*p0aT-c!hV!t>8RkB5#P0TUNXuuNkpmSCBuB88OevO{BOVY?sHsP`7ZWhTTg zUuW@JBvvUCJ{Xwth?pW?ef8Jz+0XuX_tfwGr{BW&egBULT{?&c7Pi;(Ql&&Q%VMMO z0L%l$1gF`2l_vD_EIQg{Olo@&^mEb)2sTeT?pjBe>i6kT7Bh5A9(~Xee5NC{N?tl0pQDD{R25` zh!Arl@#dRv;rRGAVoZ95 zpoEdEUHu%@HC}?jelK?x1M2B-)uP(4A!d|>mYdChZ~T|u^85KWz6j?8{F>|#LIA1d zcec^H`IArT-YS9?10dH4WCW7fN|wJ?sG$*%oA)g4p40zw9n1dC8JsdWCLktoOyd5$ z9WkD7F`Zo??Y6);fntQu37(~VAULT4-CUpTcLgl{U}2-Gzz|xE)Ro@Pg;--tq~RHt z0unZ%UM$lN#*-^8kRuQ~Sd4646>YnXt#8|2`F-&nYz_MrX#W;=*e2(k13rf`NBz3;{5@+*C>W3m2M1wsiC)Pb$F zPgtIBWlh)irG8BIZ}V-h6sWmvE}tKz9aKKOcK+ySb&PA@)nn4yU9hY*B}~KjsBu>| zg%UXeTQ?^Sqr zZE)p{Gx@URLw3f?*(G=(#H4Y*n*%9Lq;>BAu?$)b$K7@k0sH7Gu3P~qh)X8|Awd#h z<(!c&PH}#Ij=X&z%#3gdTsb;I@<2=*VvWZ7+-`4l4KGJ*D^b1IYO)M#n@u6^D& ze^Wzz#(!sRbyQ&s(!7TmfF}5ol2br%l90%|prxn!anwx?5aliwSjI>-J%4j0JJ_;h ziFS4{i3l-ChGm%#2Vw^YCy6o4J*+u{BvA}WVkJa~o|j67VV)w8 zBnEZTx}kA5A?`-8EJrR@bx1`ZBvKH301PUO*`ecozz~KqPu>a0rfEcs1fmS*BsogS z9L)eSv{Vy7GnaI*CUtApy8>QSRt&%<3^>?qu-P04eX3$X;(R?eZX?!SI1rQkC{Po3 z71NxM$u(NTQ4(CmIF-7NDMqpWG6Rk<_<)D5J%p#8egaQC@fe0p!2757aC-i}fZyE? zXBS(Xo}Eb&l#>%|cRSoVei%8A@I%IPAASi(M^`~0qYCgf|}wSgv6F}4@Ahr{JS zp?hqPfPdNj_I?wTWxlFFVgfF+33Slx(7%aSURlNj|HFUu>7q#Jz&tfp1to;SoMD=C z+4$zVBzU;w16DIZHUh<5r4g-hSe z^4t7PjXUF-rL7a<%G3Rr)~|*xx$e{+j_G|=d4LJH%&b)blAPsP-N~kiyo-nzJEV&p z(ryHgBalWAPjEcK@dV-svdqt{#qFumi17_7G}v3+t8z_~qTmkz03ZNKL_t(}@(O5> ztn(t|MTni}Y0JXwW>HMs|v^Wgef^*X34x)js3Kg?)rsx1|5 zqyUkdIcncG?^FARS?A{OUMLr;g|!7@z$G+Cvwh3Fc*kW|of~Qf)6W)BUGsgGylDYq`#sQ)_mcLSd*)}| z>a%+=&HVngGo}3jGD4hyApk>=(iFocz-tEB9q%wsBhJpwaB*%zzDLTEIo7!W-e)i- z?8Z?NM(xgUdU1w$rT{o*WF#Cok0FYqskk`r1n5N3ZjkfJfJH-_37B$?w%2L~G*9US23@CptOk3i(W7JF>K1*{p*Z2f!#hAN2&_|>eQn&CNV zUCtOMvAk=k3$bVrLU0&15~u(E={>xEdKY7im{LTXM(lQ5T0Y?Eb zM&ukTb7z_vPT@A{dy^E|vzlrv<-tJl&}E7?!xo;xI_^oRvB- zQL-x2xU>%gGG=jV`(Yz*1i1&9Mlz|vG(hw3jnTo@7+@p~n{asa(MR#(i!b8kmtV$H zPd|m9|Cyh{=U)94kn<(pcNm6JYNi(}m*W0|T#SZ>fC4(!l$0h|EL-TW`(<*zjJ7Yc zT9-}&UHD4-jxT@pkMN_P`a1;#w@Rda*FI3(T7OM2w$CmDzoJl+d<(mCsq=f|#$Vz3 z_3OBOe2kbT$@c6k5F@B1Y9`$-l>#gKy^)vh#~(T?@oY*gZa617mo}RXzVRo&-`(@M z*WPFZOkXU&CFWQEYoeI-|LgN#l_5=kTbhF=qBF6(p&jP=e5er2wi_(upjFt^J;NHW zTi&U0zbqPSP?7_T#|b=5z!c@*IBD$81n>mr2<8Zh-^scLIJaE`57ehY2D*JePsiH25z{(oz*?mDHOXo zu0t=SR$8#%JTI@Pz+-X#kt*b7{3KcElpH3_IBK?M(mAlulGVLl1mfj#9jog z?zOeK`zNDZyY2&Ru+L^m)|oD;l>SFMF+BV$!SQ?u5+Vsxpj5So(wL4Dm{?|m)7=9*{8&bc{I(TnRMe>dy+AeZr} z2RW{}-_q#A1p56VzgvRe{r#Vx!Iy#Mbs!AX1r^>BN@ioq2!qyu1&|aRn$}us0s~>A zrG~}aN{lc`M9tEN&_)V6bnUCZ6IOXMOf&oBhdm|3Vs0^=t@8Vnpn$; zCMKnfkTW83Nw$=lq)XkR&#i=tM#(VG?6NXEUjGebuDzn=VCRtyz?zV%4B9~emW_QO zq&1t1nUR_e$t;##=NtkPC`hRYPR4Yt4HKAH+en&4TiUW1K+!W0yb2PMNJ{TfZLBCd zTp{+HGI+~KPTl5HlA3+$!i6YU(P%ccxKaBC#b@kM5~dN6TFu4MnzJO{aO4nzl^RgD zT1o;C2mvMe^g6*hQ-?+mRCuG(bkeq}p2g0!N2w*VpaPt05 z{Ka2NGB`%UM?Ul-jt(CJm@wrCjzA{H;87CJnFg~xSoUe)+C8$^0}Jq6g@%2A*bb4! zXXxJ_)avMyB=d_=Eb3o)<4gEoW--CP{U5%D@BO|X0z^w06#ybJPmovkZu>?9{z+)`E_$6%<4;6Bp9Q9)BD! zz4Q`3@rjS)>8GE;&wl2g;d8J3iiRO*nIjER*|&zR1$_S9+SO*dchn0>#j;Jyd2in^ z7lgX;qJkmZS|h32uGS>R>~y(9em|$f4q87v~j$EChlYI)_zTJSe{Wm z_#HJ_p($G~&M$E5=DWCY;|6YA|0~=+zKxWU0!Aq9MQtkr3djl#H`c>CAH5r(?cFuS z!F&vJFx?8i#L#k#0?H0H2Mh4~`WJo$pg}4}c;93ocMGA6cxC+-pY?wmj%XDZ;wrmF z8xw0$&vcN+8i$xCM_LUR$>jgXodXlJnrd-h-JKU zg%y@G2B4H;Yv&)R0)GLB?K!}eCmMsX+Qc@0MR8f4k#pWLP`xL#Z&U_{RD|@_GpGeT zWXsZJbFTnPeu`3Am$8n2g$@h&doW&X0C$y{){bHoF$p8>|L&WvUlfH#d$yxsg7y(2 z(!{;4o}10wbWP7+Np&Zd5TNG%vW8UeXXfhouN$Pr74!A2;MWus3Vw+?OK>X(Nz-#q z(9B;)`@P55+SLKmMmcc5ix`?vYNqt%wK**tpiT{XTI!9D>-5<5v^G-SQE%CQ_VxyW zeqKY;1V2+s*i926OPL^~TBP2Q!@*(3;o%`Rn}9GlY&HSI;6RR%;)rS7;o@S8@%#+u zXXn_RGNuXe2SCmjm@;A5Y(POay}36}36g<`B)e6L5|hO2p*5d%g5)Pf`8%eFkOMqK zU`aC}&X{V>;^xXzpQSQuR_A$nBWT$gBC&W02o@_GU@oWTnz}aGy5=*P(kdy;T|r7b za|5b~0Ct2-Ky(6dy(QU7Vv+ILX?MN4tq1LMWp2)i#@h(iT&CK?BSY#w64e@XqNSA^ zQWA!kkP3(vjeBo>GSX_9wE%P7)aK3+jHVz7o?^}Dm@_oF6N94|lmUVRV{GH88(G3C zA(TUx2t?vC9=um=gfbl`h}nb@N#r86chewcu$;dDNHi`)K#uy3x#icoQ8IvMiD4fl zK}^n454FhSIfKB+l$5#3dIf9%kh+7L8#;s8At%;s*ikLNTIV+MI zkPPtNg~~j!WIt;MX)Dw`2w3<|G?~WSdT_#p4yCWMYB>XO8u9w8zkydi`%k-ee(yj2 z7XIG%|B#dlTfvl<^=ZzqYk456HC|)9S4N8}EU0h;J#^JV>@3*42vp`qH51=-`(~E< zjMNHnb+XVVj<9vaeBBzbD0?)49O1FYAIHlte+-}a_$To6(@*1PUinFU{*7M+Ac^RP zVGuf*xjlDdY{ZTI^SFPm7lK-|U}T2|8duQ=q`5ixZTqwae)n3L+UIg@vsEmUtMB;A z*Zvrv{^Z}rSHJqli|5ypT-|Rx`}SZ3zp>PSWd^p}9d6&gh3nUE;Kq#`c<=ZQVvJHA zhzKA7%H)#v&)grN!apE@rP_Vwf?S!KJ$q@dvTN;oPU6YJ8GruYzp;4kwKsl6m7Jmo z^T8`kh7SBzpw|j#<%-<7*qk!4X_(=pX{hnE~C=aoGUO$V<@WNXUDeDXvzJM zS>k_F22WD{NWzMuT74rZi=~&dRK7@QLe84KTTz|?fNcC_wsch?MoI_PH_PkM-&-xb z{oeU*uC6|A15|XfS_vBfD?VJY0%u8s?@XZ! zMV4iMS|670u@1KXsO&sD1NZfP`5B=Is?_Iwkk+}-ZU<^-G%ZzJWW3A#1pOuFRRx8> z<%zu3=%TdK^mFe;=*HD@#qPF!FKX{0^(dl@7MU;Uuv&;~aoQr~tU#1Oj!WF5fEr+mJDgoy;QZno@$3xe7duQBz{M5_nzcEBvDxh4 z1}K14{;ZbN;&_viSo)X|Jh0LG4d@VC9B^eCtPQlnL}C_;SB$W*7-m%KN3QSB4ZvXl zaFBYHLE>)(_^I%avRFk^1zw9wLuoph7FbXTHFRwNSutOU>tm=ZHCW3#2*dMHp7h9I z0yZRqr^P6$A1m_L`=kTFt0*(%^DVP)G6oG(1QjUrm8lF$f1A>mVYYqVRDUy2^wMKy8 z#-)s?#4Q?aaP~+s;`P^l9j|<*PmJ~Zzx!MGz90NyX`S**LV3^dvLEj*pMU@~bX+0AR87HC7a5Z^%{MXCHK4MA5Y0jeHFp82#E= zxCVZI>GNLzIY}7eyn_$o`n+1_7jouQ8B#4r3*f#STkFzGrX8ILa!X-uDQp@@&{MmU zE9|`mRLv|)T?Xisv@D*=K5+skad)=t*m8bMNI9a!=NeC7<#76E?YewUszf!V8mTaB zzuWw@!f`tn`#9fa;G*u2|DU!u`?~D7?!$h&>fG;Z09+Q)-6SPi$&$qeXb}Jhg_>ne zwk1WeEt#Z9S}R^F$wMCO$2{aIe}?>+IBPi)F^~i_S(B;3k|>c9MUx^i5ds<{C5j|~ z9=_q;d#Y;ZVeehFtIoM!H=LD&^`Y-Q_Y5`ey?=XbPS)== zCyU8X?tb&Up&>g~PcPhi$olLjQ^!gHY&|`$|DgNIlqqhlnq{#WAS!Hf|NsB{xI4aH zX($hOP#uXDjIc(%&jV4t|RSNrrHP~7cR zV4Xi2jT+zGl!}B28QAXuoB}DGN{pu7Q&<#;T*U1;<%E(atrbWh+Tv_`j@@pD(-ZkO z@Ala4#Im}VM6#es;x#iv;_=k7Ye&vdfZ2d0m=Pl3_)@?TGjfte5Fr+Y$ypaf*o{@N zkbem!vy`q$4FJPilnbEMb=rW1HgF*ZY^IGU05&qnIV6-It~f38vY&{R8J7T=y6){= zGL`H5AQu*QT`jCG`?+W-pMqlUzF_$rC&Ve>=;)|s!IkW?txO38LP^|hN=qQZfl(mW z#}GA!mcVKy3_)EVAt}{sHb)SqN%|qN7ZQ(JEgVJwg9#3rkjVPa1sn>p*5xIOD`I1~ z8G$9~m3FxMv-uL2^~Q)9;%cAf8T)yUlBI+YiY5%&1dXi@YO$Rl$+0F(@d!EYz(-kQ z$y=;;PiW=0V#<}m$Pl42&9f4(BITKa0PIK+1VRX6`Q4NP;((YYkd@P6s4@UZsbIF6 z%3b#7mart}f|Mgd%D`R-WSDe}AR2xXPHeFmoi<%72Ovxn=6%L1uYD8Ged$^3=Zy2y zg8%mK{{!6rEtfG(0VNfrB<0C?VoWtdbR(3Va5gY@UU7l5>ke6ZDwDTsOn~f&vN8u- zHxB$lwUrbIaf$$rKopQ@#+>%}$VYx1K*5JU{Lkwnw8np`5@wT@3@jZl;>VO*&l&_lk zJw(Fg``?Ib4_w284?c*uyyY$Ug%AE5e);i_gF)C#M`C5$Y^v+IjaffzZhjoA9T}t1 z@}Qv;{(SdrH*{;@ckRATNI$Ud2+QZKy<>d#>a#}BWD3_IF%|&)_HTa%KlxK)3BKr^ zz|u9^pKF$(27c#xk9jVVR8JLYyZs)oeDj-l@vpDr#TT#Rm2Z5*xjkF?J9CbeQaJ{E zI^o>W6tjvdb~`9MjzaO8aLdE4{orEMyZQ6qq7Wg6FU8f80hy$N9!zf z43fWP+^b%(P_6l7lvCDaahXVo&?%mLo5;Vvm&=DKRQY9CqDFsxR%C$1&)Exo)}s*A z5aVw|Dv!T*Y5-MYE{+hJ>){eI|29)}aY#dRFm zWEEOmy53477E9i3mSK|7aqjK7V__br9tl{PFz5LbhSAV{KhgXjEbI|TBjn#A-!uHOQ z53jeSz6KLC(NrM;!i(fu%BYVo0rNiN{CtO;7-zdJVmL(!lC)^vC(LsO?@?8Ok(b1Bn2D zpw_~mf$&vJp>r8Swe}kLHAXDSlq^;X9r3ISq{urr(?(q0CP|V7*!atPQkFz1N!@R# z2skYY5@H~fkQV?L@elx(Qc9F^FHD7uRJ2446%aEf+vh?KNw% zCVk=}Nxv@95jN9C3oS6%+(C7-g%~7miWp&PYqd_hxf{txa0xCMg0NuLnC46Zq^0?` zF?JvjraX%qdp<%WN!maZ0FEe(DyYsD|LaR1!H8PcIi?oRp0i{YR{^G&=Eueh3@%yX zS7-vo0*(P;6OnVqt2bZ4_PH4+H_x%#p5eg<-hunycm)(Elnm^1!bB>3a8ERh5cP!8 zoW|FIf?Yo*yQpi(F+!gvw*lcM6n2O0KUhZeh_DfN|rU~U2yk~9R>Td(^_UHSy4sBmyu4}(b^1tCa3!NBTo9*}C{_W4; zCx5aB!FH^cI$B)S_p4|rwf#P+Cd*+TVR0FJHfoue|&fy!y>okW$jbWq{G^ zpzh7ZCIn(T?Dn|{d!%cQN~HkfKpel(HV$iT^t{%OogYKFKzL488u;87m*DrY$Dc&T z1P~PXPM9{ETDH;3=hy>#T185K2?prKwjMnCjoJ3Lj@6xnXA|zdz~BCDg0NY=D=2m4 zk2ocid6x1=^Nc+2kmoIO+N0zdIn9_g8KNX0O(+C#2*N`;;oZ>MYI0H5)o$wPgGjcsg6jxL*ip5l#(i- zGy%*qJQFp*Yy(@M!h%_c56z!T=#;bcHEX-zZew**MFHX@G1p+K*KM+t7cqB8(GF(B z$kj3@0+WtCwQQHwGE7pFH&DMAiVJh30Op9AZQ2Bx z(AvYyh?;HEGDI>1u>c&BGF3)ku3BfOvrrJEpOYvJ_5@JaOVYFbEZMu6MKhiflGeKf z2-8NAn{7%K2Bd(}`c+mot=0DhbTg@&95g1o6w`|9?3qwbs=a0vI(45Eb$Q5Tj|kCr zaF{T~&@5hALk=P#azH7B$f#wdCMBsfz$cuZ@&O zE(l+Z5ik~ELW%v}1lRh^3NB?%gfNN=K20VrF;WP~IiWD&(MNv`ANo)O!Jqn*Kfrsx z|3{Ehk^MKg0eE4g64@#+*?DP11;EB+oVaFlL4fPKmUS{Asa*+>x=E4%5$TP^4WWBC zlh>S&%mUrouzob)lrhDCD_1V#+5^{c?bvLmb8j zXlRd?^Ew>9|32j3xBO1ekZXj{UnJbMHXgo)5B$Cg&tf}5*zYfsV4jkb^5o`QM`mFD_vVHB!m-tT8|d%pfMUV7+)2@1l@ zNnAfgXfLf)&kBe+*nbE57m87LjS0GI_sV#+#D8nx_wkQEDb9hGNYfHtMT=qfnbsGr z>_1aQY6tsN1*vL*S$keDaIUQt6-(UpCWJQnV%8g(`_e#B5%8P$31znjZ+9r$Ez0&B zdA~!M_b6$Poc2g*kNtj!{a!4C%xl}B2cP1(C>>Iz*L z9#Ls-2XyVbD!OVNT}vbcTgOxZuvp#AqTgC-GN!*CW0ixQ-EmCDY+$=(wq%-U;<@?2ox%q;snkOOj$kDG#5#%rDbe5L42?owSFwn zC!7LMGejF8w&$jt>mtob0Jda6Zi5}XC0Jc$3;KTfqn1yy48yumG7I?4+P-nokXp_u z5H>-q-~hyRmLy?TW+{UpuFu@&%ATRZd!$~|W?AQA42Z7G&8RtKF5>14)Z+BaVo?p5 zbWNz>tW2psOI@l9wd87YVL%~5(3sRwGiL23XeMV>93;pZL22>iB{AlsEv9LQs5{AG zrsiy30F0x;2-6N>GvS!Tbvl=foKwxZEb-Ef=otW(IO`~&Rc2JWQN*>bGJ4MHmTlS8 zC!{nZ?PRkNGjakrt1^LDlrn)3rwIgc$u1ShF$yAL6vocF7Q#`$=6Hk6C5hvuD6z{z zco@YPHk&kKUI7A@5M_~O%DV5hrgVtNWyY&FUcu?<32xsy$LZ-g9{#R(;Z0Y+6$HtS zK11ZcO%xA?5JbTuG9gtL`@27c=rm^Aj$SAL78m&I4!+VDuq24vY=ogO7$u3;?IVx= zDn9(7<_`VmfBJ{`o*xiPaD=QE);4CZ) z4Z}5u>I$#*VeR@mSx-hS_1fV<@LD1)eX$7JRaPXFVwO@(o>xm9X#%X>4zIp?124Vw zWn91hGG2Z4RTKlivBjBN9c@`o5>8Q*BtgM_WpXC$ab4SR`&3uzqWR5&j0ylotC?6o z#q#^?7yirQ8IOJJN!iCNvGHB0BNH&CiMm&Oo2{+37HrF0EC|}ty7TW`_rTg3wtd_z zjq1hY6c~Wz%3x@q45$EQPRP4G%5IOm6#$&KTa?`nyx*gw870kKbxYdd`|J-7oQB?apX(|j zRVob+s@6aouf}HNJqP%zU&p>p^6#N_@_Kmx^0+Hyr{f@2f4OE=wsfTmwi=)oiHbY# zHJxw6Ww!mvoX)5!Q7SJbXBE{)8~<=CKaH#}(v5`e<>_a-3{$^*o2cHB_@- zJ5*WjDjjpz+W+r76aMhB8g>8L=QYJ}8;!Oo?*xMHv_=~H7Yt)DsYHTLm*5w$d@J&& zNu=@&?97ugHcO`sAhTS{3{1%Yo5cTNbw1s6{&H?9?%|#Rpi7SBt?7QA z>qkxKYV9yEUZ~#?#6@F6jS#Z}Ia!c}g@~6tBN2d56dZ4mbH6Z1J4hO%>xDlNE&>7< zFq6a;={n%R;2=H9*#s+SOtAH_Emm=hErS<4_%X0k zg1Vk0bu~BVYDpHyAt2I5B1L0CiHsBqC~N?ha!7?m$jMqSn_228XGpRVDHo<2IBMMU zr3ur~gm|PiIz{}gG=y_;<)~CRD59|k5vVW<>1H8-4FD&Z{K5&ZzIK9>n|qv}ZISkj zcRu_cT)lb~M1*89d^u!~CjeeGCd{7WUxVes25w8F4SLAx+9sim26 z0#RIm;7@<@5AXv&{Et;RFy(CSw}I>+A=p*PK(3y zd+2C5s@=aPH2QOeRav1lZv>}f8$7e8mFxX)GD7Vc=ALayPkcK>>9>6EMeDy^D?>KA zLyzuZRjC45M+FjAVllo_=Xb8jCC|@x`1;qsj_cR2y{n&d1Fs;)w>zHrfDz9t5!b&lkY$$)P54O~P3_NN4y@sQ3?{ReJ zhdX&$+vh!@{4rX24;^GcU%mkTK1Wlkq8TP5Q1=XLV0#^_(gg^nBwKsG{m=8afv(8; zegGCcND~q=iBfKDzu6h5f~@a0We33$aJ7E;z1g>2$7E~^sO9oo^y4t!>XiHSny@_Q zUDL<$AX8rV&pOPrdpbMPTpPDq-NxDzJODPt*6*oyWK`|3u{OhG zp-?3Lw`d!*jGe^NvRaRZ0r#bbj7~GDg_xv#gVudV*+b2OeLI|rO1?+=Tv*x{)e>z0 zyn=WXd0er&d!=TJE?EIQxtLI(X7C-E>iVR}zt(5Jj+oJ`-+fve);l$#}pz_lc2#BEyRYk{y)D@bD!6e|56m>H*GE;MpjscMZN?>_r zWMH1anSni_b#E?Vnk3PWye zvDRlL*$|APWttdBA~*?vD!6rW6VE>PH0GVen7rrR-;FC*u2uncPD!(o69RfmU|aKt zfua`zJTp3Um?fZEn+_Z%7%jE50JWND08g+ufs_*nOH1%4|L8yAhkoRrVxH%!xu?(= zg}0=(_v_NM+S86U)KV4oKD$?XX5+=?Dr3ygjg{4$H17jFS($KwthJ`_>&L1JldxwL zj0nrI%?8DE49 zJ$$`iTdUoi`aW2${ocJ)eSP}@Owc( z1*XyjaR1w(IU1EnJP6VL2Z@O#=T6ziYYB?EKC3F9vt(>8N&l)fID_U4nnm#8c?NHH z;N1@8{2aX7fs@95l^NiKTxM+N9nN-VI6XhZ`EHAZ0x8K6DhN}A*kq*&@Z^u|J9(kj ztW}|2*T%~4b#(h>O$oXXw8=fo(aNgGcl6KzYpD;i_Xne>PPKclTjL9t^NrW@$~CVAJDaBY&)}Ghkie{@$LGd z?`1chq{)OjK49rz{L6oMM+lzyu+tLGJ5 z$8vp*b8Xiujl1JP-KVCYqSfD9i{z7G2A|~dkg}}GFT?bkqiNk2#s{jWDQgU{Sxm>4 ztbO-8qWb&lk5PnQPlx%J+!Egun!@nim~C)ef1Zysk+%&n`)3(}HDPn9nm%s6TpE4FlMfTKp;r~#_C!TqQpU)J3LtXhX9Hq zXb=jh1X*Jw*8Gx%X;p2K|5hPid zQH9uQaV|-+qw6{eL6Sh7oZiOsUwTe!Pe;7#UGKu>%Wp2X+0rt-K8VHtcB<~D?K+{G5v4#(%lmG-g`q;1ILmzClg8%pre+S?D13!jR zGGd7O?w&|jxT??U1j8VLn+JIPcsMt+1;es;$!{k38}Scp;TKI%Ajc@ZP|}2P()BIt zFXe=&39lY_-~l}Fzyo;Gn=a$SA9^1?^2Cz>qLz}{V6(BBs@A69-m${4c#L`VOqsew zSH6S<1GQ|M?KL|;UOUdW$*61BEP%8<*9l^FzUqe!+ziJ>?$WCk>mfX(3Q^|HJlqok zi97U9y=OHsR&7Vgs=!Ow@1@j{gmn~bw>y08Yk!9qUU&g7zVs4q-naok!aC$t17owI zq15I`E-VUsf?C2g_8fhmtnb|#cclu~zN1k{>`pluZJ!>4g2+pD7 zJ)N{~Aej9+xDyR(d#?%d!@RP(R9{HX8YmtG24>CnY{{*P3LI9~H_a&X4B97fnt^!_ z-tW;8p6o%C5F&#LBcouO_Bh#{;r8wfr)i5FGIAhLG~PkxI1GzRE9}6NZz?yMLdNUD zsARAkmNdscuX!=7j8YYx?XdEN-Kz=!ts>#ySud&r*yz^j-erJmoX-{B($-4=MFT}# zfd~;b*|;=eo~yFFd8QCSt4FZDzYZNLcVl$xNzxm5K8o76K$b&9*BJHVUHb|&fxOZ? z<2{Z3v0gXMnWyt>M^oMow6DE#d8}dSVT;iKF16<{;1@!0awjbxz!d^4#%>{7bchOW zuNrN!wcEgE1GDZWwR5@#2L%Sf&566zWHMG|1XYMnQjyuV8Mvp!1A75|#==N{n)~4)Ssp}9>e~<4!>oWs1Ihfsqm3!QHGDB)ZTlY$pMWj8m3cXp}qJfN( z0NMnEQV?_(+$mdX!YdymknxaIy8Ho(dd{ zNVLBYfH+Cr=@`wu$XFz4!VhIOR)*u!IO3CWd!ga79n^N3vsi>xNn!wQ(vI?F$ zmJ~^{7e~p?U4jByp`Kk*D-oik{&C6)IcwayGU`x+;HfgZT)}UVwUNXk%~{Hx#27G5 z1?T5C@%#&4M4SjA5*~T@J-Gk=D>CGk!krnLiGUD69l_|2LmIt9zuE6=AlMWDo)J_5 zcL1mh#-u_*oFX=uz&NV?Apnm({_FVQ&o>bKsZahszUTXYR7wL8RRvy0ehk2(?Qvts z4HOUks{K*sbs%f53E{>B>$8-JdMlc&p~jpK9n4~B3nAc&x;;Pez}s-;>J^Y>+ym8e zG7?+ayEgUn(m&f~p;~^**e1DV1i?&Ha|Vn|^$-KS({YG_uVtDZ-`9D(xV5-$EwufJ zUU3Xmn&=Pz-Fxi-sPVs}JG6gKjrpAu_F9#}vIaNs``38s#g}mN#!a9wHk+xsuFG=( z%cx$AzQ9`o*T>F&Cn7CPM^ypQB)TvNXWZ&mj|u{2NkoZtx95*M@i7$up|Sj%wl2fc z<*pNi9dI=PSi0YUX$AZ%{cM(S!cx**li>Xtp?cn}EC6V(-bKB#m_aNxevve}NlKu! z2l5Qcd!XzPkO7)eEIDZi$U(+?%LzAkr+DrB1h;ov?3j@QAy2`{1%1?Ot1zHKN1Z=j z?VYWU1}@F5)zM>H+be*q0>`!ScFzD%ttE9mcJkAxP%+_G=?|F@=#(|9`}V-x>ln1P zW9z7NiWCDgOwwKo&O&7hXxraJpeSzbtzZ3NykQLxtaPFEom`~5S2#F+WWy+@#X#Z* zb#1p-o_m)EGs8(u%R8%rqQ3`FxzF9Pu*?!*WgbT6xX-}C%GUj6 zG{LV0_q(T~74#}VDM?>vYb>bc*JXo7a?iAP*>~S|YoFg`efW1fmgA@{C2sLp` zDJD>vV9|)7ozKQRbQ3XHExl4>d7wvd%L2K)(RX7B#NgULbm)rXikn6KqmzP*D z0}0p;1SET}X1Em~td?~*UKMkW^UgAk7K^SGTEzWb0r3#+L6R!PsHHZ7C5|Dj(_7S)4=DRtfN2s-J8{4S!scjdiP?h8M`E$!f*C0lq>@B< zR#$$zq4HuBu)4kFY~@aL%|d|u6eGeE#hp4vExIl)={Za7VI-~qxa0yxK%5vQ0k==S ziKn0Wy!2}>c;u0H;mVb(h+#s`1!6uXOq=FiaFO8L3#&aNX?udY>qij0+(QH7SbsZ| z69Sq&G)@yXDlEy(<-Z6zY5fvc2wdkLkzfl`7$1S@BzI2?GNJ3Z+8(Z ze-^*|_>-DgNHXh+a%;`i-TG>fw=bdVjLV*|fA*Sg!1z-*RG&ifrO&j=-hN&+~6LI!PE!ndY?GEXR4 zf^yy^oSdEGn`bxi_1iaa-xH`;!p6fV|!(CeVm9#}@0Gm)tx`)_)H=1U1Y@Q>12!-c1cCpD8HVSp^ zs*q(?aWCArcC_`}`YU4^hBd-4dH{8Mwdb(2@U+9zJyF8-7Dwwz`79Bd9e)tg5Iow^_pv^jZ=_F$DBd zoho#kU;tu`zpsz$s0w+d^%d;-ukX6ed!-gsm$yD|SjS*Yo%OV> zfaRM#ko0t%hHFayy@I)p;)ul;5Nw+>x=gAy_IJ&-xtAsTws`<-Kw@PC$+fGxCUB8 zt$V^;ONB7E^%Wv8P2##5;{=K_MVcur1k;+bbYk2K4> z-u>?H#+55?LYM+dVa!@vH%#6|Zf*109C|{$`1y{6*R;6aBJA(2LO1zy%jb#GMzpm= zg#9e_GMTYbC-@Wiz90Mvq&(O13zYy@fM@%|tOVvVZ_K*<#W-}GBJwf_rV7r#M|HgAl~wpw_vlG@cy6uAMof$pK{rrCA;oLN{w+| zYAwTs)z?V1Jg2z+cu-12HS2vFk5Xgl%D~u0L2Aw2+-Qh*wK}xE{BI+jT&11*++zIH z`h6&ivpd#=%du@lR4u{3^E;oB#Catnr-FITnA5E93fOM9_}bULhUcDp4llm=5^mnS z0Tj48zwSM@R+RUd723wiyja%8!uG9wHU)(IuCd;ZccAhRzfpl)vI5(PFMjSX7ULt} zSGG)y5z}TujGGF6P3V*Mb-lCEgRNU0%5uraehsXRy?=03GBH%a)7{*G#wrw=K&CW- zA)ux5ZUewMqojnarHn$JLCjJSW73#s+Q>U{L7Hc5w~X_&#cSK!`1;LP@OL*~#cSIW zoaGrAj6y-OK5OWV-^Q(-7}j7fWlADr5pdWkw@j!7mi*UZ;fY$f4ZHPF|Ga|0U1O~< z(Whcn%dD}Zs1%QE2Clk~@ z=zby>mnl^lu*g@?X22Yx`*CUaH$|oyFzyDW%ChW&7izy{KGZpWg~na<%myVKFTRL> zw~ne)h4rAf>Kku2xv_d0*nApYUVTfW0S3%iDnsS_0p40cun!4;qx1V*Kt3wmX1UKc% zVV-L|VtmiVE0Ek;;O?~h!Bhg81dC8-JM>>2anvJ2f+A~{A@}al1sckzLZt&PCAY@a zsztSP4>mwEf?slfBZVETzZ6<*@7Nw&>;^cD2~_JKWD^$ak7o*uKD#ubX2P=mvC5s^ zb=hcQJzRVIy->H?Fsa2j8Zd0u+(ZHJ(o{#_8VxWHu2D1{dFfVrS^gXsR{ z`sn(vfx)+I=y-rBJtXTq)B#5ya zXUUwlhzb6)Kluc{_XmCgx#SjJQ32`2j6#0^RA?f-uF>b({`OzspZ?@`<5zy|lbDlaeNHK<$5O`m`5u4!w||QlUicDTe)&3X-?|M# z)bNFX)>PvyEysez5z6}j6Ol(yDg2`!|6(P&*v&aug=ucYX*dMLCxjSQ!S54KJq5G2 zNfz>0Yfl^ah0>P>#s%nB1=w)(Abz!3i=zr}j7mdHnGE&j=xBhGLA;o1z^j($(YDm` zU!?Oe1)xO9#lT4g_J|k)7*gMPmv=bbp5ylI6Wq9Y6R*5_1Fzh;fg9(iIM0$qGc!=k z6iX26BT!2aj$rH(6OMzD*&xiZ0Xuq^Tsi`u^WrKJrseCZmoS=x!=n*oT1V8CfB(8hI8w* zKpTywtQ)WOO6u0^Yx(CYf{fpP1@ zx*@{)d-1&5o|n(!foXu)-YSakgM51UzQ(`(`PTLV+ey{Edsq!s&Z+WV!A{Dq{*+? zm(rl-E^Y4N!3nP=7i6{gMj}nh6+o0F7FstxvW1U2 zA8Ua4&@l=v^1MdCLWtU4BSb)&6Bvxg9{Y8C@Pj@k_!Icv9}*DUV(MGl%vvfI9~qM_ zi3V9*1sbh0!TrEkED8TOhD%GGe}5%7B%*REZ|gAZQA)vH$#V{qU%V6&NOjODs@ zZSA;N%iURBSDxjQR#|MW-JOH)001BWNkl$A|hO>Rm8@hyq%#JH0`V%O^{dbB38grR18@W zuGvcdlo=s})ojln{gq!;a5jKnjYV&QfM4^ZE%u;C&(U~YmA|{=jutNy9=qq*JGc$A z3beMaS_#LjW%I=A#>&JBPmikzg=Ekg3et98~McvoR zFFQ9-+f%MBCbO{n#o$G~Mwz@RJH5V1lre4v>-rz*VsP)^nhm?RLe)Mwn$Y(VjSt!W zQd&_&L}+8o3|3b|8lT@C3VIx!@c`JqOCA;O$65vbyWz8UI>u*oZLo9QxG#q2;^*r_ z8_3lE8$Yx)xe!wQo8-@|;2o$$TW@}&+i%7*JGwo9TVC5N?)P?GdrHuK=YO}pt_=c1 zyf;O@Z-Oja0w9-=c9~I(oT5Z4e>hOx0b=!1ux7BkuY2OSkB4)Ij)j5-+&|j*5SGsz za})Vz+H8$kq5<^t4qN+6nT(kc2$<}4^DvwAnt~Ry>hDeC_^9h?HO<+^_j6)cLo8!!A#syg@>YJYdq41jr;b5Aa#yIR10wDo>XALzZ7IR0s+_nY-OUd zW^zst_Z_|7+^nRddX2`hiM6^VnURTU!`kMrWu#;)1H@bxX&=jAV;fX6PdW|^AlA6F z$&zWY6wR^hj=6XN3ouQBXuT!dXR!n!Bm|dTk~K?eg{bnQTI6l6EK{Iuwxabi=Q*hr zMU^t@=}>}d>2pHP@<0K!l~sxoB&fA}5@9t2uCBk0z)C-2jGzsHIG`{gZ3-x{68Rk% zE*6Oh6e2b;f=DbKA<8%~Gv=HTGLX^)B1WN>^eT|7r8rR)6paWYvbQ5J9mCu|lh!|b{E7dFpZ~yrUmx+QKmG*1?+1Te zGGT{Cbg6D)Wk5v-Gc;yv>$5UO_KK-qk+e2Op5b~1HEMNDX<(Y*&1S+I-}pv6@W9*f z;DZn1EpK@cgrK)|mYGyrqLsD;-T4q&1O9a&-;rHCA_%E?y7) zVQZWl(CB_Q7e@aswYKMioRh|Fr#hb{W#oCrez(KC+al*ZkY-R$;CYL@Kf`X`VY@rW z>DdWx-@b(#H*ezh$!+X*JE@)!CGSQqgv)dq$sqKRUYmy+~8$eB{#FEFucz!T2 zrq2pSM~9K>05j3TLcB7x^*#@>yv}9u4sD-MXmTgf=QZN?UTmN9t7WP}E=;O4PS;iw2$ zn-9QN$+*UVHr5t@-^n@)E&o01>1Z~fl)yf&|*z1W)8Leas#8*@CD#*tZy?q z4`#K}vEo6;tE#K1f!~bf*ps`*S$`c}YA(!X@l`N-6oKe79Z~~=mA<<{66rOXp285%uK@tZAFbT6SwH}=b z#BvSU#6$szah_B-lNWk|JszfwufserKl>ikq6tmd!(1f(xIWW_Bq!7`5J8wIV2TsM zB#EI!Xw!I7E|^O|D6uAcDjG0nmYR_+7aF@)ZzA zNfc$m=fvU;?c9s|^|xZdTRFIbRvylquwlZd|K6mg!{Df!beO_unj(NB5K+wz{lrIq z3m`#6V@BRKCQ#a00i>WTB23Si=+OgvI?lfJ85|C-5j>(?@CH^@2d9?K)SoO^zB+J*<^0d z%v`}z+Dnb!eMqxZ3{h`%Q!e@b742Vn@85T~;J2qARDooBcKfZpL%bM@dS=bDxG&H1jQxI({cex*vvZuD z+`{c!x3D`u1#*%s&v{1Lo?(A}iqrEG+&;aDo40P_89ZJYS10h zmNV;G4RCAPofH1;&igl!OD2T?;(Q^yuzq$*9vb$AZ6#BxSFqv6sA)Jf7Tm1e`rm=1 zU5obEmcPp_*T~u^9QwvPzD`XkUH8`tA!xZK)@2$`Yr0%O`i_p8`8l%EZnbm`)CF4G z=;Xr%aI(e}xOiQ(1W={T0sNk1*7rJ~TH8|4mrrVP=MwnpIls2M^`M`ph??+6+&yiu z5{hQyt?sChcEuBIPAcPG`^E4e44lLudl**ZEw%E;P5_jk+R-ugu$k{T;CY^3`Q&W(@&GZ;Z zIhpyYC+ZV8Z!@Uul))$>l&B9rYn)&y0U1(?C~?88mcUT5SX61kG!^8~ z>eUJ`5k*LtL<111X_UAy_IXBigF$mY;{s%Lhb>xdBWIu_)VkMoJgMzBu>>$eq^f8- zJ->nHp8ulES0Fs}jz@6+8?Pb;vHZ_T=9?$U7H)e+)=*FE78=tP!P)vlwuZG&vKF|b zCku@=jWNK(Zxwv1%Q-e6k~rp66Js$Rf8sas^B?%>dhehA>F-NSaF)I{OQR4*b`0H` zDei@`|KaxK;&A5=G2hX8erVimU!PR z*tZO$5IF)aixs{|)+KlUp~Kf>1Z3TNVand^+p>6u`(PH_H4Dw%0Hr&*J-=STu>-$p z#ym^eG8A!<{CB_jG5ni<`#!w?eg76Ozx*=JPEH&B^n8}Ni?=w|d1bf9Y#-@CCL zT|nEKd_70Kf1wZXF((v2_R1@`ed{Jl znz4z5O<-`^Bkj&HZ%=V@dK<6Zcnz=Jx`DIp8JL01(J`j!2w}4U#Yw<#VPyRimwdAh z0mK1Z3MMKNT4clsrjRxvMyoF9fQAZ?C6PvL1K9uXKC(ZY(?<2r`tUEGN=Y=qU zN%thZciD=u-_3Z{U)R8uDxwGURl%#}w_rco%l8qmXs2{DG*^5=w+=x;6P~JHh7L^Y zfv3OC&AIIzuC!}07Y>`ePPVjihvx@e-)1zyyn#m91hBPiTX>ER zSU9ZzeTuHVX7%dbyUf)N3D~wsYF%{?*?rQiaSUyiJOK7TJMbHW zyf29HP2we|AeJ&CJT|!sbh5THungWbO*lF_ssLDO5;Fn^9Vh|BM@N!igcE~#Cs~yl z$eHW2nbFk_uH7X!j`n_^+?0&xFj%z|HPqM^g;~0zB*8#o5M@x7b{37_DnN}*jjm*g z*JQRi_KPZs^)Lr@d1kd@YK+OSU`<;(g@Dbpku1Yn4#*N8+3QSDAZi((qdw1yBNS%o ztD16&(m>cIL;^T4BIlYFGEEKy6Pnw+n{yCQ_8OB-+%j&nDKVPc@MM2S5-&VW<~j`k zTD~R_*xZGgggK!gOaVtwcV#P)qZ_qAGI7sZr&sH9gAh?rkWr90A>|o)p0Ufai9=va z6H77^Fd~JTp*iOahA0=N$uyx#D2u#rp9<#LK)xpb@k>F+$g-VVjD9T(XxHjT^R%$I zu%qJ%jI8d^pF^O45F)UQ1XhC1x1V*e0 zI;4s-u8gQMV{Vp$zEAzJcCG@BZXD(O>G>J{=5PNNm+rZQ|KorE-|&C`^5dA(yKSZ3Kp5v=u{VLw~FaHfb`te`HKYaU- zVWObmw>@jz1I&yPiVl|Yb{h8GfpL&>EJc@gsC&aeR3*nsE8D{w&6(na&wToi7UTEm z$39+5U&R;^r%6iVg;wWRpKg?+{VkS*3BY$VkJNZ$UB6X4US54*&)NK!mcB^nUnxi_ zW1chidvSH%?{+vpJHxG8xA4k0U%|~AuOiKR98D2ZoDc(pSzN?unsBt);Aq-l6DJ%^ z8!!7zx$ z<_+A!X*`fvQ(Bp<-_fCgZ<%tgl)-u&n|rHeg03{X_RIBgc>f6agtiyBFRSBySb^sN z3$3j0J1G7ZfY}~2d_Dva`&Su|qS`F4xTwh;$<|w2b8SpUK5O12P4>In!}dT0a9-3P zcTu~#ep-yTHK1#m%Iszw0P3EC0_^(AD*KrHGrLZAY;x1SddbwBUshE7naxh+h!#TyB*P zOq$?fVJ>&TxVFV7&7$F2;S&A%F#Pp%-F2}3MN32_F+#@pOBPE_F3qiT?eK!NeP=Kd zi;!Dgj#WsAQL@Emjg>Ul*^cH6|N6C8U@^GpN;!+FMW{Bp# z#j=(x6C6TB(Ujmsq)FIXJWo`2>(I$)VI?rmsDH$nea8c7gB(Go2 zd+g^e@;qan8MB2Dgxov=c%zF4NNIMZLkO&Mpj21ld^2O7fxUu%E~rV&>i*GnTihC5 zJqW{|luaCB!O^iW-`lre#pl29S*fF&G9G?d5@W>}#o}m|U;?PdCboU&7k;N9y@>EC zF@3#9TfesVi^i!q0b7}#)TXvf)~w^NiLnL{3;>`0)8E5;zwgIdJ-?s?lSOE>#28DV zCqS%pA`lgBOrjGafSz6rd%3wnDOho1DBc4*eEl2Wz#sh1Z{UCYU;bBIzy2WJ`uE?8 zd+)sjFt9IDI%ShHjy6XU(%>v_u0`GVUaQ^S*E3J*m`95bS^*R*Z|V9^s8+~@0Or11 zOqU0p9)wolQcI}ZVa=^POKmbM=Xmrk5!S9TD7DbXhA?~glE3=`*`FX|F{B~zA>t$wGslpqI6YUhzlC2a5>JO7wSocHm{^H>(AO4 z6wRt1V>keQKc>$iL|3}alCV`Vw~IX|_ua;>G1guIv^J+IWP3q_yMOGeg9MW6|1Hs# zm84PdlckpXtZvWqevjR5hwb?mr?*dVvjfHqu<(!a9K~9eLgn)pE5Mu>|0=CO?|J2Xso-LYx zcFWa(kKlUlpXpjTT7$=q=($XfJUF34>y@l+VzU@}3t>Hv! zYt21lt$%Ic)_!mF%oO%^&cK-|NbIOQKqp}_c6WJH%e`xzE+yCZ0;X0|+utqi)MU5n z@z~QmS;w!hUF?!kHqWY20n=K%(l4E)F8i~AV7KP{zy98FPCJ@jcp0KZ<6JM>H3e$m z*A{dj@r-YE{M;_1C~hzsv|DSt4)ee!d5vSTb}pcSU_y)IbXGjOUWB+7(-QTwCA*rY zNn(VeG9i)-zAY`i5^sBTkeF3w#=M{F;3Bm2^jsusV&Q^3HwKnVLCykvQ)*zVlW#o8 zXZHu7OmaGEzb2q63v4{?-vDtv_w#ABF$qAJCV(;~-XH`*#E~Shi5r>EntosAwPe#s zT9PRPcmhy?T$3bG7LBoFU2gv46k0l?YNf~p2?-#=CJ>NO>!Sj~WMVKE;Rzf8FjbdQ za!e4dcM6&rF*fT$q_(U%W&|*bu9?ow6utF5T7oP$9R`+@0!~ptFenz3SSnC!Nxfv# zB_$;0Y8A4%Mi;HmS&$*wmQ&7{OG4&?%&dQ=?y&n z%;&%yPzvzKBk#u5t8YSx0l6?(1^5^NCUY}(4Y18#PhG$zp^QO66g$DD(ym@oz*I4hoo(-g)UBEo=!C1OO1HhmE+3({$@BK%Td~GrTUY-@mkq2LU%lDZt z?)w^(?E$C>4XA>Zft(NsU--*U;k(}T-FV@z@2`T=Ti^O^xcAv zXUc6YHR08_S?F7Hr;X<2VlUdJ#mUJDPESs--|fIz;(4hQigcNxUNfO^oB*K+WP*ofr=& zX=*L?0Vpis#$sKQ)`V9@gUVGYMWmcH=ZWMi2!Rl$2^$SBD@F2=WXI=$UVf_dGbo>j z-@QU3#WQWCoz&Age~fhM5YHLcJly=A+{LkpbDmZWB zIJSv9`r)tV?s{AQevQ|=D#>&}ov4e8_pNB}_JFylCC4tLjnQ|G6CtW*o=OxV3v-*DHC~xiQ^c^^y<~ty-F3*^jY_LS zYwfG`ekbS7T4PEx3Moi-34uZgm}rs&Ux9(Z;2!D%0p_BBDM}b?4M|9%9LnO}oU?%WqW{i2=h{qdjgmL&18!dR zU+!ZkYUwTOBN=;;c#IGuj*bFy0Zz|v;+g0E3SkO}M-v|2ybD+Ezap0Zl(8?24KpUA zGY5o`yE%-(Gn?kt_R*mvD9d*==1%Y%bp&xlVu3M60}xW$17JMy#BbsQ0|@@hKmX5o z_kZ`p0CNSw_G}__1RZE@PykiMnQ!_U*gd3y?<{uKI~7Vk|CvwWq4#_*ash7MxQQ2E zdJz-@5D0I5>sxW}z4rl-HMgH_3r9y{U688RU+_%Eay$UP z6Z>Pd`r7w{Rt$GkA=efe*1>roLdH7ywa=vr21cyT7Li7}kMVKtjEzz>;9v{zeP$SPuQz z(>ey^z8}7}wZkmGQf5zLe$zf-x0|uu?s0y;#o5_8&d+y9vn1D>RI$uCs|+!tq=b@Y zlzES=S)&E~F*qU>iy44JMlVGJolK?5ZWew9IK>eQ?Uv_AJ`re6k)z{d0T~V$X0-$h;1&67 zx8GsE+hafPG3QiWr%M(^zR8oe0*pUYg$_Fbe{E)IokDqVX{8`H(}Za=;rQqnnGNIZ!=7+mkz!7q0>d+{&!^Fg{k z{$}$Ff2s#lK+p3$eK9W-`98P+LKmymrnkA&bB+~NAl!qxzTu`^Lq~PmL*xeuUV3i;W7PfXWs|=|eR2TO6E_=^HA$@1;+uG}7@#QfBwf>$31G!*b z9OA==aJqrugGPW6BesQvDIDljbQ%>oAu*xGdZG~y@`MpcmcIyCT0Pe!lF@AKKl@Th zYexdgMwMYK*qN1>m?jR8IHQebb?)o1iOWnbrAqa=i1sig)h^_M{eF+L(}L|5zz!{I zb%2;{RTlKww28F&?7C#@Spk@pJenqerdCIoh`>RTY1Qs?d#+h-=NX8$Ig)4=vlfDu zI8oE^$jiMDBH4a3T5>GYGJ2sxCc)N*X;njrVhJKbM8Fg_8fUEW;(@9QPHlc!YC$TP zjj_|jh;~S?SAedjRs@b9E+B3-jm7;pYMf>U2neBBy!A04YVOTm>2Jy$OM;aPfC%J> z<}y#_zKzOk#Cle6cmMz(07*naRHaEY&pAo0;%PF0OOjaeES63wb)ng&wO+40R)o>W z07ZZ|5#WeOKp=4+&&s<~0Jy}*!_a8T}glvhe4E*|a==P>}VPiDmaMI7F z=rS-oZcBCa(}dN8OUDsgFiuZj!xx|aOMPI$Ll3%eO7uGWOx;abnxx?>y!3>VsO)B(`OWbMQR)3&BGqwu;V__KfUM*@PA#P6>mipIQ$ zW>iVE3Hc+jA2s`jw5m2{pZWA3;+^mPK>$*!Eaik(Z`?q6;Y-LxgvM|G_HW01_q_oi zLMjEkPqH63q*l3MJlVAUZuC}!hbGAkKiOV&fbt@6TA#K8Qsp^I%dC4%clhg?@@#b5 zZs+etIrDlHIAhxw-t9S8@GIHF15Qp)asB#rJpJ_3`0`i2jPtW|OtFuTHP`2NKKx_& z+!uczk3954(!Y{5o}FBWokvM6*;GeF`yARn(6;(0# zF-Y=6O(Ynrvc*I|d-`~g`?q%?H2ToZiE8gIa=|nOSAEb0ho?mbs``>uSwXP4KJU)A z*q%!QEC~x?EpJB<^PbWgEDdBj($IPj(E#Oqc@qc2s!_KOOQy^u2D7$c63Hn?=@ z67IeCUcBMHH{iZE+=t`iORCHfejy22MRu6?dz@+vI0F^jR}kZbdy|Vwap&CUYW)i& z6*E}e#ia)HQU)`?1iSmdUhp6s*5`q@-YvCTC#T0f(&NRem7%7PR|EFie1Xm07)STg<)pV!O}09J=RrU1Tr8vJoxo- zj{SK85Jd>q%)KB-X`kQ zsD(QQVA{A$!<(T#Es?~ZQmSsS%uOgUCYaTyH6%@1#e~QKQw+$FPz1uXY_u#^%gWQM zYcwHe>32}qC}u{8t$t*kMlOiO5@!tAXI(0KqLvLA5K9tk?Wn5N4*`=BXj|Tqgn<=i zAd|S+Pck2wG9nAJ&RRc`E3ySB7MOeAsA#RUYvr>&!s?0>iDHGU-9-e$!kTKnYM`ag zZJq&+EKDsYhVP+=-ia&sUquK(H1vwVWgbEmJZ!xlI(lKq*v3dup#b&{RDXD$ zwV+=^P3sF4$fAa7FmFWI(^!Znp7`z zF){%E-7|~NeEJXZ?)Uz1i=!g~0x+k98#iv?#TQ=$AXd0<|Mvd|_guPH6pJOfXOSjc zTeq{WjrN+GT?Lui`$N|rbb+oQpl2McHEwI%5|(RV72LWHKEcM?;dx25)~sK;((L7x zMR_VKT`9>*!GwRcif^{wPlc*1_+`o~m;ZLO`gNU+a_cWxK=rNh(xX z8~onjN(Y;AOiy$|uJ*%$fGUF0;k|ZYe_5@*I*&<}q(v1=DG3PP@71L_`&eoKMd(1N zmU>pDZ>cUzCQMsv+3G{5j9u6x6R^((({8TH=|}+^bAdKGYxyl)>7Qm4F?s}4muCaS z6$H0Yvjl&zHtBE0=AzDtyU&y@b`SL+C+P2?2Gw?hT?OmHViBKnY6-L4?-giKdv@3U z0pR(g6UyyeeLkwJWL^rJ%@OXo=U&`*-y87vzUA-XzWeUOz4zRU<4cz?O-BGrNkUr# z+wB&GB?Pao3oW(hX?XK~Xo}%cUZ(&J54Hql0SGFilg&iymskEYdB1)4yTXru(D5hz zQFe->?c;d)X&c738EKUE4A+>l15AoRTw4Kk>2K>gXzcqM$RsCcF3;b^zPGXQ1#MxT zT+JJ=lS!x>DsQ6gJEvy9ND|LJ*Vyydl1`P&|Q(h zi^hzZtImPjL^qmEE910y_C@bqKWEZfZzSoDYIutd{H}E%>Vt|VK?zi9#{^UfFgD@* z|K;r6nk+evG_lVkBJ-S6)eSVR9CDV+(LU^G8fbtZKyo;w^dK|IR+7o|Fw32_HQQge zW*pwR)Y?kgl}rz_Bu6AjfVh$%ZViAWFb$x)tE;Qd$;^mwJ-B;BWS&zEj1pF;>T}7A ztA~Gn`TU-t&$ReK^V`0^Y{n8uH+jRHYi=Vs^JZm)PWrT3t*}1YAav%faUwFiN zBss4_tenyLPV;3LU3U!Uf`rnHB53m@-yO$@VHhxO8RL|p{5~Z&+B?8?sIFniqVwtj z?zHajvfM^tTqe>SO|1JAw*m9DRAOv#}#M#*yPS4J8em-L044zQJ zoO7NFt(g&to7Y#Gk>#LV@#zH?Q6Dl?7(u4(62lu2i!fo ziQm5V0>r?QaP{hwc;Epkk;Ew@#tFod!w+|e++iQ!wXYre>^*dv=BfiyauyfL5zrU} zXI5TgsdbRxU;@}7M&S}z)(HlH7oPhmo_Ol7BydCxLv14^x}!zi&7Y*Kw04LuzGuJZ zp{q1|@409HPQ$Uyn=eX`BZtlfOvym-TPlYBK^mO^B)tPm>W75zfx;;=T8Nk2l_U9lw9?57?e>%Xwk_t;T@)zI^=JH}KLcKf%?< z{!&3LH=nD$p5@y%?^Mv^nl(7@!y&N1oZ$exdIpx`8qej(+{3un)O%d@+yTT;ni}9M=~GhvC`GB=JdBbDT)>*% z$vFZAr{|LZU*-g6(ND6KQW_)j6v0U>p>tJA73C~O)I>>bT!aa-r=1oyvb|Hl4pC9K z1%%6>IelM@p&9~xXe0!+!E6q?a%)rtp+*=mN`!#@zg@A8s2XD1axU0E1L}KOjla3% zUe|qHHT>dXZWl1^hf*40&+>IJms;+b8`(e*hV2l9joW)Ls6+!87fV)MDrM0py>saM z9-H+VDJ3}PkX27A#9u5d(mAIhvx>)8!=3ATbRfs@T3V79{g?b<-aB6^_?7#VGom$G z5Q#yi>2ujz4fv4XW;ScVG1v1;8^_vqr+ab^)%79vi1t-24OHcG-3haEuo%FAW|$6w zVe6ya13*cWoHd7+pA*@8sFYQE&%M{t%%yy=dCz2voqOefv(L@HQ}r{`Q4Cxcj7?Ra zusq`0=7nCtxX{o&??vtBMOd=nU*>kX?0>A;=k-2^^Vessn2m$|QKOm`A4aHQA@a-0 z0<|oA?SW{77rCJzPcaIii>rWa)`DdxZH*QNCCnA|PrBOsmcveSHW`2if&;qF;b?P& z^?Hr2@6h*s5f+|Eyob{yn=LU?WRPQYz5{njfJu;Wmd)x&!m^;bv}(n@dphCd71-Yfrj|8hUq5Famo{Nj-oj54iqF@ zF_SG0_0Bnu;3XC~=hRpeS-@}EaP!G?DsYS$**;_If;od+kT9zdG+#l5o2#D(QSqS2 zcqT+2N`6z!sT@eQL_9G(JaSI3+N3#4DJ97P7J)7bh!|r^Std*9HYd~3kivN z$pr|nx*nU=8o>pCf!#Qv>pC@NoWau;yIsP#!|d5J@M}NIy<~#VmDKCPHRs84PsOVr zoaEjGCn1QWz=oCB%TRx2A^CC)E%9K7y9}Q9fTMtkBJQ5u#A~m=1m`6J;jybv;K2tT zf%6_IMQ~y;F*XMj=WX zr>V*cKy!ZI!S8cJ^ z&bQ~7>f7>tlCfb^E!#a^fj}{IHTRp#m%8Q+oW>-cSj*j>M#=phc0260TbysV*lo8M zhd~H6$59!M6{tE=g2#-MBXSy*1$o3Yj@S(YhH-~6PDre!8r1{rSfaM%jO#%zXsb!1 zJ{3ZkJck;7Sgk?xw3!ZIk9+8#!9MVv>q;v$W|jl1-es?Ky(-( zx&Wsnr4Y3wA$gCk@3CHQkTb*kFayBR^rDy%qY&q%oPY#4?;s?v8976ZaFWF6oJJRT z2TU>sLY}68x-mY;8DQh7@~HuN?K~|_)CGD{-E+FdZ20Do*3K{}_-%|pvcz;H>i1a7 zEizF7Z*9o)MWCxfg?g42;AcyT+C4q*r+vPDZ~pp4#(1hQ|DIQS-pO8Q!D=&rKm&gD z^RCJsdlIv06T0(0q1ZgzJ}>Qt+9Y_f#SWi?2hY=cfZA#_QH`NlFQ0VQev&RXKf7u= zmW)s1DQdo7Jit=xv63M;7Qn*IVv|8PFr&(XS(|jqodZ&v*W2ue^6!>EI6hM$#=7bJmrLxMkED|&;b+qkyW`!V4e{307?ly ztN=(Ug1!&9bjicHgy1IytpwVQu+&D%lGj_hc7Y;T!q-YtzmB_iv(Jk>Pr`WZoPhPr zz~sT1;j?5%R;x(RK-~dT@xMQ(xnyd zyZouHrh*`o5r$Lkp=hVAPSy*#P28z`ST*DNp0A)3j6%ws;&X}eVM5BZx>9~l3 zE6m|Ul|U=`h)GK!4LpE|&{3999%h6Puv)LBbO;=X&XK2xIAT9qVlKxUA-~u+PD?&% zB!YN?H6+eC1SesLoe$#i2TI*xpM|ZOl_6Z_Mjo8aIFoZx1f1`%@&Pd>oSmQG^*3J8 z5>dck{P`2O|MCN1_7Xj!T2tsM^J{5$bAUVx+`+ij#N{j2^S>6)x`=u{`V}A^| zW|WvG*drjNgp-pKy!F;wP_%~6efG0hZ;n84!X7_Oa=%VeMf{$@VgGPEbjWe$+V=uT zW=))3ttZ$@MYUe;)}wWi=Xd#9YeXooIV$Cq_S(#RVerhd%@-foRUW3Ko;@x5BH%YG zFahq~J;S@#-@|LKzk&DPe;?;(XA;(`Q3R}cqS9_Cp`dwb=APiIkADTPy!`VELGaEEYT@0)6^=R`sk{AE(L4@eoM%6(r{J*z{7TjyQgP3Ik}C~yLU0{b~3+H z)Kr=z`bSP;qmgSBmawdX36f*L({AQket+ z*q))k=L+L;PqhGOY0LpCptJAJgR-{p2 z$n+%-=BS~oq8w9WT#-kZp{yv71=LYNntF~nf@7%*D$xTH!KvAB5@DCb8||29CFo37 zan9yxJ}$*0h$`Q0?=JzN$@Bttt?71d7ZBV4;O1OoRDKp#V+HF*lu8Ui%cE7IJkoGz zTP}@X^}syY<$^x$2^J+E${LgGh>#s=tvN2GE^|BXtv*^Yb}>elzFAl^>St&7 zXz$f1@-6rc0a&d9Hb*NQZI00QePNO`7HH;-Ax_whLO_vHYyf8hf&*#Y)yWa2VTavt zjxGdvzt+%b+Y}wbDqwZwag?K4_%nuGLQ1STyS1bHmUbIsQ5K+!!s_IfSZbT>PCSM# zJ8X_NxN`XlHk%{#*uXhLhcz5Ir0s;0J9n_Xa~B{&(2_|;kIyFf^suv>79hiM_3pB> z4LDzPDQZnZ&tR5&dt*TC#Nc4elSI^bpi$YBvj}2G1lN0T&glCd(=@@49y=A16eH49 z^V6UTFq4FD=B6KswT5!msPj&M?|ReY^5sjoeE(%!x^#@bUm@p&^W8blx97+)A^Ga9 z_SS!^w+9JZ77r+w=crBqGo+;?L{#G>h7TJsW{IEIHPx%bvxo7_izVzj9h}UCju{8yR>cAR{aEuYR zZ{5aQZ@wvWK27-SXFrF_m+yzybudk}bX<)LX$Ahp*UT$-!8J1mG}o-|?&1d3cu;}S z^8G`W`__^Upm;y_LuyeJxO=v1vFDaySgc`$S-A|NdVHfY{MrV&bLRwazkMCQ`_1q0 z!3Q5;9LH*0RGAHCFePm-gB_zyP2i@zM1;q#eHE{~R6%g-LErB{)dNa@8UqdXz9DtV z4}ssm{mu`uULVQ(RJ}OfOGJ(tk4m%y03(|bjtxC?9cb?D$1Tdtywz- z7`OK$>%OfSRL^g$Ilq&ZIug(Ci1YJvoZh{Qv$HdqXHB88M|t&rcb?F94t*eam%({N zo+iZUSQ(&4j44X4YgQ(4?*s&Q9lG@ztIZL*)e7GCFq(f(S<5eth~p$@1+4TQDv z-Lj6`d8hroYT?2KlxcSyEQfN|l>+dV`((MUD!5iXCwPg3>pWcNk(`sUpM=*lb4Juq z?HD7*X~Zy&7UV&u43}Z2)kYj}{0wI)t4`#zH{485woG1my}4 z{hr|b0*ITT#lTzxTCF`rpCAJ38asIO7mFHWR>`_Kt2I|qMt~(kv0zfFq4?$7y0!`R z9%Q9t%I&Kh6hntb4dKw525PrGz(aMyYG-~o6{N-`kfwj)x` z@IIsKdW4P;0wXzFyr~=x%n?3ku~w_|JXy#r18^fk=h3HtoE(5j8L+Crwa_=iwL(6m zpw~-Bh)B*Y6+$wpT)yXs5JHdRqsw^Y;m_ichabVE)%{qn*EsI)L*Ms6V%)s>G5+w* zJGgoCCgPx>Rzob_q*N%5+v!#WgAB@2r*0X)opLH6&+?rbQscb{e6Ikit{W;|;PSnk zk+txyc-w^($;gu0g%jB$C0A+^6PutD1u$iuqY|MYpC2*H@I@;3etla!*0Z|ix{>8&d;|vJKJGkzOprxm6At&-;Nxql}GXP|n4>+y&t+-wtPZvnxAcF}SNr?CHFABgDWz`6mIFE?q9h5KNPdf6$y@BhF*XS$0@7 zxy}XV`A4P<x`ICfTpnC03Z!%MVbM${eH`f)f4>XS(`2z zvuda}&rMY{MS+xbk(4J8IlTJHuV(l7*0;ZpzFVnL5rv$|Y3Zh-TgZYe%AC~|2Ae0d z_F)Eq$-pY<_gh6AutjLV%#3Esa6d9jo2i|)RZMw?DJ~WKrl@*COh{9dpQyicg7Y4i zE?vTUwJ!TGvlvC~EOo>Ps>ev`NCHt(0xa`p2uKw%uJYKCFgZKXAB14fgPD+-giU-H zvD@yjgY3(MC>$Da$PUO}?@t1bLQ3GA1n|N{odIA=c~aTmun?QxW}|00zy%0b%V-0D zsd$Wvu}SY?$rY4z;%PDGT$4I$e<&Ax5O&i{2As1fr~uN)!f=cj&qfGvJ~!$N;Drw6f+9=VW=$TTgFU0mA3TR`cHtBw`8q!QJ*7cvskGWq&f%hNL4jUf#A9a4b+-Uvi)Xrtz|Ql zMo(Cq2sO2?;6j-s0qVYCes&f7&L^$`A=E@6a)r7@Djt;KItK*VgS7mvMSO`dz|KN ze%8j;sHAsn&MPXD->jpB4%m8%#qe#bh!*$DW)`U-(1r1qwRrae^jvf>W>qr0DxqG% zsqGIY%<~F#mos6nSU0SX&6=%J0RoUUjAQBfwFMHofWGfb&aZ&q4n8<|=a9hQ22|Rh znZ>K?EbLfwVr=7lv&Z*=b#VsODg;0wbCA5`DEQVQG zm5kIyLOLazBT;Y=!M0(pRP zDKSM#d*~WNigyHfV6|G|@_mHs~&| zBy?>Aw%Y+GC#Sf5`!<|A#o65*B7`JumO4-l9NBwOs@kX#M(Ss04aE#0BL`6=2smNP z6#xJr07*naQ~*L(gs&a2mJgh>DM59gS0HKYO+tdmiMNB$VY@xY8*jX><-R)n*MA=H z(3OWJtTUl7oCh%2(ih;$z_%W|PotddM_;rcSQb#Ac_#mZ|qw7nm- zSort9|DW+M|K%J6|KjieAAIrYuM6l`gM$&{Exm@)bQ6el;60Qu^cR2i6Fl|IH)i7m zwZgiK#?1PuiiYK2!Hyge~L?&?kk>PGu!~Cw6?~9!&kAw&kPYN zFIoivbI)o!Z&f)bRmkU`oyiu==kOq_bn_k3&FoAAvawzCto5uOx_4W0t>wMQx_?p< zqNF%Ty;mS0=Ul+=>#x5qp5I|8#A(b4j7b}!^#V&h@zyv~$E=-NX|it3t#lhrgfpn*@ZCc zjyyK&BVg0&QCxt(0Iv*3ET9(xenHVx1aNC~BaMJ^1{_t{&KX&~Pbte@k5S07y!Vm@ zMh@&8Q1S((KLV(AUY!HDmba*6Rq~BC*OsYz?aa_$K!FXf?M(&D<~FvGXbmYg)fNH` zNXTsqI?D8MmicuoXGXv`;7tMgr4R?Wgc3C3T zpvD%?!q;J?aSR}vK3Mx=8(sdkXaxbPN!iRbN~O$U4PiDNAq)L`ajICP-qKKOrNS&_ zAjVkM43)j1O~c#w)5V|jB*}Pec$d` zNZ?o_R}=`eW|kS$B5Au5D@27qq@brfL`7EvFlM^YMY+Fae%t>2BhtgleeV6X7%dhd z@hxs>-s8ns)~{Urkb`s9>S!8y+n#5|%dUo02bz^%T|7ZSn0eH=kxfMKUcTD1l%@fC z_>e#;!6744Ess=gssAWCok&E$)@TV3N112x^?R^#btWsF4Tcf;Xxl<9y*TOuLWTqL1W-nbBN!eX2XWme1%C|0JZhPm3A+IpMj(wbQ_6cpd1Zc?PuDI2NYXs?bI|U-CuluwX7>JQm*2X+1~#w;5XI zLNFsSiUK9IFDF$fq)e3+w6E)%=F#%X9PGM`uJZ_eht2T@$H&LmY>v?N0nA$eI45Q1 ztbjLiM$8r#B<2REi_AF!J69O6vod6OP> zu|y!aUZh$gq$K5&QXC~;j2SsfUFy!Q1ZLz8)09Ev(S;TIZp0WO@-!i}%u!{qZ4m-# zl#p$wd(R>%yl40@B7}q#I^+a&y{=gc*G#7L#gac}b|RCpW_iqZIOkOMsdFA6;P#zc zcU;p)gKl}EtfAv#bz4jFlv4pa@`5}3*z2E}}fxQ0W zb3enir~VQ-n}vF@=k(u-bLC0a{vu!Xm>`KvI5|1NTW`OON!Q@#KmP?>x&MB2J}4{w zq+!;gfD5qss3x3PtCZ80WV)Y=;MrF~C*5iAqh0D@PrM(SE2T+WI z2Z0!H@O3GnmXYFwm>A<2krP8AA~H^H-^QD7UdL}=`z=0r{|2UUDyckxc;d~2$jI83 ziy26lf_Jg)mMI5Kydk-r8m%GP6}vLC6X#v1cULr-@Y)r&)11Z!HBJw5ABf`sKnFp|7RdN!5PRRVs^`|EvxcLAQ9 z0AnagB+#6jjRHz)Of*fpF^mIhtTz3usNq1d52~_Rj7>%7);&x5H>>xi$YTSfc1Ro= z{<`4GENHIaQduwbWXv^>6)0s8S;G-6-2gDqSoijP%~asoHcd=SHT<>R@8&2GLnkl{ z1E!p?+wE}o?5;4HZ&v909&Wus-}g9LA7Qguqu*@AX#h2>q^t&cF6hSkBvAs&vEsxf zYFU-@eW1T{o<*;S2axr9x%7cGf>D;FjzckWN0^u2?kOc9(<~IaMm5+y6=di794RN+ zJlAwtHK0z@B)VTr>J_(nsGe_AFvJkq7|%Gt7X+TJEV#Iz2afu z2E<1dY*{^VmUmID0v0lDhb~7T#e_ShbRZSEg=oj@?NagzGsBKL$~R~Q@UD#yi@CAL}IDcoAgHnuGMMG3cAD+ zFClof&BlO@@@$l9Q7uPD4aWz%RVQQ(A?VuD+Kv*_g+BCHZ&p~X*68~ltFS=`9XK(@ zVZ?SjB1KV#rYT}O4oLB~+O8Zp2U%-T>IlZk>ToriVh=%}?!63TTV^B%^hgqdmqP*v z$@dPUFLJ^>zbPfjXOc*{vcHWCtkIDrEDah)nE=iS;-yHqed{J(e)&Z;CJ-Kf>>3`t z@}Pv+CPs{{F^T3xZniF$%2b)7eFgc@dlz1Mn3cn=^y%IJ)r71IzU-$+gi+NI?$2=LzAJFft08HE9n(Y|nEhT8j9BWBbr`@5yk2CTrp0$=1TiIZ3|Jnn za}OxZo_FZ_B#_+Ri<{5Zb}`yzLPSVW_fM2EdNC&9p@7Ku+qdrE?dxyjjW^!JjT<*G z4Vv@o^?c>1UDXJs%*YOK7G6~jST}FS;&)k2MB)j4C=kxgc-a}Q`HCq6L|MU|`B@DZ z7|V9Mw^|`s_k}3B)jM9nZf@iXN;De-v-P#i2V_FSFJZ5vxpzB9%|6K02-F%HxBwi%n{+xv9kY@6O z>jBTHeAhrG7UOSW*~R1B0ML}V{M&TfR6NxR%=K@!NHcv#HDqwKvewmS+b@8>Sf=(@v=0G-} z#6-p5tcRW5O%zkIy@)CUXW$9*zj^Wgfe-%w0@He4lyB-Ets%R;ik`OAa};wk7V@GQ z`$PJ|p8h~4f0__z+Eec3ASGzcSM}N$fHE-Sz!EB&2p$qUGcEi4Je>TOH5FW6D3_xPC)?!^ZXV7PU*B$&LHRE zd;n$h=IM_IvX?$))^arpl)SdrK)wjzjHKie>}!97jatJzFrOP{VUA4M>cKMN5HW0T z!4a?~!rA!>msT4IH-nTW>I{?uGZtn?8gff*-bG`9Q6VGbRg4lYin$_5jYZEC|CCcH zaS?*B3Oi+qHldj^Ywk|c@T(f0Gw(O4aiM}>A>Z)`ormuU{i-j(lfcM%LX2t{;e?o~ z(wSmHoMN#+rlfhk4sf2~IU{EW%daa6wdK$%__KBBI+nyL-DHuSnfg=y-K=$}Y?i|evQPA2_fC%jb|B6;z4;+t{`IfK zFqI;nxb{Un^niv#GxWeBq$J_`60Oi!zj+@N+1fk=BoUu8x zojUuzOyV4b$~aj1qp7gWayIxth%w>LojbVx&O0TH3|}DJf8P~&@+x1WE+&T%sCc=G z)%QS+;CAjZ^TD~CeSYy?%M{!KyLx|8!$J#6=YaJP5H6+K?0e1gmpQ`*JM%(jp)n9v z&u=P5K2{Ii6ccXUx`nsjx{f#AcoYBd!42$&5y44GIXgg|=E*yj^b;#vmpSjP^?Q%s zeEuK1_GP^C^0T=5_?Kqj1i&oyrHr4R@yNnY@Zt+UpMB@s-}w=O_bNA?5+nvCSzCI3 zWxdG#fq4U3=uyYD818AgM^t&@3V!cBE>zAO+c)++DoQ8N0;|lbRI9<%SiH@P#cbit zotAd85M@SYaT16=B2g}+V_qJSnPflO)C@2O``fg(AnuibY&dR~b>){J0l zysP6-`{&4O-*W?Cnt9Q2HjzlGY!jh`>MG3KSKLh2nsTiQytJd55ILiSMaswYUU}Z$ zLvsg++%6zxW__(dXl@{>`UKJbnXvRm8AxQRGCw!EVf&kz!6}KF8+BY`#4t^uVZ?5? z!;~Z%Xp9L*$HzF{9O3x*2%F7Dz^ztRk#dqAy_0?8eTS~^q$Fnui?gWlEopl!UC&Ar zCOh8E6|-#O;4zXDyk7&g<46;wTw_o(lW%E1cp}T5rb%^y1pHW^FZmq z^t)W1$KXo*xLE)9`g^t;X})LVzWcJf73oXI#QcVsFI0Q>fioV36moGbjt^tC&(s3o zCW*ZMRK=wXpcm2#asrej2P}am0T2eRG69GYSuMnYbTQMSK{n$sVQkM^_If!8B`OBa z16>EPEU!BFz5_c#g49LhBp^5CjHpB-c1V#+;(60hKd1F~14+nhYMxKTfY-Xb2^y-B z)S_D%9gUB|45yZJ$qYMgVn;;JG;*G&~}R<+t;M&4$5oZgJ}; z2SUU+ZZVF8KmlDB0O|pt)C zOWIZ==&~hH^afqG$u_`3x6$akdP|kiCHLRfy@F;kK$cnZ%^`JUIlJP0KD&JjufF_Z zQI4)%dlHX6^cgtsg~c>#Ne3U`y~zj*=c@*pL&E!B%8hEv+UezBEfg@*uM41Qz0-@Y zG|IX6!lZ42OCnGXheN;k!r$YIPkjxXvgYiGe73wMvxFBx7@hb$vloIaVJ;l54zN?C7!skE#Px0WD2NAR^+cZU>D3==Y z4#M6+$57>;mM_nhc+5fPGPhT*IoQd~Jh%QEY9^|Es)611wKA29@!I?M;(hOKyhDG*q_e{vZke)WC;jJ=_?v$S?X zC%7tP%YIZ4{B-$D8{sqCQ!2v}7{7U8PI&db@BbLig<=5kUYO;DTt@(K1-h-LS{pvw z%e2?G5@7+%SbOEZr1I*3Ql&&Rru3D2Q(Yg6CuutxrCJs2tc0JngjFhM;A*`>=saXz zxEPQ{@h0T#kXej+1YyzbdLip{5CE0Zh+*7ecYY>ygQp#090epO0M5i9=bLI5#+9JJ zkejh9XBY|svi(UQO=FRKMYb6>;D^PYY>W@)bp=q;(A44vEh8aZ6WN;4O6zuRtj#Rn z*RdjfUi*#K!zduUf@hOqFvGRVt|G!2;0q#bS_QrxHiBU~83_YFMQ1B(sR9 zRBpni#rQ3{m*rSXn_`yS-KeRPkus96j-@YWw& zi;Fzj)ads~4NrE~%UVzpIkR93Tmf=cS>ceK{3c=$XD~S(heHuG&E9BUEBpHpFx6Ex z+Xu@__t8cA*`dq8x~)|18-JbMh>EPOBdTE5BnQx#fUT?Y4LWn;%m=obwW1 z+QgA?1mMI9!H(cqi8}PqCDKhgYp69&UNeO+Giy!5b|C8C&WXp(NQ5?<4c5mJLTb6o z%o4&GlPDd-FbEs6hE@6i1TVx>L=Nz*N~d~}y@PR$Fhd#fq@Bz_Cfk4lWLsreNrfvQ zXqbVSfaJxCNCY71ZwvqS00P=7NT3EZdJE0%b-`wc)7zXvE6A)0b( zYDhM@Jmp#Qh=4NnchYq>1%(B^~~kS~^T4^Ykk1^Cdz`w=083cLa2 zfD*nGnbZSnB0K{m9(gH_E?yFXhn1$1!#b7c%SO&%Wlc4OhO>;jT0jI9km_ z1)Zu>fi-Ht5zqx!%0U_UblIx^29g3A7Jgx3~f&)@mp zzlZlh&uNSKXDg?y}I zU`A65#mr3(a7<$GCr9w`y3RCjSL?ARk~77@lma=MoOf9D9-GZdoC+x-jt;>QTuyMD z5Ikd=NVqBpU`NPa48L8!(&#EDX<%vy5CgZKp$t@JZ2_5O9aG)oMSR--+G$aR8*GUV zO(d29GO8ad;JJ|_U@p8N7hOe<(np$>LCbk9e;eO`wkHG75{9yec-B`OD63?kqb2x) z&bxWW+O^Sw&nJX2p~whM5|*<-0fM$Qy<{!&{ON{=--2P-6Go?geov0&$i z?I}VAWx#{sNQn?hfwG?Q(r{l4F!HkGtY>)1ekTHxL-LZ=krhi&t4N#S%{;R)3P~4> zCl^Zi1^h)X|AA#tfMcAv3ltO7)+y-Xx~gXVikDIkL1yk^kQv1(10d7J4bu*16wJj2s$o>mQ+W(W(q)S~Xu z_bc?FL+2Fy>f$lWu@4@d^B|INa48+tp$ol|#5e>O047Wwfhd4;j~GWxy9v%sY7K1K zV&HdSTr%LZe9eGxo5M`HF3UlvGNmY>Dus%o(LByP!F#$5>mD{8v*_F^$h-$S2O#3? z_D#I}!t+|6lJWTC*YNN|4~bH(dEhpmedqP;Z;2@u2-se21m)7=*@6IBx^-Re85O8&wRaxXrd}(X1Hm-GOs;|Iwx$xrWp_8Lm-m;J=r#lK#~)DdU}d?-+f2D zUkvSC%956lri5{d7{^I!#ItZ!-2C`9-oAbvZ@=|6Zru2=gx6kve)fcKfA>cq za!5IsiU3~IKZ*y7>io~=l*;_rZyQ7Tw@DzeC^sXw zc#uVlwR+?ppq0Dn=K*jQxsz2tt2eLRBEV7{6rMGaNct%*Csvtj)rIFHpnWhCrg;OK zOlMt>G}94Ee_A5|TdEF&EO*<&fR%e>O5#<#b?Y{U-43f&kB1+65R8YBkuk;r8A8zM zyMzE&*1O<0>yxf$4zf?dm2A>Eq^v1mx}HZZr!_)KFhx=~LSY$CV#pzx4G%G-S!Q|A zVb!86@M@q6U~$bjT|-u`Qrj##Sw>2tpG{fjExC-Cl-J%V;12|NDvZyvHd*IDLw-Ym z>(^3+Mva9v|5Z4Mv?vG&EC3yn=IEH=lKdFROv(jg^3bYVl(1(qYC0gYI!)Mel+~=j z!dH`G#54>T#{p@Ig@=cg#|GKRU26%om@P$5&WV^J#%a=@h}}41yWL?J2E=G}p{1=+ z(~oMq1!S=b0F@fXfxbXpy_k`3RVdweWX)Z9j6W6#<8U?OZ<0_uk$aw$xWG zB@Bz}0)fWlis7u4?}n!c4qp9iv6#G;*72n zkisD#Xi0~dM&y*?GD*pYsDMPhsU<2aOGqh_gc8qEKfY%>My0^`!UOZj!ahinC$~k~ChGD>VJ7Bj1;yCVmHY5N5AOJ~3 zK~x`S%jLE4pGNV<#VBF1a$jhDHe3iyWDsnY>g*agDF!s#kSyM6Q!auk6cPfG5R)lC z3@DIh00Ca+%@`xK)-J)pQNwzyby=bRZp#`7F@yj%KtZY2{k7i~8f_#Wq{?T?2`)KA zN^mK{C$9&MZQ@j{aHdp;v@E$Nf}u+6E;U+0C8%N1jVj0>EQswE9w_2$X^U8PPq2i6BPvKthqx@N(Yq#QX7s2 zIJBDdr@Af%IWr}h+XJAIcgc7sV{e~)7bto#3E506P$x#aq6Hhol zKgaL?@O$-Ubm)ACD_5>aIWz!MPEy;J3DgDn#ye5=^>U0b6NfWki{>>z73-oPskdM; z53cdbl(B4#Ap7G|zu!g)05iQ{b}jEwjC_%iCP}@CQJDB0fN>o0(Z@IO&h>Zk)|+qQ z!y7j+4x`F5Ukr10XprU-)byZy&u7oId(DT-l?``41g%{kjH^#PjaOg%6|O$9*r}$1kbx-y!V)@3*dl=- z064`-y;~7&2^j)P7;IKr{X^?lAE|QSKscg-!XlI9(`9dFloCfXz^OoXCMa5FF};_K zDM9+2HJxHfFf}v8wZL8fox#GA%v{Syl6tV50CWp6l{s(pB{Qm*y`*|4n+JEX$5rt* zFDL6c$IA0!#8)~D^WoI}ZjxHUWl6(YS;|Z{h9pNM293-ZhXH4&r`T=JL16T~kX^+r zItPQ`!N@+8NtOOtZn^!|AFeWAazQ2KX3U~r4QW7(5j#xc)l>k?PHXUbhVKGao+Pb| z08b7cfG2`yF+c?a$hty6?pC;>5w>yhN`C2lT;X6+HUj&=HA~Lfag&v=O?m zg6375<8LXivUAAJBWvWVq?=nfca5|FCynA55vLtelw3Ire>M^s&H|Q^GgzHKF-e5b zZZ}{U2Q`>xj4@(2jM(mW7{&q9SUt$YFyef-#rgR;w%bARPQo~h`lx0<>K^jOdyqws z%)0rUYjD?rYbj|=<1&L!D?>_TP5VWYMF)(w^E-aRgY}t*npzB>x}QZKvS?CyoxliT zEj3iV=CE=O@|=XS>Aiyx40)${tE4Q#=BYyw6duADy6QTFE)?>q#3NEp7{tJMlbB<#Lp!lVaBObNp<=wjMQ zjj;)cmM_V`6rnYI2PLQhhCxCT&$s8;o&&=mZE2%6O$TwLQ4|Vv4g4BOQqf;pP*P^E z0nw0gE+r>aFQghq@<1ddL+avWMs$STrF-XCB#unASGkz(=(%l znk2Nq%gX8aAmm=sKRfhu*)-LQB8QyiEm{6X)VjDOjGX~D0dPXtK#q|TmvCeA{F)A0 ztc~>Pw4xARbU`9;v}#8kl zd4FkLbWyYB0F(mrrlb@Fge-T=LT<~aY(N_TGt+(MR>1jJ4luB)qN;zhR~zjVu|2(o z-@W>hgw7Ih_3C4I^x@B-554TwoWPUZHz?b(fj(&q7Yt|lNdK6twOAeu$>9cMX+IBo z;l_!TmJ$7=HL7;hotr;15=y;&YCjOYx+elL)Xq*d$qZ~hsdfJC?(`%{;Q&H!JI-AHTU#Zu)Gf* z>zrM1nI)Pp{#?%005?rZ%esl-#yN*^9C7Q`9lZO_dwBcpxA6}*ZeZB%G#$yJ4{Y7Y zIAy1@n5t60Xf-P60}S{%9kZ5H(DrTx2B_XyUxCooCj|sw`_eNCDrEh>^5Q(__eVee z-{D+`aU7-0k=FU`x(a>|Ux!~eFf;q)61Xo7Cr$2eYuLEgRJOoK47&;hS;G&N!aOIcD~im*5}o|+};PM|7%*yD074ZZ!fPp9`bi~C}~+z za&x&SxU|K7&=|)=p3UWTk)`&UjUQJwE>1vZv2a15!*FrUBdS7AJS_;Oy)S=eu)^jS!e zg$_reFM$hpis)^!7MzA*yCieVNr-yKVJzi3Q_4uHBac&5{+C*QZM)s#^z1I~oSx$D z>0O+kZ*hLU#hsH=+_`g#^Ybl+VZ=BN$a#`Al+h3cD%TG*Vg;zc)wU(uo~rxM_AQ~& z9rYUrjk0JIlV%?s{_K38?MI5#|63cKu?rhc0bsdz7HMYr@Bksuk%qJ;dDBf|Z6J1# zb(Y~fhkivRx00MHNs9xT$VpCZ@aT^M?z?;+`i&eaiME*Hgws0%PEJlhMA&Xqsh3-# zh6p8Yy;^f6*Ee`zz43VT(MR#>H7f`06=Q@Sy=Nlnt+kd7mu#}+cYkn4`vzD+bc>y4Wx#BAiW(ga~5?a>w?VxpA1+oL+)Qc)aJF3h$R?j-aYvMm3 zin4jqnG?t{oF|#DC_e@SV*)V9K|(gB=J`#4%LX2*Py-A&iRUus2`PIaeo_EW#30Ry zbS}$&f?19wd`GfxJjhKT2ZWH(b&ReDLeJ;|!?(DUo1X*MQn#3a;P!8rFh@bMt&(D( zO^hYEmPgPx%e}N6gY&E!&A?EeXl>oOT-qj;gB0J(5??T&rF6l z0FrATtA~uit?QE+rY1^_=7h7eGraTeyBNm_yK%%n`?H9LAASU@)doaDp2Z|{O+t(|2yegrF0Nm{jt@V)f!%HgtGQkc%PJ9!J*W^x9A++NfiMt`6GFR*%l<;O~@%&ZR2Ruux?zWE08+NGc>3 z+1<9kHI7tSS4O=2T|TeM46A`}Z^B5T%}k+TeMT*>qqlA&H27FZF0(|#C5IV%FxkCSkCwDP zk8Zs}*Y|KCXqdk|uShVP-z@1tqTjKm9Wl~Gh*QQiW|70&3ESNkcTP_5;fEjM{SW?t zn>Rnk`T1Q5v5$iQX^uL7mTn`S)Zj>rGq996O~Y`SyX$RkNdbr$ED7T12+(LJ5@OQM z^$0G&ql1(|49Flvc#JV)P^RTXVk~8sB?>_~iqM4llM~sNSgNS7Fb}~y=no0tb%fqa zUjk4)zy^RxB3h-oja4b>;HZNmfymBv@V)~&4_bHV)+@M`MCvghXStKq3>SRiB?_G{ zl@LO3=sS;9FJ!G=x2|W=KRpD5d*{%tH|ST#3N9@|#`Fax=*_XDVvOTZJixo{4%_V( zcTdl8^W&Si`SC5>J~_eZ=^5^voZ#fnDej)$!FG3!oJU>KCa>i03W;s6S>9|bOIjc^ z+Z8x;nM3u^`%A-BdFl+)EDT&rz-@-sv_F4V@5(~WG(zlIE`RrBb0g$EzH5BEK|mNFP59@v|=cIY|=p@)zU4H#K!k20gM zAG0zk%OL@*jsiBDBV4|Gghw8E7*`&;1n)hDX+WGtOmW0GjTlEsLI>>o0p2G#7X@rk zm0?732*e2(NP(_$2yh9H7O$@9e#NV6A*YO5(y2MO3n*^9gzceV^VF8-ati#-+68Dk zn%VO~N=y+h28RZIQ}gV|8AJ)eN961U{1L->)el=`u$AI__nse+iCHNBnSl_bezFQF zA_+!kXQ&Um)Qth zlqE1`$$bf3z#40K_V9kdG|0iE993ZR3OANk1HzWmdT^Xnfg0k7fFOO$85v0(NNQ>I zgb>7V+pl`{h#>jZ~lwYmKT5hb3A_SD|qo&Kf@Ql^jBCezM_O_$ez;>uEJ;099;AH zS{@G-1TTk3zo56u<(&{bQc5^KJHzjP|NBA;lsMxvkNyeP>oou=i8f&XrfRgX@iRjK zVgK1n5Ik#__HCBS+uS1?u*uwj-#Xc|qgN5yGBkSW9h2wohvOPhvJ?*S6y~BBkJE&Y zKD>!H-@K0N?_9@+H$KF6E8w^0{i;#INvWKc1=32;9eQqM4Yl=G-(%)I&vgZBx=uXG zz2`umaP`Tj@al`t?>+n5-~abu05MG+}m;kD?kNM!g-}mu$*-v z1O(@hyjWRNj7V;RMJwoI=J#p`Zn3Xf!SH+nWK7HZ3&NY~F_!OU-Cx<2B~(uFV!CB} zbsvD=O~y>o_-Z`{Nm-u(mKyZ#n#-uxJG+$m|(h-}1B%m5~x zclF+=7lqWg$U5%HdvOwYnKReyE^!EuhD${mS_}%3!z`d&Lb9{u{Q~NhRu46azTsRDrvnI_oj8MX z01!ab2|rFCa8GcZaF&pF#RHv{ahx0>bOM0;J|G0q@j~aY>N~909lFjVI14KmZVV5} z@n88Kt8RsLkec4XcamDvuh4ZpTOp`{KX@pt3m?;sI z)l$PkNjI#U5IT=;#aOKgN5>wk)e0^+Oj8eb9%HqpuRx7MF0qgY!mo9B^>CzE=AV`RpOq8(aPK8LxImvk?04a#YWpYymo(%vckx3#v z*bW$!98YGH$m3!xv=G>~+|1H?+5XhCdgk2*D^OPeoPCk?7p?_aRN8Mv-#JI*9I=;| zsX#6>kX=Sb1al?8DxYnHvE(n6OxXfPZK2t3=W4#-awB->n*$;v>-}72WxtzbD3o;^ ztRXYrqYI%>zNe(5J3fFr20KRb0(?_WNE$PqJDE!>bWT}Frb@XcF{L4@hdJe>&kI=f zD}-Z@I7N)R0mE*GaW`NbGN!4P7i!0|7;hV;z}81jTyoEgfy3D$pCosM#S`Vd)X?mD zV@kE!zX4tE5rPW!wFj_*XGR)F?2ZPU^aLNoD8gw!Z=>i#bA4oQL8uV~j8c<8hks;f)XR_S^5^t+(F7haY{2VK>OLTBD6} zGO*IQ*NO&twm$bt1%AR+qE~KC~~&52l&=^e+W`yG&m|DgC))8 zf;lkHZ^?&Mvcu{Su3`T3_E#WnL{o;NY^@#wzZJ+-5HknMr2VXAO;R!d97|}cl(3S2 zx8P~E!yDZ~h^eG)S*_T4v0n=aWfU@k@l8tiSP7eIJdx1)gs|#y>GEaV zfB${h9IXpSiy06~e>JyFa_yVvYo4bNM@p`GoFd{lVcLxt&dzau=M?96?qWRK!BIvh zc~r$1k~xFe!%9b$(vc$EiV*-LuQ8GE+)(A6Xhs5#GCUgq7LRQ96DFV0QPlLc2y!0T zbx174Qi&N^|6`X?>L~tyq`mpGEXQ>w_MObE>h8O}1$Ykxz+u?3X0(tLC2B^?SPqW} zP-D-8J(eg+;qc$*ki}I}SQ`mIvP})On50OGBtUWq5WvIR*L!bwS5;;n|8UO9%<9_@ zQdkvnm+r2v%F5;B`Ofm4W=u>Ob4qepqTyT?Cz4lBKQSCJJPG*~?Eqk}ZFdwv6jU#9 zKz86P&=lwZ{hU3J1A{$*J(nucyRv-?%cV9o40P@*3DbEbN3D&KY4`n%_(A<0E`7!&5!;24YNgu5y~Q; z&4ju>+jX+&$z>4CG}$a zgMiDIF5%$#0A1ff*xj>OPC7zL;-NM{GUX&izDc~iLipswYU!#MQWk{n^uurT8&d3hG{oT;&fwudolW;pMg@I@&bRYI_tkzxdEXm(4y z(~_V>04_#gGa~mu2vXNoz@&o@0X<8>c2NSVGU}YvGxqF}2w?V-L(UnA=#lt!xW$Gb}J+mUUG<$JjO9%JO?)0EyhW5MxD-K zW1+SuBV61w+W!r!*=zHjRVDo5l%9jb{gZxIC%1K0?_b~}svwjFY5x}mk?Q;bF`k?~ z#Otqr8_W?okNC((K7#AdzJNX~kTWn%3Ctb3&e&#AfOo5Kwn}hSwzw$L1@7;FVIm7F z-g##2%(+rz9-3WcshxwiK%II*rPGOl7#S%?co*<{|N9@|fBoP7=W@S)_}1Uy=RWo; zq8R&mV??mK3!qnYx2nA5hRg+){iBu;^OmXYR5A$~k4RDSY}4cVzH<)D5u5EA@7;V) zWKLpmP6C2gD^UU`A^+(lrXPVkxEYtZ2lD9=DYN!qzV$xsct3A)d(Hh{ZZ=qp7Gf?k zFC}5`9LEtcX4`YI9R}RJdmnH9=uOG_y?q`n|3PqtaAl0qvVCASz`Cj zNBfK;0Gj;jJe$9?rDiT8_8H%Z zjQpwrAT2Aq{HOD`0;{JzYrP(JHgc5fm)h{g2;1b?wO-$pjI&~Xec2EU2pGYVDdD1U zXOQOHSz8+bt$PHL7;AH!gv(@>Tdev3AaVr+JjKvgp4&QkXAG+M7cHWl17+RMB9VRejbOw7P8Vx4AHMa1?-jeOE3vxVJKQLXE~r27UbkY|)RQ^unSu`l1( zrk7|Q+Xt=9j%NL3fV+8TCeL?`W$ixGvI$#$a?Xv%8`bFIy~EMbAx@5uuv{)`oqOGr z$~d#6sY!$%gN*bv^W1QvjKeu5q$vpq-VBJt2+AxTN$<4^O4517aIm_+nuf;0e2x^w z$gCb(DP1HmfCwc>rSv0{lsICCM7qDTP9KucX@X2J&cKuyF|z>Rlo7KSfwM9?^95s{ zggZOkD;(4yFR{eMpz6qSZx!T0c?L+E>iu0z-N2z>{? z@B)SpIvgJ#;ppTLhX;o^3`;B*ORTyjy3k{>>e2N}ES4Du2PZf_x`t<-xsL1CKY-`1 z-@?1^-oSe|-^J~F@8Rt93C4J)dr@u-T(;MXQDIk%vIz?~)t~D3EHb$6(bZc!Hw4Zv zI@cBT_U+oFi+g`-keus!dL=TMA?JnQy;wCNgGrr7a2b6Na;bxGD1dY!tfj0EGEE~U z9+8rePg$M}Ab@PMiFowr5jLYLM%@+waCVk)cJ@RPv610}L$5hVtAidV&mQ3NrAs(G zImE%?0Tzpe+%Jt%R}vD+5ZM@mmEAc?8w`}0=WphjbX5%Q0vM~(Gc$T*NT@UKyk~!R z5eIh86&+yi{Z)Zc_Do$M27JqYxlR-fo zfH+Nvu0wROSVQ@O%eg*?DKi8wIbwDOXD~}1Zc@Oj4t%LI>}vk6YrYew31BDQUx;8d zCD0L-Qcn_Q78L}Gw_i>p0BX4;CxA0c0rFwoAajOKot)MAqLex8%m=Cq(LC0ifw1V& zPg2J;ju~;vO8O?We*FX$#a?)$N`VZYLXZjHBk{$ifXuGKL&5 zjS=HHVST#6W+SYQHcF-#8J@JLwifV8|Du3j*F66&yQ*y1W~H73!F|V5nQ?9YHFLfS z(ss_(uo^HIwrCQVF_U@5UWRSv z^?{1=wxiUU0&EH=8e@PfAXF`=WL}gx@RI&)pFyoJPx1f&AOJ~3K~xD*G$(i%2Hd)N zv&=&V;rg{}=(`2Lz{p%c6qw6guBi`#eZ;H@{`!kceOsiR@omc7atmU98R>h+^E+u%|9pDwg(c38Wpj`glV z!5rZto4M>!Z4J|;sVzTz{adrk|Na-gfZzR{-@@;G{&O0=5D>bqdaascrl4fE1IFB} zT%OI}@;&nuH`l7qO|!_GB4?OOnC8>hx~6*R^|FHf9INNoNUow1&g7g5Ay%0Iv%N%R zTeGGLfKg?`@qDcrxt5d$%1Fc@uSTbslt?l+>-A|u_$lx6{NHjN=x`IMGe8<%rda{m zRacrBezJ6U**nTfC_s{yuwv`W*6u~+`txzDdWFd>X-{sWQ&1j2 zN!+TkW-V=v#rBwFeZjVS+h_W8O_YQf8|rf!*f(QRB4c5B+vgJ{teSq(Evu9O%catOp=uhx_f0yG&QC&r|Vnjb9$wv&Qj1;C8~ z(DWDiQQc6euO$rG6IgkQoSI`Cviz`o$LblI=US?pC?yto$^Ufy= zMH+H#q4QFLN=Z-E>E@vNz5!&Nn@+tKEJcqs+JN9Gz$*ZDL7jLZNPf5`GP~f>9dtN2 zJix)x5=RGzIO-2@bZ~?#hbK5bI>BmrC@E!8^z;xsj*gDebqlOkM>tp=VX;`kdBQDr zcyc~rnnsWlGP6=!yT~BbDj3BEZtIbnJ*UbnZbRql`rVORv%OAVTfR5yvTN4cMZLh} zoPA*)?PG@Kswao6%DYs+5LRK|0n2cJ!-E4H_6O?0(*cfI*uzwyc(zQdd>wr?^7!{>Prd+A)YWgV?-afSd=Mgyup8 zs2M7mfhh?wmqiR}1q7&31Du=Yk%Bc9=pF{56H=D2(v%ZAr}+d1)R=47aIO={7tgM~ z!(z2``lw75&`Ir0@oZR$B&QzZ>djHXPlULmpuxWDB`?D~Ax48Q{|jh0>yRm+5}ua9 z6A-&j6wxk7cs^9_ivAA*;GK3J&cO5+SQa^7ZOw%NrTVcRNC6Pnj z91IAX-N(W{THq`B+O8-L74XhMZ@FfpC}2lm?K{eKEoUn?A>++G%1qn2UQtGzc!DEG zoIN?k>)-n>GDmO*KJt-_YtOuZ;FrjmF~kXhfj$7_E5oB*f1kCUsLBpmcicQH8AjVt z;H~ZIC76A-56Cr2tSOGz*$4=L&V6(Y9vQ#&JDK1eio``M&Bi|JlPn^|WumH8lE`wm12<22yrts7vl zvRNivzkVId=N^9a!yn;CZ@!5;cWz@GC)ra=Ut6?H<56<+acJ*n@@rRF*mthw9$Kz7 z%O)V=YA1JtyemxN3^6vo@tryN{p=V25JVoI`QjJxJD>VZ{J|gpF+%7Od{<;jtAMa* zDfQm(b5J?Qw57Rs^MZ%Kj5|-Y&OIg6&ce1Ww^+SgDG8~g5o$_#qf`tVt+$UZtX~5K zay_W>?I6msVBt1QRKsD_YRya_&S3W9E!I??c{ItMM`XsVwp;l|URSYowWY5s4J zHs@-jtWA{k1SAshYh@Og%4e){Hl>6-Nj>Rd7_eP$aDH}<^{~e1oiem1Ffv%v1I;t< zokmgGJmK69ZjpPkysf;CkS_uP;)-*FoK%C!UcnRt9FToh-T{XMsw8t+$!pc?T#XF! zs0M%m8!ydYWHBN!F|rddY|$8=vs5~ z!9@36{ef4I<-~hW>ZK+%Di|1-J~eI?(x^gF63uu32BdCpfTuxqRLwco{BT$(^(Nr# z>=gZz4$FRlgRsQGa)nEW$GCKI87D`Vu;`Z{1mwg(4(fbzI5=40>N8id9X436pJ2T{ z$1pxYPV(H&k<5?Acvf=a^~Ve)t%7KVpX?Y;D@&NJ(JFl=M`hQq@}gW5b3IK)o6D_A z6jPlP&5og0Cfd11oll`yA~TBzk)v8H6W|lrMNB!uSmq?Lev5H4VjM@LQHqpPHozkt zHI50>ltJBA-1dkjF5o?(Uod3$XJKXLj45xhUQb{iu^v}gtybt30<3eEuv;dti?4cr zqk4a{(k}0AdM5lb%QKenW&(0hK&f95mS9;^1@H!CmGi`6(QFS1Epkf05v1t7hErFo$y~wO z>&a3@)$f!-YQeA72bOEJd0boyflD9MJUBw7q|aFx0aIbaWH5Q;n48VLmZC^G1I>M? zaoHN^10?*|2PY-If`suo7O!*~qIfkzgmb%L0NU54pVhrm#!S8O(-c8IAteVFL`a%q z+2sx?B~ToL zWKbIp-F_+|Zdny)HA+A>=l|(H{X2Z&b6*BB5S+&!eEt>uFQ0n3eD@n){|bKb-~3up zMoQRE6EbSN2xyeQvY9Xn0h1BSu#Vq_^=@;6=4-upZ}iSGW&~0~hiRH{>(88sKIt@8fQIo=uY8&>hCsKLc9Hp77N#LI zykK2#4IO4AVpV9tc;h?YoZaL9`1}`(0_eTRAO6Xo;6MGx{{R5^(qH^vC?@?=b&feAgn9Q?$-&FE@r%}dn9LK6#SlJqaa#mD1 zY8!Q{W1#g~HF6{6tR!2K+9OpDG|Gw10GW|MV9PhQoZ~EpUAbfsSnI6%4 zWUBX>_b891R2q0Bwe+^y03**hO3WTK_iUEg+sp}rEhrmS&eV)`{ayjFb?BP8uum^x z6t6VIqgcMpG76Hfp0Mw*HdCXNx8l#F{e?NJ&owK}#?||4p5gX7W{k9Zh7fRkd?fk5 zt0kNx$%D;ON7y&Ii+#_)lKH^dQV@-eJjqXr!bLKTBZhIrG>#b408WIQIyf)7O(x?j z(bO!05{9X+qoBh){E4W@30p^;xyTT!^-3&Z!OdhX2(&9innF*M)S)HDpQz#7jp4~v zJxh0*I!@{|h!Q)6KpE3{x3Zl1CaPYyyWsh;%!f%B? z=Zrc8?{P2mI5;@OrQ=IDK0L;vKST%}f?uEu9Xj6wEc)od;R;uuxs3Jp8RWdilT(jz zJX4+>p2<9RS)&bXjaiz2%I=*tRlKxC5*h$)5%|1I@t2=8qGs9)6J&$_D zat}u`ik8PNoEmaYkdPn7I0`VF(j>sj0W@UfILQNOsPm+CeB)LC38HK?0S@Fk(b2U= zFspLabphRyN{Cd-2`);*J9da$@pOz+#&jkd(E0WphlhvgS4%7w3k2VRSzQ0jj44ON ztf8;EP?FVFb6mo1Q`y)u;-pN^6H0njPEacMrtcJNh6CW_u*Yh(LLWNxU5~B{SZ_9X z_}~E^J(3U;k!rYjh!*?QgUIp&+)Th{75p&@kTUY6GV&I3p>w5#QA1vn2T0pxbH_?y zwBr_8+Ku(Mh5{6G9E{`^n=Gp5)Vc4+4uzVNv}$8Y_1 z^#p(I@4kYM|Lb2<0*e|(xNi(l#sFn}pY|N~!VDtJn9mti^u(x8BUVZ`Izs3IGJs(m zaOdvrGMR`7FFyY~jt-CE$Vskg7UczD0YKAI$ibjsTNC*Gz;AorYzTJVxA*paXV=>| z>q7&Inr{~;s|U+4*4OPY;K74Oc;}sW@y1$LD%Y06av1A$Y9X*`8%{*yMOggE8Y_!uP)O_p|T(-se6K!GLBo_3*yKpS}7QaL(a3e*M44 zm;drB%`;TUM4+Z`RV8iYgmV@Qh#A5#U{oTz_LwW$5Vs3Q)pJ^W2V@IT74VzX%WEF| zaU8MTZY9D^)2@h2e<|)OXT)upQhCq{}A(GaJo^H|74 zyA2JQWAMM&H$8CC`S}6h=H7h z$POf_Y2-Z|2QY+;%aw7__JCoi)|>@qsFG+ruldGm#)7fl&(ItEi7ftZogAYr7FbQ`(9J9y!8%D|R zO8Qz8>wQ46h&at{*bOzbgmqt%qCLE?&n|=wz%DV3DRE-a6oC{HAyHO=0ytk;nI)H` zk~T01SuHqTg-g!1`3N}9oI!Bv=@%tE7mJ~UuvwX+vcYFH)JW13VoI1acN`!T=I{m3 zD>98qa^kaX!gcSif19zan;wb>CPsPRCH2PZxx(5!p<7Sr0-;}c^qrJ-8ppJ!cC<)6 zW-(MG&WLJlE%*E<9F|La5ja@rUNfnPQGx1Qp>C~qwCBC{Xq5m$LpVXCAfB2ZT>~R$9 z*QIy|MWHblIsxdlJlZ%8xOMBMu&qxcQjGZEiyy?%!7;$Vm?V9MGo$PJQa-GKgcmls zryWlNv~Az-zPA@Ra~<yOQkmsl&&GVM*Z&y3kM3O_h2LtbZtMTw~U0TJ^ zQTK+DHWM@AlrSlI*)R;)Y}PnGUn9ndplK*XKxTr=5LKF}T&I9jyRY8U_$!!Yk7CWg zBB+jp08g&w32F!z&#q(pD=TPrHKk+TVYB_9Vj}|B6$2F)87m$r21^*`Q+hP-%%@g~ zls&o~C%rLQv=U%y?B2>2+8znLuZ9@9pkFkePpUGMGuw0)@Ar&|uN>q0bC>Ys$zwcu@(7O}J;H+r4{&yNhRsIOUWZ|e#1jaDU7Q+I z636nqwr4Vib6FVu5Gex8nvE4+Roo#XU zn1M3@qxL~zifjHh3j+W+lF-~mhe<6mDNWdJMvOzOn+@&x{?6+bFd6f+cMW(T%}vz_ zZ}}pWb>nD5vUgU!Sv$=*?Eo|e+adyp{mz5 z08sCjvy{=2yg)&K4OB!poaupPD-#u3bnvFi}0495<%BxG^|nlwCt*VZ`ACGLowjqm zmR)-{q}Y0!c}Kv5@Y2g4$7`>A9kv;I^5q_J605KG0iXNKpW(NEr>PVC&9CC8fA$xV zCnE#olG9Z|iDmokJ9GwE3g&DKccKNF@+_GMvywc8B&FWha!{vf!ks&JN~l}T86SM% zMI0U+LO22#F;3-D9RgT$UMpDNY4JY-?skve(k=g#qZkPqqM0~NVwA}GtRM`-7WeMn z!;gRbHg3HA4({B&gY)${oO9?xrx7rw7zsl>88HQ_EHg5yy&+&tIPk7PU=E~rjGME| zP!$1Lh@Z$YUjOdCoL^z~^iKBlP*Pgv*ZogulOV@)!3B* zMD@%$@8FWxJ%kDfF`;e|TKghT+C8j{JeiVxF+84|bLxB5!(wOb(*bOZL1OM~TVsT5 z`y|h9WQ_sQ<}vE4J?lX+mI9Otj4s5tu*u!|cZ+2JYM5yHWG1r>aOU=XYj@4T%{ql&x7T#KGgeg3@ZJHT_4*9HkO|3P4Fm?EZRg%Eg9QG_hO zG)M&O7)MNJ6UJe{u-#z0S!2CD$2e_q<;qoDI=O_^YKhLTz&OS;@iNA7z;?UA>FFr| z8bRg09zJ}8$B&=j@xv#$fB!!2-o1|}Pab26BZ#HUll11K9{i|)-cqp$ZMq$(`U_=# zSN(KX&#-fvAuHd_jsDik2b9-Ea*2-6=vcO&hY&>&TA7Q^E#aL*A}I(D&Y)r~m5{9v zYRGNp35!L*!7`xlJ*ZP64KHDdeNR%emnNi?F^p0gX|vg2y#|Is0B};kVEH6DY6$QM z3{%1(PDMFdWORKGILU9A;w0XLNr97gR*D`mM!4Lgb1MWom+*Hl9F1PA@GeV74^ zz>~-4_;Gp7?~ZLbT7<$PtxAOY8SuDDj~6S#_=}J1v9~T?L2_4!-lsvMrml zivygCVA5tX=77Cj{|rf|MysUHkD}}lG~PouYF2M*QwAyL2qXxbD`yZTXe8K$qk6tH zv{_k;XQ2pCOQClN%4nN4Uxb)3F;`FiG|47_MtR9XjKDb~xw>g*&ABQ?<#UEcQi5GZ zj1j}=FvSeoO31<##lk;MvNTdR!GkdQ4uKrlhw5SGnkxmWGTp|uRsYlg1#qn;?VNOr z<(QMxl=2|;dlw5}(L>8XsSwrY6aCkL6A-6_JPw#*#P(c_I>W#i1|daDnxfpw4Ks?k z#$smgYwxL0FC*C~*7JE&0kC;t%!Ark{<&PG&cRkNHM0RlD4OD`pqeVMEJQVw0m|@R z<`t`_K;oVW-UCz2*p3_gmp6X|?|WgT^#RXadlAci1u$uz-ze*ZEsyVF>jY?3&}uTF zeUc0Ki5i9RDcGug`xBq|1pvUSuY3(AoB`nFPyTCt|Ld}$L6tbRe18VGLyV*#*kAAj zzy95?;iEtIE3>w?9%*jCdHc+Dqi#R1&n)xEyq6i79N6WW4uM@o*tRWuK8-2~K#U0w z9y}1mog9dP7hZS)$H$itoR@W;qAKZz zWI3WKm-Vn&Z*cFyXBg#v@)kp{r~D~e~VqX@*AJ{WxVpr-$7AaeO3UL-z#s=m307U!BqRV*7>bW&ncyn z^E(U!w%aY%>ovC9P4WIpeRi!RKpL^7q;tqBqNwf{CdU{_rJX5ZO`FPdHA)#!$g<{A zS9t+~;u9imgA*|9H9cu&j5g&DxHzk&RWcjf9iW1~8Nl87ytJ9B47dB*S~s=T=|*IE zuW07H0d#^q(>}pUgyN;u4WaC{W>6_=n=C6BBXj{csTy_L$Tc%&wDL|IJ*mt_Q?SkZ zz7K#GS;ws`ZH*(^jy#8Omio3>EToQW*THLOaceALsBWAxIJ+51C1)v}Chu!FK5Nc+ z7M*IECT!PhoS&XzvtG+(6?A1KjpEsSX`Ze8wRubBKZ~YvB)O=4*JIK3k}6>Rr2IlD z<|dS%6&uUvj#)vY>2el6oa>#HSPp6+xe!!K%|29=_&Po?qk_%%VxiZ4yYxeK1%O!% zH`Ihvqky#n+Dh7#I;~^?)kv(*!S*>T4p2TEW3Pp-Yj6=L?K+fc$8c#J!@@8I2c-otzE-N1u~4=@gcU@2#jo5Ep0`oB|y z-mWfT&)1HTMSJe9t*33u1XP28oqJ*SHv0ov^kLOe!vUQD0a)rHT+kBZIO56n9NS@w zZ61-L)TJ|WC?ddj4#5X3x*mPsqg#4(y_fJi08vmLGG&Zu#P)o^I8GRbgzaX)*%`3i z2$@vY&}(%Z!)wTB*3e|mz&J40w8fM%!Zd0~EMpiZ4BH9YL5yKJiDx!$~n&Mx1w6W z6Cz^rnBs&GLkV9I0IZ6FDV8~@2hA4#yvAdlq*+0LDhbXhft7?$`w;YXS1A5-%9vu( z{Brp_O%qrNUNYGRD%H32*VTTGb7RKm9bDeW;$EMflu zat~}UBG49Khpv~wigD5nN5YDPLcZB_?PoXiU1hJzc6rMKizRS$Q9N(Vq6tbxj$79*$TL3ZZca@dKLQCnM`G(O35oFtg(+~Vccpp z>=~{H+yrcfbNt{(Z%Fw8F!14s4_yBs7K=j=i}x`lM%Q)dyq2GDtdhIlG+Ap(HgZ7_ zH)^4VjPDBS0`PO~pO;?x`0N^Xzn5PAc>A^}jrKKFGHQ`A$uBog@aI4KXZX~ot0(x| z-}-9+z{h@3$gwQCyj5hI+o)1kA&7NBd8DHBa#@qkW#sH?ZXB6MuvHM}NYoyr2e}4%1bC6TJ3?+3cmwS@=7Bb)N5eq(ut66kmoKV; zCAuWbT1=BEmZ^Mav)$tMd$;lCTW{j+x8K42`}Z(x2jw-WfKytmK98cvr($Gl73^Jk zUOkK#+g|>61Y)bddr?t0`7E!26eGwvyz$*{%+CGH7ydx@1Y(dXxP{T*1Q!)`!NC0Y_kE zhjp$ENiWhEDnP2-)W5C(t-3zjb-QmcXs7Q>s3vMCaRC(i%0_8^-RgmX0V-}3Rf92V zr}VlC7p=sZPK(|8g#$=11$zZ~MTE8x;i3k7S{)_6*IrpxR#ynq7y; zVX^3NczA%-!GYA#wo+nT*9)ssQ$wun@lAlVW0*@Wx`aPxjMIqCW{tDcQ=G0(;mIL* z*9S8B~ z=Ef6jgh6IBfUE6gu#$yYqzKLC6obH&LF|y(DWi3QM*tB^X(b1c3leSR85A5idBA5( z(TTw?My%Hn!?4Bq`5DemPqEpYVVJhKe*HR5PA*}2aEL|UBe))mCE@7E z^5tu|d~zKp$5-(7JMZA`ojcf^uO(8`Rd7!bE+zw<^Yv-(H)B{9n`m5RrR^0(rnBuB zV4F0Q8cAaNs79rj(L#^#%;B?`rikOkF)m-ej8!xAW&9fUcW8JQxcEHzqlPKe_c<2Yd)9JU+DAx>I17j{BDdL6~ z%U^JWz7JR|I;>Vp_^t!9xVZ5T*&!q;)qlNv*mh&zlnfmysx!{W5EbBB)Vdih$>c4F>Q8biDwc zoEYOYs-jd zNnbrpP}$t5?4&ici-`1nYcVOQ1{dW8&LR|a<8xUBDi`t|M})qUkelu13_tuYufsV8 zy9tbp=dQhg-XDRSa1czBD4LxQ0M*hjvyf<@C^KkZ?>t{Y=X((F&e;G6ufFmPy!5ho zfM0s~<9PLzug}2mtFL^0=N{583@_`_QyIr;65!~Z!{RjR8Neupq%I&h2|Y5<`?RoUF`g;NYc|m`w#E=oxtw1*8zw`Weqzn@j2TJ8 z2~(;{?`E^bty{P7=9_Qgt+(F7ojZ3ijsv_G?;&Q_GexV7zc9lCiA=Zl8s9~u+}8eV z4Upvl%bKv)0E+k5WU@qDOZX!L7r^iDeeMgAra?kt=0kut6K`KyMpwhJ{Ic@4+4G5@_ZkOSr7{b6exudb{o=JCJstT%5^GgHR~C z!R{E=ISw7Wc3wB_ur)dZmfT#gGztc)n;o#MIe`>2lSKXMp3Q7#9HX80vBzs}1~r=- zO}|*h3IJFvI~<)H;oxY6(1#+|E`*ggGR(q?>y~2%I`aU`!>_Xvy-m}E$P<_?s)N8T zDv4Os=PC-N{H9!AvGpN~Y$8of%MmF_#N{}QMVFg(qqaNEI#57~7-`KoU?p}mOtV}j z*Nz}yW>JUDGtD0+lrfP~M757(9A+a6RzpImmO!vgL?2n#ll>vt3mpkVwg6j2{8`9B!DvxNlPOoQJhCn;!6Xa0LrfSSS%LcPC`DWJYpO(VwP~}j0m9S z-^Qdl#JW!uZ&(82DRBPi3|Eh@;3GfvVK7%hrYR?^*BgBFr+*F~``Mqz8{hsuZrr$m z(?{nxJ3GU@vs0X&omDVwoIRZagAV9=pznJu77O%!r{E4H6gQ=aG)kCuo|Mu(c2!!%-?CZw1xC1W<=w!M`a#$1(%*4qonI-Zp*;7UAYB}v)^=NgNa zb5g%oUROoV`#OQkjI`RW9oZ!<5==uq-L%HVHFUT2b^;j z@~SKa(j!NVlk`>0NoWPK2Y3=0riKcJMi^K>DXADIm2)F7PK+G4m=+l>ROKS2gg6LG zdQMe8v6M{CKy>xmU{!|nzE(;njllXGNa-AB57+RH&^sp<-(I}u$tQ%)qwg1DNbroV z3qS(4aVsG#17lQU&orn3iP6et<3)gl?>a}tDh%7`QI;h#odFh!I3+6@_Krv8#Mt@D$GuYZ3P8Q5U{9^Zf2P z%<5nJPjZ4y0h;0{DHG)I+28*YeEN6)!|eP2@Xf!$&wlimG=$uqbM8ef;-!p_Y|||_ z!0t23V@McWwmdJp7Lk3M#kJp=Q8602eha!vk~J_oQrz<4g(2(bab(B;nnB=@J}Gj`$C!%e9-W^O43s9sj_|_Q!fB~`L(a&lb`ri&GWU-r6sSv_O}J_ zzWmZJPs8 zyjOdc{v0@2eRY+m;1cQB(p#CLFJqe|oYlfuqi~qyEGcMqZuOOzMZN;PqGUIQImP8l zB&p*GiOz!pV9OPyL||b%fsj;Y%oNL3L2Z=R3o?QXpjvpd>_-<)6I4Aj4$ZIGfbZG& z>>bwti$%gKNNXWh#uv+r~QC{1?6vOAvGwqY-)-4qP&q1&gfdvmQjssoCDM_AW zzg*(@_!tKV2gO*H*(SdLL~WMH0?Yr+es(XpwdDV@zEO5puE4D9Pb`sb1-!RPOu3^) zT~+yE21PNvi$Mr1x_X=pnPHm%V)LGgrM(z136L}kpn9)$u5%l3&2?I%9UmPS z*7w0mg4=lEQ4Rien7Mt-G7lIMeOPLQTitgkkg!7V*<~nf?x!}c0 z+)0=eyNEO~(v&ey6Q&JgyBU!O4I?!`7t1pW;g2cX0phAu6k}e{DGJb?(i}J!BcY}U zz)Ab^2=E#3@ZKXle()IE?I0daN?PJ(f#ahEe(GPH;DzTugn#?jFaPq$F0?Nn4`iJrj|JdSxYSh=_5- z6sIz|V@_J?D3-d7F-DA&5-SjZOz6=eA;Kv0DKn6BNz-VIq~g`hLcEqT5Vs>-*Yqn% zh;i|>0)=&(Rk_i9r;1u`UNgW67$*U(XO9465r}=rSo9Ho1%wW83t)91;oW@~KrVx0 z1TrBGBjS({N6q;)FSb5*@J-lru6~jkNlhV@vQ17bxGi3r9Xs!pvJ|kK9SbR|VegjH zQ=*;9_Y4eI;9ERZY>H70oi<@r@^Kg%9>g#Ya(R}f{mucQlMU!>eU2ae;B};!F^(fX z{4)t3dhx%((b2J3o3%s|=d3x6l8;(8$P3Ea#ZG#v0{A`$Gw|vwe~*`5{`m`^74L7^ z%u$rvx&cU5Y$t~2Z(YBK;`lrd}t3;Lz6`Yp@xFn`NF=M z3yb&bJD%Uqe({e0mH)vh*_HR8VC!Sv!+SlzZGSVBaOYQF`|D!l+P9Woe(9HIug$-T3(8-ihyQUc|Ec&E^M+P;<(K`MuV9h%>s*ymsQI^R-3rHPF8JU$? zLC@0_R{GWa$!SNXn?daAWP$@@+GE+F(Kvv(7jhuU0CR z^NH&?HjuNG4I&GK8Qaovzz*5fj6>61YoBVnOre^E(eBPRn*C>hlV_jkHJUyuievj; z=4x6ZT{;Bi9+5UVFS-snO${O0Q!IR)^g(i#h!0mlGr@wF23`f z@8H_CYq)gj5`qFicH%{$?>O(nS{)SUG9VM9L771G8oV zDAso&8c}5rp;%(t(i&0o>XK2qa{_Z#;48H@W6Fq0yzFv+%>!Zwhk9RT2IUM+`dpcd zA>SDw2EZEPjD$k=RjiGsI9Q0V_GebmX{^tzm!C!Ev}@72Pj!(g$$cqGIKAtDaSLoV z6Z*x3E&x7=?Jq@{_u0JKYU~L?r&|V`zMc?KZ_WJ{%q#g<=6 zs+k-yWq3D?59N-i?NB*A+bU-ollFy%4o;(_TErxgDx1v)PadD*z4vb7-FM%?{rmSZ zO_OpR82GjFIBFDhb!>C#Gn%zaj1oE?*+^|z!y;?=X#3qFw=KR;D@lEqTAA@{x=fM=>}{So^%zF1Uuzw%(+yt7i5DT;)aUb+9qY zjnU3V#F0~vuqt<;vd+LfH!zTT)Kj*m#<)&&afRfrT?v3 z0LUrPlgeoGGE$zKU1o?I&Az{L)B&8oX9jpeV}O_m-bRPse_1=Fy}ro>(KoocV)Y_l z*i&cMuKmF4`!@au?aQ*sqbiP-sOQ%eba{n#`ZI6(9jU-`j!T0dKgI|i*7GV@G zij(5H!sI8YDr-z^<_t1YDGlLtUc(oISOSGCJ{Qkt1zHXP0Ys@RQZW=%@)Ad+`9BsW zoD}d1MSEnFkSl`ZZ1+y$_*eZB%f%ACUur+N8fL2X<7OKX1tbQDav@SOq9!|9PXj;* z!SaBeF3zONs}PPbXN1s$8A2#CP8#x+3Q(5vA{iN}XL%e+2f(s_58;O2v|% zfg~Yh#>{NFyru27_7oUr3tw(Sf~k7YZ9TQN0%mo*P|YXwCd1h_ZJn!4pe_$B=2Z~n&Y8sGi)-{Qj` z`6Y0$e0~G5yX{i2Tkc6^Olx>3ip;4>FA70QWqvg8LZh@c;8W&{L+AqHl|QQR<3M(ZH|d z{iYZ(YzI7g_z1Ud+``-Myp21z?_eCn^IJ%W%%j&l_Z%eFakS57O~?#JQlmzVvS_cx zoV2Xc#bej|E8*o4KYaaL7tZ~IKl)?j9FX*0!3Rli@@^0Kh3sj2=5+P!nF3?yIK1-e z-^@atne!|RdjHWx95wgaolo+dH4nIAA2FKPxJ^^UI7T7P90qKMHMX0Ll*JncOyh`{ zBtpwMLJZ=ca>2oM9$r0&PTlMVLToPWio6zd?Lst@sjU}s?un%8(O?u{Dn?goA}tiK zk_Wl!sm}`FMQ-OZ{z9ykDn4-p3xl@M-_qIwVr%IA9IzG?gk7UY{U7C=U4u`nLsXrk z=J?xYS6~?#J(Kkk7lOJLbcnGq7yYZ0rc&dQJUf+Z+jnxd=f|vF?cd#~A8WHSE{#H@ zq=w;~;k-xJ_gEdQ;FJW=cOFN_M|k%76+Hj^3plxS0^fDz*`3qcx=bZ3n2Qq8PNe$B zc_$^6vJgXZOvneo)yr3qUKo(32@VN&@87{@cp_;I0KD^HZ?m+RE6Pl4Z)yIwZ1P3> zf_K_Qc7-n||-`)Rqfpj5-B(oJlmtjm+?1Dh$i!(%MN3gkNYu)xCi2);wV@HjkL;qs+Rc;=a_xN+lM+`N4Q4<9|i5Knb1 zEbKiuW5qBGSofKWI#R8qb8(*4{;fLFQ?ySV{;HUV|LUiH0z`y^eu+oh2S|6eVku1# zecvPIhzF1EV~hjBB49;JbRmFN3s4t8okwy&PFj*^J79gj#&*5IcAE=(u1$cNzuc00 zNP9}2B^Xh|RHM%Q&VJ|s03ZNKL_t)gq-i*_NGLb=%o*}0BH6?jBhni9!Rv3~owsib zV0Q}*d6aMymaKgE;&JV;TCH$&?J5`oM2?P^Qr^iqWFsYU5zGlOF=&!ld}pz-0K9r4 z<(VZ6u%dRzB+NpPl}Yl+x=y^q(kEOJ`gID-$8m?Gg4yc7)&4B^CrG_8U2x8eue&a1xW$ zc23};XoFC~Rmo+fEJ8#q{1OUU0B$BwB1jc;^?K?~YQmHn!Db#|vnrLqD?(xWrX3~6 z9IfrXL^S_@H(IN3IoR0PwG;%ig5t5$kX~2An+fu{f%RthMqws(x72722aH=7y`XHomxe@LxIW5KWYf6@`a~J@J$`BnZ zKn+6Pj7&O~&S@RxgzaX+jT`T1X_FC5z`y!QhfBxLfE)=K(4?D7a7EcHidb{}a{)0C z;S(=??ETKbd;_Q+k@gG$n6eIlgf7VYQ&gh_2%rD_pW{=XntOu3^ACTEpZUnY0kg@0 z`6Rf21&fkzYoRKDEm2NU2-ONCx#l%|)y^Ta2mu19p+*-+2!Sw72~SQR;m2<`JOvrJ zcI_G#%SFkbD~cw#fM7!73BQ0e+wjEQC>jOJM0$Nmw@6dcbPO>DWM*tO8{EBnAMd?) z12^8ef!nulVZGi+N{dFy6ed$!{G}hnt3r<9AvNoz1XC(Z{7t8q{+tsBJ$(+&$aZWj zfU=+O1HXUtfBrcva=|;O=U0glOW3pQNm<+HtPQ*izRfFXkJ|`CU=Iks_#Cgk`n5{@ z^^~P%dsMk=qc~;VSF##&#q*mnO$nnCUJaww`xVyb^|{pi9kv^pTPjQYMTdBJ0C)-4 z??M1Kxd%10-yqr?AX!9~_&{^jp1q4!e&BjuM+`3@9xx6;EtGf-Yqcnl;Om{XSd zl&vy_l1pv3NV*gjhX*(~IKa`RBV4(11|(NZ_dH$#Bo6^%!!qR)tKrV089W_ zc>t=!9;B`w!QNHZBc(78P6UMPe*9UZ#iWt1`bdamq znMin*wDvq0Wt}D^txG8(W^)=y`QH1Uc%Ag5e|ATRbG|{Jwks42M0@Bx_pAGSFhsgvsZBY_ANYo zd=Kl*8Zm7|u3!`yX50#mB0JX^bt)8t+q_@P$n4oiW*Suaj_t1|tAWs8J_HeA$`QBM z_witJUp%myQ-+kW-fS@CEnLR{2_qz{hMY-4T&0xD7Tfg(=Vxn78wp*`@~jf;-?S>F zG-uXTpq8S%HloB#4Pa1x%}U#EUe~i6pw!{RlTDDZlFj4;Ce7a>JJR{QPRxt%sC=QI`iA+NE%Aw03?ASDGiDF0U|jRu{6+2 z^@8rM?&|7#^_F^>84>Po`e0`69+_DUCQ$v}%Z!W&_wdE8*|lqVyX++uNPu(joQq1L za}KL#pJBaTBf1ejFyOOZO9q>mpBd8}kKNWx+V=7?SIR}?BSdAsCUz?dVU%4LFbpc)Q=)8w_LBNh{uc3k&`Z+b@a{pDvZu_Pl`@Hp(S-_dm zjHx}h{+`WdngzQT{RP`lEDCJ8Ec&bsj5y>{Z`97)w&~bEK+adnAL$~$pR&QZI;jc} zZ^qi9E6fOQ79TSdpmz$?5;(O#GvKQz5P24AmaAVA14fROwZo~{7iznmutEBv15?6o zoABi7G2VLT$2d7TMc)nh>Msz^&+dylG)qn=03dXtIBXB6d7z637w<yw>g5V$j@Ne?d;NCo#aWz=DP_cI7S+rck+PgK&JmZFSNQ2qKg7o$ ze}pHGpJ1~YQE25v1+-gh7h|9?-Xz^z)OOp{ljBk1WgEW82~&(reSH!5{q~>!C*gUTWEhJ*k@1>kwks}#ea+M{g?k2oC$yPH-C%Y|NY-P z+7330t~g-of<(oWXxC%~j3yju&XXE_Wo88@QIwxI8{FO8;`;g;H@7#~DFDvuB|SM= zgPGB<2CPp87&V!>MkBavAZDZ~#46rab%yABR+>ikY!${dfMy#C>sZvWL{OWJfMl~p zy|I?_>U>tmbQa;B{aL^^*GzR9^}dbHsq;see3iNnbwZbQ;ppqgX9g-s>=zpktinM6 zDy`JMPD=OWW3=Y7QWQEklk9oPdb!z@&5_Dn=M~kHEnI)r_OgDIK~MFWa0P@VCtfG3 zM}Pt6oHOREb`n{QZl#lxD66m5E1YTm@A~uv{c44v`;MHuS0FDs#*`Q?lLjZKI5^1q zo&e7T1cIZ0jwIJKhK#=V7-IQ}Bk(qy)TD?_I1It+sd;D*pO8VP3aRvS9AlrqZ+h-t<=J51B4x;Ro- z-8+I08YF_v6TOFpQ%}Kf5wBBwIc3CbWtJou5IT=8C4`jVLkIFKU>ov0m<0Sf?+e&= zf#BI=o+Y69>`oYdDb2Whc8mM>?&HOam+|t;FX4srm#`Yv2(&7=>FoRj!)n0U*(qLl z@g83P(wFe)@u&Fw^Ura0bBVjVJB-taI$z#$C-Ku(PCQw za(zEMi(4taouevFM)jab{!^YJVw#a0z`@HR&J2!GH++feO)+9Sjo56r*o?ru6Y8={ z>fzrTXlC%HMhvR}0Ba>zjA}qv+gn}*48x2Hn|YG|*mWJ4XJJk!NTxUdH~~?ecL-gF z4n`-F$nKn;B5$vey{Qd}c$V`SUFWq75`(?g^c@0DPuA!MQ8`|PlOisa8=x9>^PQCH z%P|8pVV-4`P08|I)FYcx0lffVH6txrQ0Ota={u-jg(?$c&JtAxF=7{y9i!`d_)chq zrdVnQjcYvJmWv>Y%r@cVvo3USUC?JL$Wy#_=2@;FRvv4up=O?b%Q4IK4x|>BBE;s!t{5rC;C5W+LUAza8deFM)v3S^rRjj9MfdE$J`@11=ZkYRQXijT||1&RGE4;m(+)_a&I~-#oT6ErjNWzl_MiSW{`J55?-u8HeJV{^%io`oV|z z{K@B-cO$%OJpbi8I9lpRTBX-HvcWemD}D0dtsfj*?zjh?|tv@N_$%H`!|2{w$tKx`bG6*Rk)8K8>>+*S)C|YqS5!%^c&`j^0%jR9iM>|gR6qULsKm`VL8_>}@ zl&t^CoCHdKcvb1mWv-in&5Nk%a_k-Y#4LhmS6IGy`JeLiY|Y+xk{nQun=@6~v3_D} zBN=0-or4l(1l1^_jHG;UO#lVxmVKjf;7Wh%R!vlt)twVo9XZi4@jg`LcNL{^K}(?p z5&R6R0qc`B?wwuW{PYZGen6NR^lXxv_Nb*}z!@nKkP_VNK+H%D%fi-s>r-aHk<#Fu zl-b0Qmg@+~96^gWWhH#!;L!S^pIl zOS@i+lP7D`rHp6R=TaOWvNi@ERB+WdC7y&KSTx(%>?~f6MRR18>LQKdp<~!0(1O>q z76-~IB1eD|7H19Bv6Xv+XZnMML={eTJ8P=;chJKAMbfOW}-NWhW zDem8U0T<`@aJIg{r;pe8{K*sC+ycApR`w5OkVXExHEggzdNy^=6jjTBlLg!0K(Ji0HBmEDx|M`=*>hF(G@oY^i&jjj}4&G=ts+Ik#u^ z)I)jbz8>2GiUN3bZ?zm>+TV*A&0=t*7p(1ue>6ho9Ki=dAAqhWtb%~BIZkq%0}?~? zUxgyw^%<)ZLO*l}Lx&JL^lK^GBnr?3?*>)R9MFXh!D*3tCxTbw95Id~HoG12hLLwO z01wU?Q;smYp!9(*;xNxMA1vHfXRa(DTqmLRPtFx!MT)X0af0_!pGzpkYNTYU#n_uy zR_bBSrk)G<5Xzt`<&zx4If?RiE+CMHV}g|`GkQ{XsZ3mpm%`Iu)Vd3J&)A$?T8?>j2f!OM5?S45#^?g5W~qZ@?kzvoKJbb^KZxv%*|5 z5x3@<*~Ofzv}!VkMy?Up1!IKkcz4=B73MA=elbp(ak01`6g(&ICy6{82m+z93v%rT z>|LU*4sx(a?SWs|vsyf(1{xPSHZip3nh^^A4Xr z{t)yg0hHm$;g`SaaPRzOP>`HpsZq_~&?yK$l4n^uZU1e%xqR>y1H8w;t|>!X^tWX` z9DCU~uYE0m$@>~@oiM@5*&GAG5()lY5M<8oj~Q`rR;sgH^4K=B{MKkM1&Y4E}uTdM<0EN4?p@4m!E%*X}49cw?`>Eq+_?`+m#5|7h`Y$l`(Al)IO{% zz}li6d*HdK_k&dI={WfPlW+a`BBCdTyRYSr3Qb0CsIp{iezkyz%KWHw;QCsEI4h-h zI5(EZ+q`;yr|nbNQ#PYHsfeb~xdF+k+l@PHHg~wWxxw|*D?Git#MRX$uCA_ddwYZJ zb|ZVgE~uUB#E8xjInQ9LWvO%10I=RoS&R<>EEn*=?SiYcLy+bTYB{kMoDvM&m8$^e z;%AEx)lbP)wd(3)QD8_AW7A6Mm=SIQc+LMZ*QjZECahp}v9}njM?vDgZDRX9TRKex zD)*kDJ;%1C%g>g3MOpt)!Nxv1C+q9FVZfr9?J+V(^{<5us>f!BY-tSY9VSPTbL~ZN zs_Q$k_c|3E>g4xfy}~f85PFFcvKOl9h3~MMGx{fYh)=f&SscPSNwl~l0gO2e2;Kqx z3O;z`eg*FxW+yedvqgwhh|cK)@_O$gPCKYvB9NySF-~8?&;P>fxVpN=)9cT0b$yMS zyDMzA8%)zq%W+DoK&eQQC0dtNv~?Qg^EgKZ%WA*r_%WN#5moT3k#KpSHHV&czSk&x zyOs!;3z|k(*1*PoFdNFK!9oX4Fi}5J>1lJ*kc|gMnJ82qJfZzqerK7l-obYrx}nD~ ztR#SB?E=u2fjlfBXsIl9+)H3AfhZ$8uiFThu}rqcsP;xuFO2D>6y^9-738gCC`hRI zIg8L|=n_K5;7(QXy;o{HAs05MteL~A!&!F%7YJSGunKDo!wRc@z|gO7I-Ft{I!Fpg z1TX{C0VJ9|#9pi1tU+*yDPxXmzp+C~5z{VVnkSj_6f|IyN`G6faNC9EP&fwhjycl4 zI6xtE(icm^f`cGEnn2ciM55WM0X&^gJY z2^eI6_>33{G)E~x(*Rj%kb(!dEIZS-sRerVGbeOi*o3m0i+Y@c)>viu;L!CMCu_p# zO4@CL!I4A^Bm1n29I#riFr4-{S+9X0bme|M;N)ZtxS-xs%kdT304I?Rha12I_^!h` zc%btVmDMC?9|$hFQXR^o7S3z#EoG%oTia#BiBTL5S;fLkD9KE~sLvq5`p3Mx2}CUP z3-85~S-e(M?x9AW>)>*lc-@7%=u325=yV}?q4G2WEf(#yNH3y|qtu8VsV$kUwrJMv zTXHOX2yj8}Ew(vI&FgT;*Tty-WIL8BU@YUu-ZL<%>u|RIV*#UF_Z`>(GZ1O#YN`4T z0>-G5?>md`>UYg;+dvw>QuVTfGmhSn}p|5#Zw%+N%kXxnomlDr)v zAjT1o9(|O)-}~O*>sqs1q^cov{5dA2{YvCs(ikk2fyiT? zXIx)h;qvkl*H>4#y}8BB)fH~8Z*cqU2AjvQ8KGEl%78IX1Wr3zNn=r(7L*oE?aVRs2L;o$nuzqRrb+X$$R88xJeH?|R7 zDwy3iwB>n9oA<9^UU^s)jGEt%_8hnz&vg#inBZ#EitR(zYt24lYqs_4L95ICwoDa3 zo2}<5Ah~W>1=L7wS}EaESkfBg2wjIRhWjyD7Q3G$SK6r@w)ep4=?Ts+ z&hYB1ui}Ll@8R_945!^G`o71iTf_T+-mMWrKybZ8e0`4)IuLrb6~!QRkf7DcdW{$E zzo3CYsREN`M!L?J#!-V9QZHB>OO^_%qIY|1PDz_omaO$raYWb}yT8~lz~&NEV?Nwm ze}6r^iB!5tfJTf$7Og3(QSeRh91-ZDJBf$^!83ouj2b*W4giRLK_x(-EW9 z7y!1ITf0lCB!`m2EI>Av=*Yg-RR6QHd1LUFB1Ht|BA2w`ZvK4;S2+?E#EO4z_&3 z+D+Cb09CcM?Hfjk0+jchI@$sNO4yDYeDv_+!unv&c>PPSV|{W00Ge-?!5n0Lat>J) zIa{%`WydSCC1<3$QG3?4Xr5xZ6k3Ys{vsuv8YKjM|AQ_{kUmQ|M zQ%dSsP-etT2x zud7EpF6Fc3^%h;(%;%-|ozRM9G3TS;cfXXAo#y~FLCe1IeC_8|Ga^Q-?>l4GiUQLV zaeaM_&pv&G&mTX=_0<(Nn=N*`Eq2=-w%a>Q(};PV5aW!DtjgCA8veX2kCaP!5#30C z77#9fK%+HB7+hw^bImW6eZYw^tDe>BOj_o$Hf}|o_pZ!U*3a42Qe6xe^G^X~)fG8x zOL0s#>pOsjr}glAx;DVpBm)?_An&gwsO#Q>w!Lt;w2nBo-T+{6Y-Jkd{r$B93@c$} zXDDOL`h}GNrPnJ_&&K&d8OWKyuDQ2*ljX0hwdMhdsyYQ7U|_nN5$A~hX2Lj*n4WHN zb90U9@imwkufFgy&VS(-&{Kz11TX{)p+igweF&JfkCL-!xLlVsK;Vo@rW3czPf^Ne|(kfKDHnavKYsd#ZpjY@w)VqqypP8tYf$*=WJ z*?7%-vpJ#r6PNvmY9vAJ5%S_dFegw>N%x|NBIsrFj%8gJW~5Ww#sDuW7+1T;84zy& z?JX{X!Bu>WtAj>xmDCCLkQ5-V&&VD>o8D3aIAwSjOWrZT7(NWw0jqU~)6*5c{N-2i zbHDIq+`G7k)8Pz#*Q0YQI4?m=VOj+M1jj0>8=bI#qgPN)T3rTk&SSkk#cB|mw5JY3 zzrxk^6?WsT>Ix+gJ2>)-HNak_w4VW85+ggS5TH%^HaEYlA*{Vvj3oIHGK9V`#~pU# zj5!bTtr>`M1}0rBkpSw7*Ee$3NQu^WouuT^Ea{jat*u%Z3x?K_n-UyCA0q-{6c0`@ z#<{9T!#C$?jAj4`#qiZU)Z|3{*HHn31}p%HoP}UOBOwHbt|RnohtqolUU}^TFTeZ} z+=)B{qj*ng#LdkOo<5D(Y&K;>lrlyUG*1X2fY6CYY_ zF+qfS%k*Ju13ipl=88yxf!}EY@+8lyrN&A}0dN}CBVZ<_wG%)Tkvrk{JIxui+!g|f zKvk+B*gFR{dYw8lg72hGw46D7$CCOMLg7&MXIVJ)HBHFd`?}tpDuWe~o{+2ZDd{#y{X|zy3{FewJL) z3}V~Z4~^0G?)MGXtoL--0opcFqu&e=H0>?pS3K`2XWZT0DF~L_G$M@zuh$?4#FU|0 zgXp@hfb)aCQau2nhbj1t5h+Gd;RPYagv-k-y#M}B@!-J&Jbd^N<8G(9ekN36>y-hE zRNLQfezn=lzmEV}Y4g&BRq7|JU{(u+YyL57^mE38w+_MYfBf_BAVUnL(1~)VmEkB% z9hQl;1Q{7M5^VRi^tjm=A=(?yydNQ!@^76E9>GMIxnJ;j3&oZ?1BQAaBSYo zGs(rE$>p8}h?p^d*h&WiIc_!@UDKNOm%WM%FdvS!+Eup3)^)jAbjun~FawhdSS@S( zo=BUuS(gX};rr`YdlPz`={V>oguVM|+SmdUGxTL`aH#828#Qh=j^&m0KIMGNB0q=g zuk1Ur!4fP5q%CQtea0w4pXTV#DIuwbj^I&opytd-vkEn8bZ&Jc0C07=!FIdF{OK*8 zUOqv(xkX1Ez&(bScId_t!#sgGV#pDMgbo>Mi!Q7?qY|@I z`7n)iQnU61??EA`Q>EGi#ffcN8>|5>mPCPMfiYuF05H{l1JI(bZ#G;iipDvMtvJV7 zY1TU}PZkw)#=^>obCh|!vs&H}a~2>xC!ul2c|uMJju>EzG^e7dZRaZYlN-$)QXJvM zHU`lmu#>n(Wb1s<{nLI^MwHA6Ua$gzstr-*lR1H03xw;KuR`D%for5WDMdP)(;^9= zG$Av#d6Y7clWc(tx}ZjiIl(z#wd!$ly29z%2~PVHgwVm$AUWoclCdt=pUfH*^8p;Z zjt>c_1wUZ5T4Nd`x=y0StJNC!U$}?IpFPHt%g4C6xyE)@M>4rZznMYTD&5-}To)3Q zHPsgzq)GEwEYY>i;iVV70w_eVpFu%NQ)DO6g)vVUc|;`1dv@#*0+4L7 zu+~F`D9T!dJmx5#zy#f}C1O7AlGGmDiPzet`h=YGMIs&`jeN^<_gbDYbd zEi3?4#+zq}P?zDf(x~}dZC7@H55Uj?eIWGCq3;61&}+G|guA;9Hq(rlq*f`T z8aw4OYE!zTUPkpcg3BI%6aZ6m9=mNTC&c?exa}`ngSh_mWV9VB7c-Hg=S6D{UkZ2^ z4i8d0KNm`^+5U-8^3Mp;uaVVJp*P<~fvpb;>yRzSMMaYoK*wpqqt8CZH0?0OEm8)) z{xyde@4p7;f^3SB5$ry_I4s&^xP6N7qCIIBxBfYR3{nx7FStRiq0I-!6+^!`rJBC5XV@C7 ztYCWYeFOYNB(*9H1b_6As58%E488vP>o_?%f%Al%A|@?qnzm@ZiC_c=+%kw%aXwjhI@L!~{ol;opleSAfI~U|rC;T43=U zFl_m3M6TrVwcnR9rMX@);_V~g_gmljt{8qC;e)Th*DbXkxLq{RI9_rcdxyu`L$qf{ zX8|CWeO4Yvc^Y+JG+ZuD+nTd@z?P!J z^Bz2F+gQtm4Cq!WGdJ%WK$NfT0Z?1;^-H>|>;YZt56c0D>_GF^Wu;ZJ|XEEksGj7^%vOEDAcphCY)sK z6cW42BEVMusHFY43hr#%vEjoEI9Q;e3=oOnd8vj%&cIBir&i}rJNH`_0++dBO6e9P zF_E?sE!H()j!9BjSmyJTW=!*laks@hP2dzkEW*B=1PBYITLXCGsC4hKM5bd-+E!&= z!W7cQW}Z{jN&%^;88fTN$Fd)Ia&=#5)`GI0kpN>I)glN5h9{|%;+wVF6^ffH>jy(b ziLs+F=z|B7Lzf-a>k|+WPEJqo!iz89{=NG+`}7o#A3ws=TZi3t zD=ZBnIG=Q!*4FnkBCxHq#REP=H~BiPca| zH7e&rJ$LW{ec!|TUcC;=iT4bj1;BdMckvGBbTEZ(#%eX-D63>^_zMVLM)iDq=iDxRIh=hsCF)MW|YmMW&Aj?K7 zzgr%gb4vjcqDtj%Bj-n7+(a;`f`XR167~#ospshy8-RIc7T)3JcQ^+sUVJSpWp#UX zp-wS@ea)G$`zWFbPANJ7l8Tzl%&P1slb9S;Phu3g_L!n5M=SlUs0lKc&CY;P=|5U7 z?xpRm(QsglVBrn5-w8kw7Tg2I&_9O(c=d$~y!PrVc=d(XaB*=Drzhv=x&gO$&+z^S zAK<-@-of?tE#_pZe|q1|d59oU0yYPXK4Z<%E!1hQ_viNSS)030`A2g zDcS@nLF)r+8bn8!C&uOFQ~cy7KL&9RhR4@_h4Io0uOW0ny~HgIv5f?`#(z6j4h{LA z1$w{u7y=+U_U6>ExwH7boudKCjtE@{KxVDsEP&)#B>2Za_)8Dh(IP@`&NK1qEDcLE&wu|M?e{~FysPbYi;q73Sj3LBXTJQEuV^IL2`ePd z=(#%WoKB)LzEUin|9R4lmK?@$#N*GN;Jx?W$AbqC@X05iV7uLx`nWcl__O_ za#6yTR|ZIo5`6+%?jtvIu+1fP#cFTM4q1KE(g$wYAAsf5&B)An`^_I7JdZ#Bi@yT1 zc;uay@bDpM%8Tv6`(xJ~9fybSJB>o?X)?iR)OBor@t8MYbI62nd&gLxu-5gBi+o=> z5ZG?E`1F%c@!*|z@zIAL;_B+DR9j#mr-&RgVp3rr6?M!ia8>Y}M*TwPaCdiu>+5S= zTwI_VdaO@Qq)e1|WncEBxuGPwCOK**ZMO9?%U;$P_%=^l&`F#Xz_HzkZa^&nAuLr* z>aW!7XA5Tqme&<>f`UQYukBgsez_1TYab2Sf0jlib3IVbwM;R9K099o3g0G7ZJ@YtcZEs6+2_O_8gwGG_%~ZR;$p>)a*PTf{0#euCL6g zCD6-B04LezrBTbfXB*7Zgl@CJ-DU&YZm`3MQvk!s3Mco@Fr2M`A;5RF-fZwDyya@T zoIXDWs}jHFE9?3of@@x2Dgox?2aBV``S6UzL$L2#RI|e`58b}8#j_TvLdpu1mlcsd6|-9Sm(Iy1M{pwyh-bW zZ?GFB>TEg6MHO4wM=?fB^MrAf@6Ayv2E>#wM**Rx831)SNO@0n+GTUN%Dj`u!lf*f zBPq!$8Vx}sr&cy86r)Z6w_=bifIgaVSsXFVvpNYaFjRqIainVmft@%VZf~FA(Py8* z_YT|bi1U*z`q0Cn2S9LH70x-RtuFP2odRG&uXD3g0N;T#BhBLc8-^bJ&|@_WQc|k- zSg!}1JneCPeTCh0trYHA?fgme?;A}FTg!5`Foe$0Wm{oc;SV6aNc3F z1vYng*lsiCX~wi=jN=GI-PAxz--%j$IThu_*yNxVK%mYFBS9soA(|jb&Mw0{ht4_l zeP1~9<2>8A*0M&WEeA%t^HMS+bOD|Mvdi$1Ks3R;ch(6GRiGsVLg)y?%A+5g0O~G- z210ky!>zq+k|||o@eOsVHBrYUENaIpF!T=h?%l&HuY3t#dig83 zfA0mHtS>ifE1G^^JRGVBuz5!buA1!dNHz((B8FWq! zC}Qnv7Gz0w6UE@tC~#vG+5IgH3Wj?8>qd*_7$QQ~b?CbuaKa3T9EG+;S)%bC!Z?Wu zX7gIt=$>BJALyD6h*P36NEgxWAk!G3C!{&!>iQCIzV!we4jePS{%edEUwReZ_eho# zob34@=BTug%Tam1s2AIiUWS@PyQeL!M|D7 z34Zg9f55MP{dcr7h<`qWp+m#5`RK@CYujsp3Gm*jVZPT^8Axgni_s(?Sj00PJ$h84 z44DXD{?eBu66~DjfkoM%T>xoWH`b_v(Pv|frH{vP!jmUY@WBV~qXb0mX2xmZzv`5L}EnbLaR4xHO~IL{$thKYyOszLB5vdA%0{iYB0A z)J40GoHK5(Z}8DiKg3%oYm@4qq2!73f)V3*b7{?v1uC5Ut zeuUk)!Q&^No+XS+4%G%4fB>6lWo6prN+elbf&@5yvIY;V--NZCR(8;wo%<(l7aI#l0m z*1BWkoa(vsdtbDck^@3;7`h%^7vRY$1vDy{kC?{^cO-0zIBVVIW6h_!50<^Dy-RBc ziLjE@gO#!`QvJhDoT;`$oG%*D+zH5X+YQEX1nsuiO(Ps;%nr!DgTH?Q|KbVwVg)`8 zh-;736Jke*%3w+g@XW#~Y!fy9>YS4G$x*e16j~f(D6M5RG&k6?AnK!G&fbR zZjMqSp?jA*Db6l5c0>DF^C%1qYrd@25N^jZm-(Rkh=D@q;XME^32|aCC3X66Tb-^% z4a6y$OPSJHor(+;W$CQcZu==9SaOx4MqQ_vFisPu-6(m<3O>e1oi{smlM4C@un@1NlM<_dS4OYC+##3X$x>sbh~5!Z56{TCLFaQr~vy6Slh@MwdX2F>l3Sm=mj4At5DI9MgK5n^p>qA)f6A=*fxpZU^ zuss8wP!jnoEse_rBg=ir%T0S9xY{|r4s?k))bbhzep|!ej6^#}@wP%Ytr$x^I(97d zpO#jrs*n=OtXq~Wz;pl>oFg#h2K+8xn!hj32(!hVl*EFoeNPH3VSu{H0WOXpZfLn+ zY&R1ge|CvyPiA=k5gZN3nXtLr;>nXIxVgPUo@JpY<_g+U-FR9cY#Vk)wPzdqVF7%< z(B>)qFQHb~mMvS;u_Qi(ye7>vQn{R3n9pp`%Ah zPB6*lG|i&k>72u#e(SHX-EHtk|Mq_@=YRVr|A?>u#y=~vF&qG$p-)rcbz_X2=%9P!B~4~uH)9B2IeSAGs>C+7mHGh>bs0mXvD=MOlBsjbgtCdps$-xzUD?L9EF5)B z%#xpP^umS;ERe!UE+eEU&=&t+3vSxA19Qj#5tDQSX%Z)+%iY@Y+#CX(vK>)~!aeaM@ z58nF#Z~W+oc<{~xTwh(uz5poYQS%35D(6F+8%7oAiLozEmh0vj73e3q{#)}@yO7qlNZa1WJ zumxn$eQ<9Nc24yjblU1#*D#cVNw>f1*0PGyn(7|~^?+78E<80`$dhI3PrE|;| z19;tG92}+~0;CgVWS%jlN%CdOvs$K+5NBminqx)nWg?|O3-HOhp4By31`0bRHd`mq z($*_I*NiQR!q#KVePh7doF=jdbF-eCn5%P~HRqlrozZ(n*9ELrgRmqVX(|w!dc`f1f(tOVa)B`mD=|)U$!|8c zqOcRAC~B7|u&G^VaIPxb(=@9tl6_|B5;9|@?a~mhkzq2&?X1j|qf z3jo}AJ%*u2*Yy~N0lgdGe2>t3oDU~hopd<6IKzv(Gi){+Y`0g~Zg&{x4R*U7cDs#e zEkX9XoJ^=q#l9>`uciNH`#H}AD9ie}RJUhlgru8fA3EfI0B7+`#GOR;W@yx9o-s`# zyc82uvWg>or|PBfyBd5F2@Q(8np1h5=@P{T{XP}DkS+wB%(oJFN?l1}xiz{bfT z&Jo*j#%{O8G)Yd`9K8&#(P54WyAc>iQEM)dS&e8}zZBrqMDVO{55%nqFlA@xq*S&t zfF|;#{q9=;>_iC5YL_|Z7Mo3*|5E|(a$RyI@Crh>(HM zN-|dpv=1IW`Eq~eXkaklQD{9&+4IK8psLcEz{Sp4Y+!Ytx0dP8v~QOc{7iO}q#HH&J)s#FsP|*}tnGbj zlk1St`^nUdkLEK2iboytb{yNrT7kC#qOytUM)buduhQ#mN1-Zu(Dyyot3l?v(h{@M zUgkW(DQ($6uC?FZ^T9SPOBoR3D{J{Msb#IgYuZ-RDk2s@JEw%p%S-(D%{P!TBPQTC zzd-_m{eYA*rZ^*m(Q#MuD6LPP+kbo3+dqXeZSNm*G?m|%2ba&xt6$1DK`3n&sRFD{ zaDsD$v(q#Dhd=%<{^$??`*OOU{OG^p>%aNW;WDez`_d=|@Z9?<#?;;`m!$0Hym)!e z${MH}z9R?Mbs$REZnya4lTQ}qAb##EU&i^_Ih+^j@2u%8!E4=eP06tJcA929{`@iC zefNF5^UgbX`0yb%o2>#z52=xE|72_eTs+S;q_B7I=3FalWCg!sgeH4z0CcT_f{Xx;?Bo=uC#P7iR~Uu?tD(nwwbGp7 zAZn}CCtzoneNrEkI1^DLW27|V@}*`kRak7yfjw8obDu?d4z_PWAhtNUl`%q*vgT*=3r z%X#&_wXe-9D!pEvwQ@f-%8(($rR1a9`PH7X+-8@d!2;4ihA{oec?|0l+*_X_gn;u& zo@5^*T<|#U9L~?r5$;`JJR86#0ls%g!NGeL@mWrob-jx^uw;*8u&(!}pW=y&R){F~ zw(SDgHDW!B<$He|+1e!iVCvhXAU4yXFkA_y*dw>|TDJq(&(o~WRmYk}0QQ3}Sq&fp zl({HD5wnxzYm&0*fC7A-fuZIe>K)kJS3CftjZ>L(D4(I0oTNHObi`|bz|}od4g9P? zmr<(+FehP%~^zt40Zotr=VCV;Qeo*CR zFF)DC0%zU_48wra(-WMWp5Tnn;QR&pmBV^{D$Gzv;uK03+V+i5(x+$GZnxNt+Y&L) zDtc>q*YNdkr*^lfa|XoD89p_1y|x-@|zlAuD)vT|m#mABR)5HYfFoU2vG= z4CW{$g!Ep#iLLn zFs?T@BAk(-ovED&FAr=M!)bFj<8Cuydne9;Y0eTIpA(Xnl!5)Ud2W&21_VF%)vo*d z;H&PHFy`{U?xxevjPB_uG>a38(pro{FNhkctzsQil$HTV&XZS=OH{zF^CHpW9E6&| zbs-avr<6Xj=q~`tv52{NMWsfX)E7=^UgjIidRx9LpVfP|*WTh2cnfRkg9Uv9l5 zdwp(!j}rfA_D(BXWDW-arB1LpH~<+Rp&#g9G54vKE}uuH7=n z*TgkEHBkXQPu+kk5I?Ys8n8?xp3wG?gWg#f%~TAe#osto20ma5Sh7xYmCTIYxWm(@ zPjP#9s{#{qQDY@X$cUKJgcy^0{DsBf14&+#6C7JUjg6Z+N`&%IgRrXx?Q6G1PO6h113Qr0s)azwaNrPcPm7+;S^R zpEu5igYQ5FMwvg%Ae9m)U++!m&@xC*Pfzj3fBaqiVGDwP`1kn6Z~d<3-z;?q>^=@a z@exCIzfaH@*#>&ss0@nRy;}Ij46$6G&dV{oaf44jeW+1US*w2j=YJj-r}yO9Ga+Sh z02ph*c@MaR?PiN7kDuV(ci+QXZ@-049zMiww-cR+KvhlEKzJ#I!$<23=PZWgK0B#? zuC*BrToTD%n;BN1{)zijQA`HxoJ9md?H_y+%u4{47bd4bpy1ql_9HMjJp~tS5n&UGy`JT#TNNTX8 zB+gW$cO%AW5^$JA8GqVsBoaFc%XQrBu;ZPk znmGjDORZ}+=sfjsK8U^(p*)*@7;t`mhKu_bi1`J04-6{@=L7?mI`p&>=Z2QDn&VE= zapzGT+=4|7)Xs5IXK2>rXUuby>K!Q|%~{$r%^0T<<2Y#vygQ8Jh;iH@NFJ7lqXCI0 zxC}TBDkkM6XSIMIUOok!;esfCq;2xmoks9wFwvqo_pYsniT zgb^{b7(W{c7m2UahcRiR$jKp0Qf3 z;CiXg8+pd<-4@%pMM@F7q@7OCD1y*z6I9JOI;AQk?6$z&2AF0bT3I5C_yQF*k^Vg5 zFgHhf$uYDw)S|}io_7SP7yvf!C#lekMSvZkVrEowp`DXxM$QrJNrlE7p!JAtvrNfq z;7OEBiX-PmWPr2$&1#$)<4M<|{GB52O_${8$_IZ$uopC4S4wzUO0V+)6NS$PmXYUDp-)Ze?{mc;< zlG`QGT`ReuQ_eQaMvc-+3FNGzd)YQaf_IEGGoC)V!W+|%MdU9g{MK)L6R*AYCCOD* zBd8k4W*R;p{2ugY^V*N{?t9Yf-^b5GCY@u#NlIDWe~IZU^}jokHNk2q5;NAT75>-% z?OXU?{^vg^-}&(m{tmzXTfZxYm2(I4$ew$dZw3sH0eY$ibBUZkr=MD<*75fVUFd`X z6eAvg{+Z0ZED_SLy#8gJo}R(`9-cgAtuF|cGDqVy;px*$y#N0DckP3YhW9eHp6bH=d^&&JFbt;RxYv%LR^ zxlq;#af-OSyu>^2Jiw2B_(ME+=WSd+y((f~bJB=GQzGyA;FrpHEo+)1aTx2fan8Yo zP942fWXi@Gh5_r<3VlCl9%(@5J%SVJrq}xbbbd7J zJsRM!e3^nS%HCR?xLoL%;L4&w1FX0RZ^^4oPtpc8pml!@Q&Z(@)y8|wL31aa)95>^-6nH0 ztDsYiQBs3i0Ibim1|(?NHUq#^pMM3whYzEqgtY=a445d2G0zClw28WhRe)(svgP|k zvd=qmFa{Ht3zax(J>aalm#ih*%ue;*gIS^i+3OtDebs^%u65Svo^PuY>1HlRxB}`k zxM(RHj8mb)$w($`J+b6yn z0aPYLag=9PU~Ke!iIk4B0K{pW)X69SbKGuld;1JGH@CREGdl8!okox?znLJxGf%Fl zReKeQ>$(8O3?DLl&*(bB&CykUY0!yIi|()86^YWI+M_ z`-Y;ZFRSt>8{p8AR;XC7oqPs-&8rflZi?mD@}%Lilz)gRApoV^3iS7VV>#tYOE1^d z#CVBPSe_Y>bB`D!x;P{EJt%3Z0i~oGF|8RD@}s`_l4Wi&VIxL{|H|^r<-- z%&vDvf6+1LwZ1H&C>CcXBuzUa0uV$6`oH<=FX1b%{t{NhDS{i|Ng_3yyF0w`&JXbJ zyALp>8BYD#0t8c`L)Yh4wCBXZ(KOfc^9^%~fK4;zv~6zDKm)#Qbg^B!TjRn$UFH*3 z%G2}v-Zo;}{LGUdqtxQenji)`doGI4;#|!!;_2m6 zy!G~5_`&zTk9Qxui<_Hkt-Ic&%y2C^WKQA5b<8+-I0V4ucVoNgyl!d2q)uA}xps^J zstS^U6dCgrG5Uxu5QbjMc*TU(Dj}r-DF)SzkRN6u%FXz81lZmErE-VpzQt(*p$ zEt=apBI^<@Vn4Ok?ZRQX_Y(T4j)FZVxd3xp{}k99adI#kMg0P(mdCVA1-0iF@5xzg z-PidEhSjVEJIVRT?r6=bZ?VN3|S6hR{F{GLpraBEZ)+IHh?qx()Ct4$Z zWP7;GA+gAS?L5P8H<)JVMlR&+Rqztt~&3*N_Au}%a_-=WAY7UbTVY^0@bR$WXv563OYvhMp|3jJxqVe zP!@s4Y1LU-?I5#tTjhTRxh!i+3D}f*CpRpmwxDAPx&-OkB%NC32Nr!vwFH$p7lM9L zt|yGClbj@C8dXrrY9Y@NyWI}Yo;}0u?K3=kCjaj4w%Ba9nC7VKO(%f2vCT|(B6I;m z-wCT>=&@S&!e&SlHoIp?h=_4Q-}mT(MS_>?!Vna*d5;iSa_yBCUiS)1g-D1|#j&DA z$1`Gz7{?jYI3i9vWuHz6^F){@0&$NtGv<-;>;|~GN|+}?W-rOij?1bi29Qh`qXLCy zTs!A6^aDZ{B%%laiNxD&14BWZsc;(AR+9Tg`Bf&6QmBJ^$M;uC1Di4*5FF5Tz)3j8 z#l;0)IJ=Kw7&LFtgS~hYInS6>Oe4mG-7MVuDUG6-ri0e^K-UW$&N+u*2J@UTZxhBH zFpWT-ahR{$uKau8x4eC@@S_Z3;s#q72uAbsXS|ph$rb?pJ9Cr;TxlCZ2Q-y5(v2~f z3ArCJ5dOUwKiMTjA}uu}gRKj`dfBXv&go#~#$%UNNG24ZEFL_d3v#dXoY1MtDXTHU zjq%9LLUo#BEdah>!U0$)u-f=>wm9pM!Ege&yHjbFcm~hJFR_q%e4J4xfDTDIP!h6z`@7*lrm8 zDgjO@I1rGQG@4vdumRcSurSbTzqb)z8%p+AU0HCJ2CFDQ>w8=cm-aeTF2;s7%i`=B z1;}!|u?DPeux%W=IT)4N+C`A)YVd?%CE!F954F&{c1EouSleZeAwc^K86I^LvS;j^ zMCXlFV$LWE0LP5m%cpo}`Vo3&oClAK5b)~DufjWzIRkkbrEFZ^A4Dp?2=E>|?jW-I zoO2oIC=nX%teQ1Q&p9Xb2pI*=8I3H!a*#YaoS)sp|NbBT4FC3z{$=^@n?L#o{OZ?! z8!n0ZKAETf*!?vIgGKGyXjJ>E&#N(dxl)#y_vrQw;Ii*}RfwPCj3=Lej%Uwq@$p9= zqwfa<-$^@dt%0O*5CeD5?r?c2bz;5uGQM=5t2tU+gkyjVWQQeYvr-=(zT!eW-a9&C%rWrXUc$NS_W>z|Sr*zS}fgW7X z*8lc>9V5<*E$Tvtu9qC|ei&5brvqHjIbm~&oBHOm;bbtzc>?b4Fnej2Q~PKNgdxs2 z%>#zjfGz}4E{5E*L=$rnV5)12JjX(o)!biuCaw8s&qCp}_NUB6856eFp)9cCZm5pE z(l!7_HwJSBzyyE^u7GAcr|mwCF=CDy<^vnf>AW+%P;5w;xgqH+&Z!8LW3VHz+GZxw zX^J3K$55cJ2HL6Rk7B&^IU&tCy#sDjDaZ>1kzxunMAfkSYTww{#rXR;n}li7xF+>`A>sjTRrVoLc7!Nb0Pfo(x#8*SL3bfqVDv;bf4)%dt>-l$hW>=2=9w=9saY zfN{(i=Y(-&OgaW#0EQtUbPyVo-Crh*JESZ~8 z&VA4$G;%I`zg;RpRqntD0j0!IYfxrpI4ga?TxiSt^bCty$nm*`-Ssxx5;6Nmt(~&~ zVwxfKO&dnQ5knC`$>{;AZIu!uMv0EZq?Cj&co{&c^zFlINuOv=OcT|04h8r+sqrns z)4ARcL!v-0yznBv`qi)E{=Jvb_XAel30A`z_s(9x3-?~cX@5^@i6UUVK0)vuPS&>= zhBb)1{ zodH!^T-4}k`+eGeZU%wPYca|k`c90B(2E*l=%o%~=*6=*=UJ&ZcT#>JEo-G7VWSpM z9HU&jsB#xWM?tWrAhZsH;N`vX*$tk2^gbTF`wE`iJHtK4xPNgEJ`9+%14k91a9JHp zvXSh!|BI-;i~jo=uje0QwPc?UJ{H%8q$+UN=`);>(hLG{vOdEf{~zDMAO27OLplEK zH@}Zx`PJV6IKy`uN&NpQd($q-lH)q?n!CUEV#&;^Ua*6J1|$HEbSRES=V*SytY79F z4oPu--;f}OB1I4+H9tZU&}ej{8|Wq)XrPy>t}Qbn-s0{yAI!|%Uu0C13LrZxGb7&O z&)wXv*|lpLsRmVg-5UJLb(y1OR;vOiy%uvYnoD2x@m96jn!&PcmMjLLUJ)n*eeTQi};j_n&@$+|nh9AH2Cf1dz)rPlOxQiA*A9De|1{ltQ6mnm-mv8~i=YEz2CNDW43>&w4 z+)Hm-&pawNx4oXa-ahA8?J?T9#S$Qz#t~Rlbyw>KDM>j^)^?UD)^-X8;#Nnt=iY!F zpgu|o)Jq4GVHgm4VLEnwC*>GU)>KluX;Od2H*=4aDwb6>9)Qp_Q^b-ooFgonMWYZA zf=A*E2g!muA|$F{vn}-^=RmqY%m0Nz!1AzaLJBsQWDm9$F(~!7?eo)a6eTDKm{3$1 zL$!In4(w{)<)TDgrX^O4gluZWY4y1h_-XYlh?-a-$>&%y1Cf%*XFB~1v>Zfz7*fnp zyI44Q_{vyp=U@5Ktgxj^bRJL<31EE-m!IYRjisPEmI5{#J%%jhRC&ot@fMLRM>1|c zOX(qdNQ*fKaXiHkl;_0+y)V5;h=)~~fwGoM*qW(%wg6i;x&+mQ+0qXIKJ?P6=;i^I zMO!Il*$;e>WM@!q1E;}A?**_jxQJ9G6{e{P7k!4D5EDST>H^p`&kNvZkKm~=E(~u1 zT6^rI->`EY)Y6n8euJkB?>cZ_3^WKC;o}blt7o&&m#a} zobK@c`|snIzxuiKL@c!efHl6C2_xxv=LNV1AJBykRCxLhF_P34CuuR1a*`V+LLd(x zIsgiUD6eYv+ByvYLU(GIS;GKaUk$jvejx1$x-Fb@g%*}{Q)3eXp&+!fydZ**S-w&v zEQ{9jMp@DGq@p`6!6Av01t2FDh38nt)OL~e%jT#(S+y}HhMO`M3VDkiRyg7uK(o?0 z8X6~{#r|ABYoE6ay(gtPJ1LG&Im0J$+FQq@W`EbWVrqv{LtG7=y%Ge(1_11;fh&>u zmS&~B&N2g>RN_2qAJ`a60e@{CUMVn{^f;MBbvtR_uO>p*UYAqAcK&Fpp_ND(UwBU$ ze+9tgozygViRLB}C)#RBXUdpPBTk1ScKr=H*TeN4x^9EcZ;%rqCPwfbdOt{`a2=Bn zdi31}o}Bb7btp!+I#+dmtO6Zs8(Tcu;#hK;B_I@PRt;1r-44FAixGgk-Y|(-fS!Vv zYUZ1=mAf!k~m6{9T^)G`uX*I~2U;QHnYS2tJK?sf>BmwGJ+#FTJ6-Xbj#BeX^^ z<@NJw?P~KXMn0~AaiNMgA7g!vL_nv%AHeA2jQQzfJpJV_@EAb%<*#7>>KEbqJr*P+ zM9I2o55jt{)v>(i-gztR!-+)tw3%)p7ZBSpFD=v%o!-b%LQMXF=qIK?> zC7SOXC=gt>NHCT28yEnQij4T`%rs88w0vvnfcZXlRH30(?5ecpVAdd@*JGkN9?;T( zELg!B!Qz|?jWenJBfboN|Kz z+DVHI+`B4$RxitDUjV;0-=!BPi{Rw4ASSIvA;L1xc=Gr$-hKNW{NzV(;urt;k2v1m zA!G+8%^XoP9{_Poo9Daw0+q~7ai)rc-R^Uh9Ywm?irsW-Yn!=h3Vbjy%oP9{kR*K` zEYQP5DxDVrtl%ADQv>XPMp#Ma;>zxx&r4euO*vru6iLyi0e`k@PZ<_SIuCeTOrwsS z9s?-rr!_?~+YD55dB48BxfnEo!Lv_a44lY>V{>qt`IB>&dBd~xdR``B7izmV5prEX zRu@xh^zQ?Hl;2i^R{SZ*UKun4-1WU^QgofzesbW%092)Uu|U5D=%6e%ZSzOgB5j_L z<{5AqAp?mB*>^~OK@LIdgc(dpD86Msu`&(oilG2rLN=)WMOE8p&pK~4`wJ6RX~xr*d&SAT4#Goe+>Ikfs2xno zUY}XowUtc14w+_G7zD?5PL^wGL=6EH0BkfxyPuWTivnO{vM{7nuiO}O$>y-)B1r~$ z@n1V&v$Z*6HnLNSvb9=7!3g%OV~hwY)Yi7wlb1QUX6Ni$EEy*6lOT%iA5@1_`vW_d zg!x3F+@Fn)D4;i3Rqro6`QV7I1HQaX7~&pRc!kqI{)A+C1ef4s)7xEjR_a~nO&XaDW@W|1E5f#3m|F$lr^x9aTakdD1AZc z>elY0W!G7gd2_bySoMC^UIIC{T6~;yX(PoDr#3gFXak<+>yp#W%&XF0N`+FDGcZoT z#~(e$;qHV!{2I;&Z2AYdzPiC{4_?Fd)fFCIzk&x3UcuG&3LykcH0kc%UY#o>Y^(u(a ztTS6bb}(jHkG%t~yB;^g06)*T`{ZMMG|k8_Uf_%0Sa9lXLmA+tB*p^1HM0lIDHu8}sW$bV=2bUp6=IZ(_Db z#3)L>*1iI|myGj_k3aqdKmEy1@Z&drj1S)bM;s1!@Cfu-q zSbq71aD|>TyR5FXP{XbE*@DRo zn-`k(Bqzxs-E(9;>6y8BJ32AkzG(s{n4Lt z!?JxB{UU0UAM}x zQzLHURGcbjAftm&q}yynOEFykP6oBj=(MlQ0!AxakO1!yjHTcrmL-*1(s2Y% zrvu`AKuSQM-=GUUhOS5O9X9CRjN8Kt+#L=$jT53~dCAKhw%Y4_a&RD&1NC&RGIXC4i>u&FMibSw2V(r3vzkhEeATfsr-7JCmcm|Qr!uNZ9ikqt2zDmK6_6+V*RS+3T@!K>JC^SUHlhgk)?7zJ`2{F*U!xwCnC*! zW^fjoJ(I(BE9aN2mx!qr@KoA%sjsS3ezzp#nBW(wMZ7(pkYdDk7N#4Y4q#^7++3sk z>Q}IH9-sl-1+WW9!vgO;G9`G1_)DrjOr(Kia)1J10|8!voui=b0;MyDDpmm&X9mN>(riD_ihOkxN~|T@aSgcDxdEGZjB0%y{cx01)W8UMMc5LK(&`~(f#7Q?O+Ka zl)b73uVJg1>w7cO8Vhhn_*cL44eWP&eCu1ki{JX(@!3Dhb;8hSg zWJpux({vQM>=etUFB5|?O$(NBf)Bo)JSnwxv0`Moxab&t&vlSWbk1o%Q0)Phmr}E9 z&)a*c(d&XJjxlo))ymokI*&DN7Tu7NKf^ z>AA`?oqe5Wf9*JyIB!3z&uyhh+WHFXSZj-dc z+r-HX?As+80A}cZKniXR4=4bZ4X83Lz_n#ny>1l7N9P^(n+>jZJ8VJ+;*2znIKFs_ zr=RxlLkA9ot1o;JZgYhU5=CW4=%_D-z8#bEf1d+}`wrpd*ZJq~IqqDYx_?fP!suBZ z0m;^EvP|&q9teKtr~d`t{g?k%N-6AGn&Ua$oZ4SnCdXP~pk1#TY*`D{*inTEVAM~W zi>#nT=H8j}e!&61|Ed7D1wZw8pYM#X&R4*1T?cl3^6$o;HYGkXRz~X=_R}Ts`!|34 zcUV;Czn2F5ssQP~#}CoB{_f)>le?V$4X1;ho2Rx5sO*y@m%jSJ-R@^g#s8 zI47jIAjJi9N{BgQi3!JX!f9EMiAu>>%~lJL$eN9uC-L1R*yrKkG>F+~eH0I!i%`}2 zUi21iEMaD5ZGS4;qn#h-Pw2Isy`c@zAsc|H&$2!V+Ysw{R_E1gZZrILm5FmfHkK(g z0FQDHHVh4rY38)|zUbV9&=m%V*^8u#x&pit;u7IcGvX4Fj|;}}gyq>C=5fM&IADw; z(sDpY0rcQCe4*O`*H`fU4td+dc>(X)M<^MP6ynO__+YPnmKCG9iZ4DY9D)f&f$;#&p*V~)fK+U2f>KgOXVLXkJ4qX@U{CKN1!N0)qcm(GW$LS;y+hQXkjxNHr+3sd(#F;S2MKSHAiUxZRDwwHQHg@BxLIX7^s^{Fza{^m-W>{(MkN5GrQP zv{7SR$Vv2!&yNptM$ps*vz9Lqw%aZK?Em>b{{8=5>Co@I^`G(G-~BgOv=?J5iq~de zf$Ch^^`B?Q@86TrD=*M<2`Kd>lr@~X`^;?=r$tl5;!_VG%ocZIVB|4+O``0{i9egXUz#dgik3HV(KXaGAbbHv9VeTp}K@+N-#qc`xuFF(LI zAK~HQ(dqV=OTf}xqiQ?vpVyWf%vqy$-styc(`E&zL}F{Q6Q|N9Fj-wn3H)%eop!u7 zizY884k~0bPcdV{jN8Kj+ZO|_A6(()<{Eq6!-XI{V~e1S+?$nhEK9^`oN$_FEIA{S z1R8TD3FspsC!O^%OYh8i7RQ=9csAC?{XMpV!ps7iu9JG-e(15??Qng4jqP@ezLUPt z4E0-8lOm;vm@-n#(w-#&6f+PrXo_%CLO*5jlt8Bu3tk{$foFm{>=8~2x>3I7C4m;v zWbg{Ci5ST(ASdS*KT2DnD6sMBmwAGUm8LRAWiQ|+`>z1FE@fL+>kLaB>*`Z5GZL@G zC<`B>0kZWlR7L0PVcTBdqEAVuf>^YuwI#wtLMmcq-S}%-doYYA`^uv8HNVed$ti(d>og_&H1aD+B0kt@GHf z5~co0lN#3DMTVZrW!2ztT|Z{)gdM2M$PXFrm5%VuvkBB%|xR6OdlO za;0jQ@;tY|f+s-L8X{w-=`}l@%UpC3EVyOwF`u^H`?-Az|L))YPv}C2(7h^Dvbd3G zQ!h^E_GW{xeEBPwc!qZ#Pwt-K=IREU%@yW(#^LY+zxc%mc>44+#6=?$35YhxI;%W% zBk2s3$qjZvl)F++;3Z3aaFkxanOXZa#R4FSG^3;c4k|X2VnU>d$dYAT#tBP|phTF$ zgf1;Qc?c;*5HZGaM2t)669v@c+rNo{m;vGUqB_it(_E5foqU%zes&P0`|7+*u9=@y z&sU-@Hg4*y8^u|Sti1nTugGSd1&e;WdMs{mrfqP; zR^o*(A2T!h=MIrZX=T6gLS<@dyw6|uyPPvPYCE-gmJ3#?e^N!pei%wkzsM>jSaT&J z$&@?8T-3xBve5C1$Q9S`t+rA1fL7nkj!J~q%Vv<4i0BtkVo*%TJY!lWj8C6{KK&G5 zx;x-o6!7}jJJ4na$zU%4F}O(lyW&t$7R#czM-_raXu!-e&=x+ZPIa*y(|x*3RsiEVx|A95;c2}QVQ z{aQzc7}j60{;3@o$wl9`3C%&xYyane|`_^phT-yey(oaI>7F%?%$zpE`5m> zeSU6n;!N}^7i|a;FeFeWoW>a+ee?<5e)Da-@xveEgJ1mu$K`;ad=`ea;gR)IGlIzw z(JHWF>?S3toIMLd%V@DZ5KUytf_cOwbA=oF9-yEY>-oBxm(+aM+>{0Y!5L|Z;6uXG z;Lvvg1V)Strg_AEw?#kn7=|9hrbp-{py@zDk=|}_#lnP2EaIY)Nzc-Ecv_^znJVRW zN3XT8a(|3m+Ur!OTE}IDSuW2fIgGM4^zLhLPtK9K&O2ut)7i+h!8&kVqqTjXUatkc zbse^|QG8y9-~*_WzVX>RgdD)BvN^=`r+apwzUseS*I~cgVY}OD+oMi0^L-ERg%Z6) zDea3<6nvwy50kd^Apij$IY)#HWG3{53Bd4>de#m=pMfqjd}g?qK`{Z^3M{9L>@$cM zks~Nq8%5+5REnbz6nF%uHm+fR*c#5<*7Oh;!IcCnY{)A)ip4RAO6D@=zO+s&)+ z&f&9XpJACDZf|dqW>JeGvc8)rwTaM7&Cok+HX9MhVlFqGmWXklF{fBWjyQ{8R<>+$ zbNyyt9Wfkd#5BWr!B$5!FA=PiX+O?59Y);V9;8-S>Deh~%yUGFLeq9Sc}iVZmMqY2 zAF$nQz|movCPZzrydYwpdBvhzO|CN#p#EP4zV@Z}WP5;}zEC!S+E479l}D?jO95%d zV9txs$j5QQk!2EYAO?KX?XcZ!k%t6!RTb5HRZ3-m{e1`hUM9+F-x{Yjb1w4#B}>e8 zA#_a*GT=(vjTmEb?z}3S#$`crQVS)E>71%ug-9;F+B&y3!d5nG-bUKK%@bEcHF?RLKvGb7884nh7RIpd&-( zeCectI`_@4m&*l2EDO3WyhOac>!dk3iI55aus+wUD%+H^g8XygtIID_`fm*}*<{WP zHf8rLh_lTIpFgj1FIk;19S`S)g6qA*5PGG`7k3RYEm)Qbc||LLDyi!Glq#K)3fk#d zS@ze~VY9ERYbcsP)Z+FbV?KETYJ)WH=`27R;{R2Gs!T|JL zp%9x9bam8Lj$S)1pO@Kv89;s+_-!M;urbgb(!iYlx+%eEBmL4p(;^7c3Xibc@A17q z|2zEgAN}v;(C@wbBmB;He;+Ak6&$Qasbs@4H*2`sl5@KvQ?fcI=5)w=fOD*68+@Ht z^}Qy3W%cmXq?zQl?EI|i(Cq?~S5a$La9n9%HP|U2qXETa)b9Jhkd^LX4p+(<&H+Ea z0Dk}D-~9tp5*l?d;T^5hZ^5qxE$gcxv$gkQ^?rz}^PFF2R=WT_>bWwkdHZW>6I8TE9d2Qt)FLy1U#pda6Fyx;C+=Mgv8du(@GDPP(Q=my!h9T9@_2%&>lT?tPF&y22IHFdUPj-3y!WhIMk zQYWTm2-^6Sxh5OY%6>RUpb+3mG7@BazRgv$`R%f)4;9=1W9Jvd&?-6=|nr?Jh-sx}Y@xT5gdGp;mrZ#L|ntdh(xy@W)89$l&&6-F1867us z66`!w0dO6=Vi~F^=*o$c_vL1;+67TN-l+4^#0%|t)DPBkmJ&JRU)wV@U#s;)OF%&G zQ|zXlGob~*7Pu$tO>Fg|g_bD$d)>d+Y^RoWMUCI-)V>>F_FnCCv!Bx0zr}u=aI1;C zB?Z)8Gt`ahHmVIG2ZZCO8A>ebWJ~~n=%YkSdcBz_7wWmg)%F2ie_%$+;o;S*2svPy zXOLr|B?pwKK=42}h^W?fe}(O4E9XcNY1Yi_D9VpZj3_0RESs?H%QX{fAq!`^$zKrKrnqymjv%Co<|-r#rt#dq+HZ+-*4 z+hAT6Ad1s+Hy-fuCm-V%AN>-yw+DOvuoCsun1%BewMO40YWCPRlaLjF84Zh2J1rOn zWCcGOB*-k|q-yzvQakHDhutw6rsnVMh z&^4ki?L@6@B_z5Ny!45-O)ql>WkO2w{=^w@Qr8rMC@s2_;8~1~2#DVY!RCydze;0u z-wHfg-9iQ5o`lM5(H16i#_fKp>yl!^bewRyJHhb+=j1-7IboU>q{S%w85}FcNaih} z3jv)rfsRokyi3ed>soDUv6V)BTg@S}!Rz1F@dqh=E;K=a4Dvw@Ma|R^nK4munS8eS zs0_VPidMjpQGq2< zCjhcX2@tI4&us?y?AY2850QW=Cp2{`~Lphkx|HmG}Pqogd*_-~K)1yr6>!#MF7b-iQk*2Ee)P0T124)M2vQRY$88 z+_0OuRNi3XS;SQkX%)C@ekY%=eS966_fTJ%YrsY3Y`z$8W2Cy_Qr&#(b+H~VO7KV9 z(EaS)HTeCjzx@Hc^P;2*Ds7H@2$Jp4;MvPs4&8srJ(cIH0PXVxtz21;&A63d#o5u% zf*1z!>wV{Y;5VjJvM|TH5x@H2L%j2ock$+%Z{k-U{sO0X3kOCAFY5;)xT9y1V1^oH zE&>P^^)Kj6K}eZM@?T{eiGx(dfuvXKeXCm93aOWzxWEtT&uL&6CQ(!OKNhbXC>bX% zUkpOZjA@>6cRauc4Kq5y=x~&d3}wQ%2_;7=zG$$z$vY zcf8<^BX%w$GNWT{?~_EWp5Qb)Rw(oU~GIL>5HQq+Cfvo366PzgT zHXi^ettZzR$|hrZ4)mI9v}?8uACb)oJ#Xo2TYukzZ;Naco0?6ev+iN_*_!<`|J?K` z)Q&bIQ3J8+Xj{uq`>(k_8Y!;;n%BXV5^PsntL>hkds6$kG9EHGe0`#mi9c(K`hxw`}X?2{WZdsMs)yE}FTGr^LZC0y|09&7mO)J+^95Qm^;N%2pET4pOkuZVCVa{11 z>5$B#ON8Eapd7%_q3;R3@8NriPKN;WeTQK~*lu^&UhUw$Wb~$KLINSi1lLL5M)I?a zr7CsWL{4BVv4Y4h09_CCJ<#_a{jh;^4)X-0yc7zyVl*I&xRrq74A*7kF2M!A8en@= zrULB}5M03iYLC}meHGW62LMF$sPB6`A8!%5fTzc&nCB7mBCRiyJ*38FH_GGY%dMl5 zz^WJ@PWrZ4Ki%ZGWYSH^78wPA@;V__CODmq1#=D7#9-7Nt-D52fhqfp0!P=<HGUJ7_>&uNi*CX#-=d97YrBJ64XIRHhR zrag|(G-ZC*7A}@CXsIU3EzktEEt!}iZf|d~ED7Epwf5?W@pQyEKf@AdER#egNk8ui z=mKFFI_&p5Z2AsnV3uXU@o>WNxX5Og>bW(cT4=mBcW^e3f|HggUDu14f(xLwfLNb> zW@ulzYORfa?u<4=b)(|MV8mvFTfZuZxS#D^8L-u}TAON%B$M8lwOPoVYh;yDIS=$c zH0ffu2kZYS&%KUKITK?Ieo_Bj){Cy4Ouz)0<6}-z;?KIivIN(r1Q11BEhCa~ zbph|5)%^a|_x}#T2gD?5ix#Z4F90f%$;~EX%BJofHjr$;U)f74Ss`2Jw%6L<-Mx(V zy<-CFmNICbmmF1(jnb>VfZs)FiaFzWJmNPW{02XHr^j4rrKvv*eTJPE1wo(bSSxd1kZS-=7RR91W07*naQ~=a_QOGql-=Zei-bJ=O z!c=X!;5i~_W~XtrDVO6HAV?69UZ{9A_{*9BoW=#GaKxeS&~+X@h$v_RV?$DFnUerp zPad8U5TgV%y%$j=h!~Fd3BmVLYUDgZ=h6EPCcK!^6<&GeVX48M<{5|65qGz@I2@0d zrWw;XV;o0}(I&D_*BCZi%+ri8O<0y0i6sFNGvJHB z9mC2G%m?y89Pr(SFw9$|zK7cmprJ>%MD*hxyPV+S4CfrSy8(E($J9HFodXBL~;lPop}a1{;V_=-VZe?bJVL?4?`T%M2tgr6a4XFdYfx2(})G=7bm*C4%F;(b62t3VJQYHro5O?Un5_cK=d>#N`^wF{vJtdtlwX3a>@!-`nSYd(Y zIhh}}-g7Nb+H`xdmx5sFU*C?WI#*^3>JlrTvx_UjyX1;5l8VhVx^uPPvc{>*UuFh7 zhfH#xnYbin#r8^hrdKC$l}UyIU`hYii3nCDF#@>MB??6`rdgcwIipJs)3m@x!o%Sj zUwiGhFkjE`y~xE=kf=6%l#3Xms7epw4Cb7KzLll_Y|4b*5e6DmHCAVwUv#iU${rLE zx(@rDP*b{IsFH9SFf(qSM|}2}@SG1|%orEQ18OPRs1w0MqQ8>0;sQ1-tC|dX z&hSaIq&b6Qs^VQvfstjm?D!2ZBAfI!4{hUS)`@5l5?AK}P-;2ly){E_fY>60wxEe4 z0)(a~fJ!CZi}PxZhb!3&21~E#n6S*Vv=7jzcT5c>i5gYG41h8cuNQe$BDKhSLyyt{ zG4N|Zt9_M6r{iX9K@n_2ZA*jA8VHr!@}nh9;rVA~V0wk5diG`HD5sDObh)I-$T zPDh1CBhBq4(r%lw^FUw?iWwNr0LNMqAak{TC7cc7g`d^O07%xBJZ&M2dNg2~f#`r` zhB&Gn5Gi9$3y$Lvbi73-#um0IHsb(*9K$lfpPR|02GF*9&{=@!Jkq{?kI+n+Gurk@ zZP2fEjAZAsk_ef3r6yfJ7o$XWw%ZN<{Cj_oKWacQ0KE6^kMXVV{A+Z83_h7~g;OBB zzGr4G;(P7OnWIWnHphl!;nP13eB({aSFe)$33{^6T=>&-Xu(Qkf( zQ@RBqB7m%^2cW_=38Df`Nt!{pV9iCI?K=n{gQpEwL1)~7%(;P zS6l5=r`4S2tn0b5J1p?(3cymktxk!Br6fR*FfWX8bT}N3a6tmGnau}FNO?f+Gy25n zJcCV4A`2@8ngJ#fW$A?y9BJlL#nNhzVF^z6eXrw|@rsI$E-@l55%av@bQ*Cu9B@1x zF;A0p0XdDB=2?R0Y<*beyVR8$iwdiGZ+6oL;=Wtdf?=DFXy!Aw?}T~Z)PM%@FH}*t zsOpjg9X*vkxG1)-p{0`rs%sBs3D$QQRBR%IAT^sQA!Uc7JJmIz!g@~CyN7PTez(KJ z?G=WhgNxc0X_{sIFAEqME=7QJe{l}o;1IT3!3QdNRY#h8k@TBt^7Pd*2?O*3i@=s4KFY$FMyzdwR>J;1+z_QM*Acy6t*t| zz;)u-JT$>lJ7!@Ck}+^_Zw}fVr7VdoryW=fEb+PTu71A+3zYV3*GdGCuy+WiharI4 zT6(Tdt-%upfG9$?>R>ojr9K5ER!9d1GJzwIrU)#Iz#gC;Zs_pMuYL<#emAK|kn zkFe`KHk%E0yAGSp2Fc4N;ky~TYlaJwJxh%yGD(^VR<5l&PZc1i@;CW8 zmy9*28ro7P$E+D&mR`fz=>{q-19D8r>Llfqsv@}6lC~51!q@prz*R%7P+RrVteQ3Z z^>qvZlv-SBf(byzcH86X>IQ^8a%5zlBv|1VeBt$1@$GMa8{hcmH*tM+gV1%7y#N5t zSe6-2o_vB&AAN%7PoKa)2M(tbcH2SPfsCvzVb*h|_!Fek`H&i|uItcs9s0h<5H<+D zYvzqQbR_k(255`(z^-g?bsSr|q&#Ea3huBuJys)9gAmLTvNU(R*c902RHKr0UL+6+ zOCWTe8Z-HXf!~w_z-1i(${EO9DdQ|buA-I1bv=|I#-&HEn`HTs#2!ceo=BA4J!H(q z7z;p704NZ0=ivqq*Ao~C^E_(3p0P~m?39uTru)_!c+faRI8XK|7s`>9hj(kjttqeXzJt@_}kH>?-28RtEG=&);-TNj>jVohdUJ#jhJJ^G|f1jMvUW#IWF4LD=AyVhSst#HQT7Ose;gE z4z2o?o8w;QUv7Ua;DIzkY4zOB%f986+HU>;h^l{PQHTaa6A2q~UKY4{M(J9iS{@bX zamkii4Jzd6@aM3|9>zM_3b8UII#E5Y`Vwy&rrb(XpGGm@*DG%ei zhr>yrpznLNRVrfIb?CYteQ%|1PBWmE32l8iwbvGou#LR_pdim_OvV1!?sb*nXMdHl zI>7WzK$dB40`z6gV&$*O+()@KvoEU`qoCcQJ-}41U+&RtM6>@J2#2s#)~p=TztieD zl?h(PNRN*?j^5cBWSnaj-1dJu`)rjwD5I7tZWPcC8%kMn*c~Ld`%rv z84P9ytBk&fM@GhyBJz^qxrYxuh7b_GJm5>O{R<4kfb0p=G~qD6!0qiV9zXvj9zTAJ zCx?^Np3KtjV45e1gh40~qzkF*1ek8N0lWPUn_b3!x5ws+MT<r3NNQBy-6#j;9f) z@rb*-JKWwanC1hPI0^MMD?reilGKiTsH`fjaJ%0o0Aqb&Sov!~WV~ zyK%_<2FyJcbU2M8x*oE@k79h1evVm&xTQOv&y6w>fI=PaLqHcg_|ORuW&;blDNa$1 z(_|;tK2U%p_5#CQ_F(!+Tj|-iP7$*M7S3Y;vH zUm}cxz_8!#@b#~K4G$lD1)E_D?-||^Qa&Mb!p(yRxVgE(m%j8BY`0qkuepq6!Rd4a z(Spa1KgF}BPx0i*6P(5oj9h{jNdd51J*(zfmS6^^aaA)sl&bX9M zYVN#zFD>`f5%E-MX{#|Q5$IetXm0AB*1@|}_HVL^s4*)n(x5V1k*UaSF-8%0S`q^k;mIM00w^4bn?^Z zK^A(qM$xzpxX8YjorBAob@fK`gJdl%bEA%efUbmbn&7;tUS~v>){b$Bh(ko`BVyNq zLMH%Tfp2Y%B>_;=akq7C;K(IoLP@4hGM=3>wp>|*&I!O7Hba>+DMbau(xqdH3&wH8 z;qHjz@qlq0F-b~0 z&?PNG>DJ8uIF2|Rk9hX{DQ<6XaXcL{%|e4e9gp=n+CJzUx)8A0ZiV651$14&Fbvr3 zcDTB}!qxst|JJQC&4taA(!HnOW=R1HoJbxPRF-8kcl2{BfXE8g_1QAPvaJ?uSvSf- z0c74DcxPa0!27v5`F6bh?;wo(in0KM?x>l ztioDZGQ++EnT+l)bY}y=;?okCqt0z@;YhNs&s!K4`|TYLIcLmUX>T-)J*H0RNp7Bz zk}lpk7a=f3a@P_V0W~5tI94B+62kWWbjo6R|C7HwP(k zF}^ve!W=oRb;~9Daqn|y&T<6<6~wItp4Ona&^iim0{~LxT1E;P&M}f@(5VJ7vOZH6 z6HeoZ(@#?FuW4GI(4??@^gU8T!IF8To z{P``OJbjAiFPb2NT?L#R2%by>vCipsUA^pe>3yFMkk#?Xmp9&v zFIF(u9G_f(=|*H`zSh~)oe9m2} z_htdf&kHy(XJJC6n)%IhLYgDeX~J?i;r6r7@X3cC;_*knMxIB!_R1c8{{Yu}j|Zq{wclVf4CsRw-@u1L#g;1-rzT|)C7N=^G*5VXoN#vYb`tJ2f?>jgbN?_aeQOk5?5(bTPs+J!G z49PsGd#86E-ggLEJ8Pv#!)Als-WTUPMh(W#v-*Y;4o68$oQ|U~0ha~i>4a$(&~?5a zog3l83?q`CCvjN3lY)XC+W5jV1di&ko9bUY6QNEr%dxpEaJ52K^etSxYQIc17 zY~=eBwi|4Q4Z5y_*A3Ze8J-#Xn!T*S z51ILEUt(?CGQcJbc6o1OR%R>Kdq;idxg62lmW-DkPA`xf@OTzT)q{{Z40=ZvkU)E% zO;Fd?l$E2^zsZ+e*E(23`WMMp+x~bT{FZUxdJToa!wnm?oCzh+XX~*QqN*)Jt8cv? zb1F+r5-2+E?S7L{glNnC128dDi%Vo?kkwqo!F;qDH1@i7jE z1Lj#kZ-!DT(hO#XCzd)KC-oZS2svkrstOH~`ie+*h%v#35nbP->jfOn%ZS_C33s=^ z=?IJ`U_1h80k9|l1TX{vz{8*bc#r~Vn~2VPP>gCgvk0~{57B!d1b}+LbpQaBD!yQmu}@J1q)h5t4TkSJ zY`jBsL8)CLk}{4b#K?%LQfN7g3UmQf40x9MAQ}IFV70xZ%z$RW09hl4)>rm2NM>D7 zIb~#*k$eJWaYjq)BW|eAS+c)L8@-!?a4Ur6A(AbbNTR6BTJL1@Ru>@U;y~N)TJURs ztMmy4*5-_8W~(0}$N|Zh^(n!Oh$22Vo`6q2{uFn2NBrj3Pw>jaSMl1b5Ae#vhq$^P zkW$3yG~!pk`VjN{wnVzJMAUcNEgn92fMLTp9B+|Q(teEu?-K~Ih+cutz^^(m&S}7e zMC_vrU8!l43|Tc?wr}Ldz#158!EZG{t zM6@fQ@4ToaL+4(zw;44y=ZKgWq_jvKAvXb@^4|7y&<(ZjHARfB@wb}2MP3f;-plqG z+o0|E`d+7MqZur1EVLls*bvJSL71CsvjCDlOX>g$sGCR~BcP7)=Vgk|KX)lR+`OaS z%*%H7@@zF?Zdnz5yVIiJu9Lu3ObJB5uo>|G{^ftd|Mds|%j$6Nz4Hcs`@8=GLNI{a zf^~5Vm@eESa|w*eWwj3&+Ebg$!?GGr&UO8lHuWXC5=+6PJ zeU7;WkX6CbveshHB0?AN&f8~#SO4+*@UBBjGeESaJ$qL?jPqcK=|j}kC0wpsUhDd& z&wE*hxq>;m2b>M;mmnh3y=#*9Sr2Yu_T-qP72h%=%`?(?!hCm!>GnBjKH=sn;Aa0t zT<-#|_B&i%Z*X&Sh3l&=w%ZN5AX!rb1>W2E>bfSgbMkW}(aAVQU``2fNtnh7qtbWB zqtvj@r%}|8=Y)BVn3jwecSqbFM@)0XDJRS+sZ(ptW#i=D%Z9H9tk_-voRc_$VBN{o zt~Rvx7K9bss=@BEKQ>=6Mlr29L#2;(?wgwbq5#+l zYwC>B?a_4sA#}y(=(`U6(CaD_N5yKGb`XP9=kk`5+x$kx!hYTCY+`TbUYw~F>%5$kLXG%Q4+r->AXq;^8$4$)|IqmY|%`Zl#!VDm4P76 z3Yg0M*v@NnO8n})M5LS$7Xj|KhdVrf{v4k@d4fle9^u*3r#PNYm`2Uob5f0+b&qRD zD1JcB8OuCj%9Z&CK-dmlhwWyI{nZ{1A3Vf^2MbO7<~IAf zes6=t^iRfiDj8-C{+wGM^T~_^PDS5Ip)8-hH`n`Ffn)uTt3TEE0h$G-^0#uF5{PQE zY(N2%YD0-F2*-tCBF9fF(9VFAd;)OX`hyl+v>&|&2@DzA-rHaRr;?9_{V4M(oI4ve zqJZ+@uItL*<0O%V+uK|G>Q}$Q`|tfy`rv*;kK_EDRRiG>;-=Xv!| zeGs7Pdj;}c4-gP~5%KVBdRA7));Xo^@p|zYAht|%3xHQZwsC5`)|D7b!JOCCXByyJGs&9q z(FhUic(7-5y+_!3kS9cnV4V{o3#)(}umD&V;O?05{PqPNeR79~47D(?q855&GyIki-0luWQzYf~t zx5Lm4=tGZA>2F01a8;9H5j-&>Mnh`H(}EXfXKaHY1=Qw@l%P%{QYHtecB23Q*gc$Y z0ukeM#FMAM-E;>RB!gk{{!5J7o?}AFi-2E_01H9%zQ`<;v!t|V-1pTB__x51y-K$w z`?>j`ZH(uCFQ%T??_Zq{N{6;ub~W79p0l_D${?< zs|CbuaAVaYyS+b+*fLuH<_w%e=+NGE=sO2;v$jkD`fh{2{LB9jfA9zY^XfD2z4JqS z>pQ=X&T248HhamuIzzMTb7}pFwfHClcHvdU?EuRXt%b1aajlLU;1V#ZSU;h9h2ue6v^>zOhz&%&(@AGVu=ed%}C<}o<`6zV+g>Pzwio% zuk5ke4%luyHbaLl06sVsgJd8l%uAB~(RO-rYQq^g%aTL&Gq$0_w(sD!9dNxVS=AOJ~3K~#>Kk#1TsHG5bA9%{6y1@%_<*O*ZY zc(E!fgCKNKy;rB@Js=cjTk*wmM#@oZp~Zg3BwZl1yP*nY1qCR8Wc6)ckYw|7f{Tl= z%*Z3Ssz%MmEJ>scgapq3xd>}}lX8Y-xfqfWmhKRYQuE2F*lkdy-R3MA-#AMx@9A{H z@p#0G7ccPi*)u%)^iw=~{0O&)gKBYDjq`dS3%hPLV{ujjrL2jZOKINmDAf47!!53_ zu5opJjq9r`?Dx{=dbimk4;vL7Gk@N204)At0m~@PRXL`D zv})TgpKFz6Hb0iup`!|NFMOWsXPXa{@2xe+>PT?;-2YG6yER#o9A{#mM?_|xQ@8Hv z>A{WUidcerAVFZce?ii#Ry1;7BolZ4+EOOHEMXw9(5|4%yG$38$OQ?300GblVlkLY zS67`&X2!+!;O-HTr>Y0sGged8Rp(?z#??Rf&p)@unW zcDDQ4hx(vLhnb%39Ai^y^Qwc%F0JehB3*c;3K-TJ$NFFr1y>g@8HjiG*!A~y-W8Ve zOWpnL-VXg4NdO9h4?(Gs)W5f?ZlRV%;kq#$4+nho(TDiuFaHDX?>|CJ2_Js+Gkp5# zKf>p~^a{WB>z~KXd$)LVe~+L2azgMP>Ei=90jKpW(JsdrL%?2h2fP{-$&B9hD2Aj< zU@jP^guA;tynK19UZjBQn;TqTU)8AYIE-K>5omZ=@%Z?NkAD7$pZ@fxxc@`|l|&3P zQj!kK4oJQC?!p7)yhM(#Z-Cpo9d2HX*zI<3lSc;Qyqu780rMlw6E_TmVUS$El)We= z<{-JVc|gh;^EpY#8U;C_hMS21QX^1=p;TefX!r!7E2o4tMfgD|*xtM_nr{LV+o-dy z-Q)5l%DP#Lq8E(_JE^ss#rsmSDZ5FeE9Yh;iK1jXP`#>6+IREXQ#Z!U)C8{7Xtslt znNdPBqBcOb7_FKrHHFY5=KIZ{2fz03t@jr&dRsPCSx)dEWMq|3=SGDu*8ft5D@L&+ z)&)Q*NO{Kbbj0a&LW&uV0^WQ18aLN3@cRAFQS)yjmBPpAvOb-#hai+AaW3wrJ zZ~=^auw8202H`rz%NR4V3_A ztOgq!!e+jAXUP^Taldh*Ml&ygU-$M+FpTuQ_Ipd=+1_I7L=YRN<;@*WjNP=y&CP9{ z^C?BW&;atoQ?U6D1i$Yx4lcpk<$KK;W)HoIveNU{H50(f6)+6|Ql$-s5b&pe`aj{1 zE+WA{{_8)-Z~doVm!K6~Gvc*6vFUmT%S;i8@uV$|#Bt|k3fifBYwij$-lNo3FE6(ujAvS9KByW0`tc#Z45!!!=0wZi>r*6 zS0moLyTzyX54e5v79V~325*it&dZ9kNdF@1TWMg9y= z2q0{2ajUBe%XZd^0&`a{7{G3tu;1_GK6=IrJ$gl4Bi1!yo)?_YC!9_v&9jXaIIrs} zB`tHRPBB6Qxy7+bdFZs*I(fwcmI_bu7L>LBL zbF62b?B+V#^ZMOqHdpZ1EK<~c#Ga+Lv0kegq=d^e&Grnc)cDOacIRztqds8Q zPF4e}vLeu&(3^;Hx1O3+pl#KAyVm^bJaDk!RcCMVe?;GH94_`=Vej@}-Fyb7mjkMC zc7$m%VFUS9GH$oFAr{$q9v=_*+0TB4zyI0K@%MlK_xQWN{TV*`_!o%z1P0^rbdQhT z{1U%${!j3^&wUPGxVyy%pL-wgfAJ1q`qHoA!%x11H*fCo$=jdf!w)~iyncfH{z^(2 zg@BTUo|K|QjgO~Cq{yP)>;OLycDpOw-R>Y#Ga;n~DMx)yS2y9yXcmz~*@l5IOdh+d3H$3S4C9FG5@K1w z>#QPTGfH92r)(laUN<>}0U_+bG@;~z-JUU?cUVtC3rdSnfsNJ%CZr6>-DDv>ST1oc z8I;e6^MdR|EpjZzo0eSdxJ0BR0M??vAO);Iosa~h1qdD0Jhxy{%8k^7wg|m|<-U(P zN}RrO$skq1CN0m?0Eul_CI}-NxFoHk(f*W<7h}}C&z9}8iBfLXLosNgC7u7`FZeC2wX~F zxTZ#^A1dk@6d!>YB+jUWeg8>s)s3U|mGr*6#lZEiu(03p^3F-kN(i;D8f+@HE#s>- zLvupTsnUgO=BjO|pK%}C_?~;!M}21BzP!dIu&!?vdr281mq@#{lL@L~$cQoFbUfjK zAF-}+Q-(x%hfOZ(w(U=;r&~wGul~#y{ONP4gNKc7WY2Z^{LkFmJKu#2#mNN# z!#LtkzwurC(H~w!f)xZyUST_cZO%Ra5c(XY<+*LzV$Y;)GJ&nqE6CMSHQb^Fo$bWT z@9g*f)t5uEy-0UR0FC~fOTjP<`2Gd>{q}dh3y?=n3G8INt;VlJKx8j2HA2w=>(cJl z|E=}MucAOV;QU#U;(GlW^?AnNv^H_6`R!J!j8X=r0-qQm6_ga=ONOJ2FgZA_bvq1_ z>qV4NIDs|Kgi8_XaIr-O!18msiFaKFX-byTFpeEIe=Lp`t#XT6jFpvupYLUhb0PfE?i&Dz5>#X5u4KfRur3SE%ZzoAsIUOH15U>imRTal^E|69#}x$UoJ5Pl z5lV5Wl~Bz1HRG%sL;0?KwQ!{^- zUwU&rn`=Z~g{9|M@R)|K=Wt;{#Gk2x`2YmJ|N=?|y>a%?%z7k9hg= z6{bmQ`o4Pg9;T~+4_=?~>BAj{FyZGP&bm;g2z*K_VqB2Q2{9d!3xhnc-vf7dS9taQ zH9q*@J-mFm!`Uhb^J=>Rn0ADl+Y#5-BTgr$<&kF0Nx>Y%vq`#m z+k{Zy<0ay1h0P0Rq`2S=solz0YL13W(Hdl>m^GAE<0E5=tx;^}ccevlyDI&JeRfljf?jbx8-F`bkfYM6qvwg{$i;?58~( zd5yXiP$DD%sWjn*&FAa9=57&5-@1;f*Bh(yzIKga7!=eKvI1_Yx{4>C|16JC6JP4v zxTQX~sIX8Y9Z`*Zi>Fs|eZjyuNy)5H@VAJCxRwLVPR7HN?4@Y|-kxW?dHW0e?azLJ z>-`>|d;J<8eDDEoZf>#P?=cR5^BKFnM@|Lg2Mps5!B1G%9UdPRJiI-C+zjB1lnYW3 z>N;~{u9@2B5Jb&9c=4J#I8~}O8d8tgpm`9~lvFq1KunrUZ3DR+?>^d5BM_x1(9qmp zJ%!8@ZHm%CBNbr?xVgK<&Fu|_NmWO+K2*vDr}G(aA0P4Xc+i8Al~#$W!Yu7U&C9Jn zs?XheoZ~Qw)z7UUH@OaO(H(^;>bC|5n(q? z_}BmX-{GJC^Gji@KgXB9@>PUESqm`1yynrhb;>}^8;0-aw(Ti^MJVm_eOsSAQ1>c5 z*vA&!R*-8q=|A^OUl{#S2bO;{P;PB#l zLSC*B*9hb&pJx#yGB(NvLe~G;I%!6Cf945RVIWBrSE0I!dMhb&O9Z)!I@dR&SDk98 z&!KZ(jdh_tb|Bc+tr>+ys9jtL?3%;g7(h8o8b`_kYM_)@i|ATA!+~H1vRYp`bV#^(#=Q9q6BaWv7mSslP9O4*P zpk$rH8m-qhF^O=Zvoaq~XLNO(nj^OEkJ`^YASxNMj1Nk5Jt|>>PUTRqftR4C}e*^t*s@%iD%6 z?=}&-&)a+L|7O@Ru%$Wo552*&%^+bI>ZVP*SpVMMZ!D4LY;RrbDm=FN*rwg3{!;qB zIVB3LykO_ZvC>|AVfVwFQf3n-4PF+k%ZgDfBI8={PD+l^X3iac?JONb|O#_Mxpc`PZ7WP z=$AOn|2Ka8lON$~{~pG11P7foUQ}||@&@Pg3}!-18K=`xdn=;k0&)?zcN5dD9=~dQulY97~>eQt}|j>04f;5fN>JbD%Av>g$@NhWbI3Kab6XxZJ!x5Ng zV77X>kVvq1%`rp-5#8_}A&B@CbC$e`Bvj`WlAG&;OkULqfOB#X*BoO`I?#kz2xT^| za*)FTdPHYQY8gumzw1)C;cO zKWHhWl99W5gC@D3QwC>=0^Cs9Zc1iKOR??U2aJ^_5Q3Q;9Y&M{r!U zUa;G2dPW1S-d!7a1<}5HfB%`%9m&CajN^ctn;U%bi(kau%RBY{OI^1$M!dOy1Ny~( zz_Kn_R|4f0J?SM1S^r&ACG{;&Ji5;rI^4joy+3%TUi{0?sxoXTO`RKRsAO!!BrIVUY#o}KST5SxnP{8XLEvo@}uwJ%U}6DghA_cR`6>Pu+E95 zO%qQxuqoRGMkz_xw1oz{(g~Zsxt#YJ@m2vwBC0B<^?hm-Uq*d__Pc&;ik<<_fnTCV z`|@6*L*9j&jv#Y$YixZM_`RfFTO0mkT_nxHv7JZNgHGG`_6~!R3yMZ{5JfGp!~~8J zbe=)$DqkhTAp+{WEhQr-IfI=#jo~b!DV^>rEZ(-0NI?ZNP?|z8o8eT{`35;ZZ2n{w zb8`^Z0#m8rwWzpMR*%~lfZP3uxK3D#0K^E5%ohQ$Ab_1~QEFvQ^=IQI%4k~zGoaNP zsIWNOiDCJiq63m8Jx2}JK3&C(6<6s=ZR{!lhO7Nye}C#sZlz&LG3O0xy=oa7o%f}P zQaO~#;{;?%)XzWzS0#SwMVS6?RP|V zLCSinpVeGdICV(04_`6~o0CM=Z#_0HQQ>wJs}rN|(|-Hqeth*h)cqb6JU=~yo_$yV zEtLGO6N0*H+PZ&!|82ME&KtAE*xK20e*5>-eW|;U0pD!vwlv0r2?2_JlB7v2%Yykl zOWNyc#(X~Gd|E`~q2#)*iKqtT1Oti2MEF1dkN+KE7;tlahyB$ayXi_qubk9(ynlSa zqefzGZf@}E)%%#H3H$wsX_~NdmZI(V_n7B19?x&^_Vh`my%-gN0yH0F)xnAI_q4<2d5_S^#0rs{qSHh%sTw zD`H-;rUeg2;LRH#%{oW{u;@`SnrjCRLkRFAq*M|U&TB-R7sLpxkoOM*FplySJiy+f zg+?K6uTqN8ymLm55Y^Nu17tb8QcA`S<)VjtJ>L)p!fv<2i|hAreSL+|3x$1NA`Yh` zPDc@xaG0?!QoB{pIGJbqT>?~YGnvOJ;Oc4*=N#5ma&ILXAQvbZC<=1yaPPfa&iU#! zw31fiG{}Z(k$GoctAvzP1u`dqn<8Z?jUJP8Q-rRx2JO$jzLy=6l27Ft$Gcm!eLk=( zHi`TaF`Q!z&cpc(9{`$UOkJ=X&bp>G;-__Iq4t*pXaEM%C@lli1dLNg<`b56!K_AE zjv0?{Pk4JThsxcH6JFl!u-i>Cfk0pv;D!<76fvd+F3AQXYR@CaFkSP(ShJ{QvDf*2`f5+Xw8<1{Bj?mC@b>v*WVoZ4Z_5nnM$HN1LaR4c` zjve86Iw7qq9Ds2UhDr8GOO>>GzqO&R`;ILDzGP|lhhh)#h7j=L_6E0icTyfr=e8($ zpKv%GG0zJ)^VV_Pak6_)Dm~M=tT%VgVHg8aUhuQO{|JY}Bi41rZ~fM9;nk~GaLx;D zEfp{Zct61F{O#NQt31n}1&I64_F(48i=JM0^EeUsfPkEYVZovR|2zo(_xSQx zeh+R6jX_Y`*pcnn2*&bi3c9GN6apL@=#>MtQG_kpW#jdnSO3zusr}TAvG4j!-fQ>B zAY$yM3IG1j|F6w;zx8kaEdXKfI7bS69h@7Qh5`em^$=UroNP8+? zpT6>|94OEAOD?Q++(jujKN=Qsn;DffZcq%XA7t2ngP{+SHmpQ-Idqt~8?U)R*qLbtcyp*~v>E}9N@J*4?Ne2r<&?lVgVjiveUR!oXp_(GWzJ-o2aQ=(bYeJ_ zHn-9+?AkQ|0l+ejZOYec7?5X1N)gKtjoN->yNHJnPACM8@#)!c&9IvWYr=1WQ zWr7vhjnfDpZgddT8}3#(M;P`2w|5h6?)Df4U|!$ga7;LyA90>%lcAaSKDhwBKReXZZ20gxD7}MIrspMa~T~urj#jf?6^4;5{fvgrk-MQM)BG zP%;n*paOXH%n&5!g?SL~SLlqJoFVz2vcR09PP$w?Z5gQfM$Q4=F}!CCW5F=V{QzJj zk87IXT>!vvC;-n`wG5Lnlnl&CjYd_PPFa;0j|e2C4N?)I4(h0!mlNI&k4@2e(z=08 z>sSWDI0W(R5rMRhT^I`B5(<)pOIbX>IR&It&>}!Bic}A$XI^cAx@UgZ4qiue5xvys z@nSTFi4X#VCdu(N2g0hge@oWBGg`9dSr>C;`Nn>A0Vr6p#tfGSp~`2dmdiG-Y@%juZAysl$w6P)ZVcQF|Uo41R)lL!(Wanq)^Us&!_q{00d{*@R%M?w&<1 z#ndD?Eh7G0^vqZTwvm$kz3s#_z)1r5yKb&0#aT< zE@RpS43h^m8nPx;1ua}7?nQ0B*2c@(`mQ-6U&9da-plv!#V>pjFJHWnC@hO%e>@-Y z$)}$n#uaIeV4p$S#Y94%y;M`oIY0H-vqf0s&6Z1dJRb1zM<3zg;Vn+56MpA+eh2Tr z{~7?4uE^q5387Ol+>Xb)pYPqk_6ZHk-b z$W@31loEJ};AKHs4#>-jvL2Chf=hN78L&+tE+~}Req0qkMTig(8v)#ec&rURs}A8hG^1SGK?LLii^3gO-7`#Egj(pXs)yISt3Mx!iZXilSk4Q!{w zQ^${$std!=K(P1K5z1<878Y9~Yw0MbWtprpM77zpoK^3bb>!f54AHeKYw4xL08zxU zv|6*y3s|!@5s?OGc5rwpeOyG8Z&}ZnXDNHNt}E8132Viaq+&-h;kI1c(WgQb72$-F zQkhbgD>NZP6_6@ki~s|1mr=Q==cLY`F2{#7HKAM4O!@8_eTbNm$tH$2Z-1kWse9l|+c@)s-Md&Q}0c3)e%*a|Eb&az`=`3H` zYt+u19GWhbbl=WJoMrMAkP=~8q^x7mJu>*9f~2+$xeXxP_NTsz(UHyhrF~!R>n+bk zm`DBof4N7}lizU#{A#1t5XsZ?xp(Sr!DN5+KE(_b06+KQ_91Pz1Uq^u>dJPoeWx>$ zZ0$;a8lFL21_S^AAOJ~3K~$j*|8{$T3g)RdVB074+_dL?uJ5+(-i(v}wm+`=oN!5L zQ2PFH#_4>*LF-l@4kD7b=vvO%^7Oa;?9|;s8|Q$$Cw%@(A7H=VW52t?ZnuN?JFM%9 z<9UJi4!1Av@ZQUp7pPdD4X8(^-hXx zUrTur?vZv0zARy>)K!!VI5?v5keC>zttvRM|F zL_Ee)U;q?&Q0Hj_QXAnHR141a0OFK%g?>O!-3?9Wr#JHDo2QeW>hZGYIj|n*oN8P}3qu}X5 z&t2r&lwNBMFK&1+EM@26+Yz4sIx_O04yNv*bZ1VS@|kt<+ak zhluZJ*dV!2ELkYzDoB>2eAcUOkYgaNlFT0lZU?**&imj71a&M-!wzE@;r*Z@A|9TE zdQcPznqif*QZ>0n%Sk=j=G3V*=2&*zUOl!~Io-TSu7S(nZ{Fh6bJ~nGiQc!dl=3nK zMUBVI88OQSZuS3&7@hzk4_8RW$T3{bwGMRe3o}XqBfeR zHOPljlDQOy0pI+y{}q4mU;XEs&;0m@e}ON5<*NXNn$O;g0rk&RBV*k1b^8eAbM0`FmkNT>|m$AJXp5#uf*)mpv|N z`JE`XLLQ7=)2Pcf?f_LPvZZ6ld4M|3%^_^S8Bf=kotNEboaOEMrqIi!fSm(Xr-F=2 zE*TjOXcG(sTdAVH4MH)M^aE6<89*YAR%AR(R|Ph1M4GEA=eu{l)szobfr2njBgQG< z=H^DI(=lSveLZQJrPXRg&$9r;RZ{7)g1dwUG6`Z-tBk!?!H}vEK7{H>bY7Tnl@Y^G z!%HHjjxF-60GPSb=&3XZ8#A{vhg)>4fjM~<=GsP9D*qZ2qLw~dmj%lrse>t{3JjeW zO%Tx{0EThE{(8X8%{BH{JB*V!rpHlOpWX*JH$W^Y2}rFm3dQ<#!aSc_q;8q9%rlmC zg(D|U23y05)pE%d0LSPM28T5+7~)U`*IehMvb9oyFCc4LU9xqfpa#&|`PRUmfwj6t za9t$m**?{&ROd4`FT<-f0*vR^d2_O&Iu7cZWVLzF>|Jv*Z`S4J#?X9mwSS>&qn=-F z^E1Xly&tvU1(&1&9DC-cPO!QGcM;{%&BuSp%N%)?zoWM(ZF2$`wa$5rE0#4jiu0og z;5{A>f<2Go&}z}%w&u`;agb6%Tn0QmJRrXjy6$m) z#Pab87{trAaFita!-t~47f-T?-Kw5#f)BvxJe&u{y~FLT&^tv{PHGCrm2f_t;qo94 z%U&Xqx!`a(VtsSM`Fz6pEPz8qm>L)i0SH4vn1E@DIGql-y1K&EdWEa&YYbt5_W|Tb zU?kkV{}O&b;KkjHw{PEKIXdas1LHgk6(p(ZAt3oJVHhw?4#PNN7z)BLz>Ny*-6&qK z5>>)oIqTU@X|40;Jsbi|pu`2)IK}vupNC-(iiwpXiU3jqyLPz2OCIVp0n^UI4kRBF+G1IqWk7!wz`y@&>P8y~2wZceuLVAxwl^7A$K7 zkyqgf7EgaoiYu^u8d(P_p5RGoR3c(fSR)++;0K4@731b+hr5@1?5=k3Dwe|qdMG)Z z&u4u4;erq{a*l{8qHq$xQxD()j=60XbyL}@0@~s3yq5!;o*MfC>IFI#%5b`>U6K5) zQh-dT^=5O{xfq)wcMqs^Uw~Hdfg=IRYX(XLVgm9i060q;oMdp59A2aM2wMNr1gfmv zu82_3Fih}XM6YV(S8vR$(GSg)COvGK0qzXl>O83bmNF}ivP>Jw`EyaRK4R7%3N|D${S9r5>hrcg*&Ja2=kpmK zee_Yy0kqGoX~lUyVO>`+MAg$a>iVpX8@-;4_G9g{gSS77q@TTa*zNZi#}W7U_xQmN zejqiX8Tk6wzm8Y0UV(_Tj;vfV_<${qe>_PJ_U6V#(&_EXt<=3#ZuC7-@e(-?-~9fDV0)a;!T=d72=$6&v z%Ucqd+wXWo{N3 zcU`GY%cwXa1m`e#hcP%zgTpiu)w7T|cso~HL~sj$+g!c`SO#hsB`1vlM*+d>+C{vDbzy+PdoT3z ziLk%g;qJvAuik%!_g}xl?cFW*`yHlnfDfZO&4Yp!(&)LUcF)UP!SCbaBku3-aesf0 z!{LCL&LAhLiIgp}ENMn5tw?!5E*?1ttpU9v1QYiRO1CZ`l0DcQnwRU^4lp|po^|5) zCmpqZZF@{R$G97h%~^qVGlSoD?Wgu8*YT0-Tu`{7PL+DyZtMwF4ZO~&{yp`s&G@l3 zj@k!kb4WjDZM3vP(-@I{-u9t%LTU34sPa|qeb3t?m)&07$<& z#_@2(;qZv_>5PNb3|}-bVS9&N(}{XGxQ!J6kX4UBV@Za?`3(}z7>6qi=K&~$!{Z}P z^GT%WS6Q&plG$C61+*R!b40<4!WqF4;913wRK8sEV2PYea&BJVk{uXX^Fsl~03af! z46A=j6mWgb7>0mCW{{iMg1o{G*zY~U6yOGrR3K_#iQ!!WQ$`3LSHm7J-hYYPYmX0> z*GTh#!{LB8A06=NCvR{*o)KeG?~>E}-hi-kxZ3Y9OhVsdQ-t;fa0H4Hc8{fCjYUe$hZiU9 zKl3V5Mi>Z#_ZW9O4C4y#GiGFA8hc@p5UcP#^4V6##8z3i|%E&y$WtzlpX8YpI*rc1*Oy zhZ%-W`rZQb|H(QHPi5%G7ahj=kD<_MY~T*#3gs=ZMuF?f$sL6>r|&kBoiO*qZlcs$eR@^<+^Jp@_SEJ12W4#R*?Km8Pc{ntML2nfOB zt6%*ZUcP*(dn8NQEM|~8KddeP5D)Ce3;vGJSajoAud|Kk1^AUWKJ(rVv`SkEgZMrx zU?k`8&2RoM_=7+AFE*F^$q)Y$zxkEl0ei0M`#{Sh+%Qk{dr>EtHDF^T)N&V3pTCcY z)kEK*rb<-i0t>yc)s(esiwMpzj`+d%|6=nT-~85h0C>%@RHbJxng~RqDN(Lz0D%rS^3yqDv}gmrF~v@GSE6U}e8zk{fgeQJ%`5Qb zGQ$yrkT(M9lHb_&ifsOiC(fV&sWq z!)vamtZhe(;0VDJhWaH89!eLWnww!w-S45m&i3$D;zRCZfQWOuMj5tX$DV=B4$7J% z=d!pJ94kPz8mKMT*5;f62UDBg8q?C+&StERAY%;mpRw-}2UG)8*NBN>bv;lIN`|nL zpz|+xptj`-TYD`}zAwdt+78FMzYvK?XJKSc>WmN&zphT~ERra(BeA*qJX3Q{U0q+- zv4}BZnP;5mGnRGL@;ybtWWutpm=^<&Jk88u{d*65sNRz94dyg6 zo1dEPz}-N~y(9n-{_dB53jmnLYh3O32o#WV#+nuZL{6f8Yt(|)daybh!y)B>-QHn;?LjmkCxQhALXe1?AAxb_ zF$@Z#23Y_LiyC&x4sj`%myBhR2p<5PQ7}z2rt3w@ON}032yhe?u!&(cK>8t+M(b;y z&+X)K4uB_65VbyOfY4pCtx_lS^I`O0c5o{4;TN*Yu|Wx~2dJig6%e7r|WivVz60M8QSAnpt{-x&wFqa#0W_)!l|7;wddkRf?u zVvMqS;d6rIaR-1#bP-AbYQR#Tc*F%LmhBC)`UNvObu8?xxB$O0 zK<#tZmI7AWIwK=1)zT@jwPU)`w&kx>FKa%KdN8ShxiM^NW1k0{%yNi?LGqm*9v|_8 zAN&AT7U-*A{VHC+eq9fyqyj5}Brj@vsCL&i?@D*j+3#u_pBoR>J|G*=&j3>wpt#Nn zH6mnfFqoPkh3FyZ{LBm@k8gbAf5zkE1ODZ|{G)p5pZ@5t@a5nB-6o{dJ>wIj(C%7| zj%|CNfaYh$z~+ZVc|mf1)jGT|1yrQg=&*HZbGQ& z=1U!v($K2`LPrSB=+LM?JB>z{p5pvu6WWf2v5xA@Wx0p>I0^&KHa|2vrgyGVRV{bC zmZ^c*53WetvjKRxdS=?Xrw-irC6M}Puo#lMAJFBOwS7BN-nqW4AN4(Kea;uuZ26(v zOIzgGhfrBy#^?gX1~EsKDTfp4NeN=f3(vVDg_HKF3DGGC_C8=723f1h%-iqxxGOJU z^?yrdO^Zo5&ohqa6Xtord|rg6d6t~Slts8FDPYJcAvuRIdVpEAJG#^?>qCojqKUT1 z9_wl^+Ma8mMqYX{38fBJ^Eu}Rf^*I&n%~SSKIfbP-+1ST(p`l~X{?7_QvE6= zgPrA^%NgsvIi)q9Qv*P<^=%!cmwUg>y&5sCdy1?LxrPP0&&US6;Bf*=qC~i=L7NI>F|DTjD3bUTJY31}?BS_- z@(K!K&R{JE#M*FEw+oI{Tr0?Tue2X8$bOhc>~=f2UC;#;l)@q#(P=r=MYFCE>se@7 zYtj-r85qZm9FG`I5y%Ijggi+7-Q}<%=LqsbFC5tplMJtI6J9LA4GuIa#WWJuC1G6> zmL=hIgaF_L_52)1U|bo)xQJlY0HyT-lE>vG1&AO8}|`4LxFSJ>|+48em~+8KfrkY=20z!h z8OP&{`9w%Dg0s?WJ%KzlnqrH!H+u7CA+s7yrDPGV=Qqi`-E*W6!*Q-EQg_HQEJ0sMNNX zbly+vXZf2L6edPvp54Br7lS3Qx|t`kp%xjdoLjwLqnK~NueDGQQ3Jj9JWou{XK-7+ zrW$s|oH}|v2U%n7pjK}zp_W#-fE02gIl-hxZ68%@@J#Z!=;HU<_l_LKVZiJh-rnEi zd*AyDq_`r+6<_<>*YW!G2dWe-2L%|w#>=?{zFe>Ul)_FZa8F7BJ=b@#_x%dY^($Y^ zh!!mcp(+9~%Cm)NKl$Nb;L@B0#{u8}%crzwVJ~DA1N3k{v@%atjzIwk7uWim z-DbX5Mc3Nq0!vvSXo(nmR-;7g>vDW8s(tw?oo5{AL>IfYmCTrq2_*~VvBZdVSrN|* z=JN@Ben4Cn_AgmN^nHpoVGMfP>QAD|hE^nwG8V*I$aoEyLiW=hEsF97uQwO3&_PMSR zVTCZ@Wo|eZR8&&*L_!!uq-Y4@Q1`B;Wtaobo(=jmxsdJ?@^2}_15j}inWug}qFzUq zTrb*lxsJ@R#M4b0TcaHI?h6OTb3eE1H(*RDRYTVlsB5VmWrh)vp4Cc$)aw?olz{|S z2N0X4N$gXOJl5bf$5rm*6(IZI;n;({R5O_-#?{po?#c^cKrE}!rI!_}(u`w_SXEdn zl_=EAVZby^*iDl#dlZ1Nw$EkRABd>tsoOY$S+eJKPY`>$Lgx-BnTU{nR{)%nh}LnX zuMt9U*zE?~++9ng_j(k{_$UsNHLf_Fr9C2cCje>kdkjMWm!X1eK-fJgNGiv=2}piCsBv#(bx;I=QuILe%n*=rai7bG^~EzoovU%RJp88gd^(@C+|jD#P#f?C z37+z*f?xLxFc?W|PenN9UK#g>xJ42?u` z7VtGpszR*eXtm_b^HntRH~1jRm0Es?hk`IT#G$~?z;Y5Xg!}t54u=DdH&?j3yTi@Z z9{c?s(=@8eumh1t82}d?$R#jEFo`nu;22j|9xvY;@bbL@yDMNE3E7DNn9B}pBDe^o z%qWqu=7jZpstY)#g!$;PEGtS1h%sY6GM0J88YNQXyn|;Cql}wJt6zq_w|IMCQ}s+4 z$Sdl$a$dk=U_CsM#8~hGZZWp+J^+4fRJu}HK5$O*b4jR%4-qg{$f0ri|U4 z$9O%6f$ijg;v+C0&Y0gsJia|(J&v*l;~sIzSmp%hJQ6|6Vl)*^nWwTxmCP!##h}~{ z2P@lPv@+|LM#1CFPHKjwy8yZsROkk8Mt5z8ULt|TAj!F2zf{kl8BMwoDkwI9Y}E3s z>&1duee^*#Fw{yPYR|wf-2;{SvhKL}TMwQ=vM;ex)rBtSTGWEtabXuC%`ud|H41bC z%*B9uHzz@mdvNJI+zHGAyrxOYJ{=B6{MBFml{iaM#6S7^@8b(!_#%c;852dsv4TUT z%T;5b1BSS`e_Jc)=EBx-)Q|UNZavhK`mR^?u6GUF=EqHwtA+;3N?no<;0xJ)98FXYewEQ-Y%e@+?&j%*h5Zro;f1Gry?w ztJ?7DAYwC=EltG6Bp01qTX8;C)n%70GDuRcPa_e^kkx&jq{g}aqIU>z7xgJ@kv1E* zr~O!6(QLvkq9M{r{h^;%ZLQg!BfAA(n1yxaIF0sd#5Xu$!3A%M%%+sj8Wb$khRSFZxnb+4C>q|JAm zgxYU(;Sl5PTCV-8`zX+C%O{(~g(Ik+>-M4zSib<>8{4Hn-{m2V&9gbB0M0-$zpHW6 znqS*6k{&rw-710NA9^@^V}XLfCupmaXbJA}#7&9I_S#YMUBM zbajo$Q2>|s9@8}8?(R+^wJZ^0qm^V3QY=WS((9a9uGAg&IVEID2o%7BY@%TrL>y{V zU=s)>cq9ib$U+5#P&CeI#pB_GPu{%6{f7tKzXj&Ah!qh_=^*D;Ow)>K&;_xoxKM7O zz&nq@iwBUM9JYlE)|7zx3}(hsg#LA28Os7JtAbVqvv#TsL8(%M)CcwsHIhsAIS;rDBn4ub zWQ@E6rV+Tg1+MNq!bn*28HWY%XU1;WVVEX3$D%;(2+6NlX~Dv0EIA`B46Fq?0V(U| zuF(xD`fRNEI4lQd(!81K;eE!V-h%*Vn}KWe=CU~)yBs9i0*a>_sr=4r;WJ0;KmN*Bk+oDurA7h(`6{L&Z4)Ed+S(i9)zQfiTJOd0Z8ovcAF4rO zV4XT|@-Pff!0)%d^Bq`O8>dktQ-LL-XZ!{hvApq^t6q!aNLa*E+yySCFCk^ZbSOx3`s;sm<65K92T z%GUKd1(*G81}>2r;|d~BTf}uNy|c5+DLc+9Th8{X1_pcTXN&e+=Hhma1R`)w5*?)$ ze1AL;EM8}zRWvNxBC#N3e5RU+q?@>x=;7FK}$ptWUX6u37g-UC0{#nYmZTXQ;d>MkTdeC zs_JV-%27%}LL!55Z`5b0BT^kS1i-_&q5!5nk9c*O-Q+YUdYT4Y-(KU@`!DeNbMN8i z_F4chM}UMC$;_BdZI{i_()JH?fV948E?I)p`ppC8afa1KUXzq&TAV{+jq>+PpaWes zWuQhs?Pt^Lahv&4#jyx2w;DDbc{43H`Lwo|Y_^>Z;N)?Gv^))w$F4Mc*B4@9k{q`#if1bbEGA68(*XJO$13 zpHz!V^m0ndSYt$5SA@(9Knd*Z&{aiP3Q{}HtJl6b==WJJrR-6QUT480I)`2l+Oh}zzqT8^&W20$?I6^&y60LGU8cFl*}hQK0e~% z{)qce4mdmj9L2~94xl36cY9Heb}Y2w<;Yl9z@-A`jpCXy24EPRP;Q+@!BauX0#qMo z0j+g~CzuKZC_t#x0oaegZtpNoz%Yy$MoloU9xPSbjRoiPink6pKSJx~pw%i43I;6V zs8lrbAbJwDYG$sE2l0wZNr2rnfQWGR3v!NF&koLub0Dt3Ziu+P5hII>%aPq(0k3h_Fih{8TczQRt&;!ltqHk!39F` z8O{@mSJp#W5L1>&uX@k>K#LCoOoEg>#W(<0SHSI^$9_M;kBmYI^Lm6oGZufs74`@m zM35^I&T+;ZBj)vtw~q&$4hv|xg5v-bDM{sN5^rmDsWpQ|z>qo|O81-{Shxhhq7>R3 z2&EJ_mN`(|^QC9%@6Zg&KFW9*eJtG5vE>jeS#p2cmMQ;PzZyt&!uGY4rn-?@jbBb6(yN*SVNsT#AUVparGhiHc7^b1+tCxb5BbK4weDMok!Y~W~SVi3k0ZOrzL3?UY zKGP?cW7|h$EXX>cO5strYIo6cM#3q=H`wT!^D-97lZr zFaO`obN$)3zk{R#dnR}_46RPL-W--g)jREau)9_GF11}ifw$C`cXYP_mmUNQC~ow~ z=Nus0@u8ZMVBj~ZDktY6!b>q>nHQwP0q64>e4dd~gu?;?kZ6^NH;Xc|89P~lutl}1 zz?=%(prikB;mW#bMtt|I_8xBYuw(;PvJN~+nKq+5}_4QO0fr*WkFn$<`OR|2DNIWSk_Lyw0ra^i{{Cb@$|lh4JNG0zJQhXWoT9*}dw zJfAUyL2CW_L2}nShJpE!pWCOlzi;E{z06tY=Y&(m^v!uv8l0D=gGHl8_y$-~kno%kTqZ zV8Fqn6w-+vF`v%JYXk+GfD&0+H0oEp!a?5vNnedRkE;a6JHi4}eT*&({M30CJ2dhZ!*fCyTn00HSdeh2&u@ z63z3d>c3X|H4xw?V7QVTPiT!;n?yOwfpE1CxVpN=-OYgg)fGl9pCsZck|*dKffKMS z3r-IahvNYcZ%%mg>5AouN~eY@6Xyi1OM!O<#YLg6_6T6 zhpQ_OUJ}*_kjpS-Jpfv^Cxe`bD6DIea#sr@u2NTyxnS@C0K=_GYTykKM2w=*7p{h! zh?b2LbUk7m2Dm}qmyQ!o$1^+VUtd%GR zFZ0L;^YRy@yyCn9d}8eU4n71FClL-;WUaWspuwwJWkg$-5*f=ZUS~iRO4SInJZQ_g zB|tr}PDMkgeeXQM_Bxjh^ z@>D}Z*g!@ddIpu(^UC<$W^5UG$$ZTWkgyKI;K8Nfbb7=O|M~~Wn&=M8vCa)5@g zx7w?^s?Ir?8JoM?!V6V1w}{Ns0HP%8m< zaP;InjqqA2n<)LmE3hqqsW{*ob!qNL93&$GP%+YZ{{;O0<&S@&)Lv8T1-T0jtrPiN^|_&^C!=cB!D^sFcP|F+2b(g-xrT}B8S%;Kj z1vRmh{uIH#@+E$o#H5YEX>Uwpp!SA@3&$=4j&o<*YX4Ui5Sk;)BpC{!>}zdOR?w@? zZZTmMGnw){%Dle_2GwU!D1?Q{&;VJpQjpK=w*jp95oI3N|C*L;6&2-juj_ah8`NHr zXfed5zA>wh7n?a(z;?N(MnKD~*Lr@&cF5Pv|8s%Xr_7aBY^XiVnhg#?g3y%_p#F|& z#w(@u+KjOmz^H)g)t;0VLFGm=tjxs}Nk*JM>!i(@DQyj)0lXDS%YA8Y;8uOwJE#5> zFc`*hBrf_Kva~LmCh4s^Yd`2&)z_CL5`$2;7oDpi1eQtsHu>C9dmB#@$kG~Mqb!$s zp4jak=sL?1CdP3iz_@c54GgCgao#Z$aV|RbHF~Z#@pHY` z0JHOW-{ZZMB-)GT-##~^c*I!sxoQU5T&%gQnQf(ED+P|ZK=Lt?Pfufh^gkh+^f8!p0oNU z&DtsFVFj!8|GL;N-Kr8CT3-gEWg~_%^)FaG?FFKSP$L}0Z!h%cSzC3@^TM*Mb?Y%m zO*m>xt<5-Z=sU|Wbo5)#)zy~k>uYXr@7P{nEAvW%Qr@T%Ig&I;Q54?e67Xo&CsOL} z^x;LTo2}MfkSi_LnhrYIG&S$3>_g7EMEoNYiE<+4dWH6>>0M z`jEvzP`y!r6hqKVfzzyqNUSe&;B=fh?IX)ELv(Dqk)e}pqw5B|ljgZaDKMo-oCBM2 zPw)5i{leiMraj~drUYu!q~_K_Dxk+p58m4%Vz9ZQ>$(aMYve9W7-Q*u$95dqUX9$` z+;Fv#&(U=lV>NOjPIe5D@H%ri9C-8VdpiFm_iy*?chWDGEH$Rf5snUGoakJp?|YI0 z+;x&>!m@BeuIF^vVT>UzBH!;jc=h_04_`@uV(3P;n=PBojZmqAwyc`9Vf;y2VTD;# zq?aJHcZ&**Bmn}Fv~JwnXS&h#Hoam=dIGD)fo~Rooi@x4rf$3 zx{9xq+((NtR|8+`^iryu5_--;WtOag&;*OBqx^jhN+jJRVs&hx*!HZ(v;JE*iT5~A z@3F1VCR`e;Up7;aO-J-~bc4!q1;@q^2`uvoYQIXcccs>((n)Kyd3Dy#F0UE0^@2)( zp#U@eUoJGu;-DnFvSLn$cl`YS`v;0BNd9mBTfX<(|CVtWRFFwpmUUJH&n~ay5+v5Y z8!GUBGPKV`;MezQkds11doFs>yuWc8a$X-+VQQ3*FN=s5T5Gwzx#3U#F0)XR0}m@qjp^qzmX0KY%} z$=}KS#9SFCMMP&^L;9>W!)X;0iocMa&FD()_0wmNi(p$uGbd;(u?uhm2snO!B&6JH zp-z`MS=3{fB@p5Q0a8eWdFFUH@bK=QcW>X4b~|DWbaBA|-pm3zn25&URT{-<*4w0F zYvhit3gX3fj_5ZzOHiuVxU;}Z&J~d5T-13ZB?oBKxYWLu`fsJ^%DZZ&R03jat$RYU zWlK!j;wcJEKWJ+f6#}ckvVeS@TlHpi9<4#2=hsxV5xOj_(TtcaZ9P~SE5^w8&Ce?+ z7Tdmp2l2&HnbViSB6EHXxzbzDukZZ!*0r(f0~F=u)do7}xIEBVfI1}=9$al_6Ah_B z?=oIiYhAN`rUVxB0~M%5ku}rOBBK#uh^MR<0 zjb)hyEYCBOf(y|vK=0o$Pnn1Nw=8+j!{Y;2S0m%Np&xs?z7wG8L~zY}Pw#r!3n_}^ z9bGS(+!9#NDM{V4wnsZ04;&8y!ov~}U@G)}?;NSra+e@a$;@8plJ87{{Jr>)C7uuC6v*U5#w6My2i-u}s-3R#8W> zq24<@*^`rkl^`5u@l33d@+`E{Wh89DbWx(CC9;^xLbW>4rM|519bt%^v`#n$xh9Sf zmQ3d%EPagwA_q2(l8Jtt z2+JaXH$Y5X19FfoK#6p!lJ(G!I3KZo!1-RDrKVztyEMRlInEN(Ge&%TP6Q^$X`dc|PJ3!3`B}zI~ z%5N{joPQYw%hkfRAh`KC!UX7=ajTcgKvU6Gt8b)+&_VVq=Rn2wM9^5;J#7X{52`QC4TkD(iyO)+6ye+Izd z96%JB*a{N!lWTe(fWFMwT+R|xBIxyl>NGqF46K`AaS)UhShEzy8m_Kx_|rfATmI;e z{-^rckAL}70m0cTyQSP~uE0l6UB~5p^V!&@wbjMFK_{e0kv;s%OXiZ z`}}HlDWyybfz$EC?%h4#eEkh?zy3A5$46Wez&kMGtYI+HRwcSc?2iH?XNusZ-nvbq z$e#?-8ys~cCD2#qV=WiT>#~>3aM7bE0+1#9qJe;_`Y8a_vWhslQa@`f$rx-_x-Mxw zRyLAFi;}^bW)*1B{*?1vf&;p4Rh?2h1|l)C8K zTwh(&jh!+PY-Jn8Am?Ls2Hx%jnc;!OVL5rI(= zu}xAQ+xZQ7aP*zjBM>YxrRL#l=CnA4h+vCVVTokGS*g1b^;DDw5Q#Ymh#^Sh4eO-d z))~Cd41;6bN=>M-;{7DAw5vrj$1~DGfd_H0r=w&_5059NX@V$`r>%APuA}Q6zVESK zqE@c&Y6MFnMsjbP?h4;^oF0z6e0|H;U%unpZ@=aKJ`fg}^eLiQZ!tcb?S}34n$0+p zt+eS0G2omb=cvF_vc=0X;k{wElTCB~D0R8U_p*s;ZI6g_SxAoK;mE_i^t>wa_I17m zSk%W$PK2@Il!yZigP|KN-We5mvSj7C?;jGUlVq=7-p$1A05;QgiE%3`+*zatF*cKp zCt`@nNOm{5n&D4IYg+*Fq8W$*??#*rq+mH6C&Cg~kg*AzBzo(>PKMMOy4=<9Qf45# zNcNfR6Rs25a?q@O$f2R9t_y2bI$WbpRrtypTnAlm7&b6&q3Z!NbDECK;gR@oBE>*t z0t3;Auv+OWefQ#y7cXD2xg8ldBi$z9yd|+nZCsXGW#!V>59PqneY@)^ijl zL7u?4Ojsst+Or&W14-hf#8c*Un20AwT)@Sw;$NQZA~A_0Y_rE&DGZm5`rJ(rnoy&V z>1=g`WOFW=&K3BSAVLwDSfk{ULAH&4?ygj?3J zG-ucM8;9#jboYGp+GzQ+zh?yi@B4fEJ8L_lP7{y!_k8=s zSA6ls7kvBW7aWgAwq0f%dKNe1oMq8k+d-8%yRt4!)>dr#oE>BwHVL>Y%JQ<#5DKA+ zNu?}}-o#-Pho(51g_fS8h||TQARD3pz2Z1oi_I2?)b~c`DiF>&*9>%0CPhrzlQIYZ zo|nKhuTI($B1>2#SRRV9ZemTDT-26Qkv}CX^P84nah9!usPbk5wO(-zz?H06vGEO< zRsidaW=GY@t*17*+WoAabk>Y!$+WdWJvpQVAlB?k$=0sxrvkw;24=O-CD_%zBqLnL zYF!1FJ#x>-rwyz<1ug5b<@ll)T!OyTbG2>yTB>VZqghmsYpX2{-dOF&OimCR$G-xK zrj9tvW|z+ZPXp%7%CwAV0*Hi}4aO!43&49v*Ci49QGa?ncG#`3IA6xV^lIjKI5EwW zWPT4bkB<+$d-uTZamRkYlm4owJ@Yh^m?Zc(h^l=z3RBT(#@DMKJ@lFx9tQfp7ZxZ6 zkP^iLX68kN@=80K)8WM7aFCXx(_CBlmG$Sm!$nsadv$NM(xR#Fdr6XYl6hV?eDz7r zc9(NuwRSF^O$eU*F;@}2=l2m)&t2qb#YdaYQS2Ay#3=`%aV&v3%0k{BCy~b92a&~|pY$B7`Fpg*H;*mIh_oN ziFpacd|(dJ3%E-#^ce^kJ4i+>Cemppn4>y)O4ur*MbQzKh54A7roeKN7D`oNIzwKx z7Fhvsut=6RM#kib-r#M*2C0pjPMLWUAl7+Ug5!7yeEsXUgekJ!PM9P@IyQ-lL0-J5 zJXoh|m#fc@sB=f#U# zZeBPxn*rwonZz6qJU%|~&AYF8d{|f_(lfbJK`RHtcm!j(zPVL;U|_%Bi5jSh%=5(I zAWC)166iX^^>vT;Gt*I+1aVrIe@gNUGjI%vbb4SvoP1yvg*X66dhTjAz-v^BUrQrH~#}(CWQBICg6z7eB z>+2i-{PI^X8jx*u8s43;{P7h>_$btThCi^rKKPXnejpw$G94Cia6IJ_&HrFHL% zO%b=h0#kebp7mAM@_G2J)LgE>T;5yFrW)N=I|A~>UZFMiT6k?tuJ==baZzAD=a>{w zT~Agss_p%+oh2zD;SacFSc=|Qya4ivr!evTd}gTAF0D`EI9`O*0r`;`sq$CDCONLYerdK zw!>J%I7*LUs|h7Es5Q-^x?I5M;k4&;JTWf^xvwsYl65Z{1~_RaRaEUu#(c``w=1e#c>dki=Dv%%$^!698P>Td8XFIF4+$8?LUlbbbJ1 zYNv?H0AlTqsdGKC`W*6peNOpl$kCYd8uK=oaqbTla92v8a`T*@`Z(vo&$Fq#21lB` zv=wTVSHmdNd8sEq52rUDx%A&^fcI=IU1Z6hrQ4MO$<$1+Ikzq=RyXU-8bf9+uakex z*|W%*YPUlOssKG#Mf9-Dgk_eF1KKOrI!EUneec<9H(Xs^F>a)7q#sm;-St&mZe@dr zAe;yjCVk+p2J`#}ufNNS7cY2m{QOvgm7S4l0-dAp}7h{ z6xva#%>-nl$VsRmB@$^J&S|DGM`D;cEhot^ISiKJ_d9m`#B!A5 zj~#5cJvX<~$96jkO``J|?>v34bqh)dwAL$K&8ra%9FBo`H?!M6a+>ypI77Brld7nZ zchGkOoqpciMBfQe%4&!V9m{MuoMg~D55oxK*477Nq5!s>a?|WtsLjSeQQJ?8P@Utf z^}h;!OMIcI;3frbF~gD!CPsn-qx3VAg({ts2s1eY%PI31PaO7v-TgrfjYdWWH%bJs z8}Z&_2T}bru>++eVg;bZC>ud(O?22F2r=NjCwZZ=C$DX)j0&td0m6B-x>0CbEaS*s zrn~Xj&4|Alxt@D&ZW5b2IJ|??apLe`IPL?>3_0ZL?6fo!?>(FC!1eVNuRrMd?eBfa z%kK;fqsMs>irDS%u`cp>c*i4w<0*4GNjoDiofL2`vzy*B$H>dW75&g*yIE@0ozxU8 z%Rm*89T4dxTH8xhYjwDtlL2EbPES+XZtdu^6K*=nQ8tCWkDYo%nJ zvVipJC{qFkw!BN7WK-*7^~Si&OchI%Qpx-_Yf)x)1;&|TznY7DW*%K;VS%-7v7E2D zS+Q|y0d+5_S^j#w^4`22<1E;HE)dtgKc|dof?)ncR9XFbo_TnD zz)!Pee!Yl?Oh%OIrsX6Nq)9Tr^OA5Dd@sFqU%j~HgAYF7_T`3g9Puv5f;W-c2E%5Y z%@hS>xlj>#n!_TIsrv)(-o525S?IfK?M>IqCKNm|L~Q|)w3UhoCl$a1KnXCM`^(i?Hx|is7Qolt~1a5NK(%glX;8=>nvtdY;#9{lJT81QyW ze&M+NVC3{IJl^kk`|H3P8#(MOIWNSZv@;WtzM{|%j((HnYlN=PbbS)4#KvK*XLFV4 zhKTPCSJ&V0^*8r?{dMHsBb;W5Hy8uifpZU>mOb06kztz|w*&pg;k*b}U=@6th>N29 z?3|(RGuf^6gMz+z;!b9G*dvmtFll(O;+=xu*jDKgc1 z%2zIBllsJL-QKo*@lmnwQOxBvDWB}`M z8cD48p~|A7H_&0dt#q!-SEWj7PifT2Z)>Wo6*`+Kh##Tv^@HQ}>lgg!N8jg1Kl}k7 zy#9dBk6;#d`?r#L+eU_AgLgeK$=b-#&>16+lq&jXz1ac?+gCdWS|{**^W*Y$=De1T z+B`i^d;I5*W9weQQZn0#aojwq3I6Ek|H$`$@OvyN)qqcNl#7!k$5en`GiGZht&B^l ziT~Bl|KZ6s{l#DX4LM7hNfl=)%KjL6Zq+$&?z0L}J+1i_3hL8)uVo2vb}!G3+xnc& zfA{_|SCOd{EBFl|B3+!U_WxaY_vRg+efl|{eEboge)=i%{UgpkJ;%B2Xo5$#7V;lhSM3J1;ayyQ<51(rtNoT~>OZOO~Y#+Q|tD&{`Qh>$8*SXg&k@ zB}-ZCpse$7{h70Qx`N;~ zINrS0sY%IN=M`<&y&)^OETWSCTFBd8Up*mZjTAp|4NS?cJrfvcFTJd9{fnH#u2+{K zC8O&43vpRgZ9i5}EQ}s)dz3TQfwu9(eoiTR#8nb3Xs_OZK}xL7;&GD2s8j5SK7X z>Us*qkV!_AqWvI6_pU^A972Jz5aPmN$}B137Xd)odz^IyCkl%p2cl+_z3;fY7J%Gk z$2g9B=Ytpgn}73Nwl9T3O_EwuXQE2J3wPK#0l^t3z&J^SE+i?wo~DU;Shy5P}^ zJh=6aal7H>^_Ew!U*R_kF^L-VvMen3naAA@`&L>pnJ83t=Z&ascalBJP7HZ4=UJv0 zwMP1o2q9skp<6OtFF@FPgY{Y)-aERhp5fLIHjd%iVwhOMp0rqrs%kL6k+ohVGYp<# zlW^U{eme5mS0~;b3@={Xa{IDpd$qxLncJ5G-S{ClcU!KmAMyS(vN^Ha!xUuf<{2Iy zAlS$$?70D@O7}R|W4%*abHe3JbQ$BJ>n+`2=$+l5)bcmvolIj*MLS!+LEN29E!gKYqsk=BP)MTTC0;%uHdAoqn|n18m()e zUybGmQw{TZ?aSKlw>8C$yLXlakYg4i{X4LVUp@8lpZ=}|1_eY{ z&#xGLIbqCE)a+x4Dq3Yfl=I8;NoL)|owW?3lyiua;a4g&=Nm-3A-2)(mO5>W!5LGT zuhu#dVtaYV?d>&v=ZGnQ+TO$Q$lJH?*o-&4xO>gr-D@`ER)RBL2HE2)LtuTz&jY2) z3{3l;7KBwmY@Ywzv#;Fz?LEM_yiu4z>(4>cDC1`2Pyh5M{LvpZbm)(M%J+ZpUyx#~ zS@;$FmU~!hFx%@jI)_6NAo#1F{pTlF^A~^hH+o+QXT7qS6l_;DT)Wy`W9u5NftBin zrwVe;|8NNOlPHEyVdNGCu*=LVv->sHrl3QTVyP}w+euLRf2V{ zsH|%%xCT^|>}1Wfs11xco!>{HC+w}@43kA7k zDxC=KEKy3OB%q?>RI;Pxy2{wZrX3GX19-abqpoEQs#f+<8I4>oyZ$Q~Yx&V3?V0SP zbm@|ea-yc|JBxP~e5muV>qMuf>pG=|w=E8n)@e#0|9D(jmJ^4=k$IXV@Cuk*m?c@1 zsHch3@yM=-VI7a0rjxAK(q4^BM9M6sckrI!?LEUV(07{AHXe+YD5*gy^S=a&RL~Wh? zP4+Eo1Y@nX2a4)>odUTzM!nvr`)tW5pYPS{z1eb&df%m_p%}0-f1f$<8CXuHVa#Rm z>B1tcf*4B4Nvx$T()K7-y&7v|&08n6ggFOdlq|7Oq)S^dzdDY_5KZw`mM}?c18Xh4wl^x9^)U2oueRLWUbEefxb6hN zoKF&ccH*o^mN9dE({ppzVUm}~bhPaE2i|^r#u z+SQ2?5Zs1pt>9;w6wcH|n9@1;Ew5GjTmCHxKkJ0@Tbv`~Gp5Vf!QeNJ&8tq7vrCQV zU0}F3Ty16!`vYl`Xq@-ZbskDf5+{>A7$*i3$;b!12qi7z9F~ZU>nz52eDCS{Ui# zz4nY_kI5VQUZ@necQ@=#K^)+{jI}i)W)(^=W+U?`WkW&)RgASzRnxQ12dR_2y}sq< z`i6eo;9Q6CUPO%cGrPwf4{uNG9(IreU>Ur}8qa7pc$)`^IA&zVXMe{Z{^9>vKlkxR|HSY9@V_FZwKY=- z(8%kIELOi03T+_f{9f>zH40M|)xDP>u(8@3v@z1z>LYGT5-c`s|!e>O`(JqL;5WdoLvuuq>Idz_Q3SO& zC4_)8hL9qY4x=*yfQ?BaY-z<7c#~v*%95!o;#WltIwOu(j8TKucBPYBTLCb34FxnU*-*fpYMxGLgD8X2{9;0o7%1NGP>{sxx){T}H zI`Z^v!*w;ySec8@zi;i8cU$AgfLA*r-R6wac5MZ}MbX$g3EVhx)#30yi5O-9G-V#k zL=f6K5~x^h$a)op!DWpVrc?zkslG32q|oGuNhoj^`zK{IqFJz(JfW=-l^yBC4|biG zQW|Tu5AYfYhLXKoSZ3)HzTM39os=K$_j~4Ps=`Lc!;$0RB>jj_lYrpUN!m5-_e`gW zkQOqDWD_wNOw7!a;pk2(&piO1BkgNVlNlwt% z%hooKSM~g|DxcZ``F{&!TjmBiS73bkI(wfn(q~wmx>9D6v|VPY8Lv7HA!u328YnbI z{3E0Iahi|pcJloa0-I^1>pD6=)PS`3nz|NC;6sD0t5BuEe{l67^D^`1-8+tN58QwC zhBse)!`p{9%=0Wgn5@tso$0_OoRh^W4U`i#x~YuHC4iY_K}9c{ptnkkDig{HrMTN% zGYkXSNgA6@BBIHr8nH3Pkb>keH@;`H-Ewo&)At^TN{^C8+lRf#z@LuterNZD7}>oG zJlsDpPujEA4sy-Gl2qi$yPjx8>GA&lft=wqJ#uw(&E|Tc?|V#lP*E%~ILk8exVvW# zI>G65;SAU=;|GuJ#EDBLkpxkw!&@GR(5=M4aF#hRMxFjTxz(U&$T2rjPc=~Lq}%iP zyf(Ye@_Y!Qa4lj!5_yg}uwRb&{XNrQ88;)g6pjy>@kP(z2Zp03?qnkMgQ4#`l2f3Y zMSx_9q5{1vQCdVrRr$^qvWM(3^tjG5j9bRB6FGA)YHoQ6oTeSS`x9^8yy4*?u{%9* z3LBP`uwACxY#6ROhM}jwwp?Fd;kV*oP17KK=T0*@B_2-)<{a2eMk1bRWLXmXo%C@g zYp>@G3_Wb_;OfS4^}_Swdd z?~QFhSL4Hi28hi1z9+{{>-X)s3K+KfEHPP~DNE<2&#Nfc$`0k7?>CS=$HUCy=3*m!ADE(K^c(N8szkPqNv`_?dQX>*?6b$O*P)qB z=jw9`VSxn0IPj-`_P6{|Qxp8lU;Jl&_@n=l5E4#nvd_=cf&_68i#EeAfA;@Axt72D z@!wE-V3&4!R>5!CpHePDBW)0}1jUTl;s*Q{Iwl*mVQGwD(g1$I`Rfn1D+L zrx{>xW(BSh>nxoyB7|kYSzTW_<5J@+Mh)B*$I%Kkwm75h-IsQ4MYTD_R0DZ2C2|NF zpei;d*Sfh}bxAD6@)fI8r)e%_5k(Y+&(AGOxDesv$j4Z%Y6Cl ziWE;uQui*Ikf_<_hH_mU%1a94n(=xvU&_5}AoIC-rG(1rY)dOW1$Ct-ZnJjUV_2(f z4F%rL+O;)O367oxF_LC)ioNhPt5xo$x%l&Y!L0M9f+Rh!(X4e9ma7qlGf=%A_G!Dg zGjK3Fd+H`i(OZ&}7K#t2bbD;5zhYaOo8-7oH@Wi=#YN*7}dQp)uR8^n@*u5(ky zP5>#$dRmirxt8HbPg(&^0%F&3NlATQGR{db$^?g>XN-3>m@fUzl}ha#)*3o5fw`+I z5h#3dcj9pZ>n_%5^EdN!L4qaxrGjX0c>~?(n)^L4w&GtoPv)M9iq7+_V3uQzEKrESAskx4>>$tkQ!#mG(bexU= z@IVj0Ga;0Id8>0%7Jzq==;VQ%)&C-UN;0dXZq&)2alC)zbU1R@NrZAf zNgcv*3QSXG4$>;=`WEh9-16eXft%ZFu3ipYUvKF)+CqWA5*L;jhUHxZ1^qE5 zW-}8*A}*0rn1p&g4s?Cb;75jS&-P|y4kvO-Os54KI-K#itP#%Wv?i|vmvYl`C{=-% zCf9jJ)5$ptZCccie4kVRFIADQ#@Q_YmI-~1L#k8w zth-ad>uQ6+D)24#*Rb{pZ9s5Uer~?nAQFZ(+nga6s&!p8D=;@?oHtxuZ@7DT$M$NZ z>y@f$44v~;mC!jQd*?_talN2sY-N+mXe#M^;{~!llTx!=f*B!-t?T=q>+5UoZeK7A zTf7?xOJ?^tvD+Pq(J)ODoj*|(S2auDby@4w+<9=L9sgznItQcc%Ww%)pMvLdj5gDB zNfmqF>wGR2@VWkdSpt^KIF9_sKmR}ZcYpBT*T4Nj>vw5V+QAH`GCOnv=~9UD4EaU6h`SGh6I*n>9L{f5pYt>n})5 z%&y@*Q<{=dG}dBs5};=-wgD1n&U(%oJXtq`b>DhgP+WtCJRhL5MMb=Z8VehVW?h)~ zWUMZ4s3|R=%p-l~mGNW*aJGjq=hqlD!dsX{AtdG{vcy@Q0flf54RTdB31T8Z)C$(DXr4&+Q-vOls6ac{ zv)y{OyQn4#EbnnuVXCa2LuGltc)cQL0A)@}3 zOpbPjT{0KSmoLm01>4^Hm3n-+j+y|FX|n)jGM49@t3_!7S0V=0Tu^gO>vfstx@$R6 z^ZqpeS4O4rYc9$?YWt{WzYQ_gzQ2XNQ-oxn=*Ug}!t6ZXl*D(FdZDzCejYj*%Q?p=50+ zEE5NfUdlzsLFieXb&MO!-Q5jW*VocV%!+z$zuhnl10f6LS%9x2B7kDQn|a(laysm# z^+FcPwDUn!i#J9k>1EMPCjlcdh!Kh^?$KG;j*w2UdxRyyGD93r^u494lA{ijJm{vE zV`4Y&In9xAT>_iV z$urEm1=p!^c1kcwZ>}zilQ)J9+s&5L_vHQxH$p%3GLDNS5Q+0lWG0z~;*RBHq@D(d zapJJ-xqoNCMOn<6>Eak!=7n@`+3$`VPmu_0t~{OZ@mHR^m$wWbNN+GVCd?Q~1H>+o zf*})#b0E1$h?)IyVtPEWOo4flI^QM8_!$S+H}LX1H~iLzAMonKk?ZRX!;Of2Eootz z1AA>BFa?qM-|tTx4>R*Dbi%Bl_27>jjuYeIfz5WqaJAv;ddtn`1xAoKW4|f77c4W$!y?d)(*#*8Z*q!K)pGaTxfIfByIUyFd6J&OYgVm+gswvwEr3iEW(!((km^ z0cS29n38q07YpENcIte*F2}7EG7`ZkX^A4BE|6kJ&W3qjc>Cs_Pd@pKU;XM=eDUdL zJU%>#=w#Qe4vn#E7SjluClNKO4nYBkRfoq1QPf{-6wxpvz_+MDds8wjM#K<JO0HwILsuG8#%+dO(vvDb4p*^m7@|iLg z=UE~tFF4CP5p|uIS`NXQy=q4Mye#5;52=Br`nxq~arTVz`Pi2G$uiKjjBGkh9Ool3 zgxdP6+)q7xx*Xl|Qh%;c;H_w{I3v!zcRjw78ee&q@*FGeHyeyuRkRD($u=teR@od` zT2_)1rev3`#fG>7C}RNCL9mNx^H`7bp1v2q9^lRhb7EO$meayKFD&!K>3HCHJV`=> zp!L~-m;y_j1Q3y`ra@GnQ2g;+0}vo*CJ1CN)y^EMKvLL9;PM|-U5LtRdl zx-T{7Egw;zq6)Y*r6+iv zQbHO@Ie@XcY^5*sxEVy0b{y#Xfz4)Q7)QY#uGjmK{o11S`L5HU>U3X``thza_=j&F z_~aKK@lQYdC%*pr8}`e+Y)%^|lwTJaoChxtG!RKaS_Kdma>yig{FUBbvoBp~WIYUQ zH=e8OYi@6^>mYgWDqYJuaMqL6*^5hN_qgZRU%lb0U;mnixA#obgiQ<9I=Vh_b$!j< ztC73AJH~WML!=<#O68OSz~(n31H zoFZnHI-ocOn1wQH3*Ib#rOv%&iR8Rsuu@+ZoEB{xU5sKtI^U6p3_-+q(t?zQM*S)P zSOG%LN|m%Q3{u}GEg+K6Q@p57$1Ez-&PZ>#>pR2k?G3jtM{aL#7`8&^oY=E0GZ9EB zNd4>*h)(KWT|3Hq zEc3!NPlPZlr8o)oYoCb$`~>p}mXqAG+eEH!J2tNeUcJ6y^PLXYIVN);#D(3mBTbR{ zn0R=2KNr}r3-K^%FLLR^JWM3vjC zNL!&-uJiwLgU06T@c?H`b0gV`7i7@%h@pNRrdxP^cAq)&dhj#+Gi{i&G|y zW@fB)5&^bGS|&uHyN<)ipZ_2Ki9h(?|GTqeee|oJ^1~nf*HVwYjIEng8(d$Z%yPe13Ezx;?#KlzM@`?umCcomwlX055sS%Iaj$CxD(D(yMS z3FUuFmik~zQhO-R&>0EVb{eJkK8xdGg#PH#I!}$sRpHi>YW5d|SyakGvIbR4CQckU z0baHBk-`+4lV&u<$QT7^89laUgG#np!_D>CmEd8@>%CqYBV$VTRr7r9JT5MBV^hnI zMuBQ|IL&G|3{rMhsM56+l!+p=RGd*0D+pfAq^=()?et7GPu60+cFuzYH87TQJr*R@ z$Tva*&zdQ1f~z$%lbVT9YxCE822;xn-Z!U>p{|2+-4Z;p7!fCt^{V9HLZhI88gjs%d2F+!XlY38vC}6FO+Oq>1n>cw8TosvWhdR z>a%s8zU%N#oc|gybOKCW>3y0@9llc3lPI^Fyn=F}B+HGOaxQbOL@y;B2Ft8;UQw8K z-qmw=Ud}xZBb#9(_h!l(Q-3gv`gDjB({$oE9hl}*rO3|eAI{UFKuPC8Q>GxcXDx{c zRUtltDF9fsBb?1RU(~xx`!$C#9sl*oO7^}cldTMzpuN@SS;VZCu&6Lr6oIR_kaEOfG0BShfA%Bo`ln`^GGpL8$@ zZ#xF>YG2(LBKzsY>9{aQQJPzVWJqFCdac!3%0Yylq#v(qC=^QNP!4=dfp`i8I&#V^ zF)>XOyTggye#gW8iQU7*em65s3oe6mB1B&rSP1~p~8cNjBZa|DiCD#4 zML&xj73a)@A9^<1o^kXTqXzg8IL#;Cy}Rd|Z{G6mU1XZ-J|$WIyc(XkXvR=Mojpl# z$aR6vA9&23d79byE3UTJT;IIFy8#;pX{i&vsG9B*yN5jwZ;rfu^Nu*fJS}IDc3H%_ zX{mv#Q9477))ql5YgR`tWmSH*UV&;m$HZ+aG_ckoDZo{>m4-@mku9hhV)FXl7NF|? zDm2S$;J}n;a)!ypU#gX*hFbs~amwwmIiE$M6NyjjZ41K3HV{!p8 zMoy=R$A=yF_Xl=|$P(mvAC42>yqVY?-ZBi1e(-dDWHVm#^5t*Q4+GmAB@(I*yZ~5@ z3!h~z&i}P41k~Fe*Map}L~%@(5sU)%j`xqeefz+--@N6Uuix;yzjM#`zklR|@B9{5 z+Z((eu+GzIJDYi#KplJM99>3hw9B<{)^GLl)n4KHsFe^U1eSak+kr{eO}26>9Ydkk4x1cj_MX5!=? zjz_-y@+-dh{2M<0_+vi*{7W7m9|in&9aU&0sol5$AvFt9YEyMQO{v$by-$lug*-!t z(h^<9IYZ|R*2P-u<+F^LtJH*+0=2HA1Q+x-=@pET_g6(@wSiKDEH#z2J4FLzO1lxG z&UJCp#lKF~p{y$Un)%kN(z$g0+zSXkpYs;ec5J9%Xa)UcJ&JE3_p~~>Ni1rq;WOgk zm#!HFxRrm~;9mBc~!)YfM*MgL+|et#dk<+-s~$4TdIBRW)RqDDguM)MO!|92Un zD)Uc8vr_UxQEtv@8kM;2)?i0vRERoqzA5pjpDt|n%<9(` zQTi8wVgZ>k)wXvvqr3*HT9+2h%(k{&r8G9jI;UCNfO+ZTUVpz`J93BX{#X>eqbwE$ z_lvMSmw9RDPf0vSqvH_c!m?PVd8V62(F+P4eZSxquk*AjgKPP$Re{&GZ;CZ$bI<<& z_<#OyX>{#7K78{nUv-JD>)0I)hvSjHlU*z(DQ3S6&!k2A*UmFc+P8M817pEE2o8Ls zq8Cz>8crXi_Sbl6l^_#4GR%g{^}=L%p>#ldko)cQPQgY3HK@S4dnA`?X_29go!Y!m2w zV&Clv2N|y##jezfoWu!;OI0T{vWd-(oU_*MPE; ztWb|_ZUR}meaER2(So$h0xql=GS^GnAKy8A=P^N|dRTGbqe(;)S@NPrS?cIqD0Dl= zQIyWHA`^*@Fx8T~FyUxhz~>FBCG_%OXu>mVV1Pc75P< zTBOa%EXnku*@~8QQCpvq&;y5I;Pw29ixa6tl98I<^W~Lsl=f9FNXEGDrL~tt+aN|* zCZX0ZlVlHzhuu!Zjbcn(F9Y+GNY0X@#l#)EzRrY+@VTcDgBo+JkH;%JUUNArZsMC$?%RDkZvE=#l}~HUq5mt`z4< z(P%Zy&EVZ`4b?X)ij6d(pd0Zvin-o{I6rH!tr*bcTBAUl4H$M7ytM>p*>{f6)wW$y zW7F??9v)7djt4>)a9)ay^OCuoFZ}eQr`y448e03E5QH`(tdGPrN9I{t=Q!VUJU;Mn zoT;@eH}tx@4RBkZWsJcG(MLc5FeZ~(GzvTm-7|`FmvZKOKJ%0NfsY?Q@K^C0e1P3v zvH;cuz>#8M9A}2{l_ic?m+`?8OyBxB7N?-ZdTlpiHkW)0TDRGgFFC5emYux+{t6Ch zlcBaOxdo2v+%kqYAUMTHF;XAhKyZ2g8sA=&fZ%`mul}d@#H8+ZT~{@jSplG2*PUQh zQ-9WsR9#>1IQBPfkV=)#{e?^X0!!n@vD%!Y){fR5-SZ+^9g@w0;X3itk3aKwfA?qp z^vA#O-9P*Tm-Dbj_^qXOY^a&hn$0j95h$?avMBISriu23%|)}@Evq0=!Nnw5r>Qgw zwDXz)Hd+G=n38A?VNp=C4VrDnKz?coN6iw;rfIc~)hht@4U8zGK#F)%4XWM) zkZM+sJFsUql-e3p&`cGeO0<&wTj$!=xvk*60zG+e>pWAxVQw?8Z^vi-?=_SCg`gWs z>DBjy?!3K5{VB>+`9j_OZ7`q)i%q*1$&|_&>!r8MyhW7xy=ei&7VOhGm-O@2RHj3q z@1<>CR`JMEB*0?z+H>tHaTDO$tgV}O3&ogC;9`^UD{BVcXtvK-5wQv(5V}s=^%d1N zkS;IIJ4$hwoZCaGEENeNIW4IvU@8x2opb9mleyA@e9(lSoEOGmZF%Os!*#MI`@Y8q z>C|!9?>U_o#%W}@ih}fT73%b|B&KO*9!H^==b1$_iAl4+QoB8iEig&@kS9H-$A?Z@ zE7=wB3f0v~4Zha@XDwB#^R$Bd^=EC9v~A%fCc$j}t(as5)K#_LZr-awhqv}kqHVUV zV`Tx)B}PkN29D){G2F;(-XkkZ0D8^&S8II%JFyfBUf{a(sw zyRN72cLZ%eT5_F-PMHikpR=r)Wm)k5?x(-S2hYdH2Y&a>?|6JV2mn67Znwjk$n|>R z^Go4;9k8yW*pZZA8exzyu7?{ zxy%x^R;M61&%W#F`@LjsoY4scGdLpyninbl11cA>`@BU#)i?U3eWW_VpN zrjW8xdURRUEOle?-l>zFC_#b>WXZZ2wTZ51mdqA%j-)hUY-+w<%mXQ38KY$A4`sx< zD9UJ^q3axdADFvIjT!=KVge`hifpq+*CdKM_dTWWgyIr}5fHSOBf$`Y!*vGV8H@?o zG*d2#SZ1L^Gn1_Lx$O)t6l_??<-+As7^hdTUM6tpB#P-BhtmoFAcgF%1{RdgJIrU! zmsf^yWQhye&LZmI4bEGRrz59_M?O3ho^h~k#c0xfDcHG_u&9fPbVH8j(8v1CQ*`Qo@OpDBiGA7%t9?HUY=o`3we&j za^?Iw@nd>{V(7z>r-vs#93JVr4qtjGB2JOD6`0I(p*IV_)d<{84_S@SnvG+E7!0%7 z+-sz|8CEsIO%O&MmL|ed4O*pRnkrBs;xjmpD`-|iGgKP~re#X1pQH|7)qBFA^~6x( zn*FU2&2}99{1)ui|5nUi_Z|Vk9$b)q(?00$4xCSIU9DpDAK3AMo)9e(vPwjiL`9P02`mo7=w47=$xusR%%mLN_k>Q zktIt@lu{t3!Z?o%<1;Z{2_bVhT0&4~-da)=HTL286T>huj4zb3@bvT*-go5eNH$|i z4<+NV)XYJnwy_5C z+79VU#}~$h{;QeaWsx4^^SnrJ-Z?Xk6W@LJ1AqI+Kk+yJ{%`sIFF$a-UNOeg`5JMp z&qX;Lxlo1FvVzirfDZ{1=axYgaVP*0b80HdxuPa9y48us7>Gt{54ZQNtqq%)Rj#AH zv1KwKaxUFRC1YzO$X5+YDOjT&DU5WaaOPHh)we8{7!s2OH0DyIZY?8yfs39)=Rz@c zysA;!KHs-NqZSZp3V-!ywTWWqO$&Hd%InsyziD}8z@Yn@JT9^ECR3BcH!Kv*hHt@U zUH7$vfY{;N%+59#MX8G1YgVOZkV*ql+r^VN$7nN`+t-Eyz7YaizgKPRM#0;xYyh1+ za)uSh{o-pK1GDy8*3JsDpStyPx=)JFRT@?`73k<434K(9J(~Rt+2b%$^GLb5=28l| z)^V46`P^Gm^KxASy;z1 z5Qr+XfaFSB&zlmtoWwsYTDM(W%ats^CS?V}wf0vTPep_CrI?ip9v8-WfR@9|zU`bLtL!hTS}w%P4R0=z4j5!i>Uv`lBLGZ zf)5TlDYiBli4Yl~Du+&mID)ikD%~hO!Sr0@5{gCY2imuaG;%=MayK^Ae2Yhb}z znajhFC|sbEjVtTs7L)vxqGDybu{!TK9C||U==%k5P;1_)IT?EFyiK%o8*CBL<^QTM=NiX zm@B2MjyKTigKgEEaT@@vhp)KXd8?6bsYMFG;)7{*!Oj&@p14kv_$V5^^%~Rek3xqB zsVkynbr>q`N7i}CvSB*gb3E)N7~}vI$}vT{M!)x3qqqV*bI#0hB26QiL@^OjMT~9p zX#oKPInTUae&Qd#{~JyxPh8II_eZ?j;d~$$xC|qg>nA>ce&OZiXO=jS%FKtSuj#^G zBEkp-JX5gF(-c+BTM+vm==~)id`taYGokmi;PneY?YCt%z`@>ppncCOEy5UasVcR9 zx7*!a{pYtt1{nGffwn#VkcXx?JGL2{^>zA@< z_47F=jrwP8MHj_EnP8b0e*XD|KmPHL{QH0RNB-{5f6qLO>cp*d(Uhfjx7K6lO?Ik~ zHrG}cwsdT0nTL{F>%H2lr2;3b8S-LkG}lqsWN&Ncsz|FA3B&<83&67mQ`GJlsC@!& zfJ8BvqC)G*Dy>lG3f7Mo z76jis|N78P1#x0qEAW&0#I=mYYpq?iRc34a)`K=t9r;_O>2KDWW@1V<eDUlo_+CU*Ded z*KC!3rq&F%`JgmQXYmA#){kamv3Ui-ZQr~(lW77!a;;#jll5V%U0I*IJhiQGqXwVe zXV6Yd}K$ z5_zv?|84>`1#MZT&QwydsRYAl(e}ku)>`N~`mQ5%9bMOP*dJwFv=*z*wPl$Y#({Ah z7^jhGp12MJ*Xt{n%bDx=$~0YB7O5|m{j}OA4dBGmf`)UWB06xHFVf~nvt!0W@ZfzXeb0(e$d_d#c*ATn#uaSH zIMd^u6Qkt{*<`FO6pPdWmq;v;YznpmA2j0b4Bm>Yx%HWD=P9U~p(#QqHwN#a*u;`Y z<|I+5X^iUJ$)wLnjiYE6NcPwJfDZv5Jf=77_dW4s7^gkyGBd}SSY)C)2fMu`95emS zVV%-E7O_Cpm&t5uQjO4^hhfBZ5X;Oyc??HvaH0a7W>Q&NB+pqV4i`Nch}NUvi5K^@DAIw0)o{MYT&JH$Zy>uIcL=ouwsL}_R}?1XfZhvb0lUJ zjWQ5|m(4>dRlDA^>pMbMa2{1ZM;$70;)S}C$Wa^-jHtnP&eI18^nk%CYh#*crdh_` zIgfJzXGH+3>-O}!j=lDz`x5Q04TPBc<|WDV$O?Fq(w~LCRf^oB4+giB5|h3+oDMyw z2g@8^_~EBNvBXz){ej^3gs{V!KuU!r&0r>m>B{#%OkifPi4PxsOE5c16&xrA&us?w z*Rs6TS)oR#-+i9jP4_LJzR6160OR)o^9nfSJz*n&ktDn_CVm+x-oI*%^cqOAYlMaB zq}Db?aD!N@=#{xW-ZoRaUN`(&hS=zIloFh~zug5Aw#S$2Ohm2ut!lir>|?mjeE$5I zKmXl#{O#ZTk-z-;?-?%FCTdcTT_f~KTZh!lZfiH9t2U*ow5sQ>_9L(LWoS@sTSJ!h zy}G8WDrX%xG|RW8`mQplY@dxoZC2x54@gx4 zrmR%NHdnGf&#X$?3Yf)#)@)VFK5c2*3aaX{Y9JGufqxh5o7?-|g66u`@4sfPRi~Qu zxD{}0kEJ`w3QjUs-@OmCnKmxlSGl>C3XFtaTKCM<0C3j&{o0@FfUN?t8_>SF>=Rp7^!4VKq6M%4va1?|v%u-Kx$f&faB6WJyW zv;Yc#v&;DGF)cW0+k9!+V5LR3z;vD4@|4uJdg^kKud3g*0hrbp+&nXdKnTJR?7~h3 zkA%A1bsf9?4mj|b9vcOGNefGqEbugqT!&Z2@v4cFf$R0k<#G|)?=&;diD_CG(*h-9 zi=p!!o$r-4oVE5itwF&JX+TTJwuBO}I0sD3(?g zwq{GvhQ8$ARm0AumE1JO;<{bmZy7Z}|4FzU8Z@57M_c&wPG<=1+hAd%pkf zd!C!3))v&r}vU=+!^+JPk*rN z_j~sHg!i6Yg*M83YtS-{vp>&?xD=Kd@|>kr%Pb4LERw2Ed6vkSjTE0KHe#G5+5{nB zI-yXSKH<7fYF(8g5`x1AD}Bs@^ry`xtFoG0PD+tEFQT4pWKt|kl8pC=f*J58QVQ6Z zRAj|S&4Nb6D&}xzHGWkzDg?*z)UiM8I6VZ8#{=EI8Z;?@e}0+y@yDO|?(aYI{8G4z zKS$WXhY#>@bUZv9*&lljrvv-_0fS+hM#gExWyxfwEP)H_3ZV;llkwJ5Y>}YGk{G88 z(=@PX9c?k-J4e?AVFiSaqtX_nb~s>tkV%^>wKf2Tm<-cAGYkv)oS4%>P79HVr9{ZH z_W7(el{z*#in4UE7@z5S$8PUQhfInN>_REvg0v&*P6gjNa1)TR8Vtxf{(h6hD@6eD zb&4#X&X~_<5hmL^4*iJ~3&S}w4ihm+fW?KLzVA8iA4H`*cMQYC^Wl}xpFT647h$5$ znM7nxh7@N?GD1g*s>GT_tx%}MhMR`!t@c+P$m)bvb7MgJC#?#iwb*vM(QXW>wSYI6 z>@iuK#%lNl2-jG*%v+B-AUa2lwXL1Pnk|6F4A!}wD>zmM&^g0yx98#Efxhpx<&QYh zb6mKNSFXc_k|(UQ?Dq!_M=6sKfvX^GiOfXKGsZ~JEylI3FsH~AXJXbKf7WQ*Hc!xg z}F#`-z)BJr`8~otG%lr=H(xC z-tDV_Un9M^`IT$m_7#?U-e!bX5WEGyE8N=L(q{aA3AnF7WWBB}uqv^%7Dv)HBvNw0 z7E4|d=kt~C{^5K6^rt`bm%n_^`67LOeF)m_E;i7)X2WXWdd==q6=d%~LyPF&-OK$b zw%T`V!MUb1nsT|Z2NZ2!QiKAPx9XzCQv2!FSW^YuM*l5Hz$_sdW;R*if+Z1!O`}i5 z%2JbaAVS%Wbxz-iZ7 z)!NIo9<@2P>l4sxx}7stsl$?xl&rdB(~8(6RpTZVh(+thGv)5c+Er#lt`MVVjRprw z?ZLVQqW5!L4p0Tl)}EpA|4No%`Wl3}Umps(>vJvZzwfEr*Fd9D`uUgEThUEkW=(>U zR4PCsLRIDXKByt(LKTwNK-C&pXxGw!Ub;C(tqLf)DEn-?Khus?_wBkLtv9Lx3%kx* zxrVHJdVM}@XjTXtLyw4KS_iq1OI3h4Pj; zU(2AXT>uTdTT8JPqa~y0MfO8meZ3e3C}&(^=N2-641>|Jq3jm=85T zd^?A&iC7ykHep@Hx`IhXj46?#qGa`sjHy|16u{mlbxfU}Iu~kb(5h@LK8mnKB>_^g zqq8bvmLb+IB^l|IlGonW{&4EGP07qMXXa%Qu^`~k!^e+%zWLp6_`@H*<=bz+<>~Z* zF@|Z8I+~Z47cMU^%+o|kGjSC0pE+rZm|TEYcE*x(!X?-GDdtjE;Oiyb>4VgocHK^> zuf3)31ILHJ>3HCHlm`}5om^GbRt$m3PUv1s5&@X&!f>65<3wB{d69ivH9NUg4xVQjpOVE` zr0V#q)VtM(kCsJQ-SdU6S%iXPjL<@k2OghxJe-akKXk%_--&@tdE)i;m6XoBzCQEg zPlX?UgqXqa;hR6eS6@Bxhd+GeD0dh6K*+PniX__(S z$~?u@nbZvM5@+(Fkyazw@o8MvXu2(c$Ea37DGQ~Dz5sfRd5#QYW}4OEHe#zyS+KIC z2?4rZbPc?>7%TOl^PCvR%shd$SH>aJhZD#BmEa#RUi%H|#$4my@{_oI)qxS^N~2C8 zwzOct;pln#u;=5)BOg8-`S9U^)5BicsHH+&YVFQU%$XDyyzB8M;hoghcimoUn&z3G zfBv2n3txSld3r4DcPC14YZA%RBKu#;Uj0%=>;Cl~Nd8A<#Wv3E{bZ^RW>E^DH5Sv_ z9o>HCzx!|hd;aVH=AX6S|M|c8SNvC-zc(=xs||DPnzhVIv6X9DYjNLP>pSinz`qscw zJ;x0^DP_%Wwt(770bIfF`rcNhv|VBK{Mb4^B7C?R3<-?2l%fS8=C`nsME=?Qy*hFr zwx~#eFlP;_-Hw?^iCN7MOD%Fyq06#yHt(NGi)YDMRG`bY>lUieTlm=mlK;3kkR0C{ zoEL|#I(1SrC`!5#nDe&+Z3s9sT7P|O_rGu+vr-0S4e5Owaezhetg20Ko@voLFSp}l zjL^ulvBCrs#Iu5^&3bPKGTKF1yBW}ew{-;T(5(R(`K`2!V!d!#b9&f~?P}k+*$>w& z>@PkGka>@S(qeG#wjOr{HS2M2x_20vb51iNzA62X>t9Qn-UI~n z{5N2~7?yNvcj~?_z)Z)%rkgo>8?=Ke>0VD~?Sho+h1N?}6rO_$O-k^l24$2?(&kpl z8f0m-`lR-}v^mh`Ln)+^v>$N9E(^|jW;;`rsZmXWcDY7$J0x=~U^s-HUEgy$oG4F4 z!K<|WTxJpJy<7%fUoQ;TQQHrRSkg32Op~w>t6H+uy(;i+rD^7FU9HckvIcIP3{)#-axAmc^2@k@Au1d!hn}PB4wr`5^w1&UK?~6CHK(V!6ug|tb%uS#@XZ)_y35uia44v=UbrTNw_|*e{`1bdF z^UXK>{;$5_@$mtQm5Hz{T&~Yd(?H4#yTgut-*Hs6=c{hqt`~q;ilp#!&O{TTIx42e zTFcHUdS@rdT-EB_Uerwwhrs?2a9t!P$uJqsK2=~X!VQ69ji^ZH!ZI6{*)m--)09Yy zOcIkt(a3^sBASMGV7&pa^$1qzA;pL)ayEcR)vP=EgVX~io7P&4O~fq(0eshxuwLlU zR`8zGCoPbiI2c~a(3%0V8W63<)mn*C*Q}p0hL~i$$3a?L6hD%ZQZ=0;#*vqo7e0OZ z%=s*!Ed){0-S_Ztf~V6Xr^A86VUPDRfiBaPmzNh_U!NIuQjv508)e>byDXfSz4j6JC-Oy zP!ddyl(I0#k#Us!F&2DE6ef(%#N>5j6vspiy+o$E-a-lN_8L(S;{3)SDze68aW+E6 zcLBc>kpbUHE3cdv&gV0XBg<0O=yzD{nE{-y5kRF&+nK{MV{9P=sr~TI(b*lrb@=j` zoPOXsYvbolpS$X0Rwu;STM&Ey5>W>UL2iLAsJO`npf)Pqrtxk&cCJDPYIyUi1iRf} z<@z!$YX7C{Qm|X98d)p*BOD)Kf5-%1sd)n8ms!4JnfdT|;qqZ* z-!J$>VVme%$HS<-twAomFTJjm6WK^3a8rbe>Ac0a8fM65VaX#)mW={yC|=d>5!Gml z6C2_j&h6-Toz(m$!#K#eUM{bAx1$RWI2Rw#QJ(To%k33{9nta?Lhd_>ucT6Ws<%}KVGk|ZlEi$-PTuC;3k>s zTM+!_{_Ph)u&E_JvI)Ee5AqUcptk3!*$ELbnP+j_F0T_m{rnR@{qz$rFE1kg;aqD^ zlkbjetQET0jTe7A24WwK0KZD3thCCz^w#MTYyh zLe~FPTb1R@4c->bfXZ$SI;dlwwL`N5Ei3dL$L zs0A+8Z>i`al$_dpYNLJ=L|Mm=vOez=Ya39ft^9m>2DCu^hM`r&UpKa92ZIVhIf9p(TVYp7@7VorWe$oq(ZW2D1=$Ccq=i zgbnMbEziw5EtRF0Z`vnirDm71{!L2oq#tjJ%bMXXMfC_X#%0kTa2c$EVVkk8wnLH$ zky8;ZCTH-;kb+Y|F+*HLRlC+(R{)G*4O(j(#A*~)H?1-!R0uaq!lRDew8--shl#$w zu(bYeq*XpEkz!v_pNz%30czeE=jh!(hY1D z2dfiWz~OYn2hW@*iK6JU%s5g3Yd!t`!0uQG=QE*;^u5FP2|Ee^E~4weqI*O0jjY84 znRt~-7j$g00^e*R%ba+<&h)#U-O2Fy_`vZ&>Jdwk-dcU%^V{DhP7j%Bo>@ww>pTx% zKj6LRd>)yXtW@U0Wf*vQd10JhNhuQ?^t%AZfc2i33sYQJD3nopH^07~dHy_eew|4R zgb;ZA;OQTa91oA2j*skuv@AKF2QHUERBMf8NtI$E=TFfIHNG{iHq`#Ag-9weX8|jK zj&;J#5ayZD4iZ_5k$E18TEy!**tw1nM7+#(61ltNk#Qc$1(F6jjD_BN`aa-$p;pY% z;JScIQhO{Q$HU@XgS&0m9Y!yno%$BxUy(0Jg0Uxe;>NY6xhE*BUsFi%p>u`B{|bB5Ew5ITo*f&DIHNX%0qI7iNoWhum{!3x$f zU-$JI;oLec)jh3_M+FHY*5$oelxe#1>GR0>T6lgA>llhU?fBDb;^LNj)9#?APZzt$|t)Q(534MOQRLg5xCim^RZr^|J zbHA3ElFt~WI;XWH0ohw)Ow!Wr^_Az(7e0Ub#N~V;#e@$kD5xs2Tbm(kSJwD@!eO=k zt?uL7b~kHe|Lz_t*s8Q9V=5YMpS#T>m(6?cfpDoOF!uKS^*UH>(e`h3s+xNIQi&-?Zn-;P9ibL0QQBK zoY&sW!R>Vl=yGgFsF|-f0hskWu&z<#?5fmTGnl5Z&JKHH_bV8w42>K$QDWEeHOAnz zO<_?A^A_~fnq#@H&6wzX%L+=_1m`M1t=D35Y4^0=x7haFeDe1L*W2+}Us8XXijKSb zO)*v9Vin{RO@Qdh001BWNkl_u!#t|2!O!Fiq;$C1nB!pqAG=kr;p z)C!8HX%#A6V(n>L0cBNHuUaia{VgpUD-_|i4E8++U1@<&ZzQSb3@N#m@$I4| zC97HJYS-0HXVFhcO69M%qOK?jL>KiRt1U6w9Ydar@lIN04Wo3D>2`Fz)QgM$(M~WV zfl{<2C~F&}eJ{0jT@T08iH}b`Uw!qF!@;QlP141#|9Yjunn<^IeEr);9_Jl6QC+pZ z6M$wVBRedTnHl0JvfA|-RAopfH3VJgvCd+mR}li;V3)+=7nY@n;+RH-GFmGWylw_w z(&Cf!5uV1GXo?Yd=vwb+gTXjGE<$fei--*fK=pJ1_F1yA zU06kLvOc6mi{?ehKnnOprP!-%_dwS{o;RR8i)4^BQp2#@?dYBKD`u9(XeL=)IY-8E zWR8WwE|>v=U)WuxX3BRDl11M+`u(2Y?VcoJR{|+U7F}scn?+x*qh<$0?tB_&hH+w! z5Wv!cYHDczKb`TGuU1;{xdgXCTj(heII7g<*Uq z=PZu5QlJ}U!a1$a7J&{^`TRy)lT@lIsbuQ10w92F5~W-zvtjHeO!h2uB+rr&b51fn zK8Tu}b+xWwW*o0v(?ZVRIx$wo^ce3k&J&A_eT-41)Y-HhslD7ZQ;fx$St7rxZhSe< zr0Hj#Kb>)OSmW?!k8^=MIi*v}=cTcGjm)p2KaFDJ?kQe+|D`}mt!C=}wFSI2fV7P? z){SEYvuK7vSQi%8BCw`82}Kf9N#d4eSzK{96ddmzhy6iB(|m_PbO|n(E3eOIUY-SPN~<=c zw|4K?*&gpYin9a{WpC)ZBfI`2J$P$vjgH@YPTmR}MHe8ZnI+D|ID?IN51|kAy`|qd z`klr5Ov($>dE(`Dy>9~q@96s-edzJ7C)gc*7bUYD1@JDj;dq3;JJ5AKh7Myo>3=;A zSR0xOWhsbCcuFFU$EKh8JM-$zT-)6D8<6`e;J9UR>Sq*OzX6U7Kq)P@)V4%#*Tt{B ze(m$N3JL*v1N!x^IwbWPw=~@^pXWYmfDgM4Zd5vr?~V+s>sr*>7p4#;n~MsM(x? zR)^(Q=T)7?nyr-Y%5x~tf?w@1Yyd-@Gqih>XG9g)szOfhKA}=`liY*gZ56Cx&1g3V z6R35`hTAO1o3q?x{cEsH)OJG%91aIQeE7gO-~5)3Up;X+^oX$MLP3N-B|}`Pre^J1 ztk+UCG3uPG&$tE_T1K%wpR5kET(hXz8eCqXe+6{)xK&gs#zdTB6AH>DQKLn5q{Ufx zO$`}n_1|0Y^-F8S-hIA}Tb+9?%JH6UsR68YKP?-ZQD0lek=0VRT4-LZ_N{fds=Bui z_no)enw9aXd#6!0S1Pm`(3bVnm%D2z2*|TG`n-~?laj&O(lU#t6wO4Vd!@_+84Ep5 z3;qbZu=XylpT60o)!&g5tQGRxo37w9r;JI}U*7mFt%jYIEnuCnB9)zEHB;=YZ7dtP z4grzb*i}fc1qRl+)5g!N_g1s-i?%5=bF2>rYX!S>UEhGQcR~Gv3XTKE2dyT1Z#z%XhXjjc-JW)qt- z>)6n8=_16X^|H=+`d*VzD)g0d61|-~A~a~pHW{06-l$fHmW;M|mX<&`@ymTNWN#_O z3CJy_wIRy6G~g>i+?D;1OChNqf$(cKKE6KB#^g(hv`EQMjFEX-@Z*SggJykw!(lSd zT^m#1?;I&*Tu3+)FY3F*3 zvxL%-Vk9HLGbgJ6M{XjPM4lG%H0!25i<5qoeogpZsi`XaZG>7O&Mi#i!pqAGFP~n8 zqVO6Shml#^D)oJ!bRM&p_82C)=0xO;fyX!nr24R0e_;^?m@J%a;_~cx{<@cB9G(clW3^3Ey3Sm$ zSFYzzjN?Si@_A>W3j$R8{Z5)gANGWx)FyhFE5%VdN2k%WB`>-_EqOMK*T^so#8D!A z>erD9q^^(_3T74&waW{<{P@BTe|h1<$M1N0>T%YR z@*Q<|Xsv=uqYAg$o+!Z-MU6bg$kJU1VZ!B(lnZVQ zHk`Mr#45IRQyO9{Pwihr)Yu@UA zZ#ID@Mpd0LWTV}F_a-B!hO)}w=h~A^9XeaUTf5fM8L8t)vdgs0a0N0o3sVEsH>9z$ z@f9}v>>8El&C43_+K#Ahn6(zg2T#`Kl5O~#r$n;)n@%IPM{@~c}16^lGNfeC`M3YOeoubC&FrqK zxZCr|+Rdo78)N|ef;&Su1`uBSwEU1o&0-lY-R_A*i%WZbAW}w=!DJ_^LV?wic zH-Mu#;Tx){Y`I7;;@L{z zmK~$Dd1S2h9QHdte)WNGzx^G5`0L;E^>03MIP9csN~7hqO-`+WG}ORBp)`L+T-`0u zZ6GY&*7j~QtQpBtrd+@jLg-eYU9-dW$I>X7F-77MNy@TW1EkflmpLE~Y;Nxxvx++1 zk5erxTay$uP^9CH(uDH%JF9(J*K{2Zc+2dl>rS3|{qLF`w0h4g0J&A6U2D;|^X0ad z{$@{9YLk@l>AEpl_rBZS%x%7#+hYij*Q`IcWejaCZUYK!-E24A6%>KNI63xxZ)w>i zbq}kpmD(S-+@;&|%bssEt7-H(*Iv4EzpZtt-2h-!N0zy*t-xBA(_)SG^xoV9lt!%< zA4s36W?I|5+FA;s_A5!fRg9T=ifukR=Nka7J$7qNe&6-%`W=rCk75;)XeSBy9o~TA z3WTrMYs(l<)5yF`5@ghXABYdHe0sOtOG z9;4KCXM?m<-Edt}T1YvNOC*;CX@M6NtQSqh=zK&d;F7d4h&~fHHl_wV(RC_y&1)%- z;3i1`Em5i5Ws}L4L7)aV+pnsKT~cOo88^>ZtC&kA4zUnEZ!+#H93*v%rHbS znPJk%hcg5p=sT&=G{%tfOxIbuZpRWGDNoGRs3v(>i;8iiYBa3HyN;T9ofdmf%8v3N`XlsxFMZ0~su&h?<~j_#{QSz#KY!x+^M&j6LYk_P)AmSC zBBriIP_+I@Gngrg0Z&mHEGG&nCZt_bY1C$iMm?is3cDT=bLwT%B|U8g_S9P4TE97W zlnlWK_J;+l05;8XEh!1WbgT}G9L5oXrQ3-JPg<^0z^|>Qyob}N<2PR)`OVkA;WuAD zu;1^Qmyz@3mDiV7F6T4jqQ*%@3S8*0)+s&QVsi&E%Co@`f;9Jb`;mvkBd3G(W%EuV zXennd*MZ9=GhAdc_C177>nBgpcajl){(0f$^FoROsGSv%>@0*meEszk&RKT-Uivr}$q-JC< z{e+FPl7&u@d6`+}q)pfh^Cb7RwNa*u3QUWLz)fs{}s^nT)!}$vMZhyoOFwRLJm)Zn)NU5y@^8gbkRd{jm5 z7}w2Y{n~P2ON>&YN`t?5&mlzKzjgof>2j$P!_?OftDSGL_}HEHK2# z%j#T z?0zYGdjGe#G{Y~9(B1p@6yYz^^ieeaiEm9f%9)!wO%&l~z;v!z?7{hikhXe%{ft6HO__8~TJ zzQ11nx=O#aR^_$Qu&dOLWO!FFT$w;-1A?~yy}g8Wyfm=WvXCO27djD)Je^J)_Ivse z=t9l*sv`6jByDPOTOi=(d@B%YfrnBVJL?)P`bFtkuYfj3F}rTlR-`~}ex8BYo@e{zL~pV65>;f zdV3aH@ZC68?AmP49Wa&vxxo}m(O&fpZ?|AuRp(avF}23FCP%)ok(YWt4TjZcSBlgd z7tIutwG>jnWKnpJCa4P8y~;C-YVUD{JR~8W@uM zPZ%@n=WMGd?t)~4D~;JZp;Pbofy3dbzS3%wr)jzYzn9B}*Vk8GUtc(1UYSM>PRIazfhGLiULzwKuw=8RCYE`|OsVNc)pc^Cby2GA z*Ey03*?Nqtwb)91*Nie*dzu@;1g04LE>t$k|BP7>)sX6Z{Mj9hKS7qEiRm{fwKwJ{jG^rtsEK?L= zCN(U%0{Ln@qBxz`GkpH(ipe4@6^+&lR@>ADWDY5S0@0QHobvz3)?)bD!shdsyBk^SL72!U8e<~Z@`GZ5Znwi)0jm^8)Pi&uJihaUhXWrzK5=~N2;PAgfIbcv;v#{MeGiA< z!hR1QPJ2Fn_`t`n9_jjyDT*5P=TFak|NX%ExiBv(?B$@}LyFIIUB)@jelHn+>wBSO zLThOi=R#a01Dh2vW`w@87y;B-er^D+Aopp47`E(c6kPhl z)xOokI57^1aZqr($a+>b3s&or0x=bgmC}Ekz`BAj1?QyISW${pv6k!tctbLoSQ0EU zmrQXuw)1p5mu^2)=icV;Uka9d@f`PGFuIvurg;>IH!)MseXRejGx*}3YaV)1#w7A3(nq&J2gj9SSc0(i77^|*MZN^ z&%`vdzxFCVX;mOgsf$(|^y&;21s$HoM6+y)+{-&9;dUXPXv(TAY zsm``a<|FiA7d&18`BvoSK3GznT!1$dpFWc|0!IuU?Z_vH`t@dBdF>L^GY0nBO zwRQtib*ySzzf}FbQo&TEIva|zUNE=)PVGk3w^Yob**6KIt)i0^jJ_A(D|sWzRgg?+ zo1?OqYyq&hHA5=La^9}tno=m)V2fzF+>dKrTrw{dv#1|Z+iGo}TJ;am45QFv^`7tS zttm8W@4DyJctHJKSOAn&wY#zwvI^qF7}sMW!A-0Fyww1ZS5Y|WV{UJH=*nQDT_RXp zqcyQNod?@C6b1~n)McwnAb+0cnbD4$to16g)p`?qQEB&HDAmW~k*BApwO_D;;>+dC z^?G3(2gY$?90snJSHUpXE6cKIvL{Ke;(5MPd{!0Zwe){|4%_+l#t5!^R<+sI2)Vq@ zUD4So4KEoRz<7-DU<$=ZO<$q*BG!OLz70M#p}92@b9X6qAJx*0ylO3pfTPx4M}2Q8 zO?^AXC~b|h*v-1{=aMlI!G~7YVyzu6bw8<@V}sv!y#TDP(DyyYCgQR%jzVjmk`zT7 zGs%S0!L^9$n*fA~%RH(ouquaIseg?%N`-8wY1W3$Q53{FFPS!Lf^6^yQI;E%2tBxc zrt5p0%fz^Fxkk8NndgyVxbpn`iRb56#sL;-3#+e$F$qtW>|Vc@$*N7Atry8`pGDT* znyAJl=>yR8eDF z*Ox2j^UN?w_O*!Sp>-?P2msER zRHBSCviPPkavciuCvf2Lm4)mu$x@U~=B$^d+|*4&3|!6vq-*_f zPU2KqOKbPlB7vJs)t2hC-Ine_?ER~@GooxZM(3~^so#FHIk8s751iH$7eJNULkMIt zF)b90@S0??NqR=5(%iq>mwjs^*L#B&U`%>*0qNIlBr_+qD^SX+TwH7>J4-S})*2PKx zV?*1p?rA{QIzr#G=SbKa9!pOukHkDM$B~$%W-}K@DGMntq?kl7F4Y=P`7sE?poq^U z<5i0Gc3qS*CL(ga0~f4BT$56cOktiTzW;Gz|2KiJfBV4W(}53bg+2P+94L zxrq3YM7^b)hUO@)*Y|5|iKa*1!k0HVEN*|zbj?3CO<-FlqX_q5ifH3we5dk3<&nJ_lM z$hL949m@*H+wb`n9BngQH)GyvlvjIq|7uPgTPo}AHI!28f(0(t3}vHA7lE{;eSRII z6^Mv~P=g&lNC%9RGsE@D>#L^}>1iJn0CyW8Ypn=^m0GG&Xy8u(j@T_{wRFt6Hiv5# z&eQ;=K{G-|&|M2YRlNaSBSl9>TY}ZOWGYDAh}ql=sTnNZRz`q610&C*UTeLc3K~nU z;5%+W+|5DP`I9U7y3HoHAdb$rw#`%kTtRc)@2cokd!~h?;9VFz(!R0wW?oyy)l7M5 zV66#0Sx2@G{APYBi>j?r^^>XBQv*^>XSR^- zMw4>d9?ZGcuQn-jYpanW6y|z=>POUds5WDrZxvYT{-(gN&aqb7Sf}3h85_Bl5CUD_ zHTCH#{#6C-N-4zjm8dR9!CTUsSk$G@mkUG97+-VB&W927h(*haQ&RcDTWz5F8YunnY zPf)Y*^>;}M73~fqSZrEK6C;a@`am&~T5zuXzofnCnjFcEEqGvyyGP_g7E4k~Jw5lE zdH?6>MRT>adXZWxR*}ri2zR#y^82g-KRRJ`V>Huiz0 z5)LZb;m`l|U%0=!$KAaEy*Sk_e!*hsNulK()oa8DXq1bsB&^pJ&sPzi;0 zR^JVVQY+H6pp*<>Cisc4Of&9J516&6_)diDx+1MCo}Ed``;@XH(#L1qD-J3FZ{eQsPBB#fmz+Fv&tv1f4o9#{?7=bddK-${@>YCWjbANNI{f z4WFDuEGON-SiS1Wi<}?c0jKE>IcLOh!u|anPJR&(QXo0H z7b(Q4>?a2%QEBf{e^&L6lBGywICCHrDNm>-vH{_nKijs|0xx%Jcj85#Rmn9scg`e}-TF z-Fw{M-yux0nTM1RV#etVeE9wZAmPK7bm5AC7h{r~7XfpPrQTLWH zZJVM-gWJnE8kKC+rCYUC{hadJ4hyEEUdy^uw$L^f08QX35BDY%xC-warYMdap+*2) zlK^YdGGKTE2oHyAwiqFt0=xoVCRU|X2j+q;XRy-qOiV{M+^TgZ3kX$H9xAYlx4)zd zYB^&LfTsxOD!>KI0bIS*dfttSQ_#v&=!UrO34|+7(-mn?nqMiAi`&S&^$fF=^~yOR zr(Nq=Z(!_T()>A77bR0c6l2A+gRh}&#F;e$rl8k*$;qaso-R@2!U?#El2vAaq$YNl zJjhE)pUd?NKK}S$`0=N|VxA@})4jeYQGM_X#}(d9ZTxnFjt;-&kKylc<3U(N=gqg& zi#v|R;cJ?1bF{g~bM?q4+C9ok>NOY+sZ)R4u&s7IV9}}mW;2w(k<&XKM;hkQi7>uC zM$%eY3yW6ef_;;+Y+t^7!Sl;A)~l@7qbL4ApJS;x$t*P0YO%f%h*pLphw9`RT@z3; zz<-SJ-Ih@TBr+yWJ9mhfSk2Cn^4!6Ts{Ic@(>_18*=;+0ZA=YjAjS{za31=~m*0vE zYdjaP5VZnXT}?rQD4N8E^-A9u*QB|&r{#oYkun}WcEep9=Mu&BAvC~cPe-l;ZKF+& zEy1w5r};4UFg}k8c(tGyQF|)qsFh{vbDY5yC?xA*Ed{0JrPl_)ZT^qI$7$W|rc=xV zg_WE}!qxHdl{LYl^9@u{r&*68ko~ufmqC?ZhX#X>pKsv*c;s49xM)gWlu~hCz!Jzc zquY6pzyQS_fsY{~muZ+Y_JiYmDzyP~t~NtWlS5PD%(+Au(vOr81`-3ra!bVdZbhJUNzN~!Tfv7ZR zMsvK3`vPg&JgHrv&XFbr$bd0DZ2xmbz-P{clssGzjMB!D69#AqPE!a}a22Kkq9dG1 zbyB+1l!$vf>wka&Ws*L!ocdhad;7j)-PTqL%7+e&yVFFX$MZD7(OI39?<{n)#)Bsd%31kkXdQd%HmCX zRt!rzjtv0ox>(dMs*LbofB6fx?{;i?!ev`A&7!92TfUAHgB9J|F-|~e0`s;eTwYe> zD)l47BmlNJ0l&FQv;?bcqNj2~JTnlbX6B?IHA94UYRXDK&hS1U(N!YIybA3)U9nzw zZ~>wRd=vmoB-CDl7>R+T4)5uF!m=!~h=&M21u$1+n4CR)XOi$tJP#ky{|rlfV*Aa&TD880u4 z{VLJlRySD}O;_dh%PRSh+g`Bm8EMaVvDyByudlXs3q0j)ZqoaUT13C5ebr|X(C?bev#p?HMlZY#X=@Ag5I%i>kvI25x zE3mYmt&3*B*fJS{!`=A~A3l7K_wOGt&9Oy`nG>F#zu>1Yf5o1z@V+|>`bI7=>0*C_dY|Voz5TUcr=5X-DA=xo+SpnhaKloB>b}HE!YpDg~Tme1c_D z^TZ1LvqXNiX0q52mMkDZgAm|dP+>9MaB9Y1{_%IU0OusRkT!%rWQRptQ~Iy`z}V~TJ2iWygQlhVt^NB6c!ef*!=1^(sQ}N1_65R zw*9{W7W8%T_Ff1OVD|=2zU^UW&)C{x$gNel)tx0Wc1YXIK%*Pl&;aIZC&=;2;xzS` zCnmd-!0AC zsMmI1f6JjJ|Ij`g9CEhTTb`>llti@c{J9h)i%e?1r9`A<28dpQI$f!^ztg!c={EGr zQP%oSb9KR@WKIg!s&-a)BI){WbNtm>L!HS|MMx=8x^Y~{za@>yV_qiA)7+x=7{(OA z7+$JA%?xl6=Z*~!8a|`Ks8)k}+~=5CB9uAn_%LCw&KR&<=4ho?y@-9yv)KQD*cK@z z>?tAb39021zu@Khf|r*oUM><4dwIEF-PWcHVQS;e(J;)8zGWEz9`{GafyqM9JqSRC z2(2phA0&qG=(wrXYzu3CWqB}~W+An;X3T5v?I-J@YwI3E>=LE`vs(ZN_|;%btt>iD zSt7%>#>lg4emkNKK^b#}5km9;gzCBPD;QGOa|%Wu0N6uleGU9d3))0tuE<=mmx9X` z0Ctf7B(GPc+(Hb-rHHz2B!^567yklJ4(lvApSyR$eOeE^p6zoG|DGcb8zo+ZyBr;O_gY#Sr#fIXdnWtqjXKn1C0gkn^^ggtLa zWyfB26lA~^OmV`p1Ux>T5kf#p6ZY+db=~m%vI@oTy5f4hB5e-qTBQ`t4(0!M05!1q zL~~EvnI6b@2s(lI>0hj;Ja;e0+J&XR9a>W0(j8RQEt>oef5k`oKf=PCt`7?}pTZxvQcO2EFYC}~A4 zF91h)r_2*4K#^JM&1Fj)kN`1C78XF-0p}PGXH!-^Mzxx8Gyvev{zdBWNy~v)UBx{Q7$Uiel7vCz;&`ITE43VPPyou2;6) z%m$o>78(WmMpafeASe;3771eR`K!%Y=hbjjx+hGv-tq($+30s(=bFAgjK29A>hvgy zIYy3)KCQjG6T;eA=}5`mmz1Y+p-*6c8wb0Sby%8&|XeSf=ba36W4 z<|Yg}GBms+M6HD4wZ`-`X-;u)SQe>eYXG)ZsoT45k}`R{URz}N`S}@_%N5u4iuHQM z^?Jp&?~=lotya91TM}D9^b3TEA-LCp+_;`p7<;f39k&iTevM9V;#9fqCAAV<^{Bpr zS-}0l2?u3|RE9;dm@}NxIjcHZoT~uYN}-V_NGUa|WuKJ}-WUmNtz~Pp?AyLE6s&K7 zaDKRh^8%(aSCFFU&C3KaDv1p^t`*feq#~ZaZA-YW65Y(IM!N5!f?TTr2eVmxkWxK? zNIb%ha6ty=4c=E!ai}ip0CuS4uZIz8oy+bWOEGj_u zgpxD1u!63PwXEPIREf`@KjZmxLE0EKi73>h;!Ke$LI?;d-HlyT|2!p8!S)F?1hAXH zu6xA54%0N@?ruh$B0y2Skc9QRBCk^K^ksX&)AJLaug|z%3a&e_ZervEBHo1nglST0 z)*T#qaG7Kvg%y}CTUkKMzISn|q5xQGn(1#Z zxus5jgP`^4WDJiRC@T<0wSUXFr)mbPMmlX{HIxnXO;#tZQ2@CTs{RHmops2Ma=r`7 zRAx|BR0b2Zkk_brG6j8i_1a-0aRiUfau5Yoi=Hart5&Ass6+{9?!^FrZR2Y~BrK)Q zMDAW`y9Oq0Z`3u(IUqP7sIy7tu`)Q86LQY@^yw3xo}RSiQ2@D&ZC~NM$284a2U_wY znJO|0$Pr76;mf71Bp6wt(z7;)-(mFKdOqGb1VZV6VpMJcmWfS&?faN=-RXZj&ZVs|qz=a;&>|$N!KtW?X=3K=# zF1zlL0`$ltq3v1J`NKEsmp;2Oi`)FQ7BqEZ^A>1JJ9dZjG&>$Wy2ds>*~E|}su^O0 z^Iie3t`lv}sjXnT2-em^US-b%e`}rY&p-yu0ThVskV`s%-4@|(j;_|z&Dq(|rsnVJ zc6_w2sITQi!#2QPD}zu_s;G23&tm5el`F=_Y2~?!?gQiX^xtEeLUR`}R9i=AyadMP zoK|>{zGozM0m~9__GbhiF!>2CMsV;* zT(B06##UQEfXaki9rjEbZ7IlAye1q0f_Nq8S?*0hfhM6x5rm3f=md?{sWi<_pYbR; z%R*8~!Iew^9~`2F7KOIpHMdi87%LUz>X7S>qQ=ea#q;4|ihfB3TyR2ZC@+w>X$B*q zaK*Z1JU;{bGk{&!1eXP+WdLr2_rNp(cMI@vA2FXK3Oz-_`5bY&n=#K3K_|KQK#UIa zJn4N)Qhs4zOFQjcvCN_z zJuN!<{Vuu49~{niXT)V!%BwgdbE$ZKS@Gq|Gp<)g%|MI=z!%~BD-EQm(;-YA%W1;A zRb2NSSl6~!FeI{@vg84q1r!;uTzjWP z_MGPla}yGAQmZT#@tAG}IWvltJ*tvpM@590Tq)qfAOuKm3B(F?PNTo-E!O-g15pG5 zd4eZf1SiBW!v%dntvOqiCM{kwSyV=YkZa%kZcDtF*Iqyr1G=ct&1cNhF7r%lPwL7( zDrrg-$w{ds$mUp4WK)LD@vj&q&Jm_biq4x36-UsAd@N#{|p7sVlT$FN1&KLDa ziW8w0LfHzC015zmh$^@NR|DZ~JPCz6c;K`|oX=<6o$ug0X?cQGyz8anx+YvN8T;PX zHc7vrHt1f}EFIbrFr!!K-BA@RlP=)m2^V_Lo^}zxQ-_<>NrW0itYezsiQyeks7n-? z-C}y0vcW->(SaCAN->=uvCL<9Kf}Z?9CCjE3RsXwUe*kqXB8lWmj44c*cKqgp9|Awr?wSHsp3Oa6X6_N$G>+xxgZ zZt081h>^_pPU)*EcqRE|MI+WZ@A&cKPx$R`e~*9qr+>nq{`4n=81S?2e+J+r2D?^J z=vp4Nfz}R$>i~iYZ&8TtFwF-uLfd&>^^2_&CJMtXWomrRqPbgRZt`tAi2?cM?F{F# z`{=KIt*v{`r5pwrjD{=UKi-3($JVb+(5m$J8%P`?3j+w&JA3tfhrb; zsu-Cc&9>l9eAm>j z+prq`9>=XC0(@u0h$CJ1{vwrins}NrSEmpW;y|O;pqxdC@$ewgau)oyt&&H4xn6L2 zxwM+Z>w3keWtZ0VBHBLtuH#bIfMVlT9G>#Lw%*$7MI0R{E%M%-5jI}B&1iO`r7SRI zeP4w6gy|wd4={lyOGy%g$C(Eo04ozi(zbN&sTd_Q9ocx*7)UlJe6w%Eu4>DbMSO>= zN=zrod5a-nt}`Z<=#a~jLwVgd<(x~n!Mqlyvqp*`H^wTD?^MP-kca^IDh-l6u-A&5 zv}mzKn#r}24XlMYsm08b~)pAi6zT%~-7MdYf0;c>AE zAs}&q2Hx7@MAYk&RhIg=xw0tRI+?7cW;h}wI8d$dc8y%I(}n^uYN;kT?{S(vJk4+! zsA)slHvG5)d;wad-+sLO1P?sE1Ag_(5BTtl2i)J^X}#TuDLD0NNFG2?3VX^Ma*@H7 zQb4X~671LO1((Z)b=8`-MT~3jfn^r(yUY`&ICY8nx}#PCe1xB8_(=e8hyh{p$Xu}Q z8?N;NfZ-vcTrba8JUzYO^Jm88Dh|(S0*F>D%LU8%jPqHe^^P%3GR~G05HD9mpRqZa zpjlZ4dqPuT4kAnkE&_B4=psn&5`ex2wcTh1-qF zxlx|Hrw&G0jdCzDi}$dZhvV+@PJe^KhP79)rJs$w_5zfm3U&ck43cRxuwUgX_!%F6_zBO? zSFCGo&ntOof8(Hm8mbm69fV@gH*z&pWL{h3K>@JW_A{!RvK73hKfK|5?;ElMTp;)< zU_PDj-G>kO?)}ejKHbB+2-1>qtPBa~Ccrsdw+%1XD^BMfahgG>y3y#GtzL5n*EarU zM2&{Q|F5Hu`CCb{Quw&fA}NzeaDCI--{E`n>AZ? zJnj_aN~1KRn(N;Cd^9 z-|i1@``nD_VvLsCXBt7UmGkJIRfh}fI1#dTLqcM7y$05|3;+YOw?FoIyIunokTHGh zcxV&c4AllC1jHWBdGoXlG%Gck8DLYyrP>@B$NST?ikmqyI)X+JcZ=3ZMWe=2JwP|K z<>U zvm>?sDxhQKm}5O&cGTWrO;vEtb>P)h%-x~g!9dYcM4l{?-Nmg+k#G&yiqh1j1(dVp zUb;Sxf!@;sVhN7>HLdKD{mm*$)C9Ynh*7zrc6C$y*7qB(9m;Zz`RMk@t@d;~WN$IS zP7#|D4A7~>s+diLv23K({mr?TDB3sCoRR&$z;OjthtWaO#xfa8!Pt4weCV!vKi+2h zr|ySR%Ue~FVf!ODaBU70W(kheT;P&Z`@kRaibtVA?>yoXaXOvw`0i13SyF10>1`E^ zux?jzY`=WQ^Yatd^@@~sq`Yfw;$4;3Ya5&9eqj|jvs&GUl6bYY`i}MF-O8OoiNWH^K_C@M_y|CN?E5N6{R`K<1eU z&GRwRFZ!hJ0HH90JRx(1)9^~IvZ&Oop4P11ax%Jr&`Bm25a)pCBjPk8-Upx%^7R>c zd&ZNNav~?u^wSKS7AbS|a6jRfzkG*Z{qh(1#jn1{!@~o@+{*@}eaHIzq*CcJiMK6l zJIn8sSrg}1TrV58H8)jbK$Wz;MzwUYv&dIC1Hfl_#_M&%%jHGE-lVzSjDiC13Fq?yV#2)acz>U< zZyDPvRMwgVuwGVG6;^MWEc)mh*{riG-gP;O-2Z zPNI-~KA&+~M4%)%hkf7S-Go{RW%t;(g5(nRB9UNOz^q(KK~VX4f_VxBp!a%na^tme zz0u~45es#*-C4iTzS z8pYXYKu$L>8Yn_-Q$6hT^3&ie0ftPOvqraN;q{?nA_94a%Q7D2vsrTkHD{LfeiRAj0kt|(c+@Oc65&jI)6fb-emdQM_Y&k^$yv8P?ui=rFe z@KDEyNk1f)v45_ztV!E0=>e&1D4cZDQIEVM8QWFHJF);?a!|o5wTG1Xz)_l^<+=6! zT4?40h?6)}EG@)9iO`Xt{UjcWk~6N?6^@?ZD1vLiwq?xoNj6&_`*S;pmclLAv#Ly?RULdU7*{*0sv;GV76aN1MeOD8lZ9GLUZ#dbQ~98 zvCM7WjnRqPj4~H!N2|f-|*{y{%8E_@Be_O&!2I3zQZ&HI8R_MLXT%| z?Qi>c8GcL@>o)2opB>i)^YkC1aJSDTbj~A?8=rSne73s8Ew^x7Uv8qs^`=M6h##Yg zZwYa|b&xvaz7|#f8W4Z;)gf2dRB1Kz+Q)eF?2W+m^*z}&%*Ub{sV-?&%7 zGxi+aQD70t5s1sVoQ$t3&IeQRwd*ixWn$e=wu=SJL8b7v|I8gj? zEwVLEPbTL&t{G!{yor_Sjibbz54Y_@XbAmiyE0UqxJP`gJsBdxIXD32+MQNv4lR2e zQ)DM|DB64<@7ea=VO;}^7Tq0=x6fsoT|5XQ$#qr0ugH0=98U*_MfWvxyjd9{VTR80 zj1Xf}Bla5MCiL|#7sWSwQk=6(o%JM6c8eO0V~2DfcX~eW)%oI8)QiQ=>q9~Ne{cjj za?L|yRXkkV^K6dv9;#rl2JH$JxFUKOESNSb=LwB0PJ!N@RH7 zH|+b0Z4)|muO$!kIa^zPcqv(blv%6vcS+&tRQM_r5ionVvIZj=tYg|~8=BsLsA!Ac zk(3Jy&Dk-|MYJ}Oan#u{HY&|F)AdT{BLN88wh2$0B;@WnH;SNRh6tqWsC7fm2^KVU zDv9sC0nQmAcz}#&t(0UR+rR^W!X7Cn>`pqtF$-u!(d2yy?N2G8oI0lcOaK5N07*na zR0|w{B}#Jm{autW`NDX3c))TWG0!vn1RaRJbLTaep=6QDUek`tDs+JLase|7n4V_@ z(uj3dVVczQ8qM=YWRbf*x2@4xdnofgcef@N87_u%mE-6I|zPa>hNWu~YS_MH*q8Q}_CFAmSo z8T;1D>M%3*1YBNLTrLSOFFU?GvrvGGP<|Hz5F`>x)XN=ZFKsc=1Q5Y(8*)n6_9txH z1}KA|xEDAg_$c*Xy_>)lxIFLp^b_OxS(x4aBu4t4fa_Y|Kfg##;}~U)pnzH!%M`JE zc#rUNuO(S#8A~Ogl#1(x@#Bv_;V=L76aMR4V7ZS%!_~TfQxwly2m$0IM?Ls};2FV3L{IR3 z2Ls5NrECB>FnKT>SS0j7OyZq|dZ)NZI{M)8cWprrQd-Q1=IOH^Q?6xZ7$z1^V6Q_6 zBFS;Tap+h%0>F&R!Q>o_0i$pcku01+u3c+I+NC^MtrpeM1)|Am%XyPV7mSMS)lpFg z`_MUv8nJ?Xxp&d7g=*MJPH{#lLJiI=sT(S@2l5rtJl zMM@S`O`YgobQu#xqp~$C0Cv6X8?(Nq(cxCE!1i2wKj>!d9C9gmy1XDW;rY5D_zB)m znBpSNoh)e#-f!5qf_2^T{CvgZ<0rg-_W=+04_M|iDo?1jD*dbiF2Je6zR~dB1Q`R+ zJpkhYFu!@+7+AMXOFi|?(J2R`k=*_^V56sS?gp@PHcm0e zI^YlomX_el$6AwVFZl7NPx$@s{(yh{$A85C{>^Xj@#9B0&zR;(gdGn?zdEm!4BvC; z`g;OQjT~=u$4*_8ze}SlA3!G`pHG~MgfRzvjHK7vjn!)Be=GVs>J|X60C$hNX{5Xy z-+y%s2+LHC8PrM@wvXM+R|9+h{p0J7oDsy0(OjYt+;mUXAqw2qdD0XENi&e#Lf@7& zaf0@myvJ)v?wn97gw0oJ-i}y>4Rz(M9{BpQ3{ZIqyIv)myFH z|8@)%SbgcLnlu{OC2_XP9CHYvpTus*@uV8G_ogEF;CbxDMge@mh-xA1Kc_E>Q4I*FnO_m zA0F>jQCYxjEm>?URdg>oYZ{K)c%`aJcviLRq*@idc6C*HdDT2}0ALjyYXW>~e^$1! z-J}0jWvHb_kVV-E?D{$iYa6yTg;gMTboyz(RZ{S;_AY?XHqJ^Yl~IcdsZ@<7gaQwV z;-m!i!az9baT1!rG$Bq4oOh^pF_t_@q3%kZFuM*F2k$Lxj^-gYL7iH26LN{(VY)jb z`a9g;-{W)^{7sVb3qm|kSg6td698rG-s0;rA_$F3A@7T`c*di;6S~6!@%V#&(wgJ7XzM% zP^#2@{sZ-zNrF|bEvBL9D)ZeK=2;(6eX8F0^~$d%3Ezm7N?*mAUcmg zu8E+LF2qLp>(6;KT3Q59jbNt$){Gr-B1l`6B8r&g0_Is%B3Z|slqjhxZc(SeA@9Rrt1s z7nDLE&6BjvemuSv`TbkbVT*X&zAes~s?=|bX7n7iuU)7AE#GqLlre_`FysVt2Nnmw zZ3g_el2*TQbnvSV*Ww`MsXS8J@%g7u_~Y;Y4gd1%f5Gp5_d9(2_z^i5sSpt2tLrkW zLcGxuZC+|*rw;c%Ms~-%sam?h0~5mmx2T!5x&5YY$sHnCBd{K$z9Yat9OLV)92GjK zXJgD*ssk_*T_rjtG+`R=1-1wDXxkX=ld<{@DEsCcJ+i15KfX)j``rjuc6j@^tg%>RpqRJ;@n*o| zI6tlZoPu=CkI}iIrBtZ*M}tQ;7Fqc@Z?vC{$FDIx#^>zs^&f%(9d%w&Z6JaHP~q18 zwzilfzyJgW5Nyvbb=Li$WNf*?viSDC)o-!Gkyown>%EZc<5SLcLu($!N_%#9>;rp$ zY=^@+U`~m*v`hRU4|MMUsQ9rgfX2soW) zyn8rfxzk!sp$fHOVg&C|J(|+2O=6*ZF}Ad;VAs}^(AIU6C?{4_0?J;sFuMXCO(wTN zZL|<(0Yfe`iud3sIdZ47pLII|@BE2}coj%_2LN|~;0BE%3tm{5w)QeR#! z*f)`Sr$i`MAYD}H8O>qVoH}_EnmOkkoW<)mpJ#v|YI zE-x>*>Ua_w_lE6SMI5Qt%3iSI~Ml^XztE}m3bqU!3nGAB_Ui<8&dfG>zt zvDgZii-(S313;DmPht$nVw;fm4cjhJ^AH_^XINPxKuQ}~ecM`95G{+am556TqhV@{ z6%q6cA5x*T-9Dv@Ofi=lLJWe zv#aKn<-99!^oY}pDMmaz+~fQ2e}U6-C(jNKPm|;bBf^n~_mj4nl!uExc1NZ(NH^4p zTBLW}+uG(dw$aJ~odu ztKgNCJmM-<2TBD#e}2Xv|M>6tmw)~>e*2r>2UA1CwK9w zx1DTY6a%FfUExV=NaZ^Bf%n59-h&9%Y@^ zDZnja>KJBOcgKm)g2l!uz}QZ~BG!HF5Y{Fk_|7yGdosegir_PXuPCt~r;6Y<5JiBm zsC7dryJ$8grAKS|zRIH`&G+?|Nc9ZVPR8wgBoGC$C7h)hkf!*Fqo}&9_pU5O)*NK5 zS!%VKiM3A$5xWp$fD~aT;mikVbd!S*8qyC6bYrv#fEdd~BUutb)+iB4euxfT)B?a& zF*aBsDxY!LKP}yuCC`1 zr@c)q5w#NQIH!bF2U&1J?Wl0@F(5iG2E7^h=$`CStJXFZ`uH?UI{|Fn3o8q6))S5xRip+^@1;7K8cds^#%L3 zqoj&bfbEKw%j+Gm#EjDtaGFHWrnXv=lHfa^&Tui}?wv`3iP>TeUE=sliXsIEUlZP4`;DA=X1u$&f7hs6tEndxTyb=g#6cg@s{P<`@GKRcg z%@Gu!nmaYK3O%@qU+HH|f6t z^{;<}-~H|n`1J8dpfb#9-LBE-#uCk__WVO$ps@y+Wxq6lD=9nO5n~bBLv;9C;MchW zfITogEb`kT%Qpt%aIWs4d8>`3jD@;TTAPn*yl=Jj@qXzBSMaO86F@*;8wNV8ZqIZ4 zfINq+fSq2-YQ)|+YXDV%_Dw{ztsN{;{G1Yk_bASZ^Eg2R1=Ns!2kz$Z>ep~;96O>` zhn|?=n3~w9M6;klN?Wt-bkx*=g~=pWb6^1x?Kxy`1X+%z<&gH~X=6hj3WAH@9$UBj z)S-`X>}#{>4r6%uw{C9Dan{SD-1NP@PQ5CEbG~(Xa|Bp>nqzu!KCn6ah*XjKCfdrX z38K$gxjUmr;B_RqjTNL8s%xMAKxDNs14v-C^sg7`{NkuC|5hRykv88jW1O=bJ+!v@sOo zB$3PehXs$1kGMOD7e5sdpD}^H;2fqn;WVECKoi9?_N--KQU%olaze?f2pW-P{acP& z7zK>nz@q_xtlr`TP=SvXJ`$EG;Cw#g;qi>e#}k(G3Eq3j{i_w3v~KafiE0^ZvFTkX zw2UACB`0ZY0$dC@EsK@Z8YbxdXkXG=NghJPJ4eQ$YXR6!&l ztUx??#Jz2#8~~}|E&^CNXQZJXn|Of-Abc=1&>|$>13m&FIw|QjPnagJX%#{PbfJo8 z&pdh!(o{%JutZ9&F0Tb?Dj@ZLNE}1tDoWjuLdF($M9t|opxAPmv}T;JC1fE7zlgw| z4{$UA>`>tmqQmKY!ZZQ%GOOn~z72r2UCdZDqoGzQ!H`UKu_lmb^;DZzRK&N|b;rI- zzI7^DYxrp&BnQH*X#%*j`S}SkE+BXi ziy(y~DNE&@lvsQI@&!-lJKUY`vCNCU=OwL-bZ)>mrh@Io|E*~6f8#hBjy;m}RzUV` zBkK76VJ>|Y+|uD(--<}tXZrIF!c@7dkmh80nmaC+760)cf5vZr^IQDxx4*+*fA~Qh zyWWejQ`L(&()S<+n9&(4z0UtN=dC%gT6C6G2#p!sR6SK+X00y9WdAJ#zN;K?jG5 zf#Uw}PPa9&Ns0RQ5+|~b3sbJt0#^yO22>(&>FomM8`!H4a%%w__^sT<7o37%i}sS_ zUrH2C`r3JqI7O*I5C$-4+7c`dSYf2|v7bS0{kKS{y)JEGZFT(ldcS?6#T(eMl0&rx zF1k9c39=2XGu$&X4-q^4ggPx+)RHU(P9t?>d-`!Lpc`k0MF61*H4UWOXlu_pfMs2O znyY$r2si?2uX!v(p(>%0HP^B`n#O~fdwR^UCVj2V$ z3Z)+UmH>4=>zWI3HuMsH74?RBLgqN3aeN=6owARkga76z7}}0+G$#)0eY-pKkqTWW zYU>X-I9;s&dP^GfsS9F_n~XR|fNVhB0dGZx%`PzkRBsW`){F#Vpb~+&!dKUVM*G^>LikoBte=% zz5GEgxL!A0uNSR9Wt2-GxQc0-u$&y0Wx?aajQ8KY$K&HY&ZiT6oI#GTC&_tz-gZ@R z+i_i2>^bSea?!yUG`Cocc`gNk9579Y);L6Bl-$@AjEeQ;=6$5G$Y=Lr=@sNp4+bl>%L;$c04~l z;mhZb`26{TeV0y+nn&wAFhyXV#fwaCf^#0xi7Gek0X6NiX_v7~g9B8pl}OkV5tc(l z2!6)>V}Q%LVD6m;9(+L1-0w0aoR%5yfAxs(zyE-T4kx2P5Dot?c9- z;uPS$6Y-x?P*TDkoN)P_gZEMEI?p&Epk~6FR^+{6+bY(plyE8uVha|CN^VArzK(mD zX)`fPlrXFMb#*P(pp}{N0dP_7UAY1%DQixLo|7jqOZ5J9iYVleLj_Sp+A^x57AJj(MmLQ4w9#ofjqsYyUNx4fRc%Zx&oD3N8!2MSJukWF`w1SCO+r zcBT$2ZDaZRM165@qB>QbN7}%WqajgGO^gP4nICY#G!v%9EAWk2PBZ4k6ct%ESw~OIW4G^kV`~`hz=34 z3e||fP0j*(N=d5z2rSbX@ot85p)qxY;#0A2E4J+_rO>h{OP6e-My!UOM02PV6yC5` zN#EF>FL?U#3%)$Q$K%~2ruhu-W^wMYm2U`2`4-^6EGInNKjPiH54gX-hdVJGDyr4J zt{nt_jc#hk-v-ADhA=esF#bodIlgv#-lH)!9;4&t2)1kHaUch9O=yu9>iKMKo|X=N zi*rA+-zShizLHT-&g1iF01}NX4PWLv)A=*3k&DieNW_G@BAIFGMyY~MFKT8K5 z!+k>)*V(9b26NmCEg8+JU~7U?AT$DV8TZHMqV}4B!<Ma05 zB)DV9ac+)wYfb7-emCS2A03HeHE|Wuw4x4HQfx+qR+HG9LbDTIqiNMFO9atL$AZkg zY}I`Bgl*fA_Ka=calIHY-V`fJ>8aZ4Wm_8Ss0CncXu2%aRN9%8&1cRcWg*y@ZvGGM z&Wmt&cds?GoaB;f$a+zDr<4;qkO&{(Tl2d^jh-_PLijU#xT|bb|D}*hnz@CK+z6ni9GLHLDu}k zTm*R40z|3ZjAhb%#2KQNeF_Mt2wohnZkJkIe8of&(=?$#M7y@_1=s5p<>duWPtW-B z<$~*lCAzzKggHu0n0kUkKM`{l5ZoJ`O zN3@l}jD}LswjeT)UV*?pvd9I<9`IhM+};DhW%b}kcnW}@P^JQQ5xY-FtAGyD8fZd4 zYl;`mBi|ymEVQRF2g8o>Gg4lY8}+$zIc^L*7@BQ!u$+b8?+gF{AOJ~3K~%#bDrB44 zU_1sVYSrR>RG|npq^T0>sG`a}VlsLs*#N3WGh-0r#Hr9rm_&Wu1*Pkdl)Q>j)T|}H z17KG`V0h~HEq-*52@^m&h(t{ho8$r)rM{EkZy0t4DTTM?wTJ-OUJG&pVhosLfLG77 zL{k|hRcuA*?P(X)Xzwb5FK{kO4PaQbRW8=)kJcSG(LjCQc_+%^%L4KlxdsuyvQ!P{ z5aT3D_udQbI7^AM7z6Ik4>+A3FwbYqaglZ=hgvfBZNru>C}l%R8&bL=m%Wua$a_Lg zjJz>Q$|8b@gdJBnc&zaW^>T&(P%yoBSWY66fy$^wxc)+A+`%C1*B8937x=Ox@CSH2 z!r>&wCo^0KGDmPzBk|_w8@vss*M{3$M>Di4qfOUbyOKI6}S`7{3d*T3TO@&aOD3b8pZxUE#-aJ^1z1As21qaSD+ zzlgbs&V?D4QYW}GEMB$A0sJ1pYrn)1Xq%=-uSZMmT;tkwn*&_&y3Y)Z^Y9#R0?OeU zvIzie>fSdw<92RY`QPYEMvt)R7-m3AZ5+o@Gq}lMvfNrL*+EA`eH`Ph>_;3F{+sxr zFi${UqOKMl9=v@lCu;Mo8~bwp3J87BY2=R>G`24+omX{F3=$7UHn&BzJ4}cy`h^B0 zCHkth*|pTlEdUC$8-TO*!5-Y9@5Nw+ zH%iN_>KFh)@>(4=>N0V6D2#{G0m7`o6=gPfVz3|8s_lkUlxx_3#g6WjTRGlPP1jDY zujUHGHW;G7$M;!F6Dm!cUazkV97~n8{-Q&Bwoj`wq|F^&Cj|V8fz__fXkvQKc|g-J zp$>DIH_9+DCz5*uT*Gcl!O%F*fF>|@{G#=rQilm}@G!lBSAbf-!V=fj2&yt9hH)wL zfDdE+m7{Nby|t@?PVVa0tXd5QICD`2Yt7dk&p+lyi%nxWy?rcUxYzD{m*6fNtkE>jnC1oN+V{OuD$-uCZc2~dcjR2L zZ9A^l3$E8ynX?IdF4$ATp0WmWB;swx9Vxi4sxaLIin>LA^Sd9x8YpM0&$nwWUTPF* z5lcGZ?(RWKwXi6SF*CMpQxEno8!#l&Ti8oujnM|@5Kyr!6CS?16Cg&LY-l8r)u8IX z%j7Uk5vPUV!j8lRwRq50;JriT8MS5<2u&y_I#9@&QphC#8gAWcR-YCDa`FCz z^TP@8Aqv>tH(d7(F3DhFQfgdUv8N5ZZ%8$RAmCu0J?44Av`mt)BfvgF=^HBXn}+>Q`-M865Gr|2Y1 zjLQqKUWCS6Rt3PCQ|ei+^(sXKIyXkFsLsXaAtHd1%&*LVH~WYIjuKUjurWmlAz-E% zU_$i))yoGx1vpOFv7_cARZ2XzjR4gazHy3LecxIuDhL^QSd_bgT?ZvZ>r-d>E$s&f zrRR1{;2_XLvaE@h(Ay#^6nUdmTBD8kFWwX}ipY>BRk$D&`DqDQP7CIfjN5rx;6p$~ z!LGHWYpq~cP#{8A;+Zf?rWoi|J-FU`IFh-z%oTgexUL!3wPM?3&a+XY^%i54v3EL6 zxI5n=`2Ux)H*Inx$*}|<^e{8h-6Nv1dPZjV|Np98S!t2(p6ThXBf<}oW~K-B0{~Su zIz6+dt%~X4bkYtz@qmYih*~B0y(kSQ5hDZOA}Y*<0g944o~t-YWZf;0GGPu}rEGw- ztF(h7VOMw_jiRA{o2N#c7gkK(kh;^c6=T3WN1RU!Vw4)$L7hqfN%b+$2*Kezi<-S7 z4|W*^2|Pc+IVm2@Ro3dfZ@6AA_;~-o+v_{tE?2B;0dYa}5y8&_x~Ca0!Q&-*{Q11# z`?nV?aYoSkxngvBI2Y6y5kZR(8B^Wh(yixa=mN~BQ00-YLFj)K{HnM9-r)Hv64C+U z@%*Fltwa6p%a&_({QRSHjMrlb#Y@V1=qqPzTM{w7+m4Tq5B%jnf8sCy`8T}1y(8_Z zdGBQ`cNJ&*c@HjJ%lU3sZ@~FJXU+iSBL(JurUQ_QN{Z9dcuP9G^)5C18vKi||u_Dl?ny%7<&Wae~i%au0qF z*M^l*F&2*iU_ZR9y}g!i>2a;G?X(0ExUDJUm~cd@*JePL8UQ}Dy@IJ)JMe4tOp7cj zu(3A%>L5UvbZpF^BcQc*HU~g&&*R^EULIIcqBkPrZbz-tQec7fI(Jyw1fzv0BHJ zALjb#_%{a~h=x^SXpwuzj)HI2HS)0b>fR3$Ck)gP;dCCc*~q$1NuWa5Y+@H#6!?A} z5)my|?;Mb&JD!AwJ$w(x^{s(*9Rtu3m5vCm6zuyLWKjE{v04nEYpv#K#`)=tT*Y}? zRc(6PHr#GEi590F+n#Z|-Eg^Haa&hO&($cg39o`63h%Wk+5n^udX0EL+AD%ZGR+HA zYsJ1x9o(uBAFdv6^A&_B^kD$-A~*f(*Dw6-Z-2veTV>;FiInDvlZFgI^2Nd&@cjI& zR7Vf?t9rby$SI)~i6lp_qEODEB1!ZuWo&5|Lp3|>`;N<6ak*ace!1YftqOp5q)mX) zmVkAY2rU3i0XUyByj$UYKy(4~OqiDwymLq;Bjk)d33#ul$eiF1rH++G`{sF;#XAsE z%9uh1Go)Uh519ReI88V$q;+IPtr}5stZ(}!xqo>@tpy~EZB(zGP-vdsF3t!SBO+zM zJFpX@l6-)lBBo^)>TM}4XT@?fs)}2!mmA*SugI$!PhJ3+&2JQ7+XOI96Od!YGVefS zz!kXSB?7ToWLBu|6e`$7tSMm68NLuw+HqNLxLiJPxo%i*8JCLy)}T&o4`5vj{KpN< zXpV|vtA_scHk^2udsSRivy^E{yY{V$bA_PUwq8|%NkEW{?}p33UY%NZi#~?S%c8Gq zpXQT79Zc0hg|!@lpRh~IxC(KJ!%90t4+8^V{BB7K!GB3GA0MjZtz!kC{`yj?# z@m^C!1Yn>_MwU35F36XJd`T!v!W<`fI59ACfuoGz6Jh`+&zQV}qlj<8lG`I z?Z_#^xq$QOjOX(+PNx&*>4ekijPEah!uN0Aa5_I@@)3c&7z_-}QTJdX$s4Z~xtbx6 z;qnG@0iFP~jR>IXB&wnyW!#+1Kt0mm`rjTMqe1-XFh$b4`mbMsy{~}PBO~)3yxrfE z?SZU9aHZ4%{4!D!#mw7v!>?a&`1$vr`0HQ)j$c22;c~fR+Y|O$hSEh+3QYcumOAw4 zK3Ro-q(*mcAh#+IZVo@@PwjoL6g?VIqY_Jx@^S;IRtx<89OHSc%+zRzS$noTWv-2y zEAU-na-RV80X#fD`ez>XxvX6hKS%z#{^WF)Ngk4!RB5zs}` zh%o?8a)472qYx}PZ_zVC2++M0xezYb8(v>Ge7t{Xq-Vn|LF@Y(-Bzf!DJkpM0jE>5 z`w=`4Cjl4RwuvE|Ciq&UV04(^rwCe;AVOWxbIoml#25e)HS7j7t8`u*D7*7KW0^&@ z+CdbSx11#6by06IWi4$$ZPI!t6k{p`1P@9wX>+cqd%?bCY-_^4CZtkOnBYQe;uX$2 zxGHLPRvg<=1XyZ4a|QCw*cCh)H8~}TU^4>~0oeh`FH%|udr4wgrwbg$8|2lX2atUgkpZmgVA0c5>@E&aq5pjr@I#q0=CiyI3_ zEHIHw@4VDg1YwLa6pd;&dS88W*rxIu^$b11f{o76GFH+e?f* zU5*E%xJ59`Xtl+VsI^%jf)5V!IpFE}gqI%?-@ZTL>D!DD#j#}0D=<)4Y4J^%L~>hY z!OM+_B8$8#I;)e!`-*-V{Or2)q6tpK+P4m%N3poa627(5< zQa6Hq6TdO)E;GYB5vcM2Tw(BDw0s!Bl?uuXUx2z7Am5NL1^HAkpPmuIj2Hr@ctY@u z7%EPS^LL&Oe0t{+%ep@HR;gkhlTh256u?^NjnGNU?!*~4p_)hvQ;MRP!zyC7N< zzZ#*D|Iu9jNP|Yi!KcJ#jHlv1Mqr37Jjc5^F1*A zqiA>g`@uWNpPv7}eptWBeX%;npc(+8o=DI`okUK6Lem~W5U$dxhYl-GK=t{Pu)8bx4?XXXp&IE=& zz3bXqt1!qq25P`XPa)l59&Xhw5CK^_4tlx+;?}amHOaXal?Ei2xNsfP7_63wJJk~SCYTf?3rqf4FPPWzlKD*iPCrvXoE zU8Z5Y_n#$aDX>^O02MlNP}ZuKdDR5AIv^ey9;HQ2<=hT^y_P&;*Is>Wecmr^EziZq zv!#1vY+-}<5)>utCm$vCPwi6gJtAUrqI@e^1(!uU>vFr{dcDd%nRe`H)il_T28?Sh zZ4SvCsc6%UfnXD-fThmtmT+5l+%5t%-+o=NZ55%4D9{ulrZ{0f2b`bIAg>MX7^u|f z2d;=0Ay+Z{>za^#!Nv)DVa(f%Wmz!KMd=L_$OFMo2;O6g(wGTJ>VhWVcHQy%cE$VK z1(#dWhb_pd;I@l_%r-_@b2PQY$`qoile$AL(QVyP`GQMPQJiVPJkN(krVY+A3{n+{ z2pj;dN)dd(XQJ>j zUbPd3g-VReW~Y+eZ&33KM;(Oh%nS$?X4 z-?rGPH`4Ocdrp`xJR;pI3ck$%=?l(b;dEjY)Igl|8d@%&@P^S3ij=Lkl@P3i5qW)VCnQlnc`PPwT`?@0uk z#@fi{AThg|t2jQK7h*U=0ET%rrNFy^8Zjcxk+N;T?UwQS`igme#q(3d)A@vDUfPD> zL%>ARU$yMuTBYtB$z1Y&LX0ASwagMFJwJ(nSBQXf1x5uoPb}=;b{_5DIZimw3%1h< zrEYLL0E!5~iRJ-$5IeXkrAu68a4Miu5ZPh!C!s2zp7BpV{)`{r|Ah1MgwrzPd|I$9 z5pe=ybeJX}I;W``gy0>>1rVZ6Ah8Z>5mpehmZx9>QUTW_YhbS6Qd%CE7%rq^+3W<# zMPL#t2IUhlGu*@|s=>+Oo`?S|X+g6s8)+x4an-K?tJMd`o_1W2P21i;FJ+1^xH z9B$00B`dw(=wd2XG^`h2iB$o2`HE^Rqs_x31@sP8y;Rr^C&td?K=p(@9h~b~F?%)$>`}95z`F+jS)y;xPb5dCx z&#i85JCE5ukMCeKQd?C5l8to4_jhidJBJ;_?it#o4;k4bdjIjKdCQE!`O%-RkGt*^ z>1}2AeY~?HJ4EI~tKZ9?Kiea9dRw({)d(=HXI8pAma~Xuw$gMlf zfFXk1>d{hLd+i#B=%IezS6Q1w1*ocGv^JKsA;aKgv*qPDuIs%BrykWxx3+euZOn;%rTOdDHukbmm(F2 zgbFQzMFYT>j}KgK7mW@}B-y}oPE}be1>x=O4Iu=ix(iiyz2b7c;`+AZ@^Qt-hZv!Y z7sE3Q;IA@^poVjjYg&rX-vEG%pl&~@XJrC2Bi#yKaRCR1^XY`ssp5P-~-C6yWViS2@m|^W5>GgD8-=^G1gKNVB~bd_#gl-#()^4Jc)qq8Q!_pP}{a4 zZyE3FhWsYfV*|iZJ(PhIP^sXEdEjd8;J|>vJkNN3e!|Pk3trCOqzsX69(y{0=^eNH zift<>NxbrK;&cG*QhRF-qJljO%{o>QBJ)nJpR-W9Qv$XC>`CW@*LhJ{i#5hrQcHmwygrJ9BrqyLE{7vkZMBF#Wu!> zxKzX`BFq(W3Xs5$gL4H_w22F$EV~{_&6Z=Cb&l8mvncghwV1@vR&eAr?{{#H0UGhN z`mz98Dcu4cBNH&sk{24H6K|rbO4>aZeN|R0ou$34Rxki;3^-zZ-~--C%~MYf6Gx$y zu-6UOw?)vLDH2`$ypWpmU-14=8T=TWK`yf9@b91a(?CsTmxC2(p=RS2f%#dt#3?v6pLu~g3~-9YM#GyC&U;9T*E;Gue^E_MU2k}z&W7@)ViV8T{l3bx0%s-01{|z z8GOJTXDngHP9D((EK|hOX~q%*96Xo_9s#qLx$PK;&f~l+csae`+xZ**^zt3Qeftxh z&QF-aBqD!4z*1KZf|5jPVp;i86(8H_`qubNTCLgo`d z?2w62vy^TUQ5XQ#p=KqsGKB3iPU1r&;b18IqlbZ^Hn#>N=#x=-e{Oc_0Q*cg{PKDa zjCzY)9&&z57GaM)VO=*|K0fgNe!#xIk>;1ej(HjMaZoJ+j8shKw+dT-j2pHkmr)Df$xg;w$#DH!Rx*3^J5OnraA74i> zGB9<<_91H5HV|lbFUglBa;bpVnTdLM_6{b;^NK+%ch(GT{v2C3aBW7rhlgq@H$dF> z>EYW39*iM7_JytK@~EH1f&eRhVr}JG8$KGVM@QN5-VFnE{U%$Jw6B}PqInwh$5Cvm zTKYugR`(Y`7fBuNZM-K|KwV0f^p>2EG-pwq9rCS;s_UrcuWEn54dam^?`fLRBk()c z+r4jx@n}v7)*8baN~}Pu@GzXAow7w|@Ba=o!Nz~&@I}s9sx%Un)w+9YJ20Z4EB7*zXfFNQIr8Be+5+L~yPO6R%-29nIVxP#xY?HI1Zdg5@AL^=GoZ zrQ2f7Va3vi;1Rr9V4+7rfu2|2`lU+gswVPj5qX`5WpJR{e&x6V@S2w_YV1`boWOBU z8rPiz7$4?Nr5zYX|*b}Wp+#nJdG^!nA>}`mmKz|i+tzDeRf@@b?uM#m%n_!lG-x03s4Mc=oBoFL* zyW;Y3!R;d<7vOv*oR$SI=MzrLf_akAbWs6-TE#={v{-RrQHe%VgcN>v@#59Vy9j4( zTyTji<`cpDD`H5Rz?}qeRxz5k?S?%i&Bv=qMW}kyBvHuuBy}{Uw1gHw_8uTHj)Rxa zolYk_KR?6!i0kEwkIM%xmn+tKL(VtkElK&J+m5Su4fsaqCCAWBO<@oaiEyd&t9e}{ zd0NC0HLZ#9{QQLIBs`pRMcxUukSJ3Zp<`AE+K{h9W?goO(&1`D%pQE#q>5 zsyZhm1%z2^5uZ*4=O4h!w;l5t5`FR>IadoV0p{@=_8n#c!Z~&7ddYqBsztuX+!w^= z1!Hkd6m@8Wi{_vyeT;(OI+klffqPPn zlk~YFGQ1~b$buW(B*FsYMl!s{W27UScdmKg-Mz6OMkw7W>N=;iomyqXudFqUdqmVZ zC%H@{5m>8ZOnQHHSR}a$Rog&nR$)7%0F@#U*ic>x$c| zIr_OM{TTptB|_V{0Ezn4BIB!)w6};xdW1ja zltQ0?>lGj>2tHw+e9K8O-2#i?N&`9_pR7KGD$kiV>?vU>wox&v(`bLQ?{s58mi)%5 zHGtP0XdMBVvmIpb-0!W<_A@(3b#4^u;&bQ~B1rbT8nFG)(L09kXAY!5CV z6cF<6v8_A&UT~@`&O8s)N}v#-LjXSPEB*igAOJ~3K~&uIBOZX%f8@CT-Z1Az@Y?~; zBSX@F^U!Z!9QUB6AEvJ`)L?FFNyffse7pkXf0nR0Bo+P)t$z!>da$J+h(kbpD^uGgs58W|< z--9vsMWnU~8htXvKOdGq4;;;Yi=h0U9QPpD#{S_%qklyI&UXO8$_}*qVl~ej=(Fp{ zzwO#K&-!=zzPqr^>cF1M*4-WR=nj?da0y2LW)?;O6h z7Oll@ZF`*a^k9rw9&~qt$sCk2FH&3EL=Ia7(y@RgC=di=T&IXF!gu!^gTtfkQ#_7~ z$Kcd#3ZuSJGprPGvwQfR{%?&CvZM<=cJMq{8#T?Rn3KbIzyuJAllf(1%>h7F`Zx;{ z5e{0HSt#wJs(7*7*jnIg5tdP<7Eo!obHKjcnB>Y$h{?2(Kxp~p@(9#K(IjV$Q+E|W$i9kfu94o$Tw$nKl$*42?wo3oFpqE-=LrL@DP zJH>0W&m6S??m!X0G*Ss3og^5ECrG6Q)j_)L*tQjEOIm4XL$G>)C0C@RUgBEdgTwi0 z#`DuRJUu_*`^yQZ(+ME}xnz9Y-mtDKN)oTfGE3ytQADi_M^Z9}DXM~@D41Su8@Rk- zyY1Lg#d?)G!6{vlEGZO#*Fw5JNN0rzOjCr9v#2URJxkdjR?kQ26F@+qG;$1c1Hj+E zf5$w}xL&Uae;2?`wIY{FEgwvcAgy=nIAVWYG4A=n8TU)f8R8_I7F#^o?Q!%_voZ{rV zS?p@X86rwXS~Jsv2;Kwp;&48DoSqgeCyBPQlXk8uQbDD_WvIth@-K-5fO%acD(M2v zof2dvMv5jnyOKf9OSTmCT*LNi(G6KBg7qfWH2gxW-Z?{qo|r+WkSU+-tVLaKrX5? zAZ-c)obLvlC$IUlGX8U}pj@OrH$)gJL=#g8EpJIEyQ*WLx#7%J(jcNnkCowNYS1~! z=e*W^HswSS%97f==kp2k9QC{jIWuyq*tUXgO<1ohZgoRWj1Xp==hQs0Rz{)VQSxdOKpPu1ba^PlkNZ!h>C|MX}4_uu}6KY#m%Z|4`BqJZ4!BZ7-Uiw5-) z9y*D5FDPl3l14cz!(d0LE4XGb(qSXFP0^D^U|{!B!b=dBw}R;;91j(+jwgj7=~QJlF@l_Gjbk5x6xVVjl7PHU&9M3r#e`BPT)#7lDwAQ<{e;O(mtm`VwtIGx3?IyYCr8LnqstPW&A8f8#nVFnz z{iW!;CDauZqVS(jYYDOiP;S&zo!qjni{F@Fz}ve9$ecOOT7KPgBvE6vgXhB{@c zL|v-pEk8alAI{qi#0SsebpDOs8T#uH2>$9Ydui5N{Zg6){A>Zo^pJNoMomFko4t|H{9l)PCI}H5TUpo(7 z_usp=Jv_bc>!N`okuT?1)*d&^$BymVIDF(h9)CXoU}E$v&hF@Fd+LLJ#o; zdjHly2X}>GNBzC>`26a)(C-#P1KZ9Ne~YT=`fljkeOc{qd+*+P$29b_-V>`>5!lAz zXXnT#c+CAdkBxI&=bE!}bc!4R^4+|*@j!%Xv}F=1IP9K@Wd49#DvgbiYHk~A<1V4x z0h+VC)$YKDotK9D;0_uIr1t>SL7QWA1lyQD=r@$E@iDGN!!S8GXsiv#dDop?LmRT( zQ)91@tt&RK99+Av+V{ZL6{CZC*ss)?W%prDH#@gE#pM5E)K;UyWO=&Aesd_zaiv(w z&a3^~g~vuwHjV5$6~Pn(u=k;NY7^_)LeMcG8c5cMLv1DlTtzeOD)V&WTAF0V4hFFB(&l0FW+!}IwMT70jHX=ryc9QHBlQY3v@o8 zFh$8lolno0;sob}`do`cN(sN-KLnBIg6s8$y;xGSMsB!BLr0+k&kJKYEqHzwgEVN} z+qj$%yvJS`Y2T5v4uVP|GR346(itJhxneZ+W~=#IQBuLSZMa@H{SaeJbp0r7x;pP1X?{1Q2Q{}t>fJt*2+vJv^x}g9t`AubZpZJqELK@u40T5xzN}&r+il z9xvZc`0?AHaJ^pf^Y0g&{__>Telac=0j)90#+KF&6oX?-lgAV_lI93VNxVfYRZ^It zV6(4PwtkLytwL<9Qqe`VSo*6FK)Z-|*<}Fz9TGA3DuA{uQC|yACuv^OhQfhfa~(CteBDCmMyB)7p8FA+-1aUrt_q&8XA=m0dAuNEAPyF;GuDBxg|-4<1S zI5#X#eGw+TRyS%Lk%&z(gG|uGXg$o$3(dL-welE1qg;!EqfmMe(HUll0%62FlgxJy zR4T|^#b{^EJp=<@+PV~_B9TT)Yr(!7K!?!3wVqtidehabu@GFN!ua5t@EC}Zivd~b zqfG_Y?m@7n_LwqsjKFD$n01X1iT;RXo`n{Dnn47lv|-;Rg2xQ(o2-NDZO5J}=IM-= zr_|cN3By$GbvIekMm!OsCp^y!e#AfH9R3@AJfHASKfdF)muEcBGfp93rU;)2yk?+g zB)*xoqecMQX5S*yS)6&b6x5o)$Y5lEip+i2MP|GcsydOdW^5y6<{=8C5shk*5v}Ey zYjc9^NmNc#&MLYj{gFz+Rx9>WP~1D#+lDPweEV%feEyEOEIJ1!z`%{`oAe(=0^5c@ zdcy7PFTQ^;m^W-Rw?l;Go>tw?p zSIzs)CR)X?@_vl$2uldDsPk#oXdpm(Pj^yv%UcWci{|E$kW3=6Te;)?C zJ8f8ZD+va;M<5uwc5A*N4a}d1fRRy1oCCxX(SosFse*ZQuIjyWH%gD!{XAEWPkVPX zaMeG^YN$6_?oh|p1QiWlk)dJ?z}1GA0!E2`DX5_atNWfrpTQr1VUD3)|8VQ(R5U$ZeLto2A4+6H*X zF-ZLxJ^^6j!(3}$q478So3W1M`JET%cjXEnBVcusp)8(~dwNi7y8AVhKfP~`T04wx ze&0UUUDQeyNd*wFr7XC+_8Qxqhj~fOTW|=r=$L7xq6WdPHa}Ipm4?1)Yt$f!XL-al zly9>%!sa}64s_TLY%UnHQ314bcVmb3{;1oiL%SZ^PGfLR9R#7OeMpT;?wyAtQNos# zD}V(<`nG{d#4uutvSEkdk@AN3_XI#9v$+a|anCD=2r>3^+I8e15{REOF&MF*X-*;fm zqV%d8WkqNk$rLBVIBR2s_Ke;;Oq1jWJJPT#l!m+O*pW-1dVnTE$+>->h)|tG!^lYv zn^*CK$pg!h+ca~vFJjJnKLI=T~l!mAMT?0HU(k2_WhYZ+CKq(p9#;8ST=+m?y22qjqbV9A7lsM1t zczvzdRDeuVr3K(AtvN=9^FjKr+J;}?Tt-SNgh2h(_Dk&=fwm=2ts>;+kj zO)3%@bA`aQN?I6<+@vAT2M6h*-DK-^k+4nB79;OS7Yoaqgv!`cGfWSLJF%2HVD)Nx zIz(m;OHMP4burYR<6j4BBgrKZMCytMKCQK8_ zT=EX2Z4td{1%wIH@&&A?ID9*@cxNDqDl4C!mT@i$n^6Qn)!4 zgyEr)aTGXTMO-g>PynD~h{%IXY4867 z0#%1=+&!ZiREM?ei*w!sp8LQ3(Rcdq0LF-l3G{F|I6g)P<>TivXV?*72#aF?ztkg2 zpU)}tQDiO6c$N1B3k%@3Im%#(IeLpcj*c8ON^J*9{l7i3Jml$q@oY|!itSw{z~&sG z`9%mSf=1e&(${SHtcE2umEzd`x}QIqqhC0;8dw|G49!(0XkA}(@Mvm>-ev>H?G0-W za1V|?xR>8^@{FHpVw1xjF@DbWU~&X1$2?JBWCzNfIn5RRoh9zjf4}DtMCFGLlQD8U z&UJCl@nP+)+$sK#uQ`luMrRYi_8l?kx^SKXA-x7^M8ggH0%*9W!yeqh^srLj{ie>g zVkvX-dFMT%>t*}k(1fb8rhe7(ITghE!oD{?`q*v+r|U^I6GOkt`pkWpwR19nRxWF> zZLR&aO}TxyI}+_)#TNaX2Gr&xbJO-1YZo&}fH=$

xTJ?a%@@%HA^!W&rpQQC7fg zf}rA<@B2n`0Fp2p9c#px#_^{?$<~L^oMr-Y&$Bm0X>qIvi4ccgFF7pBgk1JE+3Jv6 zl2St1MKC3$t3*v%3^EG9=@g}|q;tqyM%fFlZUZypZ}C+`r)ZKyXDx)i<${m*cf7xS z;Bvj9RFT}~;6&l;bi$AC-|_w1g6}`R6qQoeL}?ksnTzJGIj|zAVuptkPhrlo@q|*5LWOrK2*M0dmh(>vxKCO> zL}>vc%;f|`5P`i?)x1W|qa<{bvk0!KL+d>R2gCq3O^6}Dd8x;XB(&O61e~wyj&<9x zZBptcB1&W+$#c4*gS}|ECWzd4C5a$pbpl8qZ`dtbkmX)H$+f|Pa4n(_0Lub6rK&@P zisGzdT2V!vyhPzW1@N+n@x1T2UU!t7)Jxt0tr>q@0n-Sv#Xkgjzr76n4xo5Eh#=(; zych&*A_he8F(AwnLeK@=a!K;~-^<#OZzuMV;yCmA4VlPKfZ$I$XdsxlI?)n)`FsvQV%3RvKgOU1rttlN&&ZKCA2 zRbgTPU@n*^5+ScvvWX?vBS7+b)!WCx!TAXxI?PLHdE)>h1dru3;pyp&^Epag;z?-v zjwN!x?~JrpEnT6t(N~GSRTL1Na5~L6Efb~yIJbkyBgPZ9HG>dwT3!%BcxVjS_zmna z`+#NfnBWj8V?x196*DSaF5rDf*~Kx)g;e;ho2a$r-V&%VT%*a#2e`02N38%Az!fQ} zj&PQ0|i+ZqjPXn6=O_*dWMhQnZb}!Bh8HX`zX(+wr~0Kj}5?2^8pZB{?!d48t(W{7fYa~f z`&v{-QY;4W-Uc#SUtqYmKRW)XkH0$ZBP;UWqg+VI@xC{34~8{2car`-0#0t@(UFt1 zDy_5I)lV(&)b49IH=##HS=iP#S4U23twxcock@Hi45$J6exLR`>vf3+p`W|9qUNCL zK%fI=HEtnjfNdPKDJ->ho3;G_2(~hOw%54NeQ_UsGXN_9q?d9TYqX9|8jJPHSnkcI zy#yk(98ASQU1aiZ-TWMB9~?jf0I(jY?Nj|n1HeqJe~#^=ku^2`1%Lo!-DGou8xXY< zJRaZnp1ta)=KyeIRp9enF+s2@9$L8{B4H1W*MqQ+TH6hOt5ui)ZK#laqdN>Nx@rE4 z7QlTtR&^Z82R=U&dV3cOASH2DHbrK2=8z{L1URQ@b_8}q*{|Bu#Ml~C+x_^{<}x3i z#q2P{6&7JO$DfTf)P5!mZQt5MTWoy3<62~f^drZFtZM@r@9jorlc^}7&Id_N8`fvt zYo+{>Mt7U-X5d$CwnmNCvP(lhw!0d1acp2%Su5LLT76`))DA6AmFuvV(coZoZJiBI z&rjkVu2N=)Nth_M=@Laz;R2)jic%vuGWXGuH;J1yg|yJnQipnSu=7f_W5>S6__A!S~oi}22im{%d}9A)4XSp@PXf>gzXsft9Bh&G{V zD;TY$wBjetTZvV2Gbf{yXnQOX=cf~vxBv{SYsTerLE0Uh%iWt(doHjo8*Z3~LFuc( zJUnocZ{+ujTWGZMFTZ$>Ix#7RZG)+YMG4)*N=D7%=KZt< zx>SbB)^_mH3<=q`dvpcONVO}}TE%O2w`ke|QL1`>P<@dqCJA(5QPEP3N;=t(ngG7uF z9pcGheu{X0K4DsG_N)p5R?XtqxO+ zpr?S-LU3-z9M3o{q8xoF9ik1-RdRo~EXG!0AaTOZ32V*pHGzucJR_+S#ROHL5%t!} zWLv0Es$D>Ep_fNd_Jb&561-zo(GCYSQ`u)#sA(|LYpt>mutl3Y$YYk;eklq4IoBe2 zz%1Vp;R_N4d?%c9Qf~TOSp?&1LB70Wk5W6{H_x=>P7_$9=$pat`^T4{XP7%?A=q4R z-?{tlePs8sLqqPXmDwsqbHqz4Aysn0w(t1sU;cuB{^x(j|NH;^fB5TP|Jodf29{Im zqH>MNRD0B=QCtidTC3avbM^)%j`@;f=_O_c=T2odNHMZYzG~Y#oNolbJ@>bZM2_J1 zld(Jq1l`k|8~u6A{WY-_yI1!`U+XpgXtcDpx%;4rzqIpw3AP&)`eau#fA!rCHi@+V zbpMyC48ly2JT@tlCQPX@a&iR3WKM#%AD|n}cGW8T2e+DKx))Nv*9UhAn{#aqGr$YL zYO0!5+~yJw)K2j6tla0{*bjD&W@lUb4`T$CQSdpcKSqu0{RULk=sotsT@E1>K$1fx zVYQ6cAT#>E7zU>C(4ox{%(i#U+2IJaIv9gMTul1BL)(n~J1ZU-DFh0Yhn;f2h zpo$Y2onL|2Fyx@uGrpgmaatC*^NiE!1V2lzuyaZ33@;*fQ#m8$4P}?ea<027S|%_T zcrWF5rnq35CNRxfQ`9NY@h!pzFmh(>Dm-$#i8}4N?k&OE@@Bx$axAPg6NY!xjED+} zHi9IFaNjb36~tnoBStBuqLaicoz5$zwRFn^45=4ahXL$$vQ-jQ&%%&Mk9mkml&YB{ zO7X}kBJPZ^dgOJ*wq~q102Mf&0QL^iM@)_pV#K5g#m5V1@PPSXj~w4me)@0CVZs^qAOaJZDkvAk)U z34X}!4M5cLM!^RJiUKC~ihWPWR9l{IDLCY9l?tR(;oOGmfXoHg?L)eqNf$l=$X4^0 zNOOm0f)B14m$rD>W-s2%0WEV-KM06CN%aXnY# z{unnaS%8d|*A1=y6Ce}TXy-S2qtUXt8&CInbym6T zbbxq5a1($Cg47tFW?9RYWkK{490fSGTwAC4$rZ$+z?@43b3!f~cwfQW3S`YAFAUDC zYysVzxuT+IJy5oEIXH+&-aJi+-ovx>vj-s(X_P5Q-QUq8L{@)L=b<@as!_qHZ|Ftu zg~j2LvH;&kbuI--scW8G%e`?<6vn7+cuwUuNR&Re4fXQg<`8PJm<&L@fc--Q&j9-G zfR+CKXXCpY?xWE=j{gV1cgPh!g5Qj^E3JRqa9dY=yno>5&%fh;{jdMPzy9mL;@|)M z-*H=SqG1su%)2k_m!mOa6jBkg(OZ1f1VpG*QC{DAGSlPaY%a_lnO)Me6Z6?$xA^K*-M5p4p7&&nJ@a((%uSF)|paV|0th&zkkr z!*+Lo?~f0QR(aEV&>EM)oP*vsL$O6WEdQ=O@8Dnq3~hXRb_1svqEF^PpmvxU)7&YzgF~*JeON9mDqb5+lp$&;>F&98o`Vif?|a8l+ov(kV{;7kymX6_ z_wx_uBY-f}_|>s#|_Mk;2ffs-Ec%$;tc0KR$Q@d8;TS9F?3*h zAMo__j47URI-M~46Nm_bCVYHcKtAC4`5DjOe&G4}8T0cQ&ri?rlf$~M*pmSgsZp6q z0wuuHCTM@yoTV{@5;-rP8+cm)03ZNKL_t)9r{@_li0bmXIix+|wtDRQjz&Rp1eZh< zDzj0-7=Tisq26~beIrpl26=#eZZ-D+i$H0jK7gDuR$c+f!d7a z&{CVUdRr`*0IdNEw#b%vKR_y5%M}zR_?bj#YG$0530$Jc-lR=f0doXcb0=rQX_+xc z6T>2SHz7eC21)q%LIv32oj3qarwKoP{J_ieq$Q|i!C@y8Yugjv-ac@-6{MU{iwyQ! zg{GbM9XBHEn+OTqE(w>*ipyoi#|Pv6T||qrMsk%A3GzLk*LxraV4k4jW)YqPn1QTf zWxy^uulu+Xh)KsR=iaFZ04_J}Zvne@?V{zVnDv?w5J|!UA6cVWDpQZrHvW{W)-`6h z8sXU^JBKar2t>%)!EsjS3Q##qPOB#nTh6a2?2#>0Dt==04exvdvttxb95sC*b50|% zN<}hN>9)WOMt&1P0}UQtiwYKP!~(bkrVZp1CMRMyE;xkA!v~osU{Pc)yrXc2lu0Ws z2gR;UCVXJIAWqcBeGu7uIBxIz7=_j)`P3Zw%)LpjBUNbuTPjxPjF8^5SJ6U zvWSv}2=cO7ega6%u=(TT{=1`B`***?mTP}}U;0QQze1f8=i%*k!_S{T@$dikKk+aB z@-O(0|NX!5>-81atJYFS1*ob~s;m)6o+FWy0iq7soaM7-tT-Yx=tA{yPmk`s8)1X! z%6$`>(R~0B9W;YF__ej-@LhGR**>5@`W6D^_=jB;o3oBWr_@hPhzZIvyj~*3Y@&JI)*i&GXc3Vr>%bV{-&pWL_s5OH|d3jcpjs z!1x$N9RA+!@ZQnWJ~V))Qc<<+5D}>YGJ*Uts@eMsuzJK?D@etL4{NaX#a+&xiP5%x zc`&~0<|L24JqTJHw6$knAF6`oF&eD?z(ZT$!S7WS%h|^L;7BrTY+zGt1_mHCetD>S zDx#`h86?tHqUqv=E}~8pXcrjv9wd8UIQW^JG7@Ghw$^~-*G-a zA^3<82$2FDSM1jn+ikpRlAA!IQ?o}QlY^z?)h2wc6^Pa|yGhPU@Oq*O#zw@B?; z?+No9aeh9b)(rTdA~OULs$ql)AkUK52dH}KhCLPdAT6{QrbA>c?w2`ZeE&(tdA zhyb}RW)f*9A7Cj)bn=*Hz>!DVH4! z3CR_dc8Rzn%3vx^03sKO0C{RrDFt>upFk{PTi4qa+m;%2ov@)6hkdFDz99IFv;$l{98Msdz^6$Rs)UJc^*nUS%Z38DM z(Cte`tQoFIExlTjUWaw9+Oci|-1eN1iwY-I$@k4!>A5Vf$6PB?E!c8KafC2M(I{|Y zxC_NPfSpGc$P14isXzlW46x){70#ft!{r@e+dzB4bb5k+Dp-~UJc|II3%%%liy+_# ze!w=?kA~bQ+QL6#L@VtEMD&b#_S!=a|Az~aGt!T8#!=hRHzO` ztx~!!qfwO&={Qf4r%vXm)qSEetcItzJSlzNT0a|0^-~`4&=zVS@_ppDMPxhpZM3px zbPNFX3-CL(-y@LQ`{?oepA7OZ&VT=%(c$*!@1O3^Kmss~qepS0$JeunPWz0Fhr_j~ zgJ^Zy`Pf0PQ2Tt-&1iK-2ji_pqU4RiIdGg0T*Ow>h*M zwf5=nxBtlAWtKHL%~k$-{3(?CG^cHx3A(QB+LeofH?;*JX&_cIQukZ3V9Mxt$!5J`XG46I$oJQ>nJ~$=a}j z*@L<7slzW4w_R3eSChdW7YRRIgPE$kM_DAsc-$&oK5On7@AdliUY;H z^^rPQn$u|*0~M&m_ULU7tyCd_Jq8>h6`?{)+xbH|uuoBT=Ttr19z)khbtE4Ev2%h; z28M*$n3WvD-~aMg{G`9bIjO5TPbV-lw)Y$MeZxEjF+8i#Q8=>-sR)HsqLNYrvfNhG z!cuAo6LPg$z5>AJc}6CH9V2r_=7frbQZ^}Q?FvF*WMX7yq`D(-A_zjYA_R{ZvMfAz z3q>voId5Qw*7LO-TS7nqE1hzl&Zu?4JUwBW9iE?m!}%|N#ZUi+*Vi|!TmbBv3u~Uu z&N`Xin(_Atb0n8PiJwm9U>GOgN40%=nNRzTzy?a~<Ym$;Qn)`db0s9WTzGi$} z{u8fn0uD}30_dkn2Cb-!ZlW?;q^ylmk)TfCY;YA|C=-doU{~G zt?1DX2#Bo&u(L8vL7p27xGEI&;NYuAO-f5ETK2|6a#y`ftm;blR1;c>C9|&@%cxp8 zCrAX}dzDd_zROlywQw6NwE`%RJXGwWa_&VT*^@Xjs0J-PCI*M7bjjqG@qkacM?(E! zaXOgydDtMtfXr%~NPS*b0hH=$2hZlUbRK5jku88t)m3T$6K4?1bD-{^n&HW4xD}{` zUXESD&IJ{f6M!oDN~rx=T28VW+SO?eaZ;cUSj{=3FL|L&^ku&)SghR;@}3a(j4fo* zEC^OBSg6jd8_=F2Di@F%czY7jw`nhkF(SAb4oY1=MX);of#Bm6CGQ}3oj(PZDVX#VLYUxO z7?kRDBU5LYycj4#sjexb>?_JHDI;~?P`4}U?E~A#2e!92sWZD}?E8w_?E{zFirc

8su{=HD<+tDPr{8|V`TGl&^BME`gb+oAykr@JRAtgT zuJEW>Jn-Xb!SsLq8Q-5GZvXdx!}WH>^?JeOa>4s$!|UrS{`P*swqLPjtzBPK$ytSD z8mQI$dO&M>E3Mgt97`$iK7fLG)ad|tM+2wUAty@n<=`yu&Z0s%fcisD%4k7RZQlB^ zWXtazBgk#h!h<2-Ejkk`X~u7(wmm-Yr{llW@59$0?9ca+X89ZB9-RQLMoYZAKUr5L z0^CXsMqyOV^Q@&BC-@LRL6|vva@QT-b_#Kd z_f!%GYH5ssu(-HgrMJg@RMhOGR_>XOgQC7tfdx=jyC7uYDIpw7gijP4hVJbcZCKWdo%_T<(C>#wGKSsmS)9+ShT}lT>(EYsC_Edb54ERYwU!zOV*?+V4#mPVYyV zZq8aE?#l$_VpJh+Bspg(-{76Y>3o*wi~Rrd_U6s8B+GT@FP6-#D&Q{7evfZv zxX2{4vC;ScI+EFpnMNcZUw7XHsLCZ4pFi9qGOK{wq$p~t4GmnNDl;-xKkmnmGsKZt zPB<5MWnozs7P$e%z?+VZIL+OyVqQlICFp>M7|he62iD-55iSg)s?#3D3QBEi(wL%V z+sxDcw_#932#D9naYgj7v1!-nr6sGX@_L(j{r*B)vkGgB(_vBtoCI>JlL;Hudnd^rSkFPmFExe^rY12I1Gq`EOn>px+dz?=7G_Ey^zV~ zAq$+xk@3^O^SNp?YR=3v%r~V(A4?vg<oc48w>gP;r(ctr9^RJkt&muVPs-Xzkcx z9JEMw@Q6>AOTOp()}Y;;vyO4jyCS$Bz=uNgSdL=^(dbJJ6+bwNtDP}WowYl`oGM8c ztw-xE|3UQgQnZXxU^42fP`zl`A6q{y&vDO(5_Ngw`W)&Kpe~!Yx8+?GQ@_^r97acs zFht!<2pV~HVo_|XA4~Qcl}ZK48@?ujXtb{8WE-G2kEK$9s%xH6>B0mWx!y|}U=dB- zn~fCbyaH6)zgtdR2wF^9yihI5)TzHEAw|o&RFiy;-tWLSj%HjYh9M&2h;hU@jTTcg zt+r}P1!)xRpoe0ovU{ZvBNH`hjUK1@5bCi+DL*P~wBWgcypUE;@JVUUVPqa|++JqB zO(UmqU>YYb=QGbApE*BY@G&9|ypM#ShVVF?h;ixwSl6!(y~h#kFma~%>`T=Rszjwu z=R(PmyajG6T$jRi+1M7(KY!xq zzy2eC{NMk?AOE*M@%+;#&X*^q%Y`_Mi1+&Wmc~%+@K(urQJ*%SqZ-K@oD74 z`Df&hA4%)RGS6IZGheSW|NNJ~F#h_Duiw5gFRG-Svx488l2t3n2Sc_Xs9r!*;@&oR zeSHBcmrG$hopen%%C=LX7IkL*&hv^omDS)nM6-_uUOfU+clUKCs`k70d4D{db4IgQ zr`wNS|D#~`e-`|<_CB`zJ)ouGH8UtZ_ufm3G->pt;+l;xL@wtGA3uKLr=Nb}@UUO(j%*Km^Y80R58Fk2yXMX33@ev zaZG#h-t}|0)oyLqdv6@ttFpKAc)!O!xOZmU`^?^qt2;0(jt&rShIaeh?%Ub#?GK=< zfBe1q;tm&Rj-)n&UH_7Uvq&qp_=5vfy3)EgwoEVA^RT|&tVg#;h8rlB5P-O|cf2{! z?RwQ1SjxOHam4qQ%Mo<8h;DN_y?xumJmj!;Kn}H{d$ixF!>L_g7lAp7*x6hSe80;C zu=}(f#~;V2b>W?Gt8lDy-Oip6JU)Ax4pNI0y91zgPT9HY#8YrAbx$RzQpp%g&=uks z1{gLr>x7z0uN^nU0f#eyrVm(hVV-9em)W+$k`@(!5s*;vs3=wN_j!LkM@auc7(H={ z#3>R+k01Quz;1yjxZq)VKoCt^EmzBIG+>e%VeJOY5=%AP>QXLPo7nr z>o(v-n5L1-<$~nUJ5S^asHjq(f98x&v<(Q92T}22pN*b4M5bwCItBCYMuuT%w@19? zpp?xHAIzvy&rhbPVACkXS`kcEJdXGhs90`bX*sOIwqxTlax=uq*IgyJ#n;sxl z7fpa+RHg$lQj0oc_VOi#Z4>6%KyX$7n>LL^*D9P{R+a0ZUey=^Q>m(wTtSM~MRV0_ zUf@;5*78z~a$R)3)TF+}8gWjk?L=o_hrSVXLrmzo6k?}zi;f&A_!5fJy~m>g*cetlZib! zZvfbX*P7ej0F)l&`$nmUqiw8lr}{bX@bN&~@+z=}SHnw1aXnQu$6Nt1tX0=x2!$96 z!;sm=fjBBPR}Wh)0a6G?kyoQT3%DW(MI)=#+nSeygG=wLb#n(aN8f8CzhrVZ7t-cN?ctu!i=W&Z_HN|}n7dV)DmOt+Pa zBNyRQ(!DI#c5v!@RHd_$lIjS&F$mm#@V*zhZENcB^$2#wl(&!X-w$>>XsyLXDq!smRN?fm3ZZ|DGm{TI< zOxcX3Q!E$UWo0cyJzJW0yis4hQ`S~+j+RKHRkC%DF)>+yJMgMY!A1?!&g;God1HC6Zi(xJOIEY;>H#$Kof z(A**4ZburPVouce)Rx(!FX$?kx-){>bMI>ALYqpD&V|RQrS({E$NM1I9FbKt{Y%~f zV<=#ee($>XrEmFFo?d~&K!5wUcL$27dk29XTiaM%kL~p8`0LIhZw_Eu`db5hvOD$6 zxzPZ5dtUE%J9Kv@JTeJ)VX$Lg^c+qD$KISU)hPGg--8YX65-D2?!E81tdFl|V?Xx5 z9*5oAqHTPL#v4+88&$k_rX2os2fljxg4_Ro_wRRJ%?8nS(Y+gYdyZ@1td%`|r+@ne z+HGA2eIgp1q0K!|XL2bTO>SaNJ-x0up0xjEFny0|6&P&2do)+Q+lKGJ-ACucV~M)s znDjkB+PXM`RLj?OsQp8mXRhPn2D#-hhkM@`OJa8=wEpK!+mGxExeNR#yU|tO`v-QB zSZ#lc6hjCqm>Lei_;`lYs!pn?Vkd23RzmQ^I50Y;N~V( zQJ^gcj;w0bW8royoNlJF87G}omTxQ7SqU6f3ts0zMZA_l505QczVc*;ejCIa8sXtE zNc+!4gKjp7a?drDK}?zT#M9-8(^>1_7H9MZlp$K%0nwOVzAsKyqsD-gssu|wi zTftkKR4FOVI`!IRxMvbV1i$=$>6wpVjm5a)GC3`0xQf zfA%~*KXJZzRqhp~s3)si6uj5y)$~Ej!SwpeE6cKQds%p?FKk<(iU%tRP#qA2c#4c} zq{yn#Py@Xdv}37C&0ZFWG2ueOdwMO)mdlF;6H4>i2}V;9#5Uq7I0x z?Objv>#~F4%QIY_BB%3-(^(bAz2A)zR|6v8i_vLH>;U+By)u8lX<4PEYMyb?x#MfW zxr&5{N0d_U1vj_@RpTHL?{wjM4?fs;i+20qVQ{!0)S=)aFjRbW8u=a^VW@s)fMDv2p*p}+4B@j}?t%)p|WHptu6OxA%g_tU1 z7UEdVuykl%)KM@7ya+BS)xdYDyXFyg2cuJ&6q>)%a>j)%CDOK1(~6YuNEtyUyhNsW z;?whIe*XMN{_yip1RogVp!01@$}$MaC_OL4p<2J8qP>bc=JKw)_biMsQ5S$~5CpZPfYUDXo(?A^x5S8#{tQS8FmNtRbXsqjf zZUp;5`e-bxA#9t#yDxLBJVqPXKjOTyRhr0?g3L>24d|G(gS&uiI47Kj!gQL5;r@VM zi|R~l#Uh`%TKS}8ise;H^ld9CW!sk$c`dBl%9ayp+emp+;l;GE8I3*VWT`Ecv=&~k zSGHT`zEn!f?`Q@;KLEd_*ZtME?}mKvR!{vM1GU$a!cKeVmYKliQO&Y1oNF76yQ(j&R}`!)BrJq-Z4yZ+UFP}Cx5 zkV%C$rT2ML*aZ}XiO_4&<~{ASJx8mFyg&EeQODp@dxj2|tUXoau50)4lY85zJ54H7 zuK@vvUbAi5a`@`kJND1pxgoZOTAyGJ*Vf!FB4`)(hvyUf+_8O+5!N@QEzJpq2s!6& z^Yk;u?bPWQBHr{%O15B4D`(ff4o)yZ`ueE7&CuevkL~Dd!uE%KJ(*jpJ1A%qS_2Yw z2cbx-4`1(xz>x8KlgX(fgp0&{FYU%gY2SnG=F44R0w?7o}n0qAIeYlu|#0u5`AhMA-`4yiw~{wsj>N zl{)%CdGAAD97momCq8_9;&hobD&~DxLtNLD@2?BL{`SH@|M@rO`DUtj5WRxb5Q`bZ zs=DmP!V)X;dD!MH6 zJ{kuYNArgJzJ4?qEQvZP_1F)QI1UWci8w?B?zsRS@2lC7>e=y5rHgY;Y?}i6lpQ$< zW3kER2BUNjNL5jvbxEvCqU4JAfy-sUm5sE)bi%}^njx(~DT+o+buu_A8@28R*t)^G zDUgmHE>H03czHvG+#HbWm=as5n3Q|lUrUXi^ zlvGLU%C=O}np8|I6*C$G5_Ege+-15*fj6Ua96i%1FihSeI$AnQy6}!qBG8Z zFFm)Z9o`z1T(`_R-&n4~Hap5D1R|fFKlAmkzVq_^54^s-@K>Kd@$vbY)8&acj=ff{ zcj|88z97i>2%_JxoByrVX(4I$}Ym~)F#EauG5zvsdz0ax}%ica8=CS-nScdUXGy8 zK#OS)3{gdjoKsPm5Tnfv)v~||J|tc9%{$lX<(l}1FM97P2V>IGVN{^7iR+oOsVLPt z=S)r;TUuGS#BI6p^76{d^~UXb)|K3Tr$AAwdf5Js;93B~Ks>(< z>N`OCFvbqr-0AIhjy8X!IVg^K^}QbrpjsYt7Y~EG{_H@sIWl}>P`#OHW~UyUP0|Fi z^t(Fl_m`lak_IMftsQ_ti}G89&Hxc>r5Z7D+g5E`$nJlJxAs7=SKmk_W8Y( zj{!e+Cxx#L@p@i1z`s+U_q8J3`M&RS4ND)Ot$|}b|6A)C9oRfAd;j(J9p{S z`S2`uiz9_U``npyng$jL)f2_QTu=ko~z>Oo|4LQCu74&HT)?)$ivXL=Z--nz!} zcz=BMv2+&fcmwo%ckg@6QE?ueool;&b>D}FwQ}hH-#=rN8Rf-WAXbbqqYmJ%edC<5 z9t!d2pZ|(+d||U((-<}X9dSERZQZ#=yZHcrd=6NPp z7{-yO(-W8TnK&s$IYiItG!lo1%g!jOo^8u~|MtqSfBDKUzkKD-|MUyrUzQ%}iV?;! z5(Zs}3WPoJq~crSRy8tc6ch2`zT?Cq&2D0vCeEkNOw)u3KhHv*wzK z%7lwkr-HsuNEy~`B^M2ejH8a*)1>V>1@#t>abOrCqm@>u5mHLjntK#tSytvHv96F- zRc5XN&reEuR!aAY^ZCsAJm9?})rbqhO0}qRbXg0zCTdaVNm4x|-QbO~t&CPta;I}R zBF*Ef)DK}ghr2wuYzoWu5d9G`|AaY3vmDI*}aW=Oi!AejJ zHcleKCo|%GP_KNh)#}V@6g}n4x~$|?NLwZ^h50&jds&%pg|b;7v|2l@{m$5M&dN+# zxm1W1KUBgf3?qa=BW{&yxyn@mm1Ka!BY+rBYl|k~O-DbKNu9j4sXTZRMB1RZkJEryHV12o;D}w6Lldy9OaU%>@?d%8&R= zj1d__H*^%dnn$~0wVyTF-@BrRkM{(N3WRWP^n34>;*EfK2#y#%)7YZ4x_{)gl4_#l zjc?z-Q!{Mq%=d3!`ODK2pFVux<4>P?{`iUMa$!1On8pj<4+?lq=qRU3wR8oMs*VH- zg)*`S)!mKf>cUPq`VWL^Wp&Pr3=8@P`K%6nsR2Lv8odkL2V0QS4l^n3R@ zzJ3Vy?K+QteiuXk&OLTx{`cKBD8`;fJ_Q9J|XV@dISY-jLu<^^lQBB zFP&3yh{QT5gW`dregBgFjBUQ$J3x$a@%X8_gO~U2-;Doer{_hMnb#9bd-P3^X=&rTtzG!&@6;kT)Q`!KiPsBjk19Lzlvittl1?-&esZAv6@QMDM z?Tl-5Pwfv2dK~*p-mb?|N~cZl{db^}ItVTvKEDIk`+k2|i*oON+N08k{Z{tAp@~o# zMZAlI9srWqI5el1wr@X&j_qhOw}ILYtd3Dg``=@qH1mJmBsC7(f+D6skO0m4x#)R105iI>qOP1=K%b{?jtheZJsp{OPtDU#DSpOgTgua)& z@7&whoy|Y)!T#eK?teS}>`ZChzG{IxG*Vs5U{dj>(H3>6y5W|gnCIQbCpyL{GF(QL>-Q%v+lhHr3hC??%2uIlxKt>^ zz1(`1!kRWRt?ZCere9vJ{Px=ye)-E+zI}aRT{jSo=ndmYjNrT@r>q{%P0R0$1zgc& z&E&P5k%;u~?V&?Zif))73@Su(xjYe_MuerzY-wRzR?VvlT7sobtZ{(T>BRXG7={7o z2i;V&($K0CHQYiV8f7k6#OXNL-o;(S!tInFM+AvVg-)rL%D`_p7s$oq!`cCUuAX&W z^}Ws+06sIC0Xd?^;^38neVUX`SSzgS%Cg*;mxYwC+~&mVt0^(BFwY7oeSl%m1z2j) z2=A;w<@I*u_4UTGY_@57qt)m{9HZwnT7GB7zO02@3fK8NK6u8c2lFrlt&1Hshq&)@K|;=YSA zLO>(1LB$KIm0S`8an8&t%wyR+s#s~KfnzpwNz?`p$N{aGp0wV zf@2t4*|oMO95-oiYyuTD!aqZfH)^57SzyGxv##ZFvmd@4SZGPM z+u}K&7oMLtE|(|WmqjD1f)HK2Gctbn^=OdsW5C>^QYwOc$iuS3yX74=Fuqfy?fO9v z-eL;ucztFCw~ol$gS;D@IO{iO`(8CCQSOcrRqf7f>&DCL3tzr{ht*5J5JtQu^Hg#{-sm=9q=z=5eS_(3VP+Pue5K>8R2&ap+B zPc_znp!4ovr|$ zers#!;P`0Y?->DRONC$nzFqU6j(cQ&)c3&4{anpCD`Ron?wJVe^Rr0a=Px_h>X9Vp z2#2U(+tZr8sSf$5_bSyK`g?kTcoRT%mdDL5VAX7<4t}f)?{nuLRHN;UM^?!Zn6|gJ z@>V)$T3NjErjMG#pt{-}E!`<~H&)nOjp}@;+BScHyXsV+=VkBrIj)uCnmGWTx<`8T zU9Pzgc<P0qEFPz+lFec9dwcZ0-Sjr7I=-EAz_CP=_nvrt zz2UvqbM--a(Y0195H5#YSUPpEMUHTe)1VUm&zFgD9B|^#tuZ;>bC%%$eJ5=6ZeQ`}gl$uX<=t)5zs1^89?^a=CCh>*lhRn*rx+-1p5M zE0c0op^yTpiA6gtgEPbd?}Qu*DJRx-RiN*UB7Kko7pb@^O54)_AaO7XX){K$stK=i zW?A$-A3l_x1JiN_y^mJMSNpXZ9j=2BWwQL7$tzXQJB^TkxIA$_pK&g90DQe(@jh{zXG%$=tPY0|6jXlv2$#!=5CVBi zyuQ3Jud1Lt&nvgv!nSD*+?Jf@T-Msd!^k)ug<2+E%vGuBB@dR{Eu^}TawZq2^?Aja z8gM4YCieB?`7Z*&DNQ~YRVR4MWp$ohAX#}A3aneEV%M~NIu0uGHI7Oh*F3GUmv^Zx z;%I_AdDXhlX|+;F#Z#pcqT_THiif;G*>rCBs!WCfVVu%xt2Ch;rO39r!ntNL z5uDd@XW5a~Ma47PmgIC3OnJb$!Z>-RDKJh^J&$!4G15J1H>%%mV0Y%DdW&neGBe<< z6kDze_+s#Q!RAO+!J#-DgkpSiAXCZxU_RC>4KXmv2tW!!b7v3rlAGr+2Bp1*FyIXU zi#Te_i>n}^kb8P;wSL}>o19lRSD{8W=h%{#9=hJHOuzoZ>2l$8dSaR`TuvW2Pfx0L z?lnzd7)DN$I_*3eR}(Hct;Ozizfz~PP*Y}}XXa($w#+Q+3>0MW$Y_FNRghAYiquN^ zRMl#5MNFPq51`^4eh7@?2|sGRS4isi^@{y5bUC6EU@Xhn@?FFPBj8zd;jtN&ZQ zBYRm1JFs)jDi|h(X*l7$R{<(hmi8PD>mQtvx*s17+aK;D8ZlL|puOZ!6QkO;jhvDh zW%n1`g?5~=nu0nKt7)N>^&DGjDU{(7!D@^d9&P!J@GiA^YL_?frKza`j&S zzW1ti&qM4H;C}~D{QJ@1f9th=Y=}9huAujb)_NwXV=XjFUQk9{`*$;7TPUgpOBw*` z;Pny2H$95D3*OYA0INl;o53p>NO5f*ILj|QtPumi!Rps*JzB4z(- zguR|S&2dzBDrtA}>}&OI%&o1he9s=W37rA5gBJse=78#TSLFy&nxlZ;w&o4+UYUG% z6&Bcy=TOa=Cp$px4xu(q?aXpJ4LVp`HBfQxk$A0qf__J9fg>oJ%dX#?ZEaLr``ek= z&M{$+X5XzTVLzYy{Hce1M01sjmD#C9SwfvIdsr_$w=|p6+H|#5S9Aw8&ieycclMbU zt=QYJJHmQXAKHE&jlN%Rdwwg;{xPkP+9-x#=`+zPX}lj@^xhkLqJiZ@#IY*Ft?LNT zoH6%6@jixpfBpAfcad(r$Q^*+!M$*V+ie`0^VK=6JW@)8vl?7*vSE7*+IV-Y6yGyynhMO#sCyWmanFs9cxVE(kIVBTuI@ zpFb&`xR%O%TX^~TXTE-a0gxl@L_ir~9rAmoq(R#j5 z&l8vD3(wEbeE$5*Pk;59&!4njUTq$;nmUksd3oXG_ClR+*v89D|RU>g2pcY}9XVR)2m@8zfmzy>?onRbm7hCF{ z@>W0ATTVwa9*H(M8LQz#%lVVKf0vZma@7(@!Q*_iL09UquO6>8e^gM+zI->XG>LxQ zHXE}O-fN9u1q$jwc)fll&6-QTZHa9aaw^n381*&U0&g^qwqZ9f)&AA)Mb$2=4sy|ZXUPx>M2&zW87;fz zC{=3{XA^SpPT_hfv=U@&8?1}v6^EjV!ox}&TrV+FO%)KJrplItvf4Z|@i4M(`Y~!Q zvY(9h?LFf#GDV%o#H_T{DX7}EiNR$L*;l1cTdipyJQ9qS>RU1UfD5A4j3$RfA<0Tj z8@X!KHA_XxX7^VrqZf6eP_=xNXP4-oCZo(75E3c4>W~VlXoNmj%@NyDA*D>pk(4Ue zTQN$0)_l#XN591^x*@IVlWp_Uyi}@rmg_!;#9Iz=sgzJHM_-*!h)43S66m}`awX*h zIPogg-Y9RHrZ5bHwz(w4gvq=`Tcbrj#10}AZUa?;-j6{o$5rn{VAPSI zd7MZgS>$IN2K?a2l6jq9d0Ad?-@y9;??!@;nvODzOv9v3t!d)<^33!3N%MclkxLwy zoM!+AsYC%^ATKNP>nkrW-*|cX#&y237m?!I)2dp?H*#yTgUCjya3|-F0v%jrN=PViXJz6iG!Rs zwr%BfnyjRiiG5g&G;ytF>Vv2GC~(zd2m8x)5iD;J5$UNGDo&+&klVVdL*aH~nP+lp zbqn>t*ZoD$kwy^?L31uum9ouwTZgV_1j(KwgyUh3m2q%1b=el-(^~Btw`FFYXI@`l z`Q?{i`17Ct%$F};nCFFcUC7z>gI?KN_r~RW5!-hE2H;%?>R@XsrSH&Ne*|dXi~b%d zuT7Ao4bKjK+dlEX7X02tWZwTY&~pr+l>_VUp7Aph1#Z}CQHi^ag< zu^Fz506{C-*^E{NkOoFvi*}hk(Z)I68>9-B4pDm7?z>0*cJN3C>9vVT**cc)yxMa` zHOk0+2_bv7owE2AsI=&CiwNIGC~JRa@0-p^qYBHxnRXPkYSFe}Yww-DKLExSxvq97 zRV;EOTHdotRW*LGV39M*shy?1QnD<9u-6pHXa=SgEx!hV2A-9SmHm4g1R=}&w z#eEHV{GbA$&FNH{lh^3(trEcFJa`1IxE8f_hqZoxc8K?T-^gCd==i+NI%qqVcP(A# z7&*7|;4m%UqtG8;`}JKHk#o+{|GdMM+Q%XO=l}eF^78V^m*2kf?b|nQw?y6&tCbJ( zaU@9NpF8jYZ{<_GR~dRIf~csOMNDCg6CW;)5TA(QO!i;7zFwL0Lal{4FKpY!ykryY zm`N$)5puR%&N%RN8Ts__%*RhBK7Km!>8B^omkS}#Y17-balK9Wpa3YBOvysdYN$5- zhT=_dr6_H>)=J8o(u`31=d3^&^gSVJNh$Ah7r5#Al%3f*_J91-8xUecO$l=3Dz< zbtS!{5^zCFjFnmuJ2Y^rG#R51oPs^=h^S!Ga=lZ{Y&kK{tCmGuVA~3}6{UaYLMnw^ z3|O?;P^8a|5CT{PwdJa4X)mSyE8tYOqagU|sFuH5t9cfy0?Z;pDuuKqrJ$$PMEgt> z$qRn)o!%Zow1{!sl}w#8tPyC2Rj{15rm$X3giNJs-7H1wgjSz10 z!hCz>HeXq`g;KLRHwNd$;Q>V!$g;ffxs}v8L6AG2=8tWi1L<7;j z)szh2ydBVW7qxQ1oOVswT5APsq`(XTQD6|q!Aj}16ogTuP$6YZ(12jWrXS@uKo=<$agV3wRsA=V->%{va{oLT3YZC$(f+?gS+!akXl zvaKa=k#RGk8_?S&Ueb8)XJ7rzu-1sS(cgGO`X5j>y@0d<@^P_ z8RMlW4Nk;&$4t9d-^ADrhZae|tIB-nrBeI>wEhT0*S;a9A81E4?o{_7z<$sMW9R25~p1_eu`5zezKL4F<_EZ_*v^yHgT5L<{ax*2?L0;#l^K zHY=R#fV?>m^fSenHezRT>GQVbTUP^^JJz$k)6QvVs=xO+s`cP#*dvqe-?bZMwKnzR zy4!u`pE?ThwX&MiG%-$-Y7DjLsPnr+r0#5l=J?k<_{bI`zGTg_wu&3IS|I8`FM5mu zxAq>V)b5blKch}xxE~qb{6hM=V|Rw>MXZnR_rLC3YmUmM>U~Jh(Mmj_GZY#Hz6mTg zFx>jNJ&g|G;hqk9H2&zQI6TWP{^cz2M|Y$-IP5d-ZjD!0_X|C)`9pu+?*-D&cKUwP zFu?u(b973?Km6g3JU>5kK3#~zK>T`To@b;K%k8y^TB2g)zV|Ixf?R^J(Pi>CA_ZC(f5ag?+pz z7_3?su~7;0A&;Y&@%8xfeWTdvGHQHVt_Ol29M8`e&X*J0$7i0Ozwzs@f8ph|<%1~* zY82sN*c~?0~=lhX~y4n2EB=QSEg5JC(Z zsTu}iP^DYRiCR5{f@Hy);7QqX&(G<(Cn5-|j#t?foI7WtQjQoM=ZjL^o!8Ctx@dh; zsW)IDZ8m|;JJ$AH=cV_#ip88cpU$MG$hL0Gx5Vq~joWnvS~)H;im{1&tx6-#iB zUm#JtEKFLbcpP^CU9EPKZuY8BoYNjH2Bl1QvDj8nvF_r z02r$s?J*2GCQsBcd<

KV_lt3VA4%ZME$EXel=O~h(dTQ~yR;totD3x3SNnPEDlqN%=28+{tpyNiD4QDT) z001BWNkl-21p%dK zvG_-t+U_0Je=9{)72mTM<M%mD*6gNM@Wofpa+d+$x@v~4@_vw zsPMHoij}l!buWAW2z_I2v@mgn>JpjAQYk zf(%RqCW%Z$#u~K03#x3LEgBg-)9Hk`Cb*`6ex7GGw-8$7^$?z^2wN?zHL?1N1V?hP z)x<{9{u~2ijEo_6149HAM@xy6E$V|hOMM&(VIT%gC&*QWK( zMSrhpG@m|x=5PP@@A!}Z=|A$PKmAE5;bt_}D!5=&xrcqUF__*&h#M%Y(kaFzrS9y> zxscMv?RMk(`pPzIX}lq5{d(`z(N+bW2gP&{TDR&pL80X*hFxGNtDZnERu->TytDF8 z7GdAIA?mvJz-_*9yS-|OwRvV;S53t*8fwXfY!RNEcQ7wfkcWQhWA4;|u5V|RCt-u%bMm9}Rbp4EH& zaXvisfqPhgjr9QL>}+<9yal}XbVq0@W5@kpuc;?iG`0`WRpZ}fFNhlJa@Q|MFn-w3 z4{c~5PaV<6d7_4duGP#k&n&AtWP|0=AAyuoJ@<8?%s}nKo&G)CspvX$pfnND2ArE< z7QV4z(CPyIehiK;{hZqM(GNJB+5K(o&B*$}oVT8|x!ulT8%t^TXrJHLh`~Dj^g%Fl z|JwUOOR4VE@b0ucM9$mzHbC1-S1ERLw&M1jaqoRUZ-)ry)0xZV!t;j@EZaiPDwygV zRxw4{a;>~j?Ev2PR|Aiw8lC-N{x(qW4-TdV$DKYcMvrdQ2zJ}bQ5#NbAo-!ac&!Me?R@;Z&dYrs?JSLEd+RVd z8@I#!kcYnE9@I+PQ``R1uH;%I+V|@muM~gzsk4lB-% zMuLOZ{Y~4({PnBWv?@UjphdJEp}zpItCK zPLU5Ep7{9b1LGJ0&7}hsak||!0;OV1GxNOi`f}s?nn~G=58I!b2SOLS@0)M;`b(uG z?WE|v8p-k5)D0`n|Hkd6HG#d?T+#Cxrb#_c!>EE_afn<_PrX*`(Kwez)j%mIc}w~X z%f`BDG&|+gBWIxX@+52Npj`FdK2}ws9xcBN*`qK{b9HJhN}Fz|9T*P|0OuVoLEO1Y z96Vu|?EQsc&IYZGtGV03YLeBg2hd)xOr0UEEZ1HzyuqiyI8IFClLEUENjbC3nWyI~ zx9esGoR&(`+Qtf`))mSER0X-i6AY8~|1>#N9@M{cf^}@Q{ zWN3Sd54z=-qH{;o*-F-6EB;`YiI$GlI>iN?{rgy_w9P#cE!z`(pvFLm(n~*SU0b2% z(hH}HfG^G>QiIK1M;wCE-CdwcA*I5WP3*u`Tn3kgVH^lj7~Q~#s=E&{m>9zDO>Can zYVy>jY^0)PE>yU(c0nFzl=JFM*eV8GjEGmErBsDfE2%m)_$|s&ozmN-27ER{MYN-J zjVK)_w_11BMhUw2C`JB|J7n!v8jsb^PD$%w=SjSMg~+}IrIa<56+aATfY^GXy0fcTkPbq8#;P4LL5j? zCsws$+Ob6{f`g!{*|k<0tlqDR*lk(sxi5=Gpx1Tn6zFwbm8QLIT06KD-M@;euD7+*=HPp; zrh>aio#YPuw)OJZht2S6IexD1DF@^4L6qq6rT1*W<3~pJk6*{!{(tN17#aB8d&waJ z`%Z*sH}WkL_-J%>K;YgYk$>Tyy*$?5Vp>$IMLAkpNi&*{hN?!`?w{{yEZY@TQ{eFT z4pra6cXpsZLPbF-To^|}Gzl64P0Mzg!Kr0ybjN5<#znRln`0gM`D`N(KEKI`M> zJEN{vs8A>*65e~Zv@rx_TJ^kon^VrH)4Glu5Uvzs)V8#so-^Jiy>rSWZ0DHOci$ap zHumgnhJB0=j>F~%IoM5a9gy@j(Arw@cl(pwwfAG|ul;&L{Kx~S; z!3R=U+0sVdvY9FxO~|FF_aHb0WJM_+eo3a}E9#A2M5)Q?8)-|d#f$-Ok)2S8F>;C) zeeq(~PxfG<#;Df_SSxi=YbIySw@XEpFmIg(_MI=k{>E>=3NKe36D!@SG(#}Tw(S@e zmQw1ows*U#7u}0Z3enD6w*}{fsM<}02s`eE0xA{dD2!Y-=JJ2rXjgaWJLuh~;w|U@KZ0E4vNnbj*ej)H$Y)V8%mKc8J3O!C=mh zrp~MVy=|3cDQpX@i;%X0WTk>>4y7YR71i^D;0M7C4mSuciaHezp61qXf>IM{`H_k! zDbjRT$O`ksFq4vR$jk;<;y?*6aVxN z|G>*Hzf#ghFj=<{s#X;kJ<~KYO}ekf!6@7zbU_m5JVcA2_T1(Dz<1_A*>Yk@nPpwM z%_}c2FWeSoMQlmIaI!-n<;=2b>A^jZt6J^#(%Bu#N>+!e)E!`UBcvP8yMY_L?`z~3 z`90FbAC0wlY0piG_`#q(-v9A;O=bG`UjG`P+TQmFc7E^k|5^|X+HZ}SWj6SmYc&w; zpyws_zjFkb2j^G6LHi~g6<5XhpO5cX!~9+?w+UB?t+nH`@6UQaj^KLkXy2X>xMl}h z_Mhx?qS{_)-m1H{w0pGZX$wdw+o|>6egD5VM~;6#kpAAyrSAP_U|6KZGT(o7ioe(Y zHJyU?nHF7aS`w{h{G0X)7JXAnt~%vBf>Mt?-YC8HEPfvY=RGm{yXSlqCu-mQagNY{ z1E}K#vvG^*0o>2)M`uIm&aWNp9;x8(EsNtG;JvwD8@sYMxrrj#dFrF4A`Jt(SX#4L zcVVsup8NA2BG7%^Im|Jw={LcIOXI;op>x$n(8fh;)9+3kU}v3)^qg;;<&0Z&v87{0 zcj(RIeD%8{xJ7}1L*BG>KzWxE^1x&}_G=4JsE)&Zsk+u5)tpZ~aL@p7-NEynxSBne ziZSl_!>#_X?~I1sk=EEyrDT#Z?ArC)m{dzkZISk))6SvxhtInM@v#rp6twZSdzXiK zdvx?1^N));nVg`tiS4@G5mNWPx;ZXm&WTbdPN#v>`NY#jbD7eza=qSImX&Q&rQ_z+ z@Xis6<|Gbb613rNwD zBsnv$tJ2r5SFW#DmfNhr`!LXIP-_3wQYoT9t6JWv6!5a)aYQ%lIa+bh4YmmDsG zqDig6iRLUSua14<7tOu8nKPkFKNSgyMt} zK!$)DBE+DoeNm`*swjf=P8E}-t?z1iJVqM|F{mfoz(5;`29kt=v(3NQTGv{*fM^6Z zt(oPvvfQ$cwK*$n+Y`8yo0I*>vssYfnaK=ToVfm+yb! z|M|Z&!KuUaZ~o@*IG>ea0+4GZpn2SH3}a~yrc5njP6F-hh|#m>h1aj&`2On`u3x@U zu2;N==$o$jX5w(3Tvk{;IRwioSI1lk$`sI=#cFVf85e~nW}?p5Wi2f8!s|`Xvaid+ z%gZaX0pMj*ah8_qlTFaEy8ArZcHm2GfY*29>&<>=Agbjxs&Q}mlNJ$f5hqMmfZp&j7?eUQv%@Lr+ zyQ|$_-=muMXxbPRN2f%`yho6|)02;Pdj!F|X)1SbJ4V=?({>#}yd3DC&b0{bdk&~J zXB;hucXxc=17L6YgU86%kNWfe9tzqXODx^xD7QX6{H{~Z9Uc6YYEjJIB|88+_IWq_ z&EVEH9Ka1?83x)XrF-A)8fITV){|8wT)jq5;|l>RkBjf)RP3p=Ci4z*k6`-vbN}hV zNmcJYe|(NZuOEPw{}#5GML zr_+gXnpC4AMnW7+Y|v7i%qghq*BiB!g*2uAQnRTNH)j!hs+@0j(LLQdgqDgJ_tdUF z$@B+r^DwyZCO^BqwK;73!67N^Ytr@iI*tzP9xb-DFWiIeJq_kChO*mra34iKg44EM zTbh?fqovcn+r3NH^0r&rtPgj4PlP>1hQr#jcJ{g1i*B2!n9bid7hP|k6~01Xg?;@IEj&>0T%iF#}sj z3qYai-83*W3{4bC_pD?}pi(kvU5QZ_T~m2-EO+vaxO83`h`&*VHJA`C%=ucl)CoU%>k$}%tf_S?qy@4|djYBB*neFEGD5-B5Q^y!AO%!QYi zjq9rrqtd)D=QGnZa=x4xN3AjFyu-(l;S?$PLd}}*mN%oC6tO%(A*GFFxvB$1k{NsZ z7NU_or9R6(y*gLRO49a)VPeT`KLE50R2(pBx3h9xg=MZRi_WKPz*uZ7#GEa6O4!w| z?SW7=q82L>swxw=&7&xAElD>Ey`JW8sOoEDP?%>wXql@XeN6h5&5%!JqtpVM8rSPQ z^Ua5TkU1~JK^3Gy)zMqNl*0_lrqZnZs%|*sT1nNM4WbX&)wrEdy@TM4>N2P>5)M~| z;sc~?xrv3XE_#1wB|HrHwUMYz{H%gV!MTF>3(d}S&c?E+3VT}b%UWsfuN_)dcY3!g zebCCy2)<7U?Nd`OuV#FeN?MgV?R_T3jB^30ky=!oOApsz`MX*JF$)$!5Cha&PjeUo zW7Ir*Z<+>TxnF`gaYUm9N{tr~&lpEa6}+!T-HHUShEy(DDbnuX`F4VYLUD!SRGi6~ zqs-gbI&mgQQK??l$6e5Q>VmNo+8B$`znp>Iq6zbQz?xuEu$(g-IE`#OW0Ew7(tfb1 zfiG1V0M3g_rn%j~(L+oJ*;&~WS5-y+>$kt~U;k^NN1)A_y zJ7lX-=NnyK*H8j8cIVeC*I&Q#`s)|gm#_G|a+&l{ji#I68`ToQm!f-27Gx_Fr_V0` zA8&8kBssDqiK+PkL}XS~_j|K5qzr{S`;Gtq&yXv-D|F2as>+A};D_;pnmK^T ztbT82mW-C_ydnUHpQdJNY9SKvnxTgfp~=$%41|}4x^2*f`5s|wh+DzDm0`f=K%;Tl z1oz7Hj#X)-b+PIKBk#|^fTm&WJcENVKMrCkBl7zJ_#K})2#Ou^!;bl49|7&>dq1~{ z*Z$Ry`OahuTlcTWJiuRh{iTuJkMB!n25GSd7@a0m!$ zH29N?z`>Oq?s?b?7lH4q_M|2(xkv4qF*h1m`Ybq@@_UQTp%6yjJikUX5Ej`Vz+@k2aZxR} zBj-JZ`6Fi)qhsg$e&kR%(#ZXH{JaTdVv|d?>6T{NYHQ=6JwQ%Zj8YV>q5ulx~?d7Lv1{ReSL_4<*IBg zbNmeOkLYRK13Sa9_q0r(yMpxX>n~`%CO?jAuqjB|{*&KF$1WXMl~2{TG9xPN`%>o0G3TL~QRD-ha-5Ef)jz$Iat^6BvL zGryGKn6r`;r@4SqtBJuj^dM+kL`cnQy3UYkLiXH2i%Kv@uoJA5j#AvC(uVAMSKa0L z)hL)bLjsX+jf&#bT+nM+w}MRtwKRmd0vqM-%Y%8g%N=+ufNlf>mkL~Ft8G~dY9)O* zPOOQXL&o)bMK^(#Z7XK{z>KoPq1%B{6!+VLQVLRHz2j1=l{+$zRHssKid0jM8_PKX ziFvmvVV=F8I+kTcjig#E_l9j-P}hcatt>rMhv+Q;qZ|vtoNKxG{^j222n_J#ICq~4|!7`*}W{%UP# zrXY;UrbXdqH_a1rPN($-08L4M1R9og!Mfd1wiTs4(0fH`g$DzGm^RDJ(H*E{;BuKU zT}XADrwHwboF$`hx<`^VA_1+;0a><+YWanwbd&~^rs$1xoOxJ*!get+$3}q`8a4>3 z7Ungs9(m*VrGUW@0r;~D`?XmPcQuDr>m0L`I9_^mNSICF=WnxeXeq_f>C`1G4%-0t2{*>XFOevvdLCYO2RrF|Oz!U?#c}^wiu|P0Z0Bc0Lr+jBJ zuv`V5A&vZFs_iS79%~8C1eJAoq=O&Yp`)Qf(M|M2Edzw>GJy1F?X2zVK34TbA)pc7 zWdL)3g#gwJRu?G=Xw|{F+Tl&(AV(Ls0pHjB;Hx|MQMEE%mP36A<5NGOLbW15Fr|pn z3ch~-9sd6Bo2f=K68v&~MF<(H%(0CkR8t;?qgo&D;J0oY%RW68eE;PezW?j*asTBP z)a{Nb3#JroPhpu3IjJYRVZ9p-O)Y8^6m1wWd){Cdwt;5>`T9{6vrti1ri@8|d5Wl0 z!de@aDdPK@uxVyN~Aw&>Po^$2}x^bjd+tk?zdvxhJ5;}}s)$ub8 z(RTWIr|_u%wfk3zVC z8)GodfjErX0UpD_QDae$L9rDfJL3qpKWMW972g9z1PFb!_8qXIC)x82|K z1mcgzy#4IYeFR&)_TD)zZs(w&huy~1;dnk$kN5sLt*Jxb?1sNxXG{^Xv&QBR`n&!b z>*%nKKgtb%2I9xIJV)H4Gf1re_Hp$0@5;p9$44g%-)>F}>j&;(dYXI3GHhhJn4?0e z5FISNFIryfae=zyNx(FnanO6$Du%8b1r1%~%E!a0(cClDuQ|Z5&!~Nj1`7Zlt(I{% zhbI8+4*hoy5Sw4YoS>uT?-(aJ?K$H)2hctTHvBW*=5V}*Io0;xALoNRA;iwLegDdt z>6BqgxCG{jvJC8)24*KHLOVpO`|-^1`FNZYzP`Ob$uRN!>LUOKT!74fKJ4$KZ|$0$ zRW?%V9dB=M`1b7$f3RAGIc2 z@cr#807|ci5J<;!>T;>5>q|N-N)7|*7bp{Z0N0Hl7KW{ zaJ|g<^5qMD^YSxlsrdT)ulU37|A6oJ8`gEj*V~=7Uf&j=DCD&u=LD?@_xo)`bj3UD zy#Jv(@Qk3~Q2;cxA#0zbdBRe{beVB|dBye0$U4h5b!=Os;MGdXg^S2QS*y39q6(vY zIk2|cloFoIkTTip;SF57{|1*$`7tq z+GGlfz)%u;Z73U!{@A&=yCu%I(omKK_j|$pe#7IfVKr)d^N4=i0nc#q2qS*UqV*}l zN(R{mVD@y-y^Uj`b)XuJxiz4y4S9NyGCNNI6uq&&Q4D})ietI zaJ^m-XDSc&Ksu^+g8fz%rEpHg08EqM_4SI&3&qvsK-XQ?6-!y5-$>zM&FY8cd^Dp~ zn&&$LF)Cuz@r=C#u>jgAI+rI#EvH-oTYigx(K41~yo*EVDAYU=j%UIwMNJ4K); zI;akqaew*2E=1cMY`fYa9ZcdRga~8;@E8+4x_VST+;d4Gx?4pI001BWNklcWB!uT+;^8y)?^d9ts8k@2#79cQ?_wj(~qxlFJo^pT>&wCbT!v0>}scmD*i<}G*H?;ppsn7qG zXznwh{~x{1ho6Uo-Xk>pG3X8^I22PD`HII}@x3`HL0>Z!YQuCC%(*sYR z5ge}RqHt#T_;@`>2an8xV2)-t$hDv6+W}ibwV(Qte>(%PV^ndp@h~T!pV>bsPD}QA=`5fDXl)+~&>zeR>p&dYHG7m!Bn;5&{XCo{2Lr!#dfSfxSc9dli0^AV zpz*#sMtuc1QA>~g;}Pq9jNSRtEokxVvibP+(cIeS!T}6Df9{yqdI0FY*Ep?Ly&R}H z-~6+C>8?&D*|@jQwQi117wQ7fIt9N-)0d}R8T;qw+&2bAS3$a7uTWJy?i6Jb5$LSQG2(W+ zLGE_|Knxj9B?vK+8mIIyt?LS1E!^E;9$^Y_Y)vpt6Mp(BQdG+n#L8Cicsx)FRiRaB zaL$RfbU%GbxLzh)ri>{?WUFx-nnKXg))nQkpgvZhG$iFf{MDzQ@V9^azu|BH>Ti*9 zLVYwm?ho8c!R>a(fB)y-;s5@Jf51Qf@~^nv9_ZTxAw-lSSRNH+A!ySLp6+H7(g1H~ z4x~r;dLR(f3{0p9u95|qvC61P+kj>e+OVxFYEuNsNSOoGN<*=lvN0(n z7KAB7Vxm}>)w#>x%Yu z#j-BAUT1>vrY7{jTFg_J%=Vk{%P+s+?fZshS+H%DXNPd(Do+5ln~2r*5-cx+D#j^w z^X%%_N!)|$-~m_S zGV)h8U=0qa8)AI$-~rzgJMWVwLA(S+6Yude$@5L;Yry3?5A9u3ts0}#E_sG$eh?VEbEHz_Zz<7-f({`SPN@LOJ^U5@Om*>iL3;6H=!Q3=bN$0)h_F zHWu5qR{ZIgf5CtGuN(KTQt)^G>Hol&FF%n6WwfaZ8pU2NBFBVasT6ft@%E>$`2PDp z;O+Z2wA&5Z3qoMtbO;W>4NSZ7pb=4{87xm;Q&N=QVI(9q6chfWYJw_d#f%P$>{QvdqBd|OEW)6l^)D3QYy2s7u!F~-9g#

    KgTD<-{e<%Bpz~_?XogVg} zt_Ne;z2?~a%;)M3R4t-sd-Jh|^62)1gUO?>V?XE}8l&Yca{f3A;|PZ7ER@mqU<@W= zZ0nO?^RVllTMP%YG-d}-J~$h_|Bp@x?}M{*;iGZ<*a@S-T>jl~mjJEO*$9|8XpXu-XFM59Yj~&FUGlwj+(t zyF(eaud0dHjeXET-UnOD?qI;Ex)CjHt?Q8G8V;LriLpH00pcxtKQ{i^{(KGWJAyT4 z-@$C2Iy24tT4EgYbvPwb1ad;m3DJNs%WFlmg(EbJUvpIcLxYV03NYc#bGV% z%n<(0>CVw?rStEPUE~fc2iWN{&qy(1p01R}P8lz+FSt%Kft86&wdxOVi)hHI(^FE+ zdoA4)lWhP~Mobf;0=Xo#YJwj^`c_;ML7pM_%M84{Uh(oeW1inUspr{W&|K+ zT&92`1uo8!B_b;~oGE4G*9$H$FZiqx%kqGvD{i+1-`fMKibX3UvI_{Z78=505hbV0 z2HB~$fQcIk>%G5MTn%g5U@efS{dN1 zgAN4^4H6=fB*;8NVna{6s$?@-0iZ0P-GL?@6Ii0@BSaln%XB zzVG#lbzO0NJdjgDj`XOBcI2G#>E#7=E0C6vLc|iSOh@09W@`iL%9^_!bZCSSk#oX) z39LmMt-ySsC_+%DhS|m|9j>+;!?shdb!Q8B^w(2kNu#FHFH0mPL{qw|wIk$)Sb(jt zuCRaJx^0v^YM`^j6Iy!5sibHKbktlfz-3OjUM`qZM6cB%;8s3F0#X*_DI;G<6Dk3N z!r^6}%C-x1#ZIS6sTH~?nzAHIo@fwNC~B)Lozf~rd@Q$8!0I$p2Cgp&uP;~Rd179X z3QDbb+&AV^cg40g3N!`9mVjDrEdR1LTvBFKPq|sQMrvy>Vw6o2+fXX^ZUyKqq4kF1 zHHAwBc0dhLiIA%MBmP@xiIm)+5%mMT5|335t!eSO8xpMHZWO^jeS=6bAK!Tj|r zRJ)Z9V-D-l7Ig4C&%iwKa1=8HS&qk;3LDpdtww!L`&^nP09nxk*K|rkk*H(tqyf98 zp3dM7pgug|%qb@2Jtjq{078dKAPre8x6jH$q!cOQky&012&S~pvQOI7sM}^pbuWX0 zJsKk*^)?2}g*Js(B`s^uRMG)*-Jo*Ei`sz~B#r#F7+L=}1+qC>3Fs*3La^Jz4)|(s zwug2eQ0}>xK1$}W%`(bL2paRIgMkV)qsklrXfzVKa@~X&v8}-E{uO`!_y5ff%nAST z@BR}$efn(HxkqIz{}L9hs*19#`1;2`;g7%n9UkBQfbH=>=y!U%VU-Y+d)2N^*++Sx zQ#5~A5;{s`4I`%aF(;Z9YZpdpf-84+8z0qq}RFT2l25skm} zy+_dgLlA7^{Lx=&zyU`f%(sUTG4Y7+sqBo61%g1L38&fK4n6eO30TPCejdr?-<>A; zK?`xD2>#m89YIVmqjI0L9zi`jcYf`H$LOKz-d9IJd#nw7bhfyyDel?)!F9)HeXiJE z!+zUQ@UiYPBZD8cdlzhb?n}k)1R3iI&vWJ&EgsFWJ=Mmqcj(AZbVs%`GS1Ovzn&@? zIWq2fpq*h)-RomJvRooLuT=-Q!2}xpXCI$q`IzU|X&>3eEFU(PMc51zkF8Z96 zv5y{K$DdVoung%W^t}x@vJ`e_!c%VjyY{~q_R^uwe|BK)WhxH$&|P780ASh2@8pDX zr;omO?(KWc(>>v9FFv(JPbmgI6BI`rufq=5Z*R^jFWsoRR{^kx@~=3&-@&QW%6o)> z5R<i=FN~~u^7^{1_}w4>fTa?2t(z?vnNVuM*Kc>MP)zd+UOx*$<>$1U7>X$y zJ7tj@?oRLPzAoI!qZlQYrVI!oQp|`UL4@@}YgLqLVkf4Ynx>440jCfGv{BtQ#Q?z_ z%R&&`0BpS@bSmMxdY;5&B1tCR)k%#OqopDMv2{$6FwF^R>Qv9h9kt8IF;)n=(x7Hd zPENRO+jv-mGX6nW*ZJ{anW{W7(j8)CM86fR+lE>6Z9HTiz%W@B!E+(HbJRW9`Chdv+?ZM5aI(VB&5h%eo%on zLD|SO7@AkQk8P`pRy($hjw5LSIcD_AT&mUuwRU`e`;N!s!8RSluZ}MfjEJy^mwSMz z+6gYRVxAguZg||uV(`3h4fa3Hro7CPNhMo5;2Z8g2yA^K2DIT?4+a);fJ z7_=^EA>?7LX z^R+zhmnzx@>OO$c;*r^K09AUv)`#slv{U2^$eyEqz!~72qN|7d934AMX>n1y-AH|U zP&1;APqqUj#0g1p74)eyK^d>=F_;B>`|{{+eg0~)Z~w# z|Hn53j>9Cdy#rx@4sS&t^>*9go_){BH|JCs5ojFx34jKpo~z-s0ei>yM-c9|dkD@Z zdjA|p#o%9~%zhN{7C24#41WFn$4{s^`+VCR*M2v}1p<2dNwnFWE#p}ZfbeIgb#GU2CV6Wt+70J@)ZKU#OYqiFB1-JkOw06UxES?PbI8XSHnz#)a@ zFjfZ#k1B&?+GH22dtU!f`<}BbVq`@Om}5bK;TVO6arUVydMT*Aq1T2M0=m%ImpwRS zQDaF769n_zC=_Rkbc zxLha9^Mom9%Yp5z!CD(?-B|zF^26zPX}DWitGZClyOl%U?*X7D8;6UDnq{jo2b0yu zVIzyRq8Uv%8N)>_s{9Oe59Rk*k;)>!udf-euP?Z~GEcRK6M7plmRvsJJ)27&aC%_H?A}$mFY#a0X*KM_^4mZPEJ6h>zMX{PF zngifK<_fkAm?y;)3Ms%w!A)Y66cs>8Xw?u9z&gKbc^x!r2=dpBbbi*qtR^bOD0P64 z%3dj)V~w2F-Aq zGN$Q@oF+gMbKIALZDA>+*4o%qy`&AbjGUgt@c{xfx~gkNKt|FIX$8G1dfUd{A!2kt zJH(?=PlI`^chgg?RbjLY&8Smwa5Yk;0j=Chf_AR$1a0boC%$a4my zBScqq-RWk#A!A0N&?sfZnGtkV#kv;!^7UWvfBokTzx(|^;>)MsBBdFZ`4e7WUoqti z$3M=jkNsHiumAkd_~SqR6PD$UOID;5(6BgZ=Sss>u)BHMgQ=TpM^i&EP|9Wqz6QEaD-?PtF>WO0&wPV8wvdg zXo3twX6!Tg0m#MKfaNdFj+p2D>A8>Ie|6(^k4PV1RFVA^fH7|7QTQK&=Z%= zk{;M_9U(W^Ik$K0A%}i&BlOf4)>C5p+x|B{x1Q(DIr4LUu4fQoCAoqJWA=tTkAe4j zhwN+a14@0DW1l?tnnl4!B>u;9YCp3-o(p2v2`Uy94Te#6F)$Zv6k%kR&U}H$k;=SB z96b%~MmJ~@2)VGPG}>%qBaj+n6<`nW+^i9>`bQMP`XF}$QVI?R6f1${eHCDYBy-5fv##)Xr$aJkPj@A_qR0*M_9(T0j?|^@!RU0b~kj zIij1$OwRNQqyPkTQlN#ohG?etJk3bH>6rm0F(ahTT)mi}iO-WvZ5oxpu4+L8>9x}| zLDeMfdqlr73@H-WPge8R0_yk~0ku}B=RAP| zCd)mbl!h2rq&Ojj4Jk1UbvzJS?}(jLLJ5LqAlLscz0vugVkHTz{F1jV8U?^}91{Uj z>L!tH<$ijjY`?hZi8(xiSl&{cIIfW!c^84dZ+jHq$5SYn z6#}Q3|9)(CMoW$nm?z-nWx~trjO)vcG;wa1UZ`x`DpVB#5fO@LU;RKR7HzLpcSU2% zn}+W6?aNj0`f|nPnhBVKN6k2&8+>s$^j>-YT2Z?WI)6$9IeP>?TdvuRoEp;nz~$a? zUzono8&I4IUPtD6hGuXP*4(9sC4LNSiAvOSBYs0p+K^t#s4y*Tm0;rPmUhMiIbc9$T0<;iN18Lex z1oJc_rwjUvqEtrBTdUCCnC~6MwtF4Gl?Gd*SD&)UWVjfe*i|3Vy>toeAaQXpQj!~} z5hp1YwXuGI?v!UYs_9cM1cgRB<+@(8A29ScksLCOnIcyRbu_%J3oVHpg7twvI5{3{bd)m zlL5I$(sls(Bk&8nrwN|bW&eGzzcfnxKkI(S`+oHA{eAcMLrl@#`K9*isvL)50P{L7 zE~o9Nl4@(sfR;a-N8S`V*aChV1%@%J2G*r_OC1SE`}{9{ZolsifF>GKt~?)4usF`>O=d1 z_Yamgy`Lq2ZcZOdMfrP=6lj0u@w@`)4|1B1U-vd1Ub@fAXUEy@tTAt5v zv^D7McOX6LQy=zX&*gm{3pL|)l%~UZy!P|UY_{Id0QktLP^EDUjPvXG3Vtcqa*$42 z%bJdHuA7YI$W`WbVu-{_lUH1^NU;YGB_n(4Q1@yR{JFM@TB?aa@^1paz6TJ_l5sI$!a6{esumPl&>ry-0#7U!ZM8xJMLanHV)g zCAeU~#@dz*4W+Y`hKNO?dqiqLN)at*%zedd%E37vD1{+l$^`i_v)oS-p>R-O6k}~d z(Wz@ho&(~<=xUxOOnE{`(>}2Q^jh%t_J(Cy&_VUy1_30Q&)+CYW>}#%Xo!%!FCM2G z9{&kscz(Rb@-e|Y1lE!DvRB$8`_nvZrB}d!EyaQ;%;Lg8JyZbnK-OBZl@-mBq*E58 z9Ps%wX`I)W3$8CSrYTZHC}4x(&DJXic zjO>`eTkou8+GAv1WQ^#Q&qn~E zP=g|dj+_-K06i#T<~q%3CNrUtH>}#w8>kdl1)(Wgv4hC>UD<7vFg9cCrKDsB<(lkY z=qzt#26IjZKAVoR58ZcTc}i7?upCMQ3{|mc!&*AzUJ&FBF=PV!keGujq_C&ND0dk3 z!gnC=(e>U9pb7!7R?daqef^#zH1-|b)4d;nez?$kZI^@BiftBsRTZ+byM2aN+mBV> zTU3G8P_;uEOK|0!EH8)bn?Z3h?`=$ioT5d6#hjNB-O7kmJ5-%<<6<2F=7j>#&67T& zB|*&~Afdmt2I-_s2Vwv20P+aD{LnIxWRY|2j0y+Km2}~u-YnH3CtR-?>l!Rq+JJap zp}L@UK`n}9Q+)ddqy~s~Ori)Oqgfv}Z4kiJD@k9JE{D>10Y_t?8_jtb3H`7q8~cE! z>=88XfD!h$ZevB>||UW zCltZ}_Ws_{ZhxMm@D+&A<*6+{0>6JQD)sMq{iT5SxgGC}(|^}}1kiw8p%0_~hmx>? z0UE%;95+taG$)W7wT(G5I*e7piL#W`gykGijU9J5uV_FYc{4EZ0*oAA-)D4~wAS|X z#{d`$V&C!H=-+|cj{ucl_iV?|_I{2c?jXwSeC(%-=clot{jO+bqNR9y2uRGR}{W=J% zRm4P5Lzn}=0oSPs=SO?*6i`n$+J&};Q~219Lz~r%Bm!7JU}-G*x;d^Zwfw!0oQ%(+ zi%{KFu&sTg1d+ADMJPLf(4W>s@B4M_K4S#T**>EPj{pE507*naRAGlaZ33v-FSbC3 zu%6Ak?xi((#%|ljez(0a=WO`VsUXX&I$4()dAds>^ zL{Mrp?|HzsZBR6{T2T9fQXlBLq1F}J30!^B5D=?Hpl4Hm19F_GDrW$Ao;$ABD=se` zFE3YIUlQAEbG%)h0+#g20>+!bF$La=!Ln- zkH-Ubt7xSHs6#>5Ri|4o2E+w9O@rE=C!s8TQa~!Yvdu6d0}A>uA{S#olnmsImsjRG zC(Nj=;r4aGKmF4U-~Om5i*;$(1+cuINR6nbMBT8ii!BZlowA54tZYM?7}dRAKH++O z!R7J^DUuF*zdvxl2d;-!00Ht8Or6`(0JIO)S{k7yq@*1!vi@kO{0dN*tl2mOm_lII7mJ7M(Jehd%{!jV4l&RDmva$xVGbc=piYkPF_J;}7WWqLuB+ z8QB^UVl)R`Alo1(q?n;yQMQ6*-LQm)RyN?ld`LVQ4sI0e2eRh_@4&Y!X~1HxV7Jeh zHyDSw4Vf36LSo#=#{L{!U?)e~+-7?ZuWQ^(U3nzh#i`UN*FZB7LZbc<`0OfyWh{cC zSFQn3kfi`ppkiQKBnn7*mc1PUu$Hh>#cc460zgMYG~tikNONNva)kQ|NP~dS93#ES zFRwz+2?S8D-<*cwP)cD+%(?*Gg^unh_w}p-bDk(fdIIfSWt!QKt$W?>9F2aXW!j^yiTgigGwf+ z$iXmL4xs%wpSwFQKCnJLI&yqwe*eDQ(noFkizv{Cd;QOPJpy4j!m3@(2JoObZ`Y>OXyaX3`={`JpxW5LPzwNs7H?NHMJ zIp(Q5P;X=HjPV+GI7jk+_2t(Hf{0+M`^RVe*uk>5_52>vp<#h0zNgkc#v72K=1%-^ zEIrjv_dH(nI7Y{L?-=GsOYuYJ&0qEYQRIy%TrG$J1Iof_$I1&uwHw z-~HhP{>6o9Gax$3N{+7$=tn(_Y z@!0`!+NTc#=efK7y|%MsemE#p2grTC=6LUO|GNFsZ7e$1_F=~#d&mHy0-#z6%5K#R zKqm24Hmoay5CeP0NX!xwgO2vSM~_>h?o6uPfw%AyR>9dlMAab6pyX+oJM zqw;h;4~gnOy*^8*tP{*S+H#@N?lRvhSsYY zS7HI2uV=_D#lR<3kKo=nZj{%c1v~xrVp58@_)1hPSsHwv~caWi2RM85F;0 zxo4c1oEv${1Ax`KLPAHgI=|g=eM=$hKzl=u5pg0gpQa05USDxZp8y5!Zw;@nzr*kU z4q9t)i~qA@Usnb9!qth2?{Sw>zvNoqSY3l#Z$uYgy6lKg5PO zMa(iIR(b+M^uvdBHwCWRUF^W*fohs!h+yuHkBXH*wt8}VJGj=^wry(=*-$%k5mSng z7#Vp-g@l449bsc#?NT=8*$0-Ix?GrhLAs`uR;dl86g(a#Qq}`XQ7nsMTbW;NDcHF*dum9hEEozCA&ihFLbndnq+rdL9uKw{up3-)_S06IGAepq*fBASiDInRB_Ee$iW zO)Z(&K=%mFFy_cG3LznewC7lxLZn##l~S>;8D*Q$wg*^pXybk$dubkzx`~1;r`FL5 zP&d10?>i{zUeDJLJN2Cy&#y5CL9B8DmBRr`tvz_^YwxJNVeN%LH<}Tc&B-jL_T1is z)L?)A(TlX!eRHI7@cw=8BGn!dP=#t`l5wxaJq5aOZjBOELg4AI(bt19;V;jPbujE7 z;NIx8%rRH&ksL@L9S_ca+auJr9?ZEe;C>$6xyGbA+I-_4iX&xo@54RHyMs|Rrwz|d zf6se{!v1{wYj;BoAd8Paw~I(INEOT>?f^*+ZQT2s`_IQ{T>XCo*kORG9b_5f!sddn zi)R2i`t0;9!3MB%e}b`d4k;(zkDi(nh6=7GPr^d;5od|It0^yY6GGotXysyjQ!nJMyjHBlEBIa4o=CZwic@N7+Go5OeUyH1w;c zX=3FJW0p>uQKy6{Pbg)-1{4IxhFwx0fP?^M%FLk*V)g2Txq~^g$aI{7g{iFwa>zgs z6g0HDA!6S=V|4XTvUN%=D4SwgRxHbcR_o}HF2Yg{TgCV9H>ft`obk(*?U^s65r28T z;>(vW$jNAF8JMPw6{M?{+@YzXpyP47;dXyeCHk?9y0s#LkQh>@7(zfzf>0_{tPF>3 z#9dkD1?WhV(5SvdT(7|OCF0YU2|xel1vy6xy9cy3V=aPO3VyjMN?UNd6>PPjG)1Wm zO(T}a1NXNZzJ2>;RP zbc7aR>A|Ok5G`^mZs^C1d72@JXsttAL2ny2-MzOdMwa@SGI9<^9d&vRa~QW;Nq3H< z+hSmupQVNJODcm_HWXq@Toer(# zvEX)p;C^4RtrfL&Q;cQZ>sqXKv*q7z?j*3Yctjz6Ym|l*A4vIuX%>ryGHNFwAR=L! zW~4x#dMPW#=o<69TdAm3NB*zlDp*8(niy?Qo}btVnR=&)S802DML;@y-_Nj^fNA0e zInT`1j%f$LkjPR+RREOXO;5Idj^$vwpOLC2$l$_E1Y#)93j+mx| zl*GjKb|aKDeMXK$3<#FT&-22JPYqz!zX1!YZyCktL(%BXF(60QD|k3sDPzgQlJoq2nCza36OL*oFzJBPos~z@SiH3 zt`I7vhF}hrF&<*`k!duoQ7Ec=l>t>iNofe7TQoVDD!&_`dsH+;AY25hbS}gcxwftS zA|qSOa;yQZba>PU=-8|*7uXBag?gn>q}x8-o-ruQ3Bd@NN06F7yV!U~Kj2NDL1)vY zprNqYd@TncNDvN7GMfF$4Jgn2J28d>sVo!@F@d6nBH0-qONzKqonS;*OQ$g##GTKiuE3CI)g6GtM~MJ z)w5&A=j`#B#&s+WW4{kUkp=^8MuGNnZ=>W=2&WubK+$!#Uytn;f3_z|shClJq_vLE z1alys#%>2=!Aj=%xX~VWZJxt=F`Do(M{_u%1}JrU^sbccfPV+bN2kF1`SKC)BA9vp z-8p~w_*r*q*ue0MnqP1PYFxx^7l35h#`kM(zpmAjhwZ21JoCOhtdZk6%qL)*Mb3)F zmLgXwwQpLhfLPvqpe9j_0m&3y#%C ztsy4@toai0`SWM|um9n%fG)UPNM#JMVV-BSq%^3}&>QRf-flO1|Ne&i{f@0{*tP=g zz~yqqG$q?WnU~7Ey$yZcCpQIFNHa{Lm@g5ZK2P}R=U2Rb33z#ZK~9-eXDCW*C>Cmz zn4wM3da+zm4*a?n+-^729#FOo>$2hTShu2vfV#b@g< z(wjw%2{21%P1+P1dY2t6S{^jeF)4wFNFXRwi?Y=U&4J2^h>$Rm`Y4tCEHJQ|alK?* zt}~{IqD{dJ>#ebDjdaT{2uym9nN(}iTjTKPFkhJ)B1`rxSRN1DzODHF?K^JwVi99T zVpBE+=qtsea^~-*i3iG736hHmL){+)nQ9wx?*@>28GYDIK3JhpY0zNNIN52I`4Vxt z%*YcD&QcSWWx*W}+ZZv_je{^HHYT25;^{}WQK&J(wE$ItzEXfH2y<H77jeDfJ zcT?u>itSM#Fwvk0%z4K3a%CAFFriq4WzB*HhL*Lm6pr_Wf!E};cJ+2uXi>Jul)y`S zN-L?h2ErcM_f1c5G@MvgtC?^Vof#QUF?XQk9%C1BOGbSbp{zb@AwTe@cY?4&!N9Tz zwnee5Wz@LiwTv!qv|}&T5L!nBg=MNKUmuMXF;L{uOI3mPFbtLucLqm}X|PwK(71CE zF78p`blnm4=~h~*8r@6jF%l@M1iO(Q98~Hc0_{|8>@bkpIjN*| z^XNM83f4DHy)}SlR(jV?rcY*0P%tC6ZdN<6Dq3i$(n+bZ&)4b^<`o_ZQBTQM!1L?` z1rih~vtlmuq#0%R+-N``%7}F6nPa{L)Y_p%c;+=T_6@8_qoRM^D$2H@n`)bMK4Y`P z-RlC!NLBriBdPdvMobB>*&=`woxlxL-T%7W@K_c+){V~NmAW0F9l(O>?uEk+4*2&D z93qPCSAZ?g`aMGNTq5Nd9sW_|_s`Y&{d1uDqxbL6^6Lh?wcrQW`B7VdBM5#5ThFhL z-XmtHL)F%*JE*+wvRJ`^JzD9&E_jsWgZn&xe*_)REC2we<8r>n9%=MnVwj=L<}kt1 zL`PEks4e?Ea}e?V{`-9hz&-}R{+W+T^1OfEkNSa3LbB{+Ke&ATdO|e7GBB#9VF0** zj~v=UEs_W~%)Qnq9pC4&VIM{-eMI;Fo&PTT8RZdjSGnc93kQ%N_B_-l!7D~}F(T&d z4+rzED(w{MXzZFN;kzL~B?HhN`}R1upB+~_0Nw%3`zWqEPj+Wb7-J3`T-%}x%|A=j@R+Fo&M(Q=IQ0md{xU6 zK8?;th*x(958#V-fLN~cqeET*t6G0_((vr=!};XrjVjP;#iBe9#nxwXigdEnt~gm_ zIF2=yQbO+y>HGI@nCA=gZ>|3B=g*(V0QY9O1`(L&89C1!sIiIhp-bsl7DhDJbwyc8 z8Bk%vsznb)NTuwhq8BqN0+lDD(7@A9g;ogxlR1k-fhlEEzZAr+ zLbr_i&JKA<@#TrO99{wd(Mzx@sV`hWR^ zpMLs+>C%x?f(VU{hDMNGI4HFz+-`UL;ZF9{Yo^+)9i&v*M2q5+%BX|(%9)$Q7B=+8@-?Lt z^cF~+y%#(ls}-wmqZqkZBs6%`Ocn6ROrr>pC=hc(o-*dki$#1n!DDmQ$ ziYx9pz${xq6=gK3`F%-2PRZ2HlOV^4DbJXvD`L#%XlfMn>K%2hc-$6jO9Lv<(NM5L z1BH$l;Z_4CYBlJB9n2Ojvwhw7UXQr4wlJVJ&znc80WZt98#Wz-X3la+3lt5Zny1=W z9opF^QNR*lR^|vH8o2jpDFD&2DaRPiaN;~!*Mj?f!E#?vONG`%itGZEjbrOa3lG@B zoRrQy@|aCjDv)0sOgY+fc_oCCu>xSI9y^sNz(Hpiw8Zf;ph`_B zEvLVYXY5)ncg_@{LFZZsiWGqm6C{R_s2%*E0iZ?Eq_Y0)07)IHZH%>xUeN2$av$85 z+^g5n0|of}fD5L}>=Ap`T1LXW*REXvQKZyxz0SD4Qio!i zlIb;2&`~<5JgM~d$CS8dS@R{OkEy zshQEod5IAXKezqam>fp#Zr>lCMaO#0mLjw>JC26uZnVc3n5LyWi1PLXr)v&}L_9r* z2w58*(L937Ujy&_W`EKV9n_A7jx;t|Mx#4?y!q>q_vrWWuTNqRe)hA3$zE#i&pQ}K zHw|#%=^5S^CbM_Qg{FYv^PCW`4$|L?2<`d^?2zL}k78wm%KkLn9E^=IlcPfg@QAP5 zVNsZCB!WYIWY=f#ynZ=6_gTgN7|DGW^b%p!k!JZ7!E%o&ig}zf$MyOVfIW}P9!-8; z$LBfb;P@Dw_A!*<7&t;HuVjER&v2R#&Oq=0+%X6C4A4C~iqjbRnm&WaBiQV!OsQ&HCZ^)E|IXc%=OB z&*z3a&<0C^M$MB0=?9J*cNBbZ-{an3yF71g?H#jn%zt37$9r&$DGqH7zJ$kI82v$$ zfosleAw7tS`SogT``of;j?ry|$;$lF)_3PaN*QTgH{_h5+RdXMhZHqnIf1RCwT^XZ z*w%-6a>8k%xr#KY#t&$*hs#twZcdj?0j-IZ{vd^+H~v%Gj8aaxzP#Z2@`8B|czu1v z=TEQr>B|><`OIA7ojO5!Y!ovZy{wN^Xa&~ChTFG_U;YH#-Z(fpRiyci1iiOy>fVa0d{ORk8 zZ{NS;u{hAnHhB`kPpMd!6{}IgQ|L%(f&|hav*kF4Q0Rd)Rmi4-QVSkSHA*>iB8P&D z(vhHGgf3K|qF_}ZDc|5gj<1C){Z06R=t z#kK+UVXEO>DPx{lx+={P^JT{C3juKLp0K`+kZoycP}o091|{i0%k=L3UBeC-VGQ5Olg?3zzhJnqhEbt zQ}Ouq<$~+W6;ozTEmdy~sG*}ZQp!EDQ)|Wj{vB^`->@tkyHY%g=|(7xDs7Q9nng(J zDS&Q3x&l9a4*2OaYc>yXh{TPq(*Q`xa{uQmVo2zvV!1E4-5yxi4R!0N8)?qHD-8`* zV~14qzDGMLFlPt6l@Ll%5R%WYiYm;XbB3E@q*x9h%=)PIJIk3@*$_)XumeBD1Xv^$ zpixR%wC?oPqa~|*`&(lUZx91`7U`#v%IG@tlMf)>^J6>E(6JQ?QDn>MOMy z*z!^~C&SCy(^U~cASfx0hY!ZYsjUuCtkjvpkm5uq%4GYx2-S*PHxl-j!trYoZep=iuMF*Sm<$!5D6q8l~ni+0}Fv$K2oZ_1wwQ z58(IxeSY}T11MFqfPVDWCqw<$uKVXA%%^thQ_kR_ZtU?se^JERoHsG-^~9r5-H+`) zQ8#TloFZ9#BjSO=4*-I5G>`V!S>5~C)+3-lMygyo-@&c7E2TJ?E2qcu>)Gf085|fp z2zF_ZA$T>PpW$*J?`{zbljUNUlACdKkk?-i`f)VYqbk zQ@WRLO=HgTu3R~~L8GnIwr>_jKc43qUw-<8-~9YD{`#+ei=Te_2`?84ZI$}K{eDMnR5uKr zMb4}7_m}&M^}b+vyW#%Eda~;cKm}HJ772g}xLknGpBKEm&=?LPNE4sy`bygK%j<;s z5)q=J_W}V+pKNWl+~o~rD_DyuYOev0`yFq0Mu`{=YS_wyxx!T#39l9bUOPen<_qbc zDKZhCDIgU=IH>g8MdX+;Yd|)ox?Eu{XI47{M>db!|w{e(}S zUU0o$5kg{weydn(A?^5n$MPsxmKCj}VF&;~2&AB=!-fi5A~fO|ZA>vBn!!ejv!b?* z`QUYzFQ*3wNGYMUhIukYZi~Q2NjABIl^bF-uRFtye@wnshc)@+yEP~i@yWensV?S)GnwV2J$}5cSeWHcN76FpOTsiI#Ly_`xzRhBiXdyechF`Xbtg^NkG1_T9OX6_~B0(|)d{LSB7 z@$=7LXnb4$Kmyif!`rt9md72fFfRtvglU=)rx`Ev3%-0}1p0nk@a^k&-0ur&Wj?9= zzoflsd)wNvEL>{>KvJ^3lb!c@|Nq~+=bYG*NDOP}`=PoQ07_2w$>kHp-ZBYdSVLEJ zb#-G&0lW%bG~JtGL>#y%A(-sQQ6}CBa(3{jkl3`oTHwv#%=VQIc=mO_HSHa(3ni13 z3W9YU@8{Dx8OJr>0s#fJxxq=5b@h(Sv1RbH zs!$$}2i@Llgs8K5@aG^@goK*aWY$_yrJ{NV*XV| z*Ezkr0ysehO`w_-NF&K(M6K0xi|CORSj53Y8gRX6E2}gxFxOzFYz51_VqG^ZtAoqT zO8ZdM!G3^qfk4bMMfyFZu^kl&+q9Pr04Qz6Rx`HRu$7DkYYQq?#~Y#nl~0}_!lNI8O? z-#IQD+12~dxjiRm=gm@*V_Ju=XE$0OLeDhq_sjf9_GjN(>q!sK!T;1Q!BXeQapAuJ7kL;DEz(cpj_!@%N0dQ3S^u%$9h7*);*^$|>M8P<#f)IGp?OJdc1qcn|R&6|H+q zG*d4@kV}SNwHz&&teo+BmrZ*T!&Ev*_wtcSm69BL3B#!wW>ZS!u#VtNR`lo5_Gjs= zHv9lyJ9%J**9YKf$7<60bFi}sdQ^>V=&1u+KPt^q%O{J`tCglW29xK#`ZGv zW5wGWYmL{93r(p5Yn_*hOGob|J;n+(o2EOm8r=$RhUUWc;3v`T#X;31@t8<}{v2A1-y_s&oS^_YeAOg);D4W|9 zrfCn9&Z#*Klp=v}^E5buH==N_V`V)NYr|9U7?L_wtMhjVbYb6Cg0*eSsG3QKClNNL zkw8!!QW!93woqDu6CjNdm)nHPZ9*EDk@N~2tCF5M7YuQOs|j_pjnC`3hLdEml**pO zm2KJ%c{2XU-Vy~G^l<#No<%$cC~V1ML6NR6*yVMwO<&grk}0_ZVDoX{rw((_dBl*k zv%sXKGc;l>Yr&9a%=3(xJaYD^EyIU`VMrLqh#@5sRWOy3K$=&Tl9qfxYuO3cQ7T>T zORiY*jI^>-}AZd*8=t9OFsSP{C*Dyfjiy5PZ>0K46qN!)?hJO%Z^0n{1hXG zptbvl`gsTR{m==CaXB1|tfsv6FHXQcfKWF1L3xqw>c)Gs*0LLf$33Q*o zlfAXQ_wcNopt0YP2x_g%ia)&sDg~0my;2ZbRWj=LWBo3}etv1`*&#z_L;;BaYkj8A z^q{8b&fd=X8w?Ai{fpbpKK4-Uje|AP#?8k$~e}E-U`a5hrG6F-L z{`*)Dp%XjD^Rqwo3GNf;IOg#@Mdk4ShbvKHhDMG~jo?^*MBf*BOmz3*7`4@+?}-%v z+P+8qEvle-mFU-9zHajgn(=QU`!(2EJ`p4Px}(qK3k8MUe^D~scZU5u*W}aZ4$t`T zegoD9ib>)C-CWKY(6yjwhsgqsLvbJ@oJ79X<_c9? zBqrkh{hc7E0WpRy8?9B;l0V{lc>&s$a?YHPYNZj92q2kfQh}NqTCDJcGHcBYKWH`} z5T>V_z{6pP2?^Zj>&Bjo#!hS-`vV8i^R$$T$K#GxHw3top)EDtzc%l0r|Gq zR)rXGxm%#)f?7R-8&FC`)J-SDGgg@MmQ^ZWdXFURjmo~Rx!^r@)*#QP|ohzcel2N zQVZt1;xR9nmj$_!GBW^7#psiS&o&MvY@jAwW@vIWJrc1JkiEu4nu5H(aRVCZ@q8T( z$eIUSba17D8Jb-R+FC`<6%8z97#tn;1$1$~UN5-at{8>{G+v(9bzI8nYWCkuBes7-7;@j*Nj^DEXr1}=7ypP8=u&8 zp6%^`+E{krT!zaWU+Rek>pg5zMz87+3sP#6E_-jnjHk)Kcn2MVx^8j|@EHV8^Oq{E zuZuM7Yw+rF%7BgRd+-h3vqm2dKvB6|^+0VXxzGSDRHV_t`G{d0QCoyaR>`9>$GM_~ zfTr!4_I=lan?sgMiQQ5%a#2&OJixD>p4}Q~hY&HwM3N*hDCV*i2#UQxyaR%R_=w6> zfvQIsbgk=(kN0={{O3=+zrSP2MJ1jb!!-xwlDY2d>vx7qeFPtkZ`5tN2SS!-By>uxkHy0+;UdXG07a#zEWE@rQ|m zQB_=n5~fF4^nUEqeUd#e?9WI(n_n65eKs{ZUbF3^27o_5D`CyC{$2F?js&6kOIW6} zt7!aD(V_sX$HhmGbOyaV_s@X%9GD-88oTfQ5Ip<--lkyi=%fuCNlVv{Y3F4RaW{CX zR8y%B0Lx*xuGiXhJyKtHcNj1FE#_AMDB17ydK4&pdd9zbUeB*R(^b)$hjY6d{5~dq zzaJ2lw>v9u5&isLHew2pJ!`vv*WMuk0M6&!nvrftQsLiUhXG|^m#QCKt|2V@A=zN$ zsQ)xK`1{c3V9%u<&+!PdkLTdfyNNmPRGlCsJUoea>s=4syIkFgBkt)WOtOC7l(gm@ zLQf=m=7bh|36jmj){HD6@HgT{@R@utz}xQy(2d>B_t+T*TEmiBZ1`LT4D24$k5h)MRAvp&rf=hgX^8qRGu5Rm{K-IA>D-8)l96IwD z)!3x<>`8^M4TA$*42a{%dZksrcVvONl*am~KuIW#q6+Sw=07O~4NCV(o>Ig(vgUYt znQ*y|n7+N>zy8mE;r_N_o)^pyGUze$W``l+a=Bo-Oe*^T{Y?*uMAj=7RImZ ziY;#}eAkvCDJG;a0syjTyC^9@si@nAG7IWV&|B2ZM->%-1BSqCv=;{5>q7G>j}0}_ z`PU&3G=i*uLBYCIH9O)%jxk{HBVJx!aUFkXz1&_O$BFe|HcmM4B9dlCH9MuU4pfio z8e&S6x`sgqYvzVl4r5b9t^V1GIi(hUe=2#AA6Oc6fWpl7?CCKaX9f!zCm7NPZyv_6)`aV55So4FTQ zM>o$K=Esb@F=NI*?K)}5QyW|0Y%AToA%c(w*vuay&#?{-#hCWdVY*DXTq3Tw0n;@g zjSkIatoaUshffYuh&tW}HEFWCl!h&Dc--%J%rniEH2WAe)9Ag&x(MEWecMd0<;J zmdAnxD`;vrV7d)>xn9^>P33+LyEJ9pGL}^(@i{{_W^;N^Wd-(QN*IEHF|V2Q3cp0u z*07be_fhrEz%&=Z#?`jVh(!P|%*Y0ny0Oou*9~6RtR{5%l?tcsgk1Fm*7x?9O|pQ- zzQeLO5ZN~coquS6YYy5tlS_;=l@~ju{UYET;t+7XCOBN+ur3>#_HIrw!3TmvDykf+5_tqj8syeJ z8`wlNaNrzmj_kD;ZZbV|7V8wyP(^EJEt}$?rZBBtat;41tJdbg`Uh&5t4dXas*)n|! zD$8oD53#h}r1JRMLBq2QdhaXBXSOru$Bb-uHa{})hwQKQQU3QYlkD$fq_?sH@T?a2 z-RpM%8#o01f8q64L9iVE8+$*239+K9i(H)v4CudN|B*OVz zj^e=mdF;=H@z#^``_sAYK>m2{w#s#gZ=X=o!5=C`@5>iPUC-I?lZ+SV-_a~1&&9};^Z6h2&`^%8U?G2yEhQ5zT+X3tG9L31D z6U07Wi-KVN5RT;%fF&Yq1AH1=j-Qv{PS>FfUH|VBIjNsDupi+awpMzEtrXxfubAQ$ zwN@)4Zo)K9czqqYsFZK0l}0MHR5V3Iu2ht|qItIWDOC;y;kBPc_H+UC zm6Lc12~!#or-<4rf@hl@4`5qXv{uxGZO>L7%>&E=JGhAJ?S_}Xz2fhGe#ftWuK1t- z{vZ7Mp9kLG-|_KSQA>qSdi?0%0?^uqZJV)b%||U6>pJ71rc}<;tvMI1`^~I3y-lyU z3|BaeXtiN`1k7#*mIrcfz|!D0&}=C0GE^sE@6!>uOmyCLj^pnB@jzZz#P|m9q5^@5 z3+qskVge#Tm(@`36FQ(aLEZ{wlT{~*N<2dhYN*xJ^{#ZObg2bifan66FA882ZZB6% z7fQI`nz}`+q~k6dTcWt2{Z>H$Tr@jWiY_{hy?C>> zTG>`n2XjZpw~m}>mD22*GnTpF{$Ri6A+ESyf$1_}oF+^IjkyrPeyJ1G72B!ftRN%? z*YHa0bU-F>uIMvWcjH{tet$)+8#BQwACDp8dc9$qCeDfEF;2|jn-_+6mhB|4DTP31 zUMd#tudHhfCD-deQMU^D=5f2d!U;3n(FaV!h%y%Bt*GQ5aHtr^4Nh1}05PKvD8M90 zSaYGNSzdMgZJiZ02~!LKd1hU43}LT}7GSL#9?JvUT2Y#^xE|VbRe&a%D5A5twX_PJ zEtyh`2l@J;Hl}I_=!$0HfLg4T+lFn;fT)vTOjJ(@fZEWC8DS~eFGwNWxo zK+7@_3p$+>2r{Zr*323{_Wfnet!+LQL^)NUXz=GicY0wnX3J(*y>_^B0CxPbXCx5R zLyuW9zgFL_hH=&>OYJy=>fA+10Lu^`Wqk}j)x^uo!3>9Nac7*pUY9!tBAJq6Fdz;H z>Ih1czKTs-S41?&I%HAc(v)n0)(`u@dhaxN#Ke2voLTpKn)ir@Zw3}B5F=7Z8o(RN z?E#E%-ebJnNP^8P?vEMsog{Co8+gUI9S9HcZjr`-r@>m?KYUUsSN{`1xA41OKl zzrmc(vdaG?^Tl!UyHD)#!2kC3H3;6RFX9Oe=CMnne|L^eK~@Mfft)V<8K;C{h}vE< z?r!K7q%{&o0s>#}42a=`Rd$P~O1Sb1;kjI{MnstiJgSe7^#~`=1SP9@1Tw4FK--#k}Dz$JARbbeTYjHb}gSK870p&eht)1Ml+StCf9oLyYP7Y--hjrqU zSA=J$mo6!WXyz3*7+J^b>|P!oz;B-I36TSU7@&RjvpB99jYNaPmt?Em4=c%dCT48i zjv>j&ye8EXdewqe!` zsnsBuJVvZO3~U!`0;|v^onr`NdAoy$(XQh89uV*#mj5L^)}-AGU9R@FkX36Tjh62EATEL!s>@J zMA(8S1dnNAHr1Di>QsK~JX;5p4A}rzfG98zB90ebPbodMI%xov<{m2z>pEl2RRJ>FQB6and+#kGIY$$rZNog%_4(ud7w#W-g4$A0 z3!i%$8&dLkeYxP<_ispv&aBIv@$2U=ytftWwknare#kik85w{e*A>gMAP!m=7q~Fg zS}D!kR?Hj0sBa8-Yik%BGre^87SvWz>c;FYG8#Ne%W&#ay=bkqR359g8O{TPTA{}{ zs5~O;gjyl3?F5arTXBJPHJY`dDxjfcX2qmLv?{2pWqX*t%M0*$2R<6G-GFaDHpIZW zGF>hhu9U*Xi@-;Z7%ThAg$j{E7O^=LI7som%@7<}=WQ)m*9F^F4*-UlpJiQOL&&YXIxA|T+)%R*jU1vBqgJ6R5#yOf`dr+#JdzKHBhA`+makQaGV2h_rl4=Y9RMp?Y8$HX z)rrHivcWPEy180VRYk|NGU>HuHTTe7 z;X%|;PP#Gz!0tQ^ty7e}R?^vbKxN7rw09XcD%&yXee#aAoGv8@I=X z;Ka?mR<3{W0NYLRzO#8-1Sf3m?Pr)T+Jj*;CgOUf8_F>V_zM7V2MPM$9sCOGo)6hy zYd-VNSy{k!(hsyWZ6V_H_p;Dnss|M?Sq(Pf^b z*E9~8#tG9nYESFfGru7QRjf1}`~Bn;fbM|X{%u!LxQ@x6Wy1h^Z(ai|N1%1SM&Ccf zd1lYR?_gfZG3UY#jE#6Y0Gkdb1ezg*2IPByeI7s0V17sYyApwO{3y*mj}iM^g9-J& zR4X`^;9L+9?(prgFVaVYXFRJ zF#u_66xSMH_vz+y^WMg>-51LS`%lMp4t;HYc6UA#l`Q$`ejO)(YlP$xq?}0@xq$G*P3zprKN zZJV+{MZO@;(1RG!Sl6z^f2F^UtWYttb@Gy zNJ^Mwx;84s`pB?Jcm&jk=Vg0^9O6#Op2Tob+^ zSo#nlxPdOvfNsjZ!Ys)FAPQNG zl)O6Jscc|d6cB9Ka)29Hgg#BL`1{}g0NOw)ObA%l4Z#xtzrK$6@#7o5{}}P(k8ikL zy=D?wgXVXoI$CSkHlT{YZ3T6s;Z~^ySOc$piM$po7HsUPT2=8V+9stnE@&z3rbT>E zyf3xw67trXwoUN}g*60DC}%AyJ2T0VYuZm)9haM|lmqsm7*fQx&6qzj=DA{9H2hA422hC^r(wN%_c)E)h?;&PucxH~)= z?r*?019Jo}!v?t)q~I`J23)Tfq#LvFa8xzqx@ix&0_Po)4`|xMZ_68dY(MUJe{Wb9 zO5{TXUSA!4e1E}o8Ii`wUbG?*=Q$2@Mr(j`T6bvK5zj1CX%($Dc-Jtbi0fs-&d1lqlDlz~7AOJ~3K~&9X%QVNUS=c8U4L;F4>?*?hE39=4Az&INHI8Ge zp}bWZ1vU2B+qO+j;mnOt!DHRkH|BS3o2hfW3;`KHBb1R%_1Z_X%_Sz&7DD&w61ZJXTL#YkoHE?Vu zm#4{D&IQXdW1bf*>xxq9Dd_p%yu919==(iDuOsdOv7Bpw&zawST-d)ozrK=A{wFWz z_5eyOQy>QV|AWl$q4vyzdK|9wm>IS}@f0|!Vc02a~X+Tnc(-9gKZ}xIBucu*K--8V-(eFD zrc%e7D019E**PgWI@9^pQ2;(pZlUwd3UB^tXos(4qcTjEs0R1if zTE8Y*xF*(W&$Pk$%(9^v_akV%jjfBej`S~cPK{UT-fgqf*?QCGTkFro2!XStnC}Z} zF4&=#k1~B79(-+Z)4DTSdp{TSPVIN*5b#YD* zQ^YtX_#tw^&^9U%u(sJ1013fW3`4~2cER;_!TbGzc`j%T2qmCaZs5bj0Ch<0EnFdt z$&}73nIUC^E@IePwu$C|m zG;g3$(DgdP;|0@{uq;b=2X9Rf2Rha=)4oDnhCq8APuo^$RZWFtZ)lAAHj%gykWW~4C5w~S?3uq+SUKkj&} z8MRQZWYgfd4v;|xL4j0AVgKZ!@)eRN6*XmM-F-ufj+sU8wM|xlmjNv`ct<9`4kNCY z3Af7ym&+U8FDuqnFifDU?C3E~5x47rmv0wbz72@Uqtu9HUC`E5+r2cn>QKO%8w3y6 zJX{E@LvaEhY4Q{!Fii=s-(K+T`!|FTU`^cDb;HN|2k!R;Efe56I9*t+&#XgHH*3^P zmeW)6J65(%8j{w6b|z9cJ@4UDL=p%1NC)DSXs`uzHrzXA;CxV7sc=(as|K$urvTVg zPQ>}pyk?Vijk7(hHlQ?Se$CNcfG&OR%dt}j=%`~|*F)CUWS|Hgd_!Z_vjs%wwH8(2 z;ME)pNKO!=hYY}U^?3cBy2QC;_8ZO{+X+=1Hl<@FnrrZ(!p8;|8$x1l>@<>q1GFqb zGYKh1T&GDvo$uyh4E8lc*#RkUKn&WSSXiFWD#v)0syzww0RUHcm$>mBWo6E5eVS7_ zBj{WyySWNr20P|fsX?wr;!UI*WYk7-%>ZyGDV|~y+kjbL7JB;}0$`F7rI1Lpz+jJ) zb**#yES(v;>;Oq*59CYH&9zzZ0)lg8)ti}{IBuRHM7=*`C{GT>Vy0=F%0pas| zdX__spgGG*q2%;2n{Ygr<8?XjNZh`@;PuCMeEabouiwApcAGGc3BxpCm{v!4q(=)YR=qhJ@CMU#+n#xe|05NkU!1|ISSXS4vFu!}I zX8>hu7{A}M+LB9?I$(mN0>q9p1o~-?b)vf`*;FAtw~>=hXG&jdkyjPJ1w?y0GgV_dEMuGt*|o^ zZ6{lNtq>gcL7=Dck9$fVKQ@0Jz8QY9`W1D zHzXhN2$gMbHco(?D;KFMsEtMf!!Y3GLry}_*46PwA zt1`=+EFnh5o!+Z~5d*;K`hsyBP$2{~>H^Khhgq8#33k~^!v1^2<$6JJ8D(8j3V~UX z4R+VLS+Vw0P~d&l3~NPc1zT>&Yeg#=tz?vK#l6hx;{0GSx-x;=M&LU?Ry-bee7wzg zdt0%*6U>fo#W*@#h5?t$gv<4c+wF?)l^L^-HDi7(m>0J3S(gpD5MW*|6VgO;9v5sf zBu>OqXiiiJFdy@VdD$?mGz|-ZF1ZN%Boh&>`zw%E$+AV7Sam6=u1qO;_;A7X5>*mh zdYheEDw^{c$Ap|WyuH0akkOi;V9a@cKGooJP9dx+(OK){K%H%GR(va&I3q1RAA{;l@@LDe<#$z%*41X<$2{3njg23^ZB$ zHsJN!1ux%k`2OQNt}g?8bjUR!&JhjF084G%RL#K9q_xxIIO6+{j9OTm7<|C%>lHu# z_<`5g7uKw6pfEpH1-cP=E6RYGxrg;;1+uqnApqy-ES*<8LdH0Z7>5i8k5U{;t$;)$ zwh@QGx|rZ0$s-P~8}OKAgyK>N8Y&9GUjTwcgc{IL2n3u0VI8}r30zR7^x!61iy#z1 zR`o;&!n`~lJF=#JnjF%=jH!VP=Rmo7$;e&+6x0?7@`G2$ZOYgz3F4eGv?(C@0PhnZ zl&7zA#j+HvvFYC2&?*%fRhi>mz}5PX2w1nfEbxwoVO(P=(VeCNP3@Rd8Zhd=A6asn zCskXDnZLr8H|%RG8Qd+SigqM2x!GsQFGq)u5KaulG)6e}_x~EU4RCuGoD_ z+NXR7k^QMnjZx`LEZv`T4ZpWq0mm8$8P| zny(t{IQSS5BU_Qhu-9yI&(lt-$^ZU!&KQ2a7tgPA z=J#I%-~aUWSF*&;P*eX*gPD1KKHj;HsvZG=?03A&KRH-7&A}@n65egWtAJU^@bt(=2L0N(ux?BD;*l5+ZtGtC1ICS_{e=Z@6C z;q!XVHuleiiq_P+z5d!MVUmSo#UfZ7l zyC_+G%mg3qzmdoN9_sH-Ya$N_=h~;=J7>?uNYb51HuBEyo0)+DhJ8o~hvun5>uMxB zGxX=WuQR6$?+5oPH)pKTdYm7>eS4)5Ola8F4NGWPmlaZI0@N}cCS41tt>Wc+MXejq zBG4Mvm7BP22AuQ^nqmmp8t|AGw91X=G7N}Af_H*647f}aE|&|2%M~dm6rt34D-7z2 z8RBTaw3vMFn`oKh(i+yX;p5{2k9?ySLUOw4El^!YGame&XbDxlR~fBE~VGNkQ2vw!)0Q zw2G$n+O-z4;0*{#XrL1!!r*Wjk{az008iHe({)5htdTZ%V*`!jbkUy92CSLF^%CLW zFec!3z3Ad3D0RiQt!SAW_Ew5!bGaBH0>NuYQUQ1xI{DUUexP>#(kg=UnrSBU%Ra8c zx}xf^Z3WJ4%E+n7L**FQ0V_c%*JFW;72Y=lq4duHaL={sD(wLT=afO+&9}OINrc3Z zRKyk_5=hht$v!Lba0+(B1;B|eq+DEEEAXiy3Yq>UfE1u+5&-*PJ7-r!Xgas91rUc? z8XeYSLU10}NqZIRVja~`&err=jWyXW{o%H1@Z;#z91(g+jr96!Zp@YqVE;d=ouH)VUI)jZ*8*@C41fd( zyqfAYt+Q4T>e9bkYQ!T%N1O=#7$MMNg*Eu@QyZtk}6r1Pt6?yVCkz(M-025Hk-V)C; zdLf+0We27@KXz4v;)$MRmQVNKIM!L-WY6vklB1(!l0|~&<9%Kin;4i>BKt5171H%s zqmLo|`w_?+7=B_*_TvbUnw1(UIjlFaiNMtg6JuNV4yyS$4uf99F|&U3T+*jaXKH(X z_Vc{9$_^|o&U}7#LaTYsH~qbD`?1Wt>oj)leb8)%elR#AbmaIYXsz_)oie_$c$jpoDqbR{Z#WBYQnUYjq2% z2FufUWxIzMkpHFtEOSANiO!<;_csPrA}G?}bEcyy7zmY8@OV71Y1<(m89=Yw(u3Mz zNSL=fVhmU^YcZGlU?7zQ<8;BrC&X#MOJb%pC14l>{`lM95JSKiudJDiG)l>B#{KcY z<8fyIS&9bA{V_8GghFYr)+*Y%(kel4a2p=8Lqo%om)>I*e!`RjLQ37~u@o8swN|m3 zS&Y`ut}AO@U9-W&jgMw73>Tf&5I6OT1@NUUTaZw+O8!@6aR>B_}O?{Uiom&*nJ-{1el_wV14 zCXZo^h*LyN0oi4&+lqO)<1ycHUq3YKI%8Q@?J4NtT?Et!tf-@3myv?NrG)^uHnIMvSL0?cdItF`04Thr1x)g*JmBp$$ zBu35V3m}y>n861O$$F+bw)hdDiARgbx#Dr(@cusFeqXSz8F?vK+Jcs?$-HQkq_fXE z)`WNWL~eLRDspXDvtZr8`t{OqX${kbCPd7LYu&4oGNul&H3dR-$`A$x5*DmBb>iK> z)A_3XhDFN+sCuXwD3PEWuA!l-gpb+gTmYAC6LItd$PF>FEWnKeQu6$}ctFe`O;C$q zT{E_|pjC%qWKH>y24-_pKxz>p2_hUjUcr2E2jiAQHsdH`@+v##24TUF0!6n=zr+l- zdVu14{b_TVlhP^gp$)%fYRWT8rhd4D+?Bs|U;AzH4-KTvE3eEs{21M++OR}w2mMMt0V6^m> zWv$Tl3EwE8})mxG+mwUmbIAk8_a zB(u};&aY~1e|FEL+ZR{c|IGjuv#>hnbuZlenA&2fm&Ff&?e{#K&PM_#l{CZZ28~n` z{htNl`&e-X(pp1vG@c7O&VpWdF9oqux8_lNLur*JjKaOXIgedqvOn8B_}5I{o=58U zq#ZIu)|!pw1=eLGp2`gD*zGWE`kE?GQkY;^T0wOVN91X79oNu$cpm4B_E+QoNS^RL zyG;G`+&j6Y_ga;a%1i9marn%h@!Ub;CpAI`kDt#OU|(DknO>ddrJtJ-OST^g(3Okb z(Z8RM)sx!&G6KSCFO>A8pZ*Et9A~G)PIi3tvVEs220{0NfC^EYjw;tpu#Rel-umwe ztnXvq&fUlr?ZyEh3Fpg+G;-U;E)+HZ>is*5%{?fcyELK<1uV z|4hc%en8TpD~7NGakdl{-aCuankcz!(sU(rx>Opvj!Rdh^kbXRLH~aor0V|`}-jT}#KYxz6-LAO4Tyec#F^n9D zMc{S=USEONmjTnnY!zGKG_;)6v};4D);rX|E8A8fDUkD21T@V=p*HyD zQJr#1X3Gu0$3SpWby>9qwq$H;#r^((m!A-E2)gK}K%&K~S?=-NF{+29-{+GM_- z0#ysZb4Dpe=N4O|3@HK$2w^}B3C@}M728EocDrC*X~u)XtYC6%=`p5=FzhY2oC6}5 zL8S@Nh}MAHOTqOv;p1(_{e8wg%*@`G%JyAH2GKdz_@qb`NeEiM%B*EB8IO5^L&374 zJ4)9oUGD2WrOZKHp@R}>tiub48tf%=WpukNvDK;zd(&%8fJvN1-5FDWB##nncP{2) z3zWiEUM|=I>>yGA+0c94iszu0f}yZYN>DHzAP50HXep%uuCNUj01=10ZIDuXJyY<^ z@Otktj3YOHZ)FEe=T}{G84!8aQoG&wWDg?tP3j1KxycfkIWU9oGf;z9hg*Nh#H%7e zH&5@a$8LjD`JMAl0~Ip@*=74Xn@opi;$!Q9$)fSkSx&m$LnVpMj;mz=$M4WkOY3;m z5KTRxUEo@|@37{=Y-_Lv$|8`$hJZ~PN~0?^TthaB8n7LacteCJ{ey@A2SlOfaUn|ju|5Zm0#7;hQ1en z2EWgL|KGg6%HIB!7u$3E{uqCy9(aGRDI7li3%>Z};h1O8+J}iyNii=g(&NFFiw=xo zG%J^egF89wzG~3c2<1GqCfUJQxqclz$P|+a{%Zo_40870S-{*gC9>DvSvDFX^m1^% z*VuY>K8A-nU;8d+u8{y3Ldhq3fULFl8jOnwoceM|Q-a3am3=^PW(C80

    YHjnIp z;v9;`K`roEv_7YyB~MS!OrMt3n(~@GtjBq6JNaSxVFSaTOoo2Lf*43NU|;~y$P*fX z?ayP+XqqJS_cf&~|JXq*kGq3fJ6_QJzsqC47{>c&&Y#`)-~FzA&N#D`)A7H7JyUJJ zt2Os~WyBBfEhPluaB9K>X!hEkjSc;#!1_pFd?w#I$05gGJZIF;3axe^N(9nDGmM~7 zKyD?`Rz7C%%m8-3cVgLWe!VH%oCEz`j`tC2v~{=!YopY3&g)t9eT+)cyk@oufU79m z1J143YC*^iF*k&*K)~8a9~00jWL~f=D@t)RQ+lvX5gcpPwsqk}tQ*i8{Nz~!?3lT1 zD&bw08MP)v8T10QwiT4-e!Rcq{!mXF4}=Tw@-pC36KWQ0&ch)g=Zfp?f>E77Yt;q5 zc&zJ+H7_W&pa^>>##rgn7#LjDQnBTNvTm5?8IQ+;brnd{y2C^XP=p5PZbS?U0#gK~ zxqu7G&R5ZT&rSOsvnG1*i6C0#9JNG*u%e}goOSYR#=`pm9|KZMNJ$^AWn?M?%ZPwW z2uR_Dnf?oKxlV}DW6KNL`+|A?fR7{^#vx!F>GI44ihx}-3*x;;x+M(5)Ln&JZID(t zp_)*peSfe|?FN)3@0mw0%$f-e9movxmZS*0+<<99cc2FN-+%lK`18;2`2OR9*Vh-^ zZa1V9>7J`*U2ku1SXMQz@yv1$qXyw2z-z$UT16?WD<~?puf|%6)sJZQN9BnQ>}Tuz zfa)3wD5EU3_N%>w$90);-9}8;3#e=rq>ykOuXKY&KrR)FWS|L6 zXd1KT>ryb!8@8=rBm3z! zDG+ee97d1ZZB#=|9k+2nDHW6%S@w{NFJ-Y2UR#HF)!mLVVweU@SJtFEFNg!3mxH=2 zhU5^3*uk&W;wA0L8GJx+S}*QsIMFka#|7LuxZp8(f;YO*d-%!2OG7IaW!;e14F%;; ztLqSoNAZC3g5VokV9mYrbpDbpLu7+Ug1Cr5O|g7*2#s0nl&F+o{8+GU1*LFtuiDeN zoY(*WAOJ~3K~&E=mrPl{aNdsN*cXtaX+;zE5r$N{Uk3x4W?a?ygStzr#5Pf7%vD9< zEI{y@h0%H8RjTd1XI7|j>;?@!T5G7@_j4tieGIf*-}rP-L(zImxZ35^Vga%NUfF{~ zr}NZ_nrz`v*X2CKt8>2A6q<6uH_u?Fc{phZjy*ih`Kh-+Q8{a`$EKphT6% z%&gbn&-)p)97#|S29M?)z|YAcICZD7Oc!^MBvTU~r{xM()*y{}m*(0|k~le(?klKJ zB}aqn$`8AaZVqGtzYpBd)U3}tkD#Rr0gk}f2NaO#YK~-Ng)rOdSlQY-sFywmYz#G> z(D#NvQKLYO22LhpIgVi^}p3jkbI+~32OsQs@z3hE}&mh!wfcrZ_=^0>h zFFK4+RmOS8XNfM|KF+bvDgZl&BLLoy=}-S|-~Bx1EJ0yqDeU>qxwpHBGlq74H=7EY zfDz}=yho_&8_}A&N9^a{0WsXu{X58z?QWmGQ*^-T`j0ahbdE+;hMo`p-E5b5aD3lM zS)KNH0${*l4pAy>r0MZ{jc_t{z^-8@p`VY%-H-JlAvq=EsIx-Y||U@T=gz{?9vpe4p^+k3aBo ziv*=%V4&AL-I+7Zu3U8N3w)a}O%puS^|>x6rD9%Y{QUWj_cvxL$>;#dTzS)kVHh!l zNr7p?Fplsps0@;|)FJb}y2u)t5FN&GK%7RTlpsM6yl21EoKd&NRyg;iXO8E2MguTi zCcNBUFbo5%R>C_vZ%1w8GmY$LJ58X8)S!!e%6)K^QsEtISTWL=Cx!u~76dP7wP4#S zN)@;aI5%P(N2KcnhXRp?^|4`DGnVC!pFe-%=TFuvZ@D3tN><5};gQNL9~|32O;hMv z{opMSr`-E;O}O2zm@Wa=>lH6Ayxv+HLJVs5BM70uIgbovf3?QfJ6qkV?R^KJa$;>hj8a zT{W}2N!AurE0zb1ispGkh&1V1*UWZ9Wj7cIA;3is7Xu^^ylgA5Ev&y*9s+O`4l{;f z#bwHrq$h`AOqkSwC3=(8abt|p<8rxR940Pu8vM6H8TI}C&OXsgL9GG@I-UE(n&b!? z+oeRatSYV7@k6xc>`=7Zssmg@Of*@O##*84<%Uw&Gq!4gX4w(|iPz_@0EdtjoOxK^g9@ewQij?#0;&W!hCYOet&;rp}1L2Q*jFwu-V9+a8DSa1>6nwC{buR3E6Z2HX_!!`uXwT%nxAgZNH}u{%NB`a>hK`w@s;yQG z)LIRg2wl$iU|cs$zXLa`$M4`p`2HTKi3MT;lNR&OLm(=L&9^nm%|)-*0Z!WvHB-=N ztG(7V!10=W(N=WMvN4vO)0QLRyz=oTOCzzj*Htp>+Y})CL;pi*G%0JXqO^=u8-f&d z1-6>5(gO?cBZ98A)C92pjv(0YfxrP^9$y3=9^&`xZ~r-%0G^nCw}Zu=33~$1|L(Pa z{tG~QlA{8wmHv(7^JI?nd!T%-71#UnbU6F8>(|R*no`BX`%dR_36xSs+rXhVWZP=%#j%{!_k z(BQ1>)`&7*)&obbnRDov5!AJzNr|bRn}}PNlG7u`gBa)*EWFRp5J;1(4{8=yN>wim%g*ofLO-lz1lJ-P{Pwi0ZW;jM zueUb@=Mm!tDMg?Kw3Z=FEFno-?9a01E>(?)QX!|7SAUEkOCoGx6vN97401|<1 zEyw~mx8Ut{!Q*4ak3X*em$x_VavVvL1V!xtK>87xJv;yZ@9p&Kt~|m?0nCJ+a=7eQgaCv*h z<#IvH^I+h6Zzx;Cx<2sNpEvyV*I)SKkH4|51zTw-g`4QIESBwJwll?uB`vrt7ff@< zJkMAb!IUQ;6;7~hSs9c4s4Cs5HzBBW^RFG)%Z`0##Ju0p5SRcWY~-6){E3mkIN5A2_bVW}j zJYrPLGs%on8upznoocljW-#Cqr9>tM_H35u3n7U)g`g=j+bl~vHWjKGBHf{5fJ6qz zjnSOB;nx972wHsOvvZFLA#%N|RfijN+XA!%l#L35(K9cE;pDw66Y>Pa)CW1^Qn2%8 z?AfE*6sQ4R1UYoXm@q}wdZ!q%ft~@qHCxTQ7L#2b+TWBGf7ts62NT_p&l*#_-$)KdUJ z;!Y5hpW}-_xCb+cLmL2<-VBBN2iOA~P2n+#1ZJoF_zb!`jtu8>pr_viB%lBNUEp@k z%6yi+1v6g?C-6H0&G9TwWX02W{#t7M&tCr?u=aB}2lGef_uoCXgCLwi@HgZEaDd@| z>98%7b-Ik+Gbu;5wHeXEk}bNP#u2;&jCC~d{zm{B%qZ~06*w^9d6{H?lx;YPbj*wM zb&xbVKoUp3WwcL#|6K1MG>#Gl2f*iJHtQ=dswCBfYOHj+zF>eQ1VFly|L6iu(a27= zx*J(;%l_4FL|uqbOWKG~`p(QSPdh-smQ7}q*gNNx9xk&ECJs*$eFkKo!Du+v7Xa?1 zID&7%^IUXL#%0EPl@s6q_(bHKpV9OD9g2m^r`_~yf{c_I3RWThnweRx#d4BoY=*Jw#2m#WW?dSVWCURI! z$?5pc=Q?SuJ}#Uvwy|BU?yDLBo-*5XItV7|f9f(|i6-B39RqYdR2|PHn)Yl|S&Mu+ zUoR!H9|A@e`+G(fyXn(-9>CN#yr)b(FrFh_#hDEr@sRal@5hvC|N)QI6r32C3_?YH@f1i-^iu=Y|zZR^g?nFs# zFea@v;C|Z~z|{z85!w^x`FYUS+OV!GraJ?m+IHOT4?NZ#+gea6vqLEWnC!a}FePTa zrg>)jm^ovaC(JqHa+&b@!ZtNq=~&kdKW`5Pj4NG$d*88_4%|A*z9PgKA^{zg9JWnq zmbC9iJb;8nh=_rPLcor$7OW*WGi1}IMpe*675{P_KM%S3Wex0WoE|G>|mH|#rW zTwSWrqChpmrODb8_N`&xRv*I5SjP#`GQOOIzTq^~YVy-oQ1;ziy_G;RXY}4lBB=EQ zu4Y!FWrt z!WyX#)D+QTLcxw6BZ8Uxv}UG72)JCYm=dM@3YvgbHhwk-XTh9iTrO8kDceL-b86H*{>)*3M-Mazm>6|Df9>iT2>M= z`n=X!fzY|hNI(b)JzMQeHg$lJSlSwDfq}^~HUtY}xsZl{5IK)p1@^sRe>AN3f_+uA zBItWU+XC8N0S8XQgp2n$1}k5fCe|RE<1y=-6cTxzrB&1o2u)B^$CUZJQ;3L{iL!dx z(JGAs(JBxF>w=Qm|3}tXg%C%5>ycGZ>)~C@iIkZ~s2hKQQt_OyEY|9y^^uwHjS}eA zIqn2N61E-66W5E&mk9yz$X!;sps(cMzyBOiZASrb7fMBFxJFm(3)TNOg zjC0?NDIlt;Em~k!x@Tq~;sIb9$T_$pbyp*A^pwTYuM)fiw4Q2rKY^(6-$SO%zRl;% z&l&ulU3%&GnVvwf?<=3dVuu9~@bC3=ulO8<9$BofLG0PD;rQ7<2i(63hCRy#2mjAp z)R*Hky!-wbdir-5lG9^Nd915t6dBvF1S5}e4IBn90b(`zPRx+p^XK%O3GAl;6x^DP zlp2Ab1FiA!jWjSLIv<+=PRH(F|5)G-u^!Yxp8yG9L?x7alI@5j)(ohMl?|y539Lpz z>jBMt27C&snO1tQUDl|xXSr~~!Ci616&(;n%g!QLcFUA1%^ho*DjN65oo}B3umES( z#<<}p(Dw;2kM|m}+Pi11+5v1&B+^0Vd_>JJ!>cw3_x~!?#>bFDYH(g^w*4hkYM%F$2}jU zgaE;vejSLN&V3jqogUpWZ;Z?t|H7CTeYD^C`uu+htPT7PfNMW{Dm(FK<|iWYy2Mj`$nJa6JS+%l1L3W^7%9)-Oox(S4g^Ag(YuP{q5F%&tKekxTo=Z z?fko&W^w@{KtDkJ7>9a#E;u@Lh?qj~Q@KYA0TL=oF=IO`weVzy4C?Mgpq$3d)6dk& z2mYPbb)_U>ju1p(W`Hp!wKDK+jjbDM!;r`2X=2c5z+qh;F_$F|~re_$_^JkLwU%k_d{;H6vUDCA@f(q$rW!=YM6%lk$hTLnVjMD0B_g&28J0s^f z7DHxE+gLOe0D|E4#~WVX-w<;|NC7zuE|&{l-d=6o5U4#Kg4^wZ)&%RiSyrfEyRF!^ z9WesSa-q3e&Jgjze>kx6i;o&pE|Tnj-0C{qkNs~3I9w!RO1OlGd8X_6zOi15{#dSR zFmk4M=-lW88Rx@2*cUEUh?&oD_I0Sz9a}2flcbc9QnYIkO1yr4pp_LJKu#T{GOAS# z5CrQ3d$m%9395p}V@28SxP27tr6Ny)c}_@)nMUngsB$jYx1A2wozBH6M;cR|n95ok zO5I1F=bx`1cz^$ax0iS1M3NvzV4gDCvLHq-ifjQ>4Omi&LDc}WDPAM0AP9|;Oc83b znh}%-z*~aE#=xp_gOhNufMRvIa@t^7qiT+UzVKQg$QB%7xQ@GIw>Oe>B1TLku8vg& zBKx>6ty(W~_2wsnARRFh9MoM=_C``>Z`ikvvH^W>=!GB!1~6J}D0@N5E}07~F$rOm zOOU`}&*a()S}BxstC`Wogq$XlYm{OR&uUvtfvgRyHJ_G{^~{KfnB$f18Q&vIBPqJ_UfI#_-e2+vWgxlKP(i{XOXY zd`_RwGklRW%Qx5aZ@nyNKLDa<@AMlGY@_fKNIIXZ7)TY%gfKHxuqSO_SN5cJ< zaKB!#ZY$ol4cF@xDJMi>`3|fGF|bnp6x4%(^yxlv90THY@uy20@A>ph2l2s38=g#2 zIQTdLVVqP6X8_fY`8Iwo9+Dn+%ri<Hxb#>C2?=<;<8ddS0o^y}q-rX(uR#90aqx7J_G(rS_8ADP0W~KKdEZW? zV|P#{pq#e>PC~*-2CJ>sW3CKF1SkK5&_~yZegZ_E@jGY7Z4f;HT_308`M6&J23|K1 zB%hAuph-s?p>f?l0X~g}r+M}KEeH5I5o3OxXF_Uxo&(`&ZXZVrgSg~1=(vU`wx*xT zh@LXgon~T96;kT}y(uLmJC~di_Zxo}y(8z0Tz9JB97qcdL0$2IVLIj4%DKsB@jM0x zx2T7~TTqsJ`nuXak>OAG#@9IkW5APgYY>7yrp%nwKFl$4I;IGaVqibt)=icc8j_jA z(A|p{yYKr5phJj=Q$lWv7|pP1>&zBzd^#amt*s<;BjZK2Qt-Gx@Sp$rpZNRlzwvUt z4!J7;6s3$$0i=1tB?DoOxcvUg>}RDM2O2DprJOc(0ycC4pI}B55(Qpxt_qZ$jAcqY za@wsHFhRlsgoYpukM)MK?hq;HeFFgG7$7nsCm_ZRDFc`5gx8lhN}Llj9m{e-kbr$- zD-eL-scZ$)lrb+CWUI@4e}Bh(iP*LWK0bcpeh;jlEfwop%-F^PnjUSCP8^i85e(K2 zXy5Lr+sZ|#`@{$cu_Huglpvf0l=C$PpjwXU6$CwI2ngoqdB!p?sEsv->$*`^nFIiV zU2RGOm%s_Lt_2Djj=jCU;qp3}D{{3~O$n;Nw(a=&@i+eX$A*vF9rs(s{kGaQSF8`q z2$#+*drm|8Oy-CHSdb{iE>_fTGE0c{RO_ovNZ+kojv7bCez`2jX@+V?+0}ZV0<{#j ze%khtiCWhUDORLJq9ILgbVgRTcPCsrnwbWby&{B$y;a<|6@a2OIs)If9i=G%X6$t8 z2$4N>_jSd8|JQ%v^GRyj z87x=2rH7zqayBvRWIB$zz1sj$G8Eu_K#JswoJq^gkIW&dAwd6@_Bmig80!SyNL zU?gq62z|&lqf06+`k+}B#@a&g*A4I;02lxyoX<~(S(e{lwc79ABE1OgqoD^hm%o~U zS1lEL>8N`{d35eG4@KE4js2<-cxnea1rJBth;u-4WPCrro&v}*jwqE7k(2B4*MR!m zCh3U$j`EZ5g0x?K|7R4cz*j^99IXGRLq27ozXkoUF?X(Y!?z@UV-hR-Q`o`bA` zsf%cw*)?F_!>RQeFx@8HA2+Pq123;HSe6BIUa-t8onm0;*&+Kbbx`H^qI12~Q#N>j z1bdf9o}cezIL76X{b9EQ_wv$H#@_FNLPvZ#ve7JV9qYjP)m5$3;Rr}wA?W5-&^QPw zc*fJ}j`b{gRB(+|&K(Extye&sc{5P{N8yVgnmpWt?Ap2hmnP^vSiLUiPIFVPemqCP z0dS9Je7YZFZ8`x$9COas&#sZ+UCv$AL0EB02;?JJ7-BtRY3e4L1%1Y3qinCj}J3J{@eS1>-$=c8l)3MYUa#Oh;hF*vaAuL&@}59fP+2Em{I zK0oj8jx&xi7Nk!RyNH)s zhL1t5^>CHutvPuWU@VfpCd6>;8z-2H!+HMs+I_C^XNTgUchE8ZlzehUmE95hjDhhJ z@q5hOhIE-1)YzasK^w5|1)5Gq9m@Vud+o;Hb%X#!2~ad-Js#kcCrqX_Pl2w+(aMd> zt`J%As1^6e9Ur$3I+mGRS)M0cuUE{M33;A@NhtA47tDP|E)%wGL)$HrQWX1MP#$c_ z;&RJccGTX1UhJkf9IZBd0Tk5Mv6Y6YHsq=%=T2BI5ox+YlyYe(L2L>%2iwAf8QB-b zJTG{?T&-4>KyQi@YoGUm`~A)gl4S?xdB)5854^v>BjyPqM9g!xEOf-%+Zz;Y7gZWF zuC-GB4NWGWOqlXS$$0PBEknJncdY9Jz3;4{U1pk%T^Hn>kaB}dmV58$;pll;&A6gg zYZntDG?}wpiY6gsy=86H07FA9jhjd*sC%KkxXGX6BB*T#J<&* zrn%#CA*&c;rj$KL#4ux-y`4$4e${t;{QSVSuHzb8ttOdntZ$kkCR>PGPm~(Bqn8`O z2&YqPY6eA(L2IX*o#a5$DVRJ|NbEfBEAF~NkTK;M^RywxgjzfHQcMnc^ehe`8WA%a ziDkw}-RrqKGte>F2F2{v9yk75bjZusZNs)#wwo{)<$y!}?TjeL4uO9dW-Sa@s1`ZZ z%!vZR-rw5TB5bgVy+aGfW7Uo>4U!aLvh_v+v?yRbh)Zc`J2zd{xRU+ODM9B9Oc|1d zS!XrCEyheDLqO9lw#YW)CyB^8KwE^izznSHBP;3-$Yc3de!do}VCaPWRbu9u)m|HV ziRgjSe1L)1zHhb>nDGqAti}|OrbI)!kdRZvl-X*It*N?|1XPrrW2@90uAILB03ZNK zL_t(SlN|@Zqi3@3P@YY)`=}eeISbiNS|tbV;TTCh@K?JusY^qb==)Z z0g^Lrh7w{#nkJ-l1a^l+yN&NvumgZ7tS>do3_iyX0$8R&EsG@3PEr?2GDl1b$vSzf z7ng491Z%`;7F7x6jj(9Fep4I8d(_3+Ai;X0I`iz;BRG0cTi~UEb&?XDrS|h=7P@ya zvezVHUC>%2$E%B$Dpek6 zXlf-oFwbGKZ#)bK6UxvaeqIP9`baK=fIrT)ZsnLE4aP|`}1jB zJOMro;~qVI{|TNCkjFM}f;tES&gIz6OT~$<4glVY^8jJd?g7Cl%QToR?Zd$t*4|Qu z^`?+WkR`4nBEgn=$6gLh;q+^*M=aUBh8jnW^thf+x1{_1IIRnu`pnMtU?mPpLarNG z=OsOK<36(dO3|+|E%{uhy{+F!=TZ}eDKFAjH_MJ zt3HrU;J^1U?IecNRD;ADSI*?_rc#%QHtFN`%@B?p)s+q)ke zH|QyD^mX<#&^7AG)?Gh;etzs->hYAq+hOr5`nW$XeD-xNbX##ep6T>5O4GC;gl543 zz^t#Z{#C7ZvLClvC9?Nyw8bP+z85BDB7;)Ox8ytku&UzYp;1EG1aaFjXJ)5sVFns2YyPU=5N*)btl2Ve zCd=Cxz;&f#S)AC$DWlW$$Q)XGz1x7>v92rVjPe5S*Sh2h^E@M^nFFq|6-n7E9`_ZG zb;Y`_XnV&rWxQ`YN-4O$zGGPy#K`NL=NXqvKuDAIBV9~BIGF@G7$D|AY1Ue$bk^za z+m)`_D2O3onWH@iL5ggdh~Abn&jvZql`X_P(gwc`GGV0|>y%GyCSGb{i!zDn=7EIV$uJIYq+ zaLm&}5Ey|%;vyqMyAF1}^%eK~j>k%KtKO|1+|(t#vybYwt>~Q@_Y`TMFfTL?o9Efi zsUeDBm4H=uY+HqxM1PqVcovC<9LhP=Blf*w-&O+E<_vqlUJ5hKm9?@EAhd><8>Y#? zshNg^K%f(3G3oVWK~P8U3%V|-C72nTOQ0jJ*9DjB1vy7sLkLnI_Z6koAtO~=P;$!b zZ=Evs{4sYwDqi38*A|Wa%{OAd}@m~>ribC>b`h$y=`qr(+U;# z?p}03N;HGJUanZ?897C0ZxA%J0*K4)TN^FMoGfy7|7mlz&4D$%&4N5X*K-iY;>U22JeF#g#a=I)>f+?LE$t_h+zWdfY!sZ1Kt(|P}IItN-aFErq7wf5g3d% zO-GO|Pn%|d+J07xWeuQK(jY)LWkQE#ldUeTRrILP1ZeCCF`E$-0~*GpV)OjOst3;= zcpb4hTU*q~KEgn>`txAsFbKAvCK&VXn|J5hW%bRi32If;(osrB+XHG5^DXG8UD+-6 z3D5-sr%!wvYTSH`KNo_PWRN!I#sD;7@1o$Wh2o<_i{J;p@h*5puGOqYfzs}mjIkHxcz_~ za%5dv^L922QUz=&7_8)C0D2hVg77q_f)hG0u-O{CZJ9lIo(nf*geEjP_0qW*2k1p> zl#HuDB0JEA=}?=TYbu+qI}**!J|!bePvqi>T=IR#TfoIm5SPrvsll@CFcP|ZujTU` zI0z>Px?bOVoZqvA*MVGc6WRVfSo>~F_uih2f+QI6)=vcF8N>i)EO;9G!DZS8+=Bq_ z#5=zCBt^BKkMA_n)Q{?PAn$8L3ISa@im8;E4?qKiT>x*{3I7uuoP8p?PW#>YXNT%T z1}Hx|T%AGK*ZX*WIbnOg=btnDzgi1F9mwBsyl)I*9KW;kKYs`RlO$G9OH7QpdOQOK z_dWB_LaprtfCF+S37@l=$=FdxT-&McSdTVCt=4gO`*{!d%d%@bGTcYtbeubl)^toQ zSGk-?)5AdY7)NsYmUFhBr9VE-Q#5y3k;x_wU1z6c(i4paSOWI4g9{s(wJrg3q$D?5 zpW7(O`rlfhE(E{`;ppLIi&QBE>%L=MfiwYmo}eW_Ye&`z2tddLIw}FNO%O~JzwQ~A z-Z5=~S&yyY;K}>(%$hYRcNz^-xN?9X;Ie3$jJ-Kr&7?T33+liHa@U@-%;)r0jrtEWXvg} zML|!3SlR!$SoT%1BV{1R480_D6a*3E#D^Zy5keb*tJ54Bee+_UT-GTmiVfbf`2uPU z#}ffCYh#aEp4Jq#R1|C1gC=O!vv_^%P|0I3GGonFKQsi{v2O&x)j*bZv7Vt5a$*aq z*S9x*zV$IV%Y(-eWRPv-_4;$s@QRn02OjHf$bWkWLIhGYFsu#td$Y{coqePeaJkHQ zd3nLh^@=HHOjCmB#Woe8Gx4qfHe9cT^^lX*aE1VFovzFKUsxY^-0r)zXrf_LiW&0@ z!Pj^ou~F9REqj7DIA4tYPX>gU@ovqsnei2^7Q~75=-HJBbH?RDGqz|M`^V$KmPz}H ztu$YmP75y$qH-c((pp20&0{&ll-OYXz%!H6>kYTChm-?n%X z{POv#8j#2lF$IJ^sQ?wnt;&6{7Xx&WRE~C{!Y1nlLX5Uf*8v z`t~1~<}17{OYenjqE@W;JGAXwBb4%NUT!0}uMD^jhTa!#*fZjS9pn(9o@JT6GeZ{} zprJF%7)a#A$g$j1(9w*+ro>T%bvjcfJF6{1b3<=p%7QxfN)KST$@LMWdRZYqx%I{m>(XA~|Z-Hv8 zt)uP*e3HW8fPTYZq0RXl0cJGKFj7NI_-+z)H>*@c+$X*YkDP3ob zn_}jED4s0^nz8Hx(7?|2Kvl-aO%5k`6@hdsaX505=v}Q0)M{}9Nm3`B`JMv?6MtEk=ho_&>lPU)KB-zF|Yc*VZ_*=Nwf#N(@-~-w~^0VUN z>y3i#lh19g27&Vl1pkVd;2Qm$@pbSB)$#M^?>LTe^w2#BDXs_1qWUq;>#%2sz57S4 z)!GlGkqHJ!*k*T>wsBWV!Cnfgt<_Xi94%~*`(v{B)0#dK7b0UE!HiAefY=E+yMN*Y zvmB}cKc;t(Ac1T5<l()KBzqevCGM;pfE>WSe zK<^A-r1M7K?;C2Nw5PcPaVJpny3&{g8Vh)P2Ra zu{}@D9r+q@y}sb>^&R;_DYAwN1!b7tGK}-10H}agGiw5SOHb^}eL;Z2465dg%S* z63moJJd0@A?{2+Bo7(Xrv5Yk{A#AbOf#*0RBwZ4Ze3y{%PI)Cmn_&sM<^|TnAfBrek z@vE1r;&bNt|HP}y^S{3az4r5ea(+ja1puD!&FA-Z{37Fg+K)n@*MRpRk133dEELe% zu$wY23fsf2)66yga>cS-u`G4WMFy*`26AEskZ9|rG%F1QVCuKe+v3_K<7>|gY zu2(%srs{%{263dy_(FVhI1vcKHb`Q73@@1SLwATaijJ`)V4hlTkTsC)>HJLAYUA-t z@Ubr`*E}ENN1H|aY+?&Io+JQwzm;d@M7O|SLpXsV)?Im)b*zEsM{fUf(y&9(Pfo=S z&;zJ`iGs2I_;aO+mEXssjS+|Bp}qnHpJnf@b%Y>;JapN&ubGD$=NWi;#u;)3LBArV z?0L%PYsV3TsScw{31K*lyEI$u*{HkzIw0>(j2Jiq%+Qhqx+t%OJo-^$(g(p|T@Qi} z-IE&35x2*}R(tNsB?t8>WxICveeS)nFSP?@c<=3J@?qQuKNk@j5Xe0G5fRJ`>1!PT0;~^xshF3*JugK1MGjdmpI9A2F2(7DeaXt zDq7j=6r$&G-aJru1G%vN-it)i5QDOSpK#3!0NdciV0Y-S!3jfc?L znnNbm>b|^P@#DAO5#K>Gh~G2b-d`Y>#GY372TED-cu?xx9|5&C%*`^_C8E>HIbZ7R-(7Ks;iD}~32R?2$?CS^bhqm$HnO%yAUjHTus0oj<;;~iy zyxsBh?-jS(9ox1+M6fK=2=ZyJ^f2~9N6)Tp+t_ZYFk=|P-4cGish1#Q?goSg8$p?j-Nk& z;&%J63B%0Xz8`@)tY0yFGE0SsB4^47b7Bu)RZ8%t6p%uKgo#8!=&XrOiGU;p#KfB3 zT4D8^Tr`+z=lDD}Q7)vt1KS4t@#hETdBTz|cv%D~unm^>884TLA8#EISM2q{`xpXi zv)|wG`tpM5N_ntKLG2Z#uq{=!9<-$v+W;fM8wygsU|tqX^MsJB_A)9`449XMX`&fb zsT)dN(R#zS?(92!Te0s2ttg;02RVA?3AC|hxb|wRBI|LZ1a$8qt6^;NUUL$}wdDpS zWI|9gvJhBS*f#oZwV4*^*IKbzJxLt^xFKst2FEIUNk*hOVwq;>OxD-k6hi^QetQnk z#|8);Yrx0H4caH<#Fk=ZFQ{chDI2!+f!oJVtoJ+Xe{JpZ?@87=D_EH(7j8Q9(l9Ha zRiHwEMliy@m==huXHx+;V_W8o*Vik4{Qia?zg=*BNtl*^knNrskgBypn-JLbfVu-a zSW6sZFo)<2sEqSv;3zg``=}T1rXYysVjfJM?i*G&lZ@8*x2g{2S8#mJfwL;lPl`ZI zQeA6BDaVHA;|!Wej9_{K2tguExL`Gi!mJ1LJr?AC0va(U8quYUD10v+V}V`*l@gTz zyZbzb*Mt)QX!i}>14WY}Tju!iPEY_;1^M;3tUrW+Bu7^GxL!F7+ibs(7%YQaDEW_# z;(~Bwx;-$IVBHghN}b^H0xc*xqBUl*L}+^DJ=I6NaH?%Pzdi>G=Pd3S{EmK+XMh`Q z4%^SZ3*P<}2>xfl`2Ww>`8>~m1Hchoov-ts0Op|-IX+LE$yzlXl3@${$Ne+)Q#FGo zD0UI-h03Vb9mE~J0}c#Rg6&Vw@>jmtB8X$@`I?>lJfDB>jnGq+VY?Wy@1}Fjyh8$e zu;Yl&4d{_*RBN^Oe9w-$;6tL@N48H*rs*bg097%rJrx`QaJN6fKz$QG5kb@g0H|OX z-Bqs{ZHiNamhCZ_<^`8&}5;V$shZY zF$Z|Q(bj0M|32TpvkNi_zG$&4!SeH197?S2rhwrfFfDs~9P=2ktu)s7oZrho(OOEf z=dcKntS9qX{n<|dxOv@?AIoAD0&cDWF0Xf@lvIF%-sx2=qz1oMJ;rC?u}WeQg(d&{E6GfOz*us2(UNy!OcnWqpSY9aW z5~1nW?S8}k_F-heifv=|t+!z2Q6yaIUfJHKb^{VXN(sw6A*YEMmCnq6?+qad+B6|X zC4mv6^|f_rM8q_~nuJH>DdKWjFikT6MX$DrD;e)8tymw%;MNWMzG7YPh;e2ned9Cu z@%}r0y#G!~6D-IOU|A+yt``EG7*K`JQ#L{E4NLFH^91%Cb$M(;o&o{)g*BlebG}j9 z9T5|+r?zS};{=xLW5dVC4UY%w)3tH#COd94<`l*lTI)eL(XXKobGvY2%eygyO)J4( zv3jPE5o1D#6GA-o+l`|TjV^*_j#Ns;w(rdRDIij??*%zEq&y)fBRN7t?>kx%Y%AM4 zK?EsBpdOpH8Yt7J^_*nWrVsQY2=NZ>KrIcu?)=?jWu5f4(>uTvCkV_&rxY;F8EFnk zS%x!t*%~v^8&EbXV|o#k0N-tGi4Fh=_PA*z^@s))5CA)Vy|`%beLzb~ zk=Nl+?Liq|44_#T*`!#2U;%Ilh`}9X6QWF1*}&Sp>=C^QbOKTXTJbtU13^#qfeyad zKF>jsJFEKZGx+uA>!ku}We5PDKc0Zj*Vkb6)w7nz=l|8~bHC-!^5fCIo-&3JV49tQkfPtsrq znh-Py+&TUEe))JduM`8j3?hMufF6YzRW=gB$c*t$VgRC3DS!u}N9!A!D~&S$Bdo`v zq_H{azw@Bn{!e}U;ov0dXl>U$IR{vfJitx>MggJkS)F?Z{~4)}IXNCP!zfnHbIODX zfELkOM@qg{`biGlj?dX)Ct_&~s@v^8&Wl-48RU(ZPN}NU7;k_)hz2niSv1^lcRU{3X;BUcDIvuKbPKi(<+CQ( zohv)M6_LyFB3LJ!=Y*Hn7ref|;pOE8x)e;)geC>|ZN=aB4}5(5#K-+%^{I5sT&@di zYWmC!hE8M3hY#SKMzm z-0mw{ZAf#+G{J(8$hI=}z_x9}fB)mZaev(L@=jSWVnNc3*cnU(VSnAa(WI$co0e9N z8s?lSvlIy^jhRnD!Zcmcwhg5ci~vB2Gp{=&a}%aPhfAS@k*}`9kHYph5(C>lT@q9k z>sE2Q-%&n3&}zfJ-|>3;!0YQP-d^9ZTqcANuv{|c`L{t@tPe_~*GIwac0;Xq_6c6u zT4LXs(Tx%jCI&YtP+g!J(F_2`#K{uPXhxMX^1T$??>kyky+|A1Y;8D~we5D`4?cl@;%{QSA1>?-kExj>vt^=%#z*v{BPm7cTS2KiwzXi}ckCPcE7w8-K{^+y z-a$!PP}J%zd<;NZ>nvLVEjW;I|BfEN7(jC0ikYPq%45=O22SP`kWHqm=3L!rAm+`@ zndxMfO{8EC6(MZMfll3zv_c^4v0FhU35>NqWf~z2ppWZN3r?tN=-SX*u|?OK-P^{I zsD(0h!bx#prfUSO0eKFXCK7LZDg;5=p{=6^SP$lq-*0mWki`VP1Q2IIta>hCekyt`@XR@zR~ft z73*bdI|zXtrA=Aw9_bNqb_2}l3~r$~-9syfNt8E_#`S6hKw#f>*6$x1-RM;ByR1no z-S9`%H}{h)(V1gabC2aYG2!6Bpna}`HS3KTtRAerPtCLd03ZNKL_t*bLKmmy84$Dr zL->%K5TQspvlU(t1Tzrqs88T=$h3tZ*7q6*7aBU(fetemX$Vo+z6D1RI1Hx}WwXru zMg+;0#kX@aHb16BX=ezCaRTKDo|!tp?>Ns95IqM^{|x+o{=B~*!L#ZIusmlHwEY?w zpF#1zdVL3e&wu}ad7Y1O&T4zm>Ott&vovDMvooKM>A{+l0Ij3h-ss@*`8?D}b(4__ zpjy$YpzIN=^{3`o2;;dVHD3!ga|;N*^u<;%o8ur@0hcX{nZt>VKkujRfNNwlc@P}+ zn)q~V+YfphbJA;kp+jtaWaSJDI*4~r;)FwhmzMbbKgphfqwe1Be~^RhkQ4LSZ7(=u zYwsNlQ!;393F$G;#E$95cpiaXZx{yA0M9uJMi1rlBj$BA|HrY?oq)_iavb1|KabEc zUtAVF&UAd%YlYpw$k#shR#m%ICkd-KXl9ML;Uoh1W_zfE`B94W>6%mrU}vas0(&-g zqKz3fC8DKh$9WIHH`Wj@yRtC~&JTX4f#FU+pP&lSGz>Y-d#@kB1^p@94HzSDc3 zveT+h{l5p;9Yx#6Ggs(%z6wE;%4=&Zfzo8_O>9O~b03ostd2gJEZXi@S5t2tYk*oA z5X@WTOdyM`zusj;$68@6KznB!D^swI+ZC)F7C_qf$_2M^;cME4^DRJ|{xz&9)|>UV zvJFrYUVuzo$H?|^(~OBS#hfx|8ni=uq||lYP)kAAikw-?RQ7_O_ZuGDiv8op8?$U| zm$N-6jYOxkR#>b1vb@uUIb8SvDw(;qEB0+4F2&IYLSuc+%j?bL+pOu`J~otn$JQ(B z{VL;!`8DC~?G?YjU+~-8E8gDNr+8hf^@g>Y)s2g3ErCGo4y=zAk5%zlfx1(zQA)Qx0LNAV?GXW)h+FCG8LhU=9img>)1yPPLIZ1jBsGL>djcgA1ZXz#&3vJ54coS( z)QX&#NlYn01G7LmUGd{RV~#8C_d6bsVv8oVo^&xD{1}+YF=HnY2CIruPuv?2=7g8G zA9%T5(IsGgtk}zLvKdMb*T)X%4Y%8kjH`5WK=!(+jF*>;oT}ab4eLrUTZ&?P0B998 zR_vibi(-Fl5bI?vP9WrjX-Y^FndVXppn_UD_8ry=2Ur$g?Ae+jMP}ohRHVe(ofs0P zi8a|VWrB)Ths^kozy81<|NTHM9n-X6nrGxlC%wzd1((Zjczb`t%gY5CI2Wn_xeNBB zkkAoL_B}5d*Xx4mLYH#(;RZocuOv1)1Mwcjvg8JKYsLB~xIb2GYsI$hSl5PDI#RI3 z8{G72Z(yyl17K#V#roX_1T(E_wu!(9CT6|5S>X>uD+RPQgoeRDbMfJ^JX4{*uzS!Q z$)+^xe_cxfdc_WA1+8cS=*)rzL_{;93s(Q`*%9BoHP}LJQdIVuHA9#RAW{M+NI>h* z)DU{-nx%9hR<#=9Q#O^-MrH$J(xc~g(4i1HZyH>CxjuT$b*mNIR#BQFtQ|l@SDHv{ zwNfG$xHRM$xXcr-%N1|0Kk)wgJ1+ApV#-*Sj6S6Sa7(FlR>!$FE$?A(K%O{%YH27{ zQG=irq1&kiLrDd>NA#8lV>>ecjikX*JM8SN8nYiUx!bXA+RbWqSSU`X^Z^d6PRO<5 zB9@I18QIlyFnMG~SWhcWAR0J6)MUVBX4N}5CJRlndW&{2{w>|l&$FSdqpMXAi)H3} zhfEoHN~5kBLYABk=m&G{a?)mPo?0_fD6))3k`mb3{XwvxIGVKF6g^%?k0F_6`>@h0 zO50IdMD6E*>$oq6tkN@G9&|a;01T5I56nK-{GPzCXMfLajLy8ed;);~Zk88cj&vN) z@8_?;?{`1@XL9T#D1ScJ02)E%zVD9v?__Ka*|Xha53~o!;a;gu@WIx&;piMJQxcBg zZ2ZTGC<9Pxg~&F3$MTqpeWxkbWb(u4HLX0saju@38`;EDs`zT5*m zt#O_S_Ih|RLJB8YubjTiFcSfX0a@68cMHZ@PinVB#bG$*sf@rOLZd5BuqgUz9(;Xn zUZUsn&VyVN#BLoh1UzuEl?k?phWLdVz<`{+>1`#SasBnDxJ4XPH5 z%rH9Ue7}AED2}~P#N_eeC@0}>4?um~Hy!8k&tCtpK=K&R<%H~?{NUhYd*=eJ65)G(Tv2B}4Dvw~znXcYCiWX>V z*u}CC^NeMh@%s9L_xE?ay}cpE38fVDMu7P9&%f~JUw>kMtWf25^xjdnpD3l^CVv0` z>dd~R-7-$oWx@4wHPb4Bf!;dyx}&RN-x}7(in22Uiq1^gB~4a4I3dj$^L1hirZq7` zwo&RWy(0&~FxvZEUE<1bcuV1vzJ2(u|Z6rp2U}h4OVS zbPev>91QqMpP)*|ZT3;FtQX7-!h)FvR%y=)Cj+7?6yuBg*j|g|w?!CfS(AFC6w-5aJ*WdX2;{&ZX!~mq6@p65& zEF17xSM&y|2U14PEBZupDeWEGx?yj0|5l~(R+u7EPPn`*n19T;%ohf?t+3y507AZ@ z?5mmS2y0Tejqcu)N$eBlU@-$9q|EzkdK7Smq0U z(@v#>63E6mK*EF`6s0L*YMzY3wiSGQ>{!`CXn<4!VK$y^bDA-6T<|D?3UD7RJ&}Qu!jQJ1UHvEJZ*elu@S#3aTV&qo0Oj;PsAz;~|T4_ji zT5y9{R}rZ8k!7LFJ=05CFh z4CEw|NC+_Hg7rF8rR%<;qe&b6$G4Tf9d%3Cw;g?FZM&-#ya)FP5`dxV==y!&_0MX4 zfA#t-!F$U5esP)YHChCjy3fO=zfMRdd{A@$&LSx zWMGFvVnE0V**XT~ET-nMxpTUAtlt!z``$M5+hC@T{sN^GOjE%;%?7ID0KtA;gDg5- z>v?ZrmbcsAUbpPv-0IHpEKStG?dhrJ)Pq(UIfw&bJwB@rNbEQv0&Itdr!nX2iGRk& z?bA8n6sUWKO?@9cp3SJS9>KGW3|t>26*xb?0EpqgwV(Lgdii{8<{@4 z-=66Q^jngvTi1n=b@k^7n7_fXj~?*i5R17OU#S@t9^lf)=yz-5m;<8cVf;_m zKsk-MU;W-n6pT$lmQGGpI&+&8*Y-~L+h=U;!JY-F=i zyOgZm5wCl{@8-_ipq<&GlqYBl04nM# z*w+o)+OcmyF&EP)0`!F5BU%Y4kwyFwE(>6v)SjBj3~e(pVq&=SDr-EiZ?Cvq7Uay# z`rr48ecP~CX8xMh`UXvO1T+BbgGtR2E~G}lmt}y-WWkTBBBl&xx0nG<;zkOb0JVkT z_zD2M(kT@%W0uyjZx1{ktcAY5UNFrQ1NC^=Pzcy==O6$08~^oR|G>}N2NW0??->6g zvx%dQC8mTaWxTz-;&mny2y2hDZySF8-SAj}5GqmvrU|&b^I1*vgqPPBq-8>i86mO_ z)^^X7&1=WH-T}~+8GWI=G$tIqO4&GKYa5-(t*$fA3D=heZ`&2E0*}Xr?a{E74forI zTfCv_1BwcjJGT9Iy#1E3Tqa9Zh6fx!9+4#qBw zIU8d($Kwgha>Z{ys2+ISD;|#xb!V+qE0tOK-Z_6`q-@xN8nJ+()rM;Bq9T#TVq)!6 zv{|VE*xR^yUB;2wU~t3@O?voJh}SwnTPx83~iR#RO>zsP$qMj+b*g9G17LQ^x4EV+ZA0y$fQgmh}&0IPE@!z)Vzv zJ^xOErHz14(QOX7*_CIYBz9QSV0#{3bIbFpMa;9I)BnKg&UIJRy`t7=0fLcDrUvpr z^=N@}0MhSXXDRd;=by5_kyCg_Wx$g#~NSu03ItZ<1!rQKCb2eVeQSfBT14aF;O$~B_aT1W_Ppaa2|&L z|6P0_&z-rI3xEiBH#1c}h?==a09jR+r1#0rN+1?rY*A4W74?)N!14jDdlIh}f(g_E zm^KH($NS`<(F`=!I@G*IKlgSf{hk`Imo>N%SJ=Ud0p4C`XM-L&);pl`u%7q1Vz_rv z23*!AR0efW`T02MT)`)Er_SBS+Q-WsS z=WA=7S{QGcL2E&&@YuH^)IMm@l4BC3m-qzm*V`*@?-?m1%oBmH zr4dV@8?8t{sRc0vJipBN`t2)TzP;f2`3duxh9^-7?3cBAd!7x~_baxQ{bZqr6eFhi zj429gO31ljuu2*BvS3w1^|nA7S*%T`R)tj7l(xk;M!Ij)K{TQim!d`nGuuX|+SuA$ zDCLdQH1K&`7pz{lyKNgbcbzpK0MS^>3q33VrjX1{G(<&8(UTV=h9+ASV}DAI`&C*% z;uD|+&Y5!J;sy_<1tRR_OxNv~PaO~5cFjKho}4Nw!$ya6Q_yuQBU$Bzv;8>R`E zCT`+p3+NV1DegE$oX;mbolkgrx?qSS1cH3s@c#aer5ctS@b>BnhzN`Wuq+#*{=g6b zT?*1f*Xn3Ms0OP_CaF?6U^TgmZ$a@|8VFF-ur3RJ{oc zAX*lP6l__ctD@oua$TXg!Yrf8j3+%~6t)2i$uQ0IysT=-m38Y|E@(A6DX|8SQ(JfG zv3gy02p9&#II`aR@-$-_&oHAQ#=5Myy{%Z+4Y&6dZ?A7y*Gy%>IKWhqYe3cFGGA_r zO#WnO6=-DbtyZ8^LD_)30ePcLn%)t{8dV9NIH>^k_F8uvryBCI;{Cd!6f$2T5z}QmayjGa`Gn_}GftNYaS*Uq zH|5g^Mya^>OkTDHZ&w<_!3=||U`|gLq+#$ZvD?%rTa|HLU$Nx{+qR%uL9F2X_OX_R zh_NXPK$&GJ+5wkV_Vtudk&n&ahx?{1V9)jH(r7~r2Ga#4E8fO;j;)j+ zA)zXeH?LJzH_TE6l`Nd+5(FWEJx0|_#^Rpn=>b|`;-Z!8n6ghfOxY*dT0+&(B&iZ; z)+L&D01P>pw|KzRdN`_*DXRQ=Rr5p(*UsP!fk^1ALSw}CV8}Dl@MjwWmEeLN9GTbB z_5c_z@oXIxl#*)pV{~~~t*{bMw89SHnSngB@2z&K1%*e+^d2bf?C%Hg`x~(Q7~J;q zn}_3({r#`h{{H`ae9ol(?l=aXJpi>wNX6sG0^k1vK0lbCs6|mWs-I}k$Swp-hBxy| z#v)Bw(Vq?WBqssdhFS}9WFl!Q#ih`r8_`g5sKRixwR>qtbCy}f%lNV zXD?g5a8EFLKy6h$u=dw0=VYte^6l3~u2>i(@t8s4b;r}Nr znkOu&d~jeT(q-Vm_V#smfFVjZb|eU^2CW!AnIm|(vlkYpdHxDFWT># z3a8~jEVMZ0uyz^f;{Y^?0H2+YBhCN-MyWZpG8rBW!Bq%tePN5zV*+YVdhpYD-KAvW zmYkVTs`UDi$bFKEACDV6VU=P;iEjSsV@6F~srGS|XzI*%7IzAQk5Bl+zmFhzUy~ce zY-95Ca*{n^bN|eH0^@Pnvim;Ekc@H)o*PSL8___T8XA7 zQ%uu@Ax2yr2%k3eEtt$gIVL+Wrf#r>hjc46UF)X(Q-@g3|m&@7ZbJ-EQ z)6^kioD-(=h_7Ft@W1{0UkJ~<={H$$Tdw$deZ{)1P?PSOno`1fJOKc1*Mc|<3Ex5j2k#k1GfYUr+ zJfAR4GsNY&ml-&nUhs6zc>VQ?pA-A}Zl%>lx*M~2U62_WnWzZ4`aI{N!hpKaC`%PU zMnJ(eyhHy`3@IUwWKpZLF6z?a#=x}&pe@|7Z7QMl%=CcKJd5kHE7i8aaFnRIp#=!6 zIG|}n7GgpTf=c=o%}j`yp#%|1iN*TD;%z{=VV1yyE?qSu>p( zu#JOwMmzc9!}_==)fr&6dK%*hRYR7I_s@Va0bicj?{^*q^E~7E<%DnFzT)NOgmD}o zQ4wRroD!n3#-x-2Nqqf$8kv;}u^SuYoRQrfyaCNAO?>@inCBBB2;7G;VV);gF_dyf zt* z4J!%+8|oa~h$>+i&X~s;+m^AO3IX4;0bn0#8VL9`Ca;-Z397cOBIgww)Fnv48UNao zwY8FQ4Ka|XZIV1+fXQULL?3~R=gfaile-`nj?L&`ZyE;-DRvMnM)Y9STqf#fNzLG( zgI((z=TTk*%h*(*Ib#U}7g}%gvuzncxCj%NjPyi`1dii0Ak6|qj)|>QY^!2jD%Pc7 zSt^#rkXJI|rU1MqeVQkH`SJzd{_%ou|9HXE%L&62XwDW45VjiF%8F7qRIM1xfMJSU z2dj2tp=DW6wmh%^jrWhay-HSmk-21#zx!rtJ_u&0=?#l)J{4itTDO3di9s~R0? z1?X*~nzvPG0L$sD9!xYAs3{i;dTkgPc@j9Hp~b}xD44Ehzv=+(fdpBx(CUb-u@kJX zhA2XGDS1?cK?zv=2;Qo#u}Bo%2=4o@0I=rJU46||4={Z5mX;?CGz0PeFF_JwFw_Q! zM0!}q))8cvaTiqXVC612It0*XT1d)j+03$kZ{^Ys%tI04Q{(by?{~kMz^G7z! zgZ;x?_zWCskF{8;77y%rd(Tno`uOu>a)a*g?sd>W-^1(gnfJ=NWbEq$&{*I7Xn^=A zkLLJb2EQ3z9a&+&6a766klX!9b;d6tL4!cleL-5HuP29&Oz4rlZ`uKCX=y4XAC4W6 zwFHoKrCStV;|_0gsExMM_h)8?X!dX&A0E%$q3YdXwv4I;CWf#D`oF}$7$EZB;$~yJ z%dsmh-Q9S<|My8mCaitUKAhiu62$h`KCDxRJLTi1vHADlm(O+wz76spZ-h0K)8Sk` zs1Q6MO&-B({KfCQP${CKh#H{He<-lTOq#(R98)y1rU7FAZ%*XZS!5<0xP}cFB5~i8 z2E>#ggJB#;Y+j1Bm5Oy+5xi|>o9avyXO4ra2-=i3JFA_hiRMlrunh>n{->|6Z+-)~ z(2hDnOMxID#(_1Yr9zWu-E&1*3*Pme^`=W^mS2HVzCgT|lmUof97bF&hT+846JZ3# zQ^NSf4Il-Yz7%n{WM@*UGo1-zuL%@^%RL7SLuOVqyZv=yR6flU#`BCX=O+T6r-bM8 z1@kZ>iq|4qMbVqH;q1|ACXn!id0_2ubwagd!4Tag)n(SxbjI@q`1WnV^;^atfBe9Y zpTF>ay<%Ny{**WNc`2#cu{W~@&**hKb?#O@OUc>E_C95Uu6n;vhR5iNM|Edc6K1Rg z;KmqQ=BGH*%Ahw`ffe&Ud(zK=ZD7b$4{6v3=rAyAwq@kJq4nL%o8tNgQ~|zzdBVT{ z`#SM0A@cCBqJ{kxQ;kY6WQLUCpCMXG?QJ^Zp@$nwp<{R0b3|Jw}k8qU`i3wX~Ihc&gYpj<2m7Uns9y^G0!8WX}~;B zIA2Dj6kxKsi@9MK1!)uvDnJ+z8`)wBpGqwycVky-(Ew@+MHts2h7+k0aff zV@wFf+OlyR@%$WcI(fpSJ2MXe3?WH(6DG^aL`U^St5zZTCp8+tQZ zpae>(VzCXI%M63Wo*8ZiP8K}*BZ81b1Bc6^@i#-zb^02z_wJ-f>mdr_I}j+<}TgDM_l?WcTtakHNOr% zn`W!O#A`9F)j=}=Xy$Hw5zV?J8Uv$J`}klIrUfQmk`UU6;szK)tCdm@s9K9K-81Ik z{ZZq4ss;!0!KKxEUw1vqXSK;$kK^rQkbT$6=;1Im_;!sWdwV>(B-sD^@pC@Z0RN5J z-@hwy{;wQ==k*;-)V3%8^=G!g^YL@UnGrQmMFsAkrB;-}vZ1OGp#lZG7pekwDo`Y? zh?=0GIX){?TdiH_V-)bY>HrQ9?`K|6<{8sCq7EbKP`e{A`laoR&wT*ypjGK(P?dXa ztND+rZZPC{(w%*q>0gL~1eO4_a;RRnuXP8S?beCm$jUeM2gI3Sb5PU94R-L>KEnLN zT4~H9sA#Y2?S_uQ{(dVN+^gO@7~g#Yn8kdX+K(G5g zju9RjWYF zG{+4Dz#%Yc+gkj@*viwQw}g`3;o|sNZBN?)e%rI!&)fO5d$I3rM+W!qTpO+CmW-37fSC31q`*{-_#6-0CYKs zs^WIL0x&+{FnA3R7reG%w?gI`0xY;2ZdT;&Mz+%os)BW4YaVO_KsqOHR1n!rYV}&_D*TWI3|=_@&0o1y2Xlo4G>9~#tWXFo^W|O zG^!Y%hNNyJb%HruixCW#Z{W=qZt{T(RS9IFa(4DCQ({g4Ibs?o?{7*;A}#cTv#%9FU3LkYbIs=g(;R6l z6awN9kcNbDWNm$j0Hi|ehE-|2L>J!;IlH`c%h;9-kquVq_DPrLj9TIIK(Q_xYBpFk z2Xh4)S<5_*WKs!$Bgc437~<>>eFI9ZsCn}mGk0O$O0OS3vH%1yKK97h0TK`rd;KOi zor*3M>h7fe-k@%j5d%^f5E>geu#PQ+#0{vj-f>+Pt{tVKSlxY9gguaX4m3I{wIbJi zCxLG4aLd?6@Bc`L8U|btX7&L}yb#PCTBToiDGK!@(ONcKuk4+@+_JOdKrL?mb--n+ z^gg&=ulW95a9dt6|42ApMogyxDe*c&0wftojI#y_Vb3fV?`2*#{++jqoDEt8qMOII z#|@o;i19CjA9eMBszI}%q9WG4<&7Y?&lm3rWcPj`TeH8eXPym65)jhR_SidShCTVR zgMn5L4o^{mp8)y)LN@L2{k6j|%kdVnmv{q(; zU^{5&vhrFLc?)#zF3#Q?qg)0JO<5$KgydS?_5t+`|M7T~Et^NaN8tO|Cm29?(&T;r z2!4+N*Bz7go8bNbEu;Hq$6tNsk=a41_4~gFQx1CQPhrZU7QhdA=)I1`4!gCyU4~q{>J;cjg+|R*-?iQ4) zEBuC15EIKG+T01v!dVzAgvjw|9bg;iTCAw*PON^fLcf=X`zcM_dY{ng_v!#rb`Z?* z+E~C=_j?3?$MJW({ypa z!@Fw}Iz_kl@&51k$;8!&=E+ZiCo=c*4-y*h>`8}Dp2Nd^mxt?U5e3)(Hpgi0W-wsm ze2Fn4rr6s&G700g*3RyWCooj^@z~~A`|iiFdAuk0j4%%O=E&CL0EGA79~u5O9{P34 zVGdZ6rc+|x*0XjW_vh13?rx5Wvw zal0)vTJ~PUlt~YWL&7wV7%&{-(~3EdSho>*+q~_pbR|bqyrvo`bx$yZ&>D;MngG6 zYeHQ&Xbof3T3eAJw)`c$5w}R{2inm_{?{9B-dn4F~vEF8kv&(>HN{Xw| zvD01VvTpl^=jZ8o10ev@42V>WQ9yRMx$4?3y^RMGAwf?>0Dy`hq||?H0`KE&eOibJ z(lDVl@CJZdGXyu}m4-J(vu9Z%!Z>0G!vhd-GqgfE$T-hlD?XtVMgCVo-ZE6!(>A35 zHP(L9Wig&iE5`Nr>Pa#>^G6%*Vr zfx#3PTQ1V338ujrYG*A}S=$DstR^ME|DMx`h(NY|<1>fHbG1@N(~Pg$_Q~vag_eS> zirc#3{ryHMa@9TtM5t;(a+ku&nO952mRDR?ph`f&01YFmjfjI#2Au?P2nfjoQxoT9={VMwvK#?Ikjb(Mx@OYg${9$Z%W#YlA+?%pN_|V&7<)qz!hjf9(@N)BmTIKL zzIs^|TKSws;-1A-!@>Q9fk)pwo0${nm|t6+l;7XBf!~q72KE3JHzI-ex|W_;phD8$ z*n+S2y(Ux$7=RYwX+(F`^-nAzdjD@)1SQlcs_dkd~=4WMTznm z{QdpmxdgOv)=YP_RA}^CN;EKq`x?yS{1&r{v5Pq)AVPgU(Jc4i`hNuTX1(@&zo+{>kv7+Q&rz;Fyw^VN zAMW;krMz?z_TTN#?+7jqv8uE$Z*T43dH?@=R;_(+1C*ZhxqG(vfLMKu?8y)5p8?<)`NA@T!~GF9?z-Zm^wW~7ubP7}s?#yE|L-Uf~}#0k?lVxDFvlrnNX)_NC~gZ=ZL|HkXD zR{+1@dzDL&6)`ZIA0!}-11C$~d>}U|L%taJ?6ayU8+!;xyJ8rC&52EjB$&m`^U5N3v= zg=SNkf#5K+W^o)@|2$2TXKS-FHG3vkjneT7^dkSCKYr2OuDJ^fYr)ssl}0!L7zXRc zLaf7OP|}Qs)^$ax3x?r}WgT(Zp73D}F6kTyHnLuQYL!R&zWg4C9D#WXi2A3-Gmb4q9{hNn0wMrAyRtwJEjN?$w>-s&H!0+NfBu<g3@K9bqo#;z zh}Do1P08qR*!p}bWF+n_R{DC`Hkz0MrfIS&C+F z3AJZkV+?>fxD5fZD#23WdI2$iMlR_^dyZslXrR^{=qtoaB0>+K1mhT>DIgAllmp7f zwUut)tvMr7>gB4v>x+;>MVU6rj-%4cv3u?Q&Tb zBLFwiG6#_0{jtM;-}SaNbk?g$D32}Q`n`$)sBHJu3>Aa!$w{j;T!De|I{NawJwxE{fz=OSuwgkLgN+RV;2EwE*WI^?k2CGBGox~;)Pkx3wX){l#Gv51`gry2n$#4q3^kTPgg^ijq)GW(B8+YH zLi9KZXx@K*9tpubF1ceBD@tjAtdbduf+&XgNw01}rK%$I$eVa#uQPPg!ELWAY^-5Rg!OOT|LgeUJFqN*V@hXV$I#u;`)R{)tA>Ce?O_SFEu;KgaeceOE(4}%q!w6!;#r9h6Lb)0U9hF>3~xr= z47ckI>sp*W^NAbT{$>sg$WDV`9D&OOTrLqWFEh?h5kY|4?HxbtRZ#Dse*Mw!6k}8GEJ6-i1{>Qnn%2ReZlEOQ?TW>;C8#=dR?(B zD{5}Ru(zpEpk&q`ZX1c@n0RhcKqfi@^94B1EIglv5z~0WFb-h576GCIjfFsSSrXn} zZ}@q7rPS7eOJg~jq_%2>1cJJ893co$tqAglsvF*y65OG@)#xWr!!I%<|21o!I zvE14}WN0nExftdXCE4Y;526s8xPPG>}k{G2c$$BeoL07ZF6S8;&tz8d(FLl3*N@yKx8PP4WJIBLlx~&aQj* zv?T)&U?4CgD=ZA!1jw~w%Ufr$n=wobkxtNqV44$R3@|OwLS}VU<6xFncN`!p9YpNG z1+$3P!ge{RzNra)0-i3k(MDXkT`hVrEdh%l2;WKwYMK=$L`ph5QYIF2>|=wmQt}U3)W>tDVs|i z1!@JQQr_Go#Y`YjIisc!R8M+EXXm4{=MiZL&;ckZAa91U1!NSMmTqLz0?(Ed+NIbI zJPl~l&Ekx8Eb0b+EF-AJdr?_1V3-`z-l*585?6zURoe{1td_*Ux0A_SgrIyW~i#>pp&G zuWxOPvGGJ(3lh#XL5hMQ1;hx1$g&5Bp(>bgt*IwF_HhJf>3ys>vp-?7h_aW5YeDm2 z@BmlAbXpQwKBxQVxIdG}p~ay7=rp^7g5&o!fYLzX?$jPT91|$uo>+IfbpCG@H)zFVg#f2hmX@Xrg=^demtAh6HExKpOwCAIi}!S;IN4hW5j&4AtfNMvC`Tk11jFt~N2nUP~Nf zL<+GxxrZ2$hBzWgf~X*`WM*QDfGSKY-bCr(S?Si4`?gtgowYhQTwc z>cGOFr2-o0cpMDF8F(6imzNj(>z^0Ayu9E%3C3Z-G_dw@T{6D^_|e0@bdD4 z%d;Dq*p00%wkCB{0+U=(m2HEVIdjL*q%{7TBgQdc=ry_{Aan<=wLr5ESdUHBTl8rL z%F3+vH~>=sh5<+e|DG=co}Zp^ewlGTpK*FRVH^fz+mQ2yt*)q5yA;~q-+Db+iU~tv z;d&a~)GQIS#}qM6Bc?gxa+&dbx!}u}XZ-x}it}Z{fBwfSZr2-zWRS2Tmn+s4NI?*y zVK7%B7z0k2VOdu!H=4MK(Is3Wi}E#QXaY(!tain%W{g=dYypxCxvt3NhAm%Fb%g{& z8Ujl7zNp&J8L;KxeF<3I?d6T18d|RMz^7 zIso(+rG*+vJ#! z(_C2lt%{tB%Q8<6a7UyxfE*LqfA$t;%}WZD`^GTR45J9n=QF;1c|mnHa@#g6>*8hv zJeWmxCuUR1a)Y>xw?IrN`>Tc&6-W^pfvOwUjlE_Y(*QNp%DSYO1k*GC!d5jov$?$l zAh@}iYC%!Tiz!J|AQ-|B5mUm`(-UG!-OvL7a#?Y`zTxft4Y^VsFvS5+&klJUm7Tn%9Y*Jx$L)lpS8A4-5xroqssOze2jc*r~(ou-_fkPc?e*WuXYaUx_kBKkas(1c38UicVyQudT;jF%&7w>ChyE(!8^(X_*4x}Dxf7`wIENJTI4t)6C zBXfLYf2Doz-vqyZ_xKpd|0ZyHc-im3!-t>~A21)9jF02KC3G6g{hQB4lk9q=XS*3) zV?8At0VxgTsK7a1od>0Tet9_Q_c};36LcWhU2;9ygN$kgs;ghC&mn0>TfFEPT>9vx z3CGr0_iPOg$*xu#|51Ld%>WB%Rsy~bG{AUJL>wMrOE&RY+yhc`X||v#dk88SaLaBO z>VOA=UPs(hB)`|CO0i2E{t`=2$4H^nApB$EZvP$t526kGIM&)T z^)`Wec<Bsl)xZQ3v-3SpenZJnO=K9WnDgOFNiR2IvQ$*G1HMh*vrlCo32b@kL-Biu6 zWy7`+G$-2qqV;(ihY>Z6C?z9Y|A3+5nt`PPQh;%+h%rDtBU~)IPlP+YDKmXc^f|-h ztvH4V%%=fgpGW-rzx@OM$N%^@{@Z{1H!d^XU9Hlsw=9Os(+LTz`Tf59M5&5jzkr`V z*_P)t1LtpsX@=J!0@Fl>uCZFBu;zGM`JR>?olaz)&46hFE>CQMvn)5%n(=-!Ow)vz z=(H9<#xI=*XjLpLfleG~U_@|RkaeZob;-DXzoNMO8|H>gtGX0=@J8MhK@DSKtQKbv z#toQf;CT+1PZP$00B<-YJUu^QJh^jli2R%qU0z=Lz{@4$_IAVVW@w6w6!^KPr^Lj_ z?1miUfLW_E^dp|1Cyeue^W}t>FK7JoAMg0}>lJw=D#!f-NR*s#!1A|*E_t9>EM z>x!+pq{oO-BW9hbRzQW=hHZOuAWQe2VHnxl5yG}TB8bu0KwZ6#M470_>IwicBm=S( z??W50TE_c(0Zb_QzuvICXOvPg>4+!^QiV?JMf;{wtMw9q%#srXsjQpz1xGx^nj$3t zlw+*;-p0YPYn5ZnfzjJU8Cxn|VD7F`6gL^Z>Zx;ld(NFXe5b!p&Zjg$2` zb-iBkB)S%+ z1c?R<+^$M3(5)aSng0+&Pn@akY#PB!L$+gs7L?9bk}Zm15r}!Mcd4j)!a;_q001BWNklkv&TDk1_9 z;c~$p)V4rWq=BQrL__ls2mz&?XqQC0oZp%5zhsJz5@`7d9v`2_pB+ba#S#2|CVT!^ z|NA*Rb(C8F6|?%;@n3n*hieoDTc5JPzxl3XK)HYB4)EG_GVo%OaTp>@hYqH30I$u@ zLx2M#%wSTLtSaE3gcF1bhT0T9p|he~yI4|Ei+Qa$=R{N2q(pWEN29<<)2$f2pC?)n z>gQobX}wcwO!8|FblV-5!u3~4?A!Xa;Dn_Jy-b$3~ndw{`Z zTRhNl2Wvl$z^i}9r{lfiSO>g+c1wahtYIMg)#3-P!G+Af@A;hDO;yrrLGP0uM}@#6 zFg_lijrHz`thIw&CN_6ZnfANmUfAX?-@AigGbea_sc4dL*1Lv2-aAX`;4DT5Y3=OW znhlO?#&>!Lg!ezVPtdib+Jg~Vi?dt8rvty1Ao7H2A79;Y!W_JzD+8RH?qgJ8-9yCu zZwM2w$9sRDWRT97wj_wOM5dP_?ckR;lpvVzZ>)c7xyAp+-S@z0bMa^0+W^}BtogZz zWa#1jZOz_UgU~hFpCIHLz`MPh?o628ys7?Vnq7>{X0r2IA6|4Lvj$QD0+2mEI(LrUni#HTT_MNI-qE!f^R{QU6?k_cF3jC*ir zH2x7|59Mjh*fN>(#ToRh1*N=W*3({N9wL@yLyT9L6}l@ABffln#^rp*x7!o0uNiM| zZ+L&(Q1XIhGgRA9Zws@nc)Pvf z*Xu7zEwi${Ph}(SFr1NwfxypuD{E^><@Fmy1Ztr(UnN(pH#q2IVnRI0)9SOQI3uM2 zX&hMpohrgA2-UEx6(zeXG1wNPWJ7CrlygB|IWNjmv27We2?zv&6b#XOk9w0F21K&6 z`e~%W+B}cG_;RjWB~u+{0)ly9-uh449RQXXFpL8k;h1`2?Q~`j>FBk>S_<1=ZA=6}&|4^l z6d-k%-*4sMCg`<20WNI{fg4=~Zp(so{SW--fBpdo0es6KvYxM^S^-=o&=Mpflzx|* zVbYk@{f`AB!yE|0V+u$Ky?&a#iWxLjt9~y8RoyY!!B+JCpb(%UqU4Be1w=El05>Tf zL?@&)U>p)coG}gwry1DJZ0{CiKvluEy<^>IxE2yH&51H1p_@H>zbEgH+~jQVh`~^^ z;SoQn8LUvYoq}@w1wI#%0E>WDLl7poN-eAbE==C+Ac+C|=)u1PI*gA)!aPOxVT{f) z*0z>Wa;}BJa%*?Q$W0t)G(N2bQD~{;zPYxrSi&*mPRXZf3shRXAv?3$f&y{2MZJtA zG*{H>wbx|Pk8aQa+;!Uxb%gs4TYC9k+L#sNpI~ISYh!&)_G^6z=39`o2iAw*Jp^*c zfbOqA@FV!;2axe>?!edSF4*O z1|x%MYQ6KrC-@tHtKQHOJzP5>=0MhNB&H7;u9mdCFnB3VmgG*VD3?9ErJUJi-pw&KeH+8ZO zG$;v=2awty(k{{T$$K2<(b!qz(RhpN>HeG_pZnvnGgau4@Y+;zMyTbAVzgE>O&%Uv zshF9YYu;-v{-)vi^8x>2VmM_GB_ z*Xss@+xw1YSN)HVJ;=v3lc#8Rv+?rk3I z&)XrtUkbm6^P}DW`)AAq$1!2_U{EHlZrZ==&Od_xek>`!TRY|c`*0XX?fEIJo0+7z1jg6n{n z1q^XSJO|9D8K^Wj+qOz@?7^KVO;S>bUX-4os#w>}7cxb%h$soC6J4hPvV7ONA(sVO zHq?5exj=}VGLa@(=ktJJH~~R$KF@gh#|h6bCk&^AI1qqs+lIw!kxL~ITi+Mfs>*;N zjR>P6rUB#NuED;bMehkqc{*#Vd7W;5Z!UYOloE#k2a_AhDWgmU^L)l>NSM;tlMY2E zJn03SvYwez)z%7$HP)=@-mtBPyt!;Wj+DK7k_ z$K5OpmpQAI{|y7P1?zy+X{B6bIY(8OWe%ciV>_RL?Tf9$^{5jXrNgNH0e$>xcZ@a6C6R6 z9+Fr<^yHyBpyfR|g3sggIkI~}+O@V?-v$6aKCcekbytS8+Re7V_3t_`OnbmjiEop} z-p|SV^XlJuU>xs%hTan#*uhS1wbs651Z`tQxPSM=*`wpb?~gqex1Inv&b6+{u={y_ z{Qdp4h5LJ>=5wK`VBp}EY9Yfey_c}B5&Pfp@2?%Owl%#c4Fh1<8So~(2C$c)1a!69 z4g#C+fOhcvXy^yOepLm6&?bZf7%cs<{aJTI$3xB{BOpeJHve}8usZ%K)sOxj^K z%-n=hQ2}}oRnD_o3X;`|Vt}N8TG{`1SyoiNxx{&6CjLZ|D@fSgY}Cl`J zu7C|dT?@9+@cw$m|3pU3ir1F`>$2kZwxO!Q>V)^VH~jd|Us$dyG*df%IV(=HVjRvm zolh8@$s5je98***%YxqMJ#dl_1A)La2_$7K%Nt6)AvRY$jVPreNx!pZbf2Q9kyDAwZ-c zrG(Szgr}zqo}Zs_Ik@JSPw<})X zUh(rSVVWm|F=0MUIGtvk&L^Y*vdk|NYOT2addKUpH>{PCoJ|$Waz)+(#%W^Rvdez8 zPB1epwPINe*Y^#tVS}42_QgVktm{1I{`{sfV>>HMBc7iJjN^o9nz<+k&WT(%EVmne z{rZLX_Zx1v1$o=>_FC}km*IA!`)-N=P6gwT5XXoi4cq`!0VRv7Q7}|M25*0K8hP)> z(Gv(PM`#8n%&4M+6SlZ2+??Eoo+d8MWU1i&N^`qf6)AFYiV4UiW6K38El6@j43X~1 zs@Tfrt)_gjbXibLypA*`y7{Hi`(8&>(2#0fv$q8@RHOM>-k3NLiAYf~Br*VMg6eHG z+9FH`Qv*^&kUdxvz~|He^~&o2ASoByE>VKZcB;ZOct2y8$Vp>&+0S=h+;{npSw(fn ze1$ z<%E>D$xq`6^L)aSD8A|!Eb9%o+dJ0nhKkLl(A@Y{(X;p=@EWuzO6DKc05L@pwt7Gi z1Q`J3eQgfiJk`?cg~_72yjMNQ(&i$}>~jYWx&wYynt0_RFb}M)1s|S3!NB~qiF%)2 zJ>>NZOqev2Ae45tz*wZ$GVQ%bee+e`3u&@+-_r$NUI{mJ=iceb8Gi%KiI;gf1e3NTTgj{s{6xhLq7qMp8>)9K>9u;-`z+*K_l%( zp@F`SuaV!K2->~;Gqn3T^LsSS+P~wI&zC*W`t0XSP>2W5_pHwS`F{k#?P$QY(fJYt ztu|czS(=xDgy7*+B`Ah5xg0%V(%7~ZkRQ!v+{VglzZ>AA`5|Sf+8JT-7GkY|m8!uC z*OC+?YGr9#8it+u5g>$uRH!)9G$5FH?`^Irt(>Qk8+I^H-D{kg4BC@Xdl`e@&;#h* zK}r)}HxSww%$93t_kVw008H5qtq1=P05&*#>&n7eMp{E_37C_$IfuykD+${3^Mld=qigtBJy$k?claO1N7@U9v_kc55If- zOf#cDh3}6h1cbr+rnh^wzi($W0fQCBolV`)Iub~Xy}YIR_)+ZV#PzfR{m<+E|0+q= z?m^pP_WKhKe;=-0IBLcPt z(L^Jscc5$mQ#xZ920YD_871-B!@&dem=Lh*&Y3}CPs(WyNUbeStT51OyPE8+I*|M^ z@V*RbVjwLMwXjca$s1xcX|IFPzwh}!i-WX8Cf@E zA+QiPEn|<{(`m-(a>nx$TkTX7TvNnWH>}$V$O=_MDU?r()5lSo=~YEY0YOHL!^ln6 zDCsn??)rQ_v(9)N_j?)4>tM5+D(o4uoHGoHVPHQ_Q$>nEhz3DH>qVMIL8@frmIYWh z;MZFL-E}Gbefcus+dseJ>&pq#Gaa~7N+{1?@sEG4*i?{n#`TtQy)CHL5)JGrrV31_ z3F&==#E7D=xaCUYHUj}W;}f#K3a?>h58Y*E@7QW|HoTmHVVHUVLzxeyr^7H~8Usut z^aSKwQSy}=y940aU8m>MjA^79R|5&POt>ifpIHJ~-60|l?4g?y-9m>nV2q=?Q;I7M z8pBI)o7dInDLi2mK~m2dHX9&DRyPEeC9GCa$_+6r2r{?}pFpDYHUJFrz4cO}?0y^v z4AaET(VhDmGt$^%Q`XRxyph4E)i>5AcMuNV)ou z3_}8Ha6k%$*ubQq1*9~2UG@l5xYPbfQ#eT&6Akm`dBQLzgh+Y)mKUsf!EL!>%{Sz- zqSh5=l?hHz-q!I?!x-lMvnv^Dt=0iwh?M54c)PRaid?xbsO{I^lMq7ViYU?VXYkEc zJK!(PtvYXRKIfY{T5nyh*`;U?Oj;6x_u7Eo5<`F(5QYK65HY0KgLP|QLK$$>B5vpw z-04%gkqXD;=RtyqaP4TBb7#-!^6W_h2&{tO)&L}fB=oUHgG6U`TuT4&Eokz@9<+bb zGUfC0`~M~(J|1_>v04w1K4X-BcMgBntJh!g```TKd+*Qnx6E%(PVDAwf9Gg{wBeXE z;3sim62PRdQCb}Y6&fIw&;mU{Efpz7m`nBcFA2Tot1B`-T9fSnOATfL78|&UT^3ub zd4hyx6D4>OQt4|_wZJeSw2~7KsI@Ap*Q|$-AT6oVzWreS1c2%U0U+k>lI)Xv%DKv9 z&|bT|2g^tJ@Mj?Bp8b5dD<78R4*Y<<6#J0WXcAGu{n*_>`{DBsKvY^`s=qeIh#D2~ zAoC?hL_&jW6VEb6*%NAA@$qmiX4q8`vNQW1&gDLFb99%!yN<`}!pFIK1j+6Dn+k$I zy9dy1|K`dUfRI@CUaJE~<+>=wL`5JXW&d-&pYG&6n?v$dQcaMYQ{^$J9 z_V3-4?0D5?A7%TG$L|yjXvv1d2ijp1?YTPN&OXN`VSL9rtW;N^V9V<`v2 zM@ISxem^KHdJD8R7WSBXSDozh?fCmo*UbjFv6JZSb=5thn534w_`weAL|Z1BcLeot zTsK>CO$>btpgI9QE*LKuFVI1}Csjld6o+Sj&(Np&bV6*vQv^@v6HFChWCqK;4{z3t z*3+;xa+aLAU~BD}v~igHw(W?$Wo#Po;+-LDT&+T+c5{Qt23m|;M3RJR6_n8kpb8r6 z0Aq;W^GW1qsq)9ju02isM?C$Be zXXgHIZnl0;+pdzhV9D=CWP+5ce7a|zPv`itYY|0)AdnFm841;Z8i1&3K^L3OQ!Z`| zq=gG+69<9}_EZ(E*52c>)`o4}@czEwAR)1$)AzmyH7R5MV} zULP7HvgUd)TY2S%+l)LB1HLfSuzU;`kQr%#|4BeO~T&}a3P6Y&5ZMK2ZT?_AvhQvjBBEt}(>P!lS);7rS|henH<*urIs3I?K;AR*zCm^GKKUiwDdw4wzDJrV+fk~NQkYqf|#W2E6*4WNhU5FIo9*hWRV#>Ot-A&fDJ$ zoIvnzUT1Kmr|*3N{e2x^V0mOYv@Z{S-8@$7trMTF7?f?=SK1!#k7u{~jh08EN;P+h zFaP$e7w>h*0kzPZAvJn^gb*+ehgU;WMLcDjAXFQ~5UKn)Tv?8Q*#Vw{q{#7Z3sOM> z=rs0FuU|X@R}W&3fZmUPWPBc)${uHeUgmJF=Z*20JEjCW0_xA;<~-16GsPpbB{aK) zK&1A}(_`x?#?*am^vHVk7BzM)$7enRyd$7jZFqiOdMpwjpKbrW7(dT_2Tb%GIRLU} zU^~IoF`UIKemB)?e(gGy$)jl36OEkI5KS^{3M?lkOu8P$0WN3|X!ox=N#dqzexZQH zI|o@Het%B)?qQ5h6Oj9BHF+@^&4;#W_Bl2Kp(lss$9oSOKi)&1Scj{4wdz&eQ8_!t%)c`*j3sb>+!N0#vRi zAsn)Q;4qvMb+V(`z0{N1>UcfQXEh9Rx{vB5SZd&#^Ue6^2f*D0{OXwa@tIC*MV^H9|SjWWRqo_%NBPE_P6Tq}|W562% zwr#`h*A4IQin1v_J_v*@ti|P0fx3{Po#`g*+f5T|S<{q@{b1*iB7#N?A#wP90k8=Y zkSv&?c~i{;H>4bqOYWf8Z;S)a)-t?5sR$5;Z~%!Sy`i)lg{T>!&{;WS-<84IhVIN< zYD0=NB4Ul`S*F68;bmdlnp`q&_ZvQLcjR0xxMxO3l?G*Mi^VjJh>@A(aWvOpa|mZ! zq=@ly!S(e8m+OonC6rdM?Hlr)GT&U-bM@SAfLS41jJ$P&-RBk?>tVG3jXgBy%Y^Cj zR~k6I%m^`HtE>}rA|b?zychi3-|_Kr$CPFQg3F9)o{*-5@p3iOGTx7U->@p{dWST0 zRf9G~N!7AVl&uVw)kI*;yNS^tLSR$N4cofnBisqhqP2;NW3T@ZIixVdFd>Ek^Lzx? zt;WE?VIwWpL$A%pd;{ZrN zX$7_HY@JjqnidQ2XtKd)ll8hWRMbqf2@?0sTK=?yA#O)~7dKQ7#*g6Ffxsb~qNLw9 zTMsm~N;i$Fq6koy*EK!4tp+ok@hpo~TDOc4g#D;P1#)GZJp{xSd+i?0s>GgCLC^uQ znp<|JJd+N#5v`O1%y=Cd*&DbVOhIC=dfAMvYy=k8NeS|}280M8q6D_Lspwx({`9@p25;5a=?{A#;vG*u6Bhc$D;2+pwiW6R6X6Z=P?4D5YT=M z`_%q7AB{7}eH^zlL1;t8t`n9CE+t_YMx?}8FI3Bj0#{N(S z{3)4vdIf8j7Az^|nO!GJL>T8h?)6@a3$`6J((7S;u<;6gO#R{Hc)Dc%eBYet_8qoa zjG!mK05`~M`22h(5y3RiczJp009Zs&g_$|Z@v0f;0J&Ag*iVvehXST)!pr4~ z>&pwKX&``!mPrOv_WQEopa1;P`&2Ibj!kzo9iRgsjTw<)zF-^&gg_^oW#3RrM$538 z3zG;4CvLRtWt@S_^@5kb5E#Ulf_a`01F+r~{QT!H{No@0z(4-y4gdL%9Y6k|_;?3U z$q?jNu*nWI!8j@gGfb&aw5_29>(zH*P)#hH5Suj+k3Ok9$Q{hwhnaDdnS{a}_Q105 zZ_74W!Vb^;svO`|w4t>fwE^3<^@mA?CNx24UL|10aIjWBbySl?Tkk6cYjlK}`+eVO zO4Wk_E~0zc@qS-$zpdE!j9el_k#wx_mgK!SjZ z<|tp1xV&?3fxEj1t< zlWCeT&jjeq&{b>ib6V)5Nnlgx^+l9YQa0EMvy8140Ksa339<-QEnAzbnFm>b6ukWu zGv?DcVoU>42f}nPk1=74gURzph$Lu35B^HYSk^n%^+rJ0oTxH@UMgxXs9DUZ-gnv4 za(i-!Rwb!a3aLqcO%p2*bjU^@nKA{H9_zYMl0Gzyu_47qQ#vteS)qYll^wMOQuRy7|Ag@DfB(2;~=9VlZ|zdMh&+iL^eIkN>jU*%@s3?wIO z*%hK^i!IRg@z6&G++Cp20|kFMmFqvVAm0GJ6INdZhM%)Y2e1YFS=2AV>Yo{0ef6`R zIeR{b-`4&b(I)=YW7hXy$)68ka58InI-lQx;7$yD`4Rqe1@zHB_!0CrJe;Bjy6VPJ zB(J@Wo#hLMAt2vk^|Osi2LHY*TKKgG-_3w~Gi96_Xch~CJ@ecEeI#pIYwQy)^hNMz zxmuR2wSrnneny|Gr=>24FtZAD2kah*S6{#FcfCH=uDy@niF~jDliL?Com_Pn}^8P%79lzCIGbiWl?iuvd=Czgf z86hABz>OdK7~3=9+1mC*EF9-`nAV0T0NdKJkUWCX&(CKw65uFnc&v^8QuzQ^vo&a7 z{NcULp}xMOgSEr_s@Ymh>7t0hO~QsmJP_RF(@qvWkJTf8BTqj&uFr|>eUBK1Oyl5_nV7qu zyNbZoR*Wg?7d?ibU-EE%4?p?ztod5vF(G;afw)Zjy7^3|ILUp+y{boM7eFURTsh`S zKrdf&lEY9p*Y(pg^GGCcE{U?2_v5+@q@O?kiDkLrc6(ueTpOgd+?lbe4A|qy8ojNQ zZjjR%1UY0GF(q6t7t9x?>eE2&I)oX)yzCf8!R2zn<#NFvKYr1TIgM8Hm!NfkwuEVX z#pOC9#eg;M46ZiIKz3G$%uj9`&oeblDPo!A_gL9G)9c_;g$M&vx-pv09~DU( zViINRHp*+5)r+`ZXIw59 z06<3VwWZAD`Q~8m*maQLn4SuGbLoLQa-xvg0?nfbC9mZGMpL_!j5rNOk>3~^Entt-v7&$ne4jn ztPd{@`<_`#*%W2lkW0q8(ljjvncQfF5KgNQT^czgMV*Oyn!b3hs*hCz@bu;+|*GskkPYje3vZ!vJnVE6{? z5+?zPrX<#GO6dMB4K(1d#5hA5@N&6g8fN5Du&f)FW#uO6t#_0lwdR74jq6!T1Ez7t zI1KzVGC+tSAxJeBM9!Vsjym>vzVf*WUL3)4vggmg z_vfJY8T3B<{zFiCRyjRNv40;7{`;>pNcQ{hj!3GHa$r~%&0U|5AkxqOFyc8YMc`Rw zJj#T{2u1>B>6d=Aq~SQJ7?_9xF}Hqi!Q??a59o@j2x-!#p&me&QV;^&;#&h!V~ZB{ zVTZLNI{~-T7<;LSs$a*c+V(_t>4|I=3(C!g!3UD-Tdfb^>nuqoa5;giiBl=D^A6*^>r*pLH=QrC;ySIm1YXPMj%9N&UGc2(Az3 z^qi&s-MZ_~WB)zqX-v2}^?|ZOoZY;SdFRiN_IdPB8t2!IV?O%)B!;s3d5c3lDI)@) zazGnQZY{pn8eOjFi9Ua&_xE=@!5@9FDRW#+N=6socp;$i8UfF=xKn7Z8GvAkG$$!} z#yn3b)i-mtOJV;~PS)%7g3`Fqr11*C+(K)^zE!LXk2wqx2+CShusGfs@YVnn^x(h& zUAx`UwBX({F3XHDj3~8Wx$Rij6;T2%^965jK&|hn2JEE302yTmlQAv1GP|+sj@lZ^ zyUBYeMM?pe7r|wo5GI!cWrzf1GgtB~1j-0iVBe*i%}7+%GK*py1%LTA9)iW82ID(C$Ib0B%6Z4fo}a>-CP8ml1DoZ>+yfqxDi1 zW@!QeaP45wTG^;Vt+uzeW{a8GL{)Pp&dh2?VdhRkf`k$Cg*|Lr0)vbeQENe78%jB~ zHwXzeRE$wDjaOXbcPuX}){;?b!CINAy}hrT`$M3#f7Z^pg%Ipn2+&qdLVRR*5rpF_ z=s+shhAmg@xguwD04$(+l(v;M@s)C0_Iuv3?-zcSz}g4crdfBB($ny)6d3Slra-h9 zaUzHyA)rmr6etjr7)8wU3;yywAjK=*R;nyYVJ&5d0p47^xU;8Ny;opXbs9&!zP{pm zosfor5EVd$#1*AAGGVb%)9wC1-?K9_ln(tH?DYW}u)!iV4#?Kj$k zFo6@nZrX9+3TWu(A!fGK)ZCxt$a06lGo6QY%;}(NWe8^(^6?^YayQ;y=m-NoPj0wp z;Q7_@&cX9D`2F4M>+|~8uQT}lZDzP5jW0ge36ZZruO6Z|efanPKj8QI^E}hrfv}la z!sc%em2F>$F(7#&}E0V{!aGp`8;T0S7n0jE8~!F)=Z znbG+$JY=0}CE*y#$!I4dmrPQo30f4is3hnSjbu}M4yZ&6K|rkqUk!>D0Mz4NoPmS` z+2D@oJ*#GmJ&u5w=gMyj0;Dzr!32m3aF4Q)5FB!OkJAYN-AVnqnEuo^7>DBUt3Rq| zWyDkIACCEU^p^F{IFtato7<|D@vSrj4ZSD32l!_>1i@6Xd+^#@dV?|Gk|es;PHzh{S3obL!G#eEo`GnoW{WLCv_Sa?o8hQ7}7 zLyxfxwr5c#b|xGES1whHTk;72r`|e}-Y3ywR$FUQ>oVz{nO9p=PV2yVEjSccN8>&R zyPoxS(ArFS67X09{IIS&VD+)+>zVE0;c+d35y!m8=+4t#)8DDVPWH4SXR9AAbYmSxW?GYFjBG7K=6M9t2!Wt(z`pHWH!gNFnYqc>OTnIjY=A1wz~w>{rj#n;z)Twl zo&*A$p$lt$O^Q%*KxrAO72_E3?UnsmuP-D1_P4*`uYZ5T_wV0vePc$k){J#saQk4p zsj9$UHw$X%!rEGcz+81rg3J=xh?4y}SOa{1aC6Ch%Z!P2a4AJh(}c^Fna^BzyuMxV zw(lr817ew6WFDt&1{h)BgDrOyoF`k!l&J(?R2y>1tcQyMp(SQZ0TflTDks*C^-C`0 zVC_;1Bx`QBJHh~5^@=0|Xa!YKwOEdf4^1-`zBM39#N{&K+sg$|pjuF#mF=yT^^SF0 zu@_!n5QS!?qb(X%SoMdGjJ!q-5*Mg`vm?Edb0gpn!GI+qPIH zm(sRr8u9XS#r1_oWpkQPYeUHe-WN_Rz=|;<1q*nr=0jp2_=p5L5!PM^eC~n>#&N>y zOTau#C|WvLEQJPI)fVEu2?jb3YZENnj`040EpM!UPHf@A;29=^KfOX=FAn|kn;20@my?xxMx~P=(a?Jxu z;k?|p+)bz?L|mp3As874j(19Qt*(}xi)n?ML-Z`biD2b@=XFT(U{Me{vEl%i*;2ZH z({wIP11{4Q!!Qz1rV-;XVN5eZ7@$?LZv{Cw6!9QSAwdzMBF2U^G=vnr%-HuLKBJWx zW(U9tBM?RaG?`;l`Ns8EDetdBM{cbvWze}?O2~Y#qRzoh#z^3F5)($*dKc@Rq1T>Ne z3P3|AgFeT6(yx!l0$|t7{==ZeS_O(^Cu*i3W+Kx(HDCret-)$AkIdzBuz4`$45+&c z>r;^Y7)*VB{TcWT=S;~LuTR_uM8*KA-Qi zjPJ|O#}Q;b{H_Y5OVW>k8zQFw-Rgd=g<47hLn6>ggY;g$U1sUWQqP81;0NuQM(w+~ zOLi^jmi}!9v(?^bYlUMmI6$tAEt{Tz6nmHRd8#!4tc=M zPQdH)&GYee5c{uQ3Mg7%$ka?r-2~~p1P3|xCHhFf)|k`1@q60Ku#V$BW>J5mBJdCW z;@Unxv&Z+@!}Q>)z5AwLYmJY(KB6kQz`!MH&WM=Q#NU(lfaZ(4ZhDFru^6(#>2$^!oYO zO+_DW$!S0CAXN^60-wOq(>+x^o~ftbJ(C2VKl7k|>|>tp>#+wvuF3xV9)Q@->FA$) zkT_=vd210NRFo1;xyW&(i53@tT1ogb;lgsK-?daapGO}r#izLmFeW(Kf%<;_I6qob zAox9XV(atRJ^XE8yQ#2-Uk{3j79*y1tKN<+p1?O_;B%~VTosVU$t0oKo$0J?N=z2O zS?|JNjC)s$DCh{v);u&P3V;+S3UUROor@k99tQ0D2CVCfb!qG&S}YjSg@4;R{yBkvP>R@t zVKPIo$M0a$2#s7YV)RWdF}vMs(>!xb_NJ+#v}%=bm3>J+QwTa-h;~e)1yZrYiovKz>o%1+j*))yuMcCykl8cyx-oj?JKk#21DDn z;p6=sxBCsH5D13=j?;zC%$_-em|;?LISeo)AP(G^8pzaX3#_BucdTor+!Z@gx?`Sy zbs+rq^2#<-ayVGhOo;|mN0vNBl2tqZtjmUVU9npk1#5-P*;oUL1cOmW@WAJjl2^*5NBSBB zL2eDYt=L;dxZO}I>%;H&JCEdR>l3cptS|1ZV2G{$3)UF4Z#RHB{?DH+-Uv{ zmF`r0J^(ajyDHr)ir4EjmPCjKz{n42n+3iDf|zWwSevT7qU;rWE-2YpZan~5=po}L36BW!{I?O>U^RLvLvr#-$0x%PgpNA7x0zX>|3E61iqXeB_dr9qqb z4E2{01Tk>)Z%5!1dPe6A_8x)ZbFlkoHNBk6pJm1WFR$mC-+u*m|E**Gi7ob5!1ohi zwKeoXR`^3*s931n{wTA~FQVFDZet{6u9~OlDSfK2jryV2vP6 z`@H|Mg^kqw;Q*3qpV{iUP0D%Q^8nraJEE&`Tv~Y|_k#8?P;ty1RuLQokO%BdDf17d zpa_lYJO!<-L0#F@8W6&hRPhvuhu;$(o`s`A$|R#t^Fi$x{$B@|9x(g;^y@Lu(nIbJ zV7Q+7XZ{&c(&e8bXv~k{{HqV3=yY*x=XY`<7i$NI!tMhhoCp@2)*hQ@Cxff=@t@C< zarPsqZ4HmtUr2&B`<*kX_EjeMGZ;R8PW1tkYt`b8;KpAfj9aYZgDV<*zUEA&UMz+^ z%p58X329J^tw|Q4?=|-41b}&Jj8FU;ZGbw-a>SB!2NoC zlm5=H$j$RT<(xPlNBjE;hOGmFRCqTCV!2@1V1nXtWO-iB#T0+_0T8=P`nV2`)p0K$ zPrsj^5l}c8m%+g6d2V=@h8_+cm+>%;k3jr1Mt)wWA3rSPYHsxopuIfA=U>lQE7I%h z72CE#)ugni0SzHwoFY;h5C#H@hGH2_MJ)wGWX2^0vpLsHsh(s2Ct%&^fLV4ywqBb# z7qm*?+EA=c#4;?lNu^XVfR3m!go9MJiwMRxsIW#N4Uvx4S0JVc3>OA{MG?b}AQ~B1;#f z%l2ZTA%O%%$ptAW9k0v60N<`H4%WtKq={N-in3LcnpQ}tmOaf-TL@JdxDjMu5JSYi z?}#a4jD@CQrO*`0fCj-shU`|?7?|lCf+EF%^2`v-%{m*1s*tuKr;J?bv|GXY)tsqN zSl5-Zo4{j87|w^3J139l2K+^|dniHluB97p*Caeo) z-Bh!dKozLUl2xSu1E=eP9^ueUry@pm93YyJ_0dtZe=grS0$j9fwn0sT(YeNx5kOp^`*QA}K z@v@#;I0m&^s|o`Y4q(oEw$I%joRBrPP21#rrP|(TdxH_=>?=%Js0t;CUg{8nLaVj% zt1$Dm+CPFVXxNGll~PH6ZVx8?(e;^QbJXL1nNfa{G<){87g`b>62*o2?U9pvlYi@dK*dY^Nn9e z5BALfQ=+gZbn?F5r+e5Gq48O5jbw=v_ptV2lq-7{pMaJBwypp@`aA$8pFuv89&85@ zBw^XZdDc5|)fz~uDP3~uuP*)h1N@!`I^G#_RhT*TckS@$l?qh_+tG14Moz0SA0bbN~P# z07*naR8GLRgHMOKdW;K6G0Vc*?|6H+uJRHC$mR>-WBz##>*@18D^ncE`n))@*H1)_ z9;84g7Mh>CTB&O5O4eYCLdN3LNi`Rd5{>Ri+&^Z9`B|sW#nV0XYcyi&G4pNXa#AC7 zp1~DM?QtIUwst2_{OK`rz^licJ%}o?jnPOe`MhQjAoKH6iUFGi35Tnx0@9c^AK0E{ zoF=3gDcRIUM_f?iAQcd$#2He^np;2KZ0&IT0jO21r3N6<*oHzFB#A1T)oY#?f>tYX z766&RB80yARG$Qq&b*g-!rR*$#y4i6WGo0VpzMmA8@6jh(8xZYdp6k_-H`LX6YvcK z#+dqINif8PW|+8NSht%(L2jGY#$R_Xj%@{VO$@Z(3uUVxMu z(#V))Fj@UDn7rO)o!zX31esbBT#14>&>4CdDDidUwY+C+dBc6Zvu3vzG&H0kVVEY2 z(};PPsQ@sC>EN)(01ONmJsSB?R_#5lhkLVliB{s8x|h>-fEIwv^)SguWlOTn-p;mJFm89q0y4`mIXDAbK%v^k6$A(#2%tN@0t~Vx zc;>0J;@#QyfaHb?n5@y z$RW=xwQ4=%D~SjZpaz<)wVHWd&1(1^3<|T)boN%Dngq;b=)wNfj=4P`e|ovOm!2e& zO*{BKzn%f(V}IVq`oR7kJCfz$}V&e=-^jQ~BPj{rzDuxar* zGp%wELQ!ab=%kG*`>zLu*t}x4)YKAI4;z9Yg@zdDEDuo8mWBig(G)6FVu{5Zl<70$ zt*rrO>=wEd`E;*ign;hq2VrHzo1Hq_xp*SMYv^HFZJW2^>&fGoe|0a;Uw6PKhiuq! zbI-Oq$N@byVxvODL0I5{c--I2rQ>xb9gg$=ihnt00p&zM^vvw(8e46hL<*r9k$yRwR-amFM}2*lP-!~_AAimfGQKxbg<0H#z{)W(drld;~pha)0Z z;wJrTa7LfVgvW95c;n%7@i72y*nS1rA2;^__r(Krl}n5AcG%2 zVjN+$!beM`E-P*@C*{!1zWN>>1VIndRZiE=z1Im7#iM%YxbE}5(n*C+FP}3;L^!_k z1Nrmo{Faz$WP5y`&f}JT{Q7~CGjeu@g&$IDgUG?mKxqP$#%QfUl&y^R9c!zIeX}U` zaM7fvm}_zn24pblWE$*2wO}sTE+;jjSfg-&@(7dyMYBb*Fi5rjo_^D#X_HH#E3b|M zZ6n464C9D6dOMcc-ot*TrBZhKbN|T+vj@DszG5&r@xJZ&`Nu!8t}8Q?T+5IGaJ^jc zcA0UVE|AIkuO`|qxLfqWq!BdKR#4U*%dK=a7Eo-;@h`xh>?AQbK#BJwu;+r z!E!G&JQ5(rgyxH!M2OI|W=Ij2%N5_=zGIqZj>+0^zc1KU_N(+-NzZPn)xNIx57vKL zmPl8E;9GLHRb@sGyl$0G1l>Oe)*0Z$|LeB=pFe1c+ z7QG#mwXy1pFUci$!7Ujmr6TVemV3p0%y?OMyuH2R`f|a`%N5f!Vu)lMJuCd{*A4gk zik4a9UMgLN<6z5;EgrcPEcZL!fBoS3H_Bh8@q&52^k?8QjSx{R%Z_zh*k-Bmxh@5` z-S{-85g12co(o=H1XCE0#?+s|5MyuB9zsCb3v27e09}Z^HYWmX)m^?Q!n>LKB_f3f)$%BMaxxQ>0&9<5f)ZBz)izYQrBo9({ z{_9}_Bg-l%MX+x>ZZ}Hly@i1Y-Ka%kmmG_d7_6Bj3sJO~n>K_0WTe_S4LyUH^Nx&W zy>2s!?4Zz~-5oYaLX=?U6@Y{W$<0VGhHl@Yw0}(iw zX&ZNbmb)+iCfIgY(o^u_e>1~-fMGGUM2!m628{-0g=2dJm5;JB4=y}5t*6i67(8bf z%tXuNpgj<4@^69PZ`1`U)S@$yHQJUJa&JZX{ zYu2tO^mWM9VgOJ=K&=ByaU2BO`r60cFnLp6hxZGwJsZt&O(}8gnzw6mGR%R;Ig|EC zuJuURvc1pGrh^p%oD+aJWdME2YoZ7b1W$!%L{Puiw$9*lM))`u-}iV9$Ek{6lY{XS z=sl`HZB6M;(Y4P%mbyi_i}<6j#IZ*7XR{qfXtqpt2mWJxS_j5GbAFohpVolWW8l*8 z5Kg3pXAt%DIXDP8z;q(5A!|DbBO@%l?iXH*tmq)81}1L&Yxw8OJ@Loc*-McTz)bym@73CuENOaSw4ip8xxBB|p~n=e7Ne;2)l;FTQuq zDtoKN!$I0xwH|&E-f!5)%^j#+Y1zD17)QAQ8hTr(PwSvR4{`#)%6-U75xnR5SJ&dB z(fl#?dvzW=Gpu|rV>pu=3Vo2O`zzf(K6;A>5y3F94U6R=Z0tYfat_cE7B^=B&`uIudi^c^4% zUv~tJxL!xhbHlf{3;zE1zvJ~gd+s9bfB>s5*!B&Z1=!;-*`lT>+m3C?Se6CLvSQ!) zP&5Vd$_?>yEvWWB_F-laP>Nt#c5JIniWCszfH5#L)AXS?sb|J6*viUIUsnb|FG5E0~kLXr{F zJR(mOi00NA(OV=8A)-oz*RkY%$8y{8{;pUT0LX|bBc*q|zWy(K|Ne?^Z*Q2V8JBVD z(rRb1VvHCgCAYZ>O0Wlh-|?~DaQoO0oAtVl6JB0kaJ>%LbHV+#;dWcG>` z-!kgP#cl`%drTP8j2M}5_1fDQ6ErY$q#<&V3p9graGT$IHu%>xItQrA&x1&}DktuQ3x;dT(uVIoNz-seaQwHN93=pM(T?}UA zB>@s5f-rC^g}^XsWgkumqQp}s;Q&`^4&V}fLk!2}7!F`4qCK>QQ6Ny(H8-$BK-G$3 z*{B2TJ=f{N+N8PU^BkBY2&m=>5EN}Fuz=Mi&<==BoBr29w(V^XTdyG6wX49)T&%nx z#K+%sBOVV)&yS4n_(d$CQV^ z0X$@S1s;rtW8CBb#9w8WpZgS_Yn-1mZhdS{-waQ|==of~0?SSZJ)SkMlL51CE z2?wtv(LO#tuq-NCm2 zfBU?Bt}{0mV+m+-eqXa=$#L%L?=dn&YtQg{=G;kV)h94zYm1sZy4FK_{JYor+4=3W za9U$|eC^lk^XlPuP7k~9^8vt)d$T#U-7U; zYQHzI7$l&X(V+vpzHj!uL!ON34zk4wTL=AKb9(G|$CaON=#lY-f%fw~ZVzDkxc|Qg z!G3+`?5cM|sI}VhLwAm*9GWGsZuZ&9o5nVhUW3g#Zj)GpUK+k$A7sZtf^d{tPu8Gc z>xs~InfXKQ`a#5aKVUv*hbKp$lL|Opbe2{>XQlnT6pEBH5k9kF11=+_rkB?XrfEc} ztb^S0j(y*ug^ZcNYCDI3QZCq*J2P%pM+sw1VmP*mRvRQ%1Vl)vh{8oQHlYbnYoL}+ z(UdGiuGxAz@|6EBgq@GZFiZr5`2ZQr z0Kp`7E~8`*_cT~&6cgegNKoXR^{x8`1BQTHfN^wt^TCXVXy_CoGtKYs?|?EZxG#*X2yk29v91eB+i8}x7VN8{ZQ!F4Glroe z0!U%v{2wCbIboV7Xc_@g>}^4<1sW5_u>|#XD1@FIB{4@W=eY@k97i@W9 z`ypMSTA;XM7!$Mr+rD5g8KqLHzpopjBt#9E=MfP!5lbmTMrQRd(~Nalz-~-zf0OO~ z&fu}#SMASrtrcNNc>SgrFPVlrLbb*`Pu3TBIDs<;X#2imStxDZw~BqssFi()_d;jl z%#Ju11`Egrwvu{zVL$L;bi*`s@I$xjiZvIkx^d5}idI^$Q>oUbNWo0~vMgBF71!&6 zd7d#%7b*^7I5s*_gh3ExK$O@QM`uY}tJw2`ZCkMK6{QxgE2W^gT|Fp=uB|{#nhamZ zOy20AC!F?sflwM4z1@eRwv4@0?E7ZyEa%NM&KTmzAhSi(%(~#b(PXMw`?C-drg6gM zdd17jjA@F{P_UO9a$8Z6QL&?-p=pH*gUS$3ZnU6uk{fO5^+W*IfYbtN;}#~S;TB=p zM2Z1X0zoh=YaIm5T0FG?wv8~=gcDvO=0|Wc%^|`*HpS1c6Vt9{KoeTOhkfG>*0v!f zpcJb?K0y`_vK!zX9D~(pd)ofo+C+qaRRM&Mdd(9h*LGew+*K8N1j#+z3LO}+?=R

    !xsi9F7cXT9`ukNb4mLn>f)f|_h^B%xL`Eo zi}{;Wf0X{!;un)+HLx`lP)#6Nr-|nK1bvR0eS-V#m|r#dQ>Vm0Z~d;Bf#{S`Ja<|d zuq7}jiu4B+XIN`ASa(9$z|U#q|MEF!U@HzbQQ1x~oB}j~(gkHFTvckYr z3OUUj;%UI7U*iQfWRIV{51tIra!a@ z{#w`-dtZSTidQdsO@d&Y7owD5A8ell8ix~y9I9{c3`!m2J{Et=XVUR3&a6w2oijdGg@^Csg)j2InXA*jE5su;#v2jy@grd57hkG8yy&%=z^gFv9|;fwZwfwC39OKnTy) z&&kg1jfJc$%bb&csTzMpoS3ql++hRK1=#-aEg;i+M^)js!y^N>1c~LG+P)n8Ft|57 zw|-n%`SC->0VFZ7ZoCTIM#2Er=1zogOzzE}`lfK`g-z2t5*voeWE>fZ3g9oN**?=$AomUurwZ$K_uQ9pplY^ztA7(1>?u`)=hLiP(>{sUrG} z>SE8m<9Pkglas)a+39@&kq;0G+;VUg;Ibp}(yu(pLf*@N6ah|voeM_tVWtcGTvY>* z&;{5;Ag3P*4~KKmCwUdy7PA^FXr}{ZS|84yKoT<{OaN#aWC#g>5E40k+4?qe%mD!b zh{D2KV<7?j2VkQq#DWB7X1I&1%8YG%LAMKf2NPt7107xkn{P?U*NP|G|GFg7<6gwq0wRgG<~@hU&{Qnu%5 z!-Uc7@s%1k*`!;F+;D`z!(gN;v*iv>gP;krn(A82Ia?`qPwtKjR`RFvj551b^A^AE zUq?}i+J;J|VBcwk3C6Ev**&qF$El-(6UREHZDoX(?@6tQ_u-tYLX-P4>;&!qr zuZLeoXNkASkn=J~3&K-(^c3>?t+eA^c9djON+(;Lg=d@PaqAYZFydlW zubZEZ<9L_CNBPOvk(d6XL+M%im1rqSnuDNtb=^_&btSdX!bM-*u@yIYhOA#ziL#St z+#48^Jx|usJRlQ710TO|Nxk4C82Mc9-o0zmOQodJwmDj75rN3c5{jbo8alt==GY>>yM4urYF}oE zvS&keJYS#g{A>=+IP?HsGVyL5u>VHMex1r$2c4qTS*%w+oqDRzkQbWd!G` z*QZv7A{+x|wP}`)e9zgwZf}zQvlb)paiDykcFFJ6M#Y}Y7@xuR2l>r`XfBT$^UbSs zk%6?*iDRnbxYfpwR4E*n3envc4pHqWNhkd|SzsW0&&}=Zr_IuRosgl&YXW?c+os1{ zW&*^|o4cZ%P=A)Gerr0-D}1yzs0;gZCG%DK+plLl1T5)ZUc6A(qwRm*C3f=0@>)Vl zvz-tA-~29RVY5JQUij-rXi|rnI|t(uJE`K+xlwV)k2wqF`gkS>GtF=*DpeiQyi>s|8yE5qjgBzk1+fJ! ziRj(DM3XzU>uPpP+pZ!*O~xU`AL>5kRPUtvS0)x`erfxlGoo4;#8Gv{(!utt?1u&V z6AW(#r11UTNeYKv#j!;>@~SsB_sPcb?KU;-%EonvC5eeTS9%fOq0PWtQi3%)?D^)r z!4;~HO3DmBMI7XU3C@)ij0UdoJ*eBb*$0{3HGFU7!-pbS?1bYk_XNCp=JP33kkJ5} zNh$UG2e0HuQZd6fAM|4eJ`C>812#;oiu|1;!)=I5S7h;VQr8(;^k$gIqW_NQX7P`Y zA3t9H6m~Nj1b^pF+BQbmbVDWw=+$@(ngoHq>nX6s8v z783JdU36U3#xTOLF=R)`JU!Aa@#aMwaOIUN#WM=POv5*{10xTpB}@R-mJVG*W`GKm zVP3j*Lm4)vvai0woHN=c4c_NL8_&x9j@U!2M&1HR(DTd;9vvR-zg~j@ND>A@;2#80 zwA-d5%~$=WCTHvOU_1s<41khH;w%C;tMcChXF>+Q1T4`HAnW6D@Z4ocx`Q|G=9~7w z10Z{N&==N}nl_YR&#ndTQg|zdjObu+EO0{|1F|Fl6<~ftHnm%dy$ssL9atzo(R`;U zLDT6OK>KivT2mTvJ~g0{(tkP>m`JTD=AX;eW@Q_AP-qf^?|={2y@df-k-C z&vTCo)@8u0FrI`Q6%2EMMaa2|W?+L|5WLNvyPMaMTy7Yc?xA@j8T~*C?6SzDKh(q{ zHy#|n9r&d{6Af_@t#t)57lRBI~+MwE?m6%UU^Wq$g;NAVdPwc_ZrbYpDfQz`>9G9tgg2~JL9 zhRD*uKxNFz%b>Ql54KXo3Nz*8H+!cAF{#{KTvK4Cb)oqRfEKh&P&DBV1$Y8ER#RCn zd3KOvIgWJAAp_jN@+l;Qfwu(oP_SlE=>nw#cLID4AklwP&~5l;FvNg5^t#Ey%&ZxV zNfC%PSXWmE-po$ z>Ho$70J{b+*9ONGbN9~49L%0OpnxdKf6QVz@Y4VFCx$y^9V0q83&0Rg#M|}W_B)E~ zco^$~5jn(84!9C=dLxg=)!70=-RHFY>aH{jzvRQn46#Qy_x-LZ-LK*4#zAN{Pt{H6xF) zT+)A_Z5}%~{y1qzg?O9@rtk;06^E-IHY-zhNHoXKywXqUlO@TF43Q*K)(eSmJo^

    #sT1>;HLY^4Mij>= zBdUY82qjkZW)fe?_4rv;UNtt|5pMR_jL|=1!kFSWOE@u?jB$?b?r^@%GAwN}$+7Z` z6iSfy@5A^rDuj|$TQNaN@pgCvZ5iKW8uNo2g3=E{#z|0uce`sZx4bF(d#qi^n!~E5 zmSe-=KAmUJ>_+ZZzdK4VrBvRNP%Pe^Cy{m5`Eq5k*~@kzJsX+;lT=Ju_Q|tXeTn^} zIv>&rR82{ld-ep}4o^1WbeMo>xkO=cVM@xk$`*MTAM?nIsuf@ zl`!U5x#NK7)bmG2K5D%#s%L37`b%>NtP9aY;v}jh5a!9^H zaIEQwG;RKhQWtlYkMd1t!)a)toaXZkProHw<0)$5$CA{t-w=qjSP7IW^~#2MGb`n> z@;Tka-ixhEob1YHnrY5%vLy$mvWj=-q_95eY<5iN@$K^%xg~MiapHzONv7shXH0cq zoAsi_ewCUa2CLT->uVbbRr~cS+eM zmd@Z&(>31`V!n>W4B^R7s{;xH?ZqRM!UAgQ%pUs(sFhm(z_pf?kE<~SpNbrtj8Uw`hS%~<)`Z|qeIf&ZwUY23*d@BX!*J6k~%$QtWOcUD@vts zE=BLr37$76D{b}^2s_W74)d0I3#=)u?C`4WMyo2l4Q$)(`LR}65S&6gnCDR(1erP^ z1%YI{PMHBg-tUsng(#{61;V;Ry-?msW~AxQlVLtQV3T=!o|n{-#N=!qWW>?buIYUY zRl4viyeCRagFMzsLrg$-Y3g06K`EoSB)k`W__TOq`3_4R+HFWDXR9&kYEm3V#i5Q7 zHU-{B4o9SHt&m$Bm8BkK=()-Ld2uQr1?H>n48-j5*(PQfnaBmDb(-H`kF*h@!rNmW z5FLQahjA1tM*a472u164c<<#U{1}n>@2EJB5rpYe9v=le?n?_wa@Kb<+UT=lP`T~p z?;j2A4uFT$J?$qDH)!oR(kk%U%6ST=xo63exsQQ^$hicGc>smN8O2|YxXW*E!3qd= z$i}UPpJbFT#EXH;(^)tlIEnvAB(T2JltN2$!Q@X_rBUF5klisbAh2#AO4r}7Ta8gb z^)wfQ@`B?#f9xL2Iz!qGa1CCtEQ8AyvF3u;_Z9TVS6y2D@dHVChClzcqgSmEx~Z5m z6MFW+7zuI?_+uf<4iu0GILB?ep~*xcP{F`y04*hu?b88<7Fna$FYW}CSeJnVMyCAj zhB5*^z>MjBilPtmktCZxP^Ih)43hIbAPHb01GH;!8MrPWm|&#_Gz9i^Sf3_tWDJb0 z`hw&UMiX;8F7vA{&kc~Wz>xt=4K#`iSin-t2z55?C@pvQgqiYvg#;FKCz{qat9K5C z0@?xLlYk3@sGmeYOAx06y(WN9oZ0z33mGwCEu@jH-5}>bFuo2DB*_HQSE8<0L&4q1 zGG9(V1mJmng|X`>aNEE&15yiUJh;BV#MO-X*7eI*g2x)1NJwl>dlLv-$j}WSKA6Tw zD5fG)6EIdV!(qd4G>~Q*5PkIg(hT(!;^c-uenslOmXkPr^BDeZtj z5Ihas8$1yt*${~e_JnkD9G@r5iz6kh2nPHQbMG(P0GrbSYq8QWsGI;1!AbJBF%eEI z%%uUJH8bCj)Umd~9R$!Gnc#wBfh8K47zEUSNd)PJgH;;F${~{mywC_Lf=vm`og*`2 zK=y#;8G#ZNW)ynA$JFU6nZ~ymtERw}4C88m8~_%BoaBXYSzy-!i#sVr-u|Zc^;!dlJQeJuoCptl_HG(z;73&Om!L2<};kVH%@_@o?Zc`*Thq0Y5-FMTBJN z3n5hI9TfoD_E5z;`R`y0{NYfri~0zGJ7&Tapmc^b0whP0&>_7UZYHyP&F+AYVG9P= zWyJ=t3^G*@UME{PBJg>k;0}_$CbTWHba{ML9vPK~+X6hzRVN6~yYnn?ze+zbvgF?O>_&X>=*&$9Lgbdvzb1>rglaJO|HWjOnhXE9HV=0T=ZteE59SfhTQ5F9W8@UBtixQ#NJYJxwZc0$~vlnK&{^+Q^Wo&tG`N!FR z17CBLyS=QoX7c-al6U zOc6gypTL+Vu$#vxAFJ|q?#;;#keX?DupD~@b#k^xsl?1tq%<-mlR}4dr}BKWW6BH8 z@IyuOVUs0XJlG=?-S1kcY9u`SsD3z%cN&(Dxdg{v860oCZnUl(c^!SI$fbp?+Vf0Y zk_DZ|VvhsmOyw9V;`N{xwiXN}kJi1$}upyOf zig|#;SuO;7ejuAzO+|!$e8HnIs2^AD>m64kVVQG9_dqT=+!_ z@1wSR)YPs(m>vFbS&PUKl|VvPg}F-|*KFzsOM{#8(;*_L>|djP2HPcHcrN55JZLbK z7RZ`NL&uzn9gWGx%Nes~Cgf}?FSTh?4N*@EVP|>Hr~Z6fb&`tIj9wI9KJ<-(J1Jb= z^3;bNIi6*1ETYLD2LjmyLT2_AGO4>Jd)XM{ulOve8m`U}SsTmFS`VQw z&@#36d5PcO(kK;ZaI{$t&+4ksXjE?1KC2M!nop?38_@h>TlFYYF<7Yj~ z6|2`f=>*qKpUm6_$F~X#!Tkz@A6x2Gs#RtIgPA_I43m%7 zP6iU!TD*mJHP`Qb+^Vk>S+U$;6-QHiyy1TGnZ@QDC*??^1?OP(sbTD}NQ#`mHhajS zx8B0kFXm2TR_e1{4jqc_-OxyX${H_K9K!W!PT|^3$>~R;&u7A)GGB-~G@9e?mo-W~ z;5<6aLewu$^rHh9feMocKJ_J)rL<4{2F_?$OEjs7Wf%39zXbWUoS|JI0s%!BPt z9PyCbFcQ!x1ViB2eM=8No%{;^4osf6=50v`l(i3w`^>X2>#OS=y&{OU2QFO zkyDWD1Wadh5JT;l*};{xaM$ zO(jKo(VWf~sqNbAju(a<7MUA$mXS=E8WY4WWqwxWmu%m7F^Y&Ii!&yoUr{$p=_+0* zps{7pSkZ_MB5E^MF7C_UK6OwvtF&SgwJ62?NJ%in$QLIF&cY;;GR4(37RnIIt)WR1 z{n?G%C|eY(boh46i}%p30b6E(F)(h0Fgj&r5FN&q>3X3Y2&3}8pN2fN6mH*B3{lRJT7Kw2OEH}(ywb`C%lAT1Lx6$3L_ zp8xi@W}?*gkhT%%xXMy-f*3-iyb=;!{#$$Jj@z_A|7IvM+2ZbA9$3s6>cj(K%k1s) za&qCO$KE>eU&@A(D)^${QbNK&e}BcECN#r_F_nA`XM`mW=%?@Bzq|Gt05>NEG8a7S zFO5M;#=M;g+-;zPvFl<PX34BrCM&4S*oa>xNPJw_=egj5bxRJ7pr1zpB=q{cpdihwZQba{b*!W}WTIIBZX zCIJih`1v8lAFmhk+Mt&N$qBLr3-a|ZA&luJ|CcXBLgN_AjrEb~clZG$XAgQV05Ss4 z2${xHcUB>>8Mp@dGMHS#GcbUJDP;Ul_2La39cu6%13m_lQ5q78!Q=wS1Fjyzfg#WY zoJ9aTkVtM=PobItsqcWHHT+R7sC}@p;Z5LGO8`hibqBoBd%qv6z1`oMWGH4uD$W`k zRgs2?yuA{e8mEweRICEDjN%PuS7)4pEOI1j+7rrI;js|}1!%Pu zv^mh|;1qd6p-14q-N{Z6V$Y^aN=Qg^GJImH_>D-RRaGnqF$rBSx+nP6 z5yGaai5EQ1kU0sNI8*gFsn<hIyOul^3NpZxOk~Ovd#wH&mVfP$ z93trX6LF-?{n>8^8qhm%=|aAu=Va94k4Ip-5|@zRW*>)V2lhAMoH4a2VI;$wrS6Co^ zifYslPX+_MP`F+;tJMCpG55+@S@ecmd_4dWBq_B8BG590OQ+EqmMcoN6gJZtP)m`8B^+?Y zd=a6{wEC{tX#N7Wuy(HA%<@Vn6s1&z)2D*hjhk%O4J%AQh21MOx^5I4Lbp ztDyE}rN7j@sN-2jGB=loLYY#U4;^`5L@bYUj|=0d(eqROFi-k*Fyg21DP$`>;`r(z zF(Fg;uY<)TDMysVOS-+kDW*w`{E@S#ysn?ucN2AM=B+Rp3?22dl8ULS`Xix*&nz}` zEuK1CFJm^)NM4pdVqo;~^!-oXS=(0q%~B!XGRIP?9n3Y(?h|vKh4){eqxBhAbScth z4lk|_Jum$%STqe&#C+a_C`MDtFDk}&3tvnbp1wKsQHYTUPWj1S>O8;9w&m_`>~6ewQmfqJ1)A3KHw8FNU~xM?jmtk%hevcC#R~>R+%MqJ*kTA zDF5(zX0}(yP7}-0s;8*EJzAfhdt+GKU_glMYufB=-H(Xom{`F2_q?^q* z_xS0<*&){;2YJlToiS7?e@k4_AjED_$-X2!_2fOgf)8C{LRKGHie~i8K@3Mk(a$E7 zlxOR6^m_%zp4mi^UnnPQm0Hug!ew?!$(N4O3SM?t(IIGy$9pjHhelI6&Z3_`t-?h zbhLN*Q_6l5A0At87EaGSfAV(Ix>--PlZb$nzKQmmx9oC9#=b!$!l31$GVNpA18||XN-H8{N%?ckr;*x8x5U= zT!>A6GpFaCGnnS&4l%jLCD5!hN#@UbmrGPMux($i6!O(iXAN5!xl40HQcvD#)Is8R z%IM4R=SoKp{@yUKJeGO8thyjr2**X)CMqgtimy_WM_Wid6B?~_vrlJrz7GWmB_D5T zRxy0ww2{z!T+^1zu`p`RpX8HBOT3?H^Q%9VY|(UPQ|H#Idrx%*=8uiH@#T?smonGV zoI>us)TE|0Rg6qS+cU{JSA8{8GQ;^;4$FzX zi)(vrwRvs7ty35Lzv}S+x>V)XO!qFTTB+>izosCLVxJ~MMZ@*e^V_HH(K4Me97t@~ z+Pz9`<{)*dDf8Q2!f;;MH8GprCbhkfw4O@%yy*Uwzcuu zT&((r{W7tsP+!NWI=S`bFQPN>$PblNlT-dUOBpqDkRvJ2_ z23&|HpFfnTd3kQxDH`yW`uNQ|@?I(gMdtUKAs;ya#f4&q32mWKSJCYjogKsDv7gWR z(A$R>2FWcF1|vfn2aL3Bscl|#pQE@_P|4UFYQoit|AGi6T%BB|#g#1HBar70iptu~ za+$-OJK1H1w~b(+%f}}Ttqi&!*OW*HJ7yGIBvdlVrr(itU|q4bPi4V}q0tTS1HupV zrZB~I!M`Z1>EieA$cQxJZh}k|Wb!ASnZ98R_Hy0cx6O(S;!CJX=`gk2C1hNp#QuD@p?o58x=Oa*C}xI znoS#$)PiI;BS|*5*98IhK=CT18g-aF0+tF{+QFFwB^gMNfh`bO7S|B`0CXE-fuC0B z0I7DD+Wxp;gyFjvM(+on)%Ov2S0&@@^>GAS%2V4f%Dz$0%;Eal(cvPxiV_x9S>O5U8aE zbtN7!Wuo#ZHC-`OzwC2#Wyr?A-iP*zdJdo{cCHuN`rrvtC`wMzuI>UVJMswv3Xkr_ zIKM(oVf0()roT2+SEgHRJf4nd%;aFPFE+a=5__H4+w<#H(_vHhu-K!6`Xr|~3cb%X z2jdjmhYK(`QQZdx#i@-$2eP$Cs$B{){I0PU47PUJixnGKK4JF~C!EH)X*|%#G^Fj6 zR9}uN>{lC6?k=c&8Zbgt&0tL$@{py?M-V|U$Nnlw|$ zQTFja{wRz(fu$hR7(|jweU3GSl9)026oXzALabBhcX+H0z8Is+q^TF9ke(Dw8p58v z`dlINg#bN=D1{(|wx{NB# zL0#^!82ZC{8Tn_31~{PBB`$Jg7UI6S+@Sa$L6~7Igaa z4}Iwx8ET}@sv1pXDLJc86+x+vLgzowOW`n=7f7kcGo`p!I&BL$IP99xo|klWkUT-e z$7$$tPJd!!c!D3CITUyQN8Vo}i({Yn4X+!_F=}XDJ$lw)@`#MRiV2_YlC(D0F$%AE zLNs4kw2hpgtr;T)&OUMOygr3jGyb|hRg#RewicfdhMO=*tFNmI|B%$KY?T4nkDsN)0l~?VJ#JgN#Cvm<@Qs*CB7SCVOh{2Coqr2ma@ z^5MqoW~ln!wqAo@6KKZ_S8tvH?vhw$ zWqfuMg`MSfwZhlWPom0WF1k{2#>HRsqU{u-_O(QdnTNxeI)9ruXKvF>;4>E}l#Zl%Y!b9FbE zHVa5@E36*)60SXoD@y${J`-kO`tOmIukxC`)FFQ#zZY{h3sMdL+D~Xyo0bl^OV+FQ z1&<$;yd1cYFSp^d_-BBjlShqq@%hTe>X(A4ZYvoE{s;adx9j^4*AL9fa^D@W81$9~ zK8e=Cg)a%sh~}rT)l<;IZ!s4I*csAIM#}Zw7ntwO$}zSs?OMqBqxGELn?0%0(sm%W ze-GEwU-m69jImXvc1ZP2^e}ZpGU`j5FG(BQEJ;y=Hnkfa5KY%v4yRUk`f_z|&rc!I z)zFWJp}j0V#Q#LM$b$z>mWdOK9t9Kk`?fO^F++>rG7r8EwWxk-Jn^zBmqC#d=|M9j ze?XQQ508gH3V>4q{3Hm&0G0-LpN170n44{d#X4{z%g$VQZ3XM|H@yW|ypaqT*na!? z`a+@)h$o3cY;GDdzy$%#1$C9c*958#nD`5B`0V{%qafM`266#4fOjmsId}6k6qTk| z^ek*31q`r)AqE+sAAD}zdH_lktYC;P0c~BH3@YKkQ2|*t10%;sqb7g|*f0aYK!5`* zWK;nvNKfZj67YPsXh;-VBhTge3mPyTIxRQ}y2$7u8{TgbJlh zrkL5k@KqoqkYY}S1arxhrRlC@0X#SX z-XpDF($ROB(c*v=9;CGba4kxM)1(Pywct6)+6Qn*4Tq1U`~X1+3`C~eQy_sDRR0oy zS@D`~rvWMo%A!=bUa7&;n;ZuYuvO*-Vh;lC6MQsCXZ?>KH$dfi;g`Y&y&K?JnKLX+ zWYo1o(r@7R0E3A5kEehDLx>SzL4GuBS;Kjca}otPt9lrM1$7{H8V2uuD`%*A{82!) zfg}dbKZK}ALz+DLlpm$FA{Y<&IL7b4?p?N44+&AbG1+(*9y@TWZt@IBiNK;Eo zlY7E&BeIwO{nf@Wvp&}gU^Hb%!%v1RP zy#N50rh$F~qEMWp7S0UksT)XqC-O@!UAkoUsOr4vRMWw7ljp{~A)tL*&>W!z1TI-$ zo-W=7a23sYeYjo1xFBx)0#_$omUE;FH2#_~dspGpTa=g~8au~>1a75Bka&M@ZVG31 z_srca-~62kv0K$KN8^$&N%2*MjA8}H~0g!!K&$mJn+0D#!4ytm=U5dW(@>Vkt!AdDIyZC7Z=iw3?~W+ z4S@MlaOSlTfFF~DSO~=OD0&QPb+zOx{2_(P0TK=1?Fz(1Cn_Reyw%ByZ6@|-0ODa! z;J^BE#Oz%qT#nk1-CFZ`km)z-ouKNjC67X(_%51D7w|ku|_S?2G?4Ov=M{E|c8cv_%G@mCFv8G3emz$(Ax6;K{ z)iZ>}ukbex9bYHudlc_6pD3)Jh|QSwAck)*x<_Jeyks(Z0_%taPfa>X*ILWrMjx3 zbO)2v_iv;9za=zqC&iCk9?wCKa8NIQV+(00<|^Z!z`SvP&4B4ndhSigGh3&q-zis@ z(Q7_hMj#XvU}f2zWtSc%Q1Fely1)TTpsmKuGpB;^oFuGH|m5^m~SM(Sq< zYbE_e^PW^u7Qx-`y?aa>^z6?F*Mlg@vq6mkQW-C~&x*QM>!SE0zeUBaO4}?|x^eW_ zQ>8E|P+E|+Zj`P*S8^bwdejk>gMs5Y32`o$TUj7wDMvq^fJDVaT( z<4i~VZ)V!L))2H@gHnGxN=CSNzsNWFN5>VH;lwX8PPt-#|IhfK>c`PP*Ee%FEk4w_ z%uFu+BrUg*Tb@0ublGj392)fPD;GBtzi`&w{A(uOrnNthy3!#vXZ<{PUxD*##M0ZX zr_XI|7FgUR&R=Ogo5rxP5LEMn=HVM4e7g1WCy~CjI6Dz--+nQRx zIUjvM`Z?Z@4tTA(p0Ha(;ZKrc{L6@6FKoJZb>b)1+{*i^?_0g`1?kBRdJ6aA({T)& z@lXTg+ z`9U=nbi}>$^UTe;j*=7YqtpQ}ANd`rzd1wwM-~&e?TsBNy~Q8$&wPHrNYFB?>Uv1t zj`fEL(H!jkzj@lV_Z<>~2fI~-1zWgoBzV@om|a)ID^E6jJjA{^ygGcRFX!P-Ktw>W z$Gxl9Renkt-yFEY+wl^G4(o`u6%?iZ5FWY|3$moe0f<+iN+4Yg zu%v{9@PcziMCGN$-7yplBR~2C%h$|MA0l z>@BQd&a4k?*ML`IV`Br@2&4qkUiuAo=5meDNjwAD&Vul>kucN^F+mvcIMMuKD@JVL zpaLSZQD9xK%1Tmpsu~OI-Qj^`8e95q31&LlPXd&aG5fLX_8<^KFhZKiUM(YH67I9r zE`_nWmJ~S!h3NnMVa&D}u=W9S1ZzlTybVY;g`)ZtLuje-oD;>_y>m(3j%Fq)E8!@V z&t1`2hqK^TIQi=Z#^9NPaj0!+Z$nuS4K`>OmbCz+m ziHnN}uO%eo)veDF7nLzDmZ3{qx|=U<&zd0?h9%bLD#_@26zk+F;N{iko?5G+)MB6 z?nEsv+x$~R*@BDdM8oe7m z%3QdpnCsl_kaAftYaVo0E#q)dZ{chLK7=O=;@z|7&nv8i(0#z7L39G*#Eas&gG0i! zRPz_sWO9u_5YK3_3ocwvzKd=4*z52h#PTDw6zH80>KHl<uT{_$rJQ6?X&Q3L`-H_06pjxQSVq8VzBvi<*a99W5DD{CTuiM^spFWh5FLW@T zQ^pC6dO$NB@U+utiP5t~A}1C5l<8?WeM|uP2GxmX${!pCgdjI2y3d1C=Vwo>38KduCl{?^1}8zV~rhEv&ICk7IK^{5O41Lc)8E^@L^78K}%Vlu17*$E|-7y zKMoME3MgQ4LZ87CH2TOY#SR-vmtXGT1&g&9BMDhr*mhk3{0CgCoQWM(sVSS?u`sDV z{=<)$1{Hd$_?A?zuA6{mif@^CpLMTjG@}?7D;tv}8Yb z20u*b2&Uh?do=s*(W7^RVR(8?Wr#OlfH&_uB5VRPj)r>`W>*sGE;{2qJN}k!{}ehU zw)ot02T`rf18&RYScf6`^alpFVSUDKR2LXMc>YX+oM1ILL8*6`tgoVEn-o8MzCwFQ zl~+spj{}DJ^;A9GtYveU#!Vakza9tkq=#3&ED)(EGcAaZzc`ghG@S9KI_6K((Ca$V zf2sN4vXrPsja9p)&*rRfF`iLZKvAyzhJcyRLeke-Fof-{*Y4zt3DH zNR8U7*)>?($*N^hN!sWO5S1%y?)1r#JX-yWQ7kSw`AOz$*^>!@N|ViVCI6V}!ugJd zXMfyfZdymPw6;JRk9GDXv$6TWl~K9At)fX6$0A-$=IPLmw)fV8X68I>U-Pcs4m{h~ zz_Zpt;b3(9jmMewE1vA-6a;A>Nd~>fttH}ND{G$W{3B!AcKej_U@6+}ZO1v?O$`d$ zz1RA?CB!*{;=|@${j)EHDy{P<-M*^7u{*0(UdcJ)HQ9a4g?=*p8@YawufyGj~$i+SB7I~j;KtnJ-Azvx$u6$ey z-8NeK#HGu0?koGfNqu|x{F{D~IoV`O@_e`cs2M&()w?E4Q4e>nj-0ihI7xb!CbcxE z_%doW^AZZhQcn5(8Y+T;V|_V(PG8Bt^JwC!)>uuA-mF`#_`Ua6*Xl3r{4u?8CH9`9 zf9O#DzQu^yc6A_5QU9-epXE=^XTq4Ov%w!KS)7;GZ$;0sN7apaf6)r#oM+A04@rDO zzoz9k(0*{vkrZqC!T31(E8X}r%wRL>OY_HDzQ?JDa4m}J)#U7N(Ao4ni@>OVOIFdp zo^^}M;&_%XOD|8>C2T1*&skhE9YK^*0~e5v&vIn4Xz7(_7?&d-SET=CkBUX5qC8Jh zOQ_^q6S3)7J67Yt=s2gEjUdeD`X@hq1$aJlG%2d(^Qg1*UL#DCgdZ~7(W3o1Po(g8 zF{!>)B^Sk((wph5RTYh>r7Oidi{+h5uJ5@#U>iJsE~@4Gy>BAFcH-ysW&}rfY`J^W zH_klxcj$F-dGy`5+3KSey%$GXSWMJC_~=DO08~hT6`NIz@~(O>L?PUZgJ4}C!bUX+ zjRD3s6(%Bxt{nCoSTmjpmh4mVKiL%l;o50J_P6}^R9PaDsHAra&;2)_kVW%wK4hK3Lm8q`NAA5JT`!T}l0 zgE^cJJ*3Fo>AwD7`jD-_8ewZ7;{sM}B^aCP?&%pn@(pBODB^4<{AENg z4HH$}sKq@K)I_D%Y}uqE3qbpx{uz3^P7{6r$kS_K5BZ9YCCe?(pi=)#duNVuys5+4!Kmg~^l7dbhkNP_2|KS&?P?(QyZ zoxLL?Q2@!nRe)dQejw9=ve#1PaiGn%Xh=dYK-yMKO?p@`<`?7yAkPUR=n36P2~`n! zqD%X>4lf#yx#kNX2uSK74skgYejjm5cAT?7b7Q{YqH0ZdwCiL4;veWRSQROy?(_27 zxtZvej1Sz^u9@8Jpy2EGBJrA7I2$r@fDebTjZe^KCVB2$fROJF&r6Uc0ptRB3y8^I z6c*Az#3RU_K;%dJ{kW-TTO0(;L#FOM-aZki3s zlG~Vm7b0}_(`tyoTuYWo=2i}Qwl%cqi|~>_Y{Q$+|KQ&cLa-8?8&Ea?#QcJ&48!1E>8AgE4-)W25DpOGi@`?$ap>^k0PnPX z2Mb%U{MU0*E_3TU7_$%8l(&=*s{A|7f>@0_ac4dKwhyN;KVY@+F5Yo>54}l744X}n zu+{|F5uTP3*dXEAB8Nl7@()Ow0EDp_;BPo?#KjO3X_WQro1$`(Fdwt)8`D`@LhV^C z_s{6c$FWR5{%){m5vE3qTW?g~R2g}6##=I(^yTK7K)a3@y-pVC6KhgafiK$b?+KD0 z8;V)|!%0_#?1&Gav|%*DP@7is-Gtqbxe-d;#>u;PmFrJ&m5jkh|{5oz}lqg1)kgNnb>iwF-?NkNK@Q_-1$=I{5J&#v!c76#BOue@Jzag3dChW~dD19T zZp-#4Y?xRWo&eJ@o>4b3^GW0r^!3-caAUL`&7g^@>T5O;O0ldn;q)@O^e;&76CTW2 zsnUJcBg)iiQ?jcG+qN>ZEvQi3$oA3rnSN;^yD{^GS=DfE?T|zHM7o%BrPq22#nW(x zw_iJ?hDcG2HirCWYA0DtTnRa&x>p&e&FvJ;me;!5qmv&N#=A9c2Ok#AKer%#=l*Vbgg$hLet2;VyX<2l z_*XISeDABV9%0$TkzY+Bt{+IGVt6!{PBiHXP+%gBo9^adZV~=b9FC!0F=N?qm$N<_ z!P38NzX2>aNUAWF-OqR}hyD#d}h|)25IJ3;vaBBIwz0<-;&jyQ7+~Onk zp6K3keX#IFM{RwdxJ$BJANbEt&@-VvM9)q)*cET`}j=*`V+N3Of8=F(cU* z;rA(m-KPs5H=cJEHpPKCm#*4}<44YOrFPuMuJtL! zFMEq`t%qWU2>n{y5?juwW8Ly5R0QSnx1?Tl@yAc=%<|q)NFpa#hMPM6s%Gj9fGCC% zbgmu2W0$F`<`%bS55uVksmBdO2^gnSYR(}>1l_0aAN01P+8YQsW>j;7fI1U_w2pbs z_KsgiOy0)+;=8TBXDgl)U&Si|U!+=b@n+HtpOd(Ear~+FVo-9XU(${BrZwB$>U@QY z{PeR`u@c;t)W!va)&tx{Z@8G5U)o6LnHDGZY^XC)cRo@&ID5TgVK1QHujovfKwm|0 zD=y)N>nVv0);1{sZ%Fmwvp!qsCsDe@UBf6G#xJljs+3`wha35b#$ql`E*1&E2BZSf zH!odRZbq`3^o});AX?w4=d4!#5TA@#+<{btWrX&Zg|)R7FgxJ*f?SARXz>IV0>Y&b z&-~fHCPdx~5RsG3Zy3uUb*U-{xHst5 za#L#=q6*WZ9uj}Rq(F}nING3?bx9Te z$x!#l(n#4hL^s6(PD07EvQ*aNJ&C7k2bgZE%lc6IPGI0FYv?K~!jeLy!9)ADSX&^a z5D|D)-M>>vWqqFGeJnyvLJ4bwo4XM+)XXBc02Uyy%OUgztRw(sKpSrxgK%Bkd*Dm; zeop{pxV@HA-%YCo!ZgTJxRX6e>fEKIS^4$%`mdU!s=sYPle2pguNQ?LGS2UKKPl=+ zdFNU+>7ge=F{?G?Uo&Z3yK^`eiprI)((~)Afzn$rBoNt$>GQ<@T8#qR49pWPI4u&& zC3Z4|9;T|4LJql{n%Ff^cToftDOYaWV|30rm6^ki&ijzp=?(9kdg<9+s{)f$_IEWk zCxM=YjTf$*A`9>}Qxk!IKLHz7{R|*B2XequvZp|8G5~!icFnTL)LeJ)uU}EHK*q(>HmnU{2B9J9{|p>mGA7H{ z4a$4AxQh;k4e({>K&@^m-sb%@>6JUuYnze5=~TF3K1}Z@9(rcrd#Aiz>AD$D>48Y> zo2BTRjzcA3S4doYhn-1-=oO|2_PoUjjxWj??VY$O#PU{1mTx}JBx(v=TqgN|N%9h- zxTss?dwTV>1mPFy)sHqg;8Fb7Wj{7esn;!n`Yf-E&G>(DAp!M@3vDh0u?NDraHQ6n2WOieb;1iV?qc#Zwlt6Z51Zw+f$; zgz5gOA#SkrK3mFI*?hm(hiSk`YBY%lvnyP`g70aim6z&}Wu$p--{IvQC(wSu=1iI7 zo2w%2WPccKcuLihl@qP@`hxeQlf)$jNo~^-@JGu8N>l2DMU8uTr^v{#?g6>$R4XJC z$|3uu$RG|BX2W5G?6r{Rjr&+pI>Sw_DD*P+W1Do+AaOq(alTAUF&S~ym3)| zZvxI>kHw4KloQZ&KgfIeF(Dz@sebb4+7VyJH9KZH#XuSNrLD2tcY>L?@V|VDF5er% zN`)jS{bD63GU6X?>}I$!fq~hLgPX9lOLTMbuzuMeCSNc~HW9)e8O|{E{-niWWx(D& z(Gm1H{!)udiVtK(Bl(=D&UKF1&(GIAgC|3(2)UTCoYE=DcX5l!bk9<*1c^Vp;t>_P z`3dblfAi_wwGD4Ht#jv>qwm`%R=&qW-#G>|Z@-ALQV86l;<5O{(-B#4YTC-!I{_7U z_`TVBy}#RkUN4-{S+p^$;MaHj$!A?PvkECOyX6-{TK|kFtY&Nl7_WJiT4J21D=Tgj z>fV|BZa7j%dXMoGOw&tocAMFuMs3di71^m@oqKi{Wluji`~3Kyo8CCzJ8!*bSHc{~ zt0Vj_N7NWi-1ZS@*uky2&wbwte(!flnrl)ia;A-Xd_DH8)=T3c%CiSu$B2H*U+*X{ z|LFlx`+Q9u4m0brOS>~ACrh;B-Ch&4`hP6|Q$Wq)es%(P^N#?rq0fPLl zC9Wh>^V}=XEJrH@+~VPl%#eaK+R-ez+OPkDTNBGGQ(xMLMNK~bV*c{SEo{S9SHiy6;+KV+WtJ1? zI)41Hg`+Mdk0cz@jD3hyo&EW7GJ?1Bz^Q|Zh!K9G%R@;*OG{hb{a+gfY6>(jsAvu* z8@5I$P6g=;NK*g@kCLP{-}M9m3(P%RHamZRNV7%ERlv#fpAZxfK(W0S8oeU&1azQC zcNZe|odvX9Rru5F0-P(sDHR7A0|Y|(y93_=WDFn_K#tmAXItH0?@`l@0uL2=KCB+_ zW%+2;_GhgR`4P=Q&>x@7=AS=#>vq4sQx(1sCtCza(bor~&ojjUM$j4iFO{^dJP6%> zuw6U3cYgn?^}+E!^+zF=;H81Xq({`RA&VTah`})!`G#BpGsmn_VeYg7j_V;nGOiWN z0Vz2!YY<4sf0Y+Teb+^LIyxxDu(7crj(vcM4*CH&4v)NRCkIZcnzMio20riyND)Fs z1z8?5NOO>gCOCN`ni3l8Z4wa1%&&t;23`RohTsa>wgsjG@h-t>8{BpX#3FsnlUfq} z59W>Z4bbd3WMT5aEd~<^;&?zMm3)Hpz82|B6|H8tknJRlcAmGT*AmBDcaJ4SamDbaiyZY6AZ=2pIdg{e{^ z={o=*aogPYL_GtxCGziO;rsB_DS1Fsj7G`b*${$l2;{w6IUpbboC5$DR09AFscCPn zy&hUbpdLs{WQsN+n&Uv{g0$cQPskOxB!&E#zz(S?Wwt^7B1zF1XpZpQ_+_McxIK*o zWald%xV)W2R6Gr#0F(WsP~Jwv%{T;kb;kBj*7`{0g8}7FNOU8z@qiWbzYbR4H4d7UleH7HY)&C0d>`ZL`lixqnAFYwma~4z=cn_CQd@6 z8rURJ(aIa|PRqz(crb7ym;(CFz;8VNrCOe@ef<5W?T5Vriz4a8lO>|D(a~8T-UIOw zQuvW)EElpbSBBCw3V-o}2fU^&UeQ2C!FvFnPt>(**WfV&&<=r_?)5>vujH9CpKdG3 z$+hn=3MJ$30ZRp+3|`_H z7_JJJ{}dW97bLvE-#>M^rq8+9p#poiEetR;xL7=~_5jI|i(j%{1k%{X9HjmL{tc?>rrxiR_5cNkCvqaWlPuJmJ zDR4v0`a|-rQg4Wz_F?WnOWm10*s>v_6c=u5{R|dbh>(S6tb~-Q2QVIl0{kx+4!nM) zy$=?yD7ZYl<4qhUA6XW+lP@k2qhIUuyK7_ii-w}%_&)JC=Q?XO_{j2-{fN}$hW_YF z{$XRcRsJR`{ERsYP!U}w>-(k9!6agbQ0M z9vdfG$uz`{cNVJ)@w-n+5m6;U_raz3Yk-{X^ZSXHE_^$NN7Xb=PZy1*cjn2gYRReQ zq;}KO+8DFWE5|RnW5s{zWT9zp>7dMm((h`E1@>;;Zb+%JV>Iu;~+)zwvWT8*p#N+N*IGF< zO%aNL*K0OrPuK1`lj3uf{*aW@hc`6lhx2(UC9(|$)wlQ8^%oYZA03mG{z*Fg29rT1 zo*3>u&^f5tr}XskSi+q~yv{tyMB7Zo%)h0b$&Q&T zz8T8l@~S;C5wAI6wqDD$BD%R45n}K!=leHm#?${)ByLpy6+7wPSVt@VZ*HBIYjcQc zrz~%pH_!@~s4PI>2rnT05ogQI zFm~`t;5pyAEBD61&6tt;{Q}>h^|q^_N~%3N6A}mdC^j1p+4S?M?jyOKg=X~vUwv=) z-HFjP@h_LwclIU9{T|q+qA+ACkd+x9{}^)pkn{Tf{ywL9&3;mc!^GN0*jgZokRA+I zfKodV%|K$o(I$6$iS2X|lrXKMu2SmUHvYZ5{As9e^Nix&Qknny=d)gu!CODT39knD z!|7MpJrhu6Ku#kVcUHEiA6N@xVft#ONBSUJh8#hPS+r*@gv$H?UlPWqfe$`!ImA3t znj~jFxI$nMyi9=F%~T(a-g7{ejkxhD^I%{$0GxCehh#D%Ljn>nA?pB$vyF`nq-`9O z;ZX8%om>*Is0H|LUjiYm8Pat?aoq?c!Szs430t$pI)?;3~uwckdUG&zmR#q z6%VL)gK~ON>m6!D8{5Vm$^ow&(a?kE{+PxwWV1lDRUm|ceMQXiby5?^WdW~}I)DDN ztmS`I8B^_7`4fhM5E(n9CDGE+*}}YiSG#GET{kKIm?JMU91C;Z<7$LoVvvq?=D($s zGZ~OS1VyMMsGxs^*5{KxeAIJsb)`X)PBExz?^$Yax|1{vvr0)BhYGwO2EGmnEP}i% zNE|>)XCU%`oNz)9xd4S<3EgJQ8;G78i|M{go~o1pU2h^!iUAWLp0eA{mIhW5(N{l$ zF^ zk~XdE!u+tOAVPa284ApbAOlCDBSuGmmcsf!UAOlK);dP`iJO+S?B{KFzv>#)Z-O3y z(rZw?tdC${A8~MpGv*HG=T@a`rvZ$kJ0Uss!+zGA9yZl5iPI@`v}2d$V{g5ynu6G|cVk#}-cmB*^(R6T^&Dw%BKkacO$)n^K>IK7?%_0+1 zjS-W!@68@w#+PBBKNzp;12C{*Gd)_&ZV4n3w>PBI}TdR$7B zpTwm_#`aI56+JU^3%|`{P@!DXzR#X(Y@U0`Ja@o6xBp!30Q@q?*s>IuklUtergq|J zKl`!g9wQgVfaXT>9&UrZn}pn~?`~#Ni}p|SRf~xau5?d1%=&#-SJl_Vau4{{!tST| zrCUz54wILV9$RS{sr&Z!l!<c;8LOHwwGB=ap+&LpWu%zV5nXsK3zbdX)NNz14W znxd2B1SQV)t!u8@`Sl0feuJ2&eV8ud5NpAys{|+69QFG9ApKM_Yan(ebUzZ8Y(Jb> z{9(-aOWIK-?nT9ER=KQ9EZaaB^QAeDu3yd5#E8eju^IJ)58q~rrT1e(BzaToF}m-}NoSeg&N7=NldtST;jz`Ei-BKrO4+Y&Hae7`UyUBN z5tMqkPqLV{4XTG-8ag}mlKEq=f&E8Ef(d=<>!@XY1?;m`iK3mS(dTHVKbzxh93`*b zrEQ`qZ6+yXV^+ucC79i=Yr1aF&&OAIyCdkjWI=hBo)Zxldf{;BPA6$V6`q6`!07#@ zN0{6<&HL&e*1dtoV*UJSKGyFc-yZ?!Jr* z4?`O~7(9EAIoI<*2_OGH_n@`szU}DdNcr+3o~=s>tb#93U+Ga=>5N_M+!l3Q?z_Hp z+J}aw$&@_YoiKR8IexJ0qFaRfKt)l3wW!ZR+&i~)FwLn*M3or%2kWi9`Y}TJW{^LD zF(pXHHt2nGpn{Dhtzc+@h0?N_e#|*Jndp>I+3^X}&`wY&z zeiA~ROuxupzWMXfOb^3z-2UpceS&3L7()}^$0y5m*Unc+7rIq%0yuixP~aayPsuV{-Mv_k;*sTPq0fDD zXHjWFmwpFb|K(!^*Xi#3EMIa9KhnKS^oG45TUe_B`XfsCty<@qb{kIY9x=YRiK3^% zfLkkFNuPUMeRD>15Mwek=c3)rs+RDUKcro>yQgdRf;Vb-+qx4 z(p551G~goFvAy}weFG2!AHRO2`kTp;N3a3gYm2c4Dr6L$>?==3}L%m!V8B%gzM_nNqe9$4; zpqOZERG5fFxXE2QK4c4(K;n zmtXzS*?rXD4NMRGeb}pjRLT=CI29>;D*dx6Wt)k*JCJJ#jf8l$X=#yB244*9YHBe4 zB<{kx6))xlp~9ZL0fr>Xy=N$I5yV_oDFI0#|BFquz+z~nX_~RHZz26};HOEmeFx+b zKoCaE2#W?R8&aZPV&67Aks}1Lhb^FZfvGB2j|gY~Q>+4c1(#Fg2_P>}P?l8zHkKc| z?y~=xxr$6lby_(Aivhw8!odOGqHQ?A#TD`G1Rx7wH%CANFaS}Q02ilcIU)RSV*^yR z2x_FuKJIX146=915O59dmgoMq7XmYkC8*#KMhbjehySdP zj$7~lWJUBkh%fE?1Z+;gLczC0ocrLPL(;6_{=wlNunf39aQ#(vqd>jR(tZZKhJZhT zK^*i(zQMAvBDOwwbt}O~D>vtJj-I)*f1%=;-;<-!#wM@>!5XL85b=ez#e zkDUZ7SE*4w?~&RP0dSq5w;KT_p-@Wueg4%uu)`0YfiTJu29`$}kom(F=AWGs(Ya9Q3gDxDSm0bYJG?x2+$A;6#dOJ#yB3*~?+g}P0^^xV z;a62G2FYcB4rZ1CybdB1gXau(e0#tZVNC~dJMP;j;9n~});{4`U7}UqTVCuaG!;4i zM-Qkw_#43UNw$L4D812B<|Tw}u-PN2VqhS(w}p&Q(6)gfs&W4DyMnJbx;OHZ9M}22 z4Zw#7j?z$!<-KJo1Lu<_Nrzs=e|*0O%y-O4-spV0Ao4&_Rwv=Dk1+h8We(sfK&pq} zM+BHDZHEaJCkk&PME(U(5rlw3CS{zXxN`2o#4ZbC!V~GyFv~YBe55#`ZR!~HbXtW- z8uIHSb>%coRPm{f6<%Hec7jac!@SON z4kGpum{WIqMk!qAI&!L~Si;T-NjlLikYt$nlgLyPUZCW*AIMtBF$jGWyjwC_;^0qC z^FCYX#bvIKpv%Cau6{w2dsE(1Y>K~|7Lfdrwwa?TvXYO-ePKr2{Lom}GJ>8kH)3E+ zz)%{S*IT%sVGQ#W50QZl7&|ykew1s-cjFwpfkr4@K?B( z%FnUSL)-3>?kQtVzb9d-5mRw|-^$`g6aGACz;h8)#57v8@$4GRJAV8sO?BO^r#9EG z&Qe>oCh&{%J!c|+ks|&gW$7bEAnYt}+cv9wCX4Fk1<_+sGC1`eZzjE*q@}*tPmh8= z{yM0P6SC&2)4HL4Y-8rONvXAPti?biMdHF1zP?@7eNQ@!yEd39J}TD=E&4=6F}X~N ztc{n<`VVtr)+;sPK9|4uP(IpU-T(fwb5i4KZsbaPKyiTLG7%V23$SXmFSEz#*$F!8 zOquu0u;>xo`&a)hHsqk#)G<;9Q`sVROo?tjFDQZ&)z6OIO;4|`@2oh5zFwQg);Kr6 z=W&N)mHRK#tFcQ{V&}C;8f>Iap{}}Z(K`LPS$gYHRBuN4^pflz-%wBQHLi`}>0+B~ z4z6m)mLSbavUG~z`9rZrucQY*0v=PaAKU9a<{hbX!tDVwmhPHwD<7fq9p8F}!adHh z=;DCcQG9ybCrv#kE-7*%TW7pTx`T19+rpu7w6&&!;d@NIpyJkrqdZr`=g*h**0)9L z@69(SjEH@GS!(szBj=h?ti72nXJ9o3Smm}TkqST)%O8gb7YvjEYUE<#;?ol(-zbK9(xT92POy^4J?Dk1` z*)CyjQ4z>YpL?@WKcF0BG%2UdW1MpDu>6LiMZIdaL5rAS0NSj0fvtJ}u12DYCE<~G z`}|Uu#C|tHf@U?98QrduR+{);k?x)d(Gj)vVo)GSo=8pamgbUuz%n`|mzRh+r+e}| zb@-iUvAPQtWKY}1D$ebF|Ft-(9QSAdUG?W!o7CtseL0Vd{u3Aq4C=2Q6!I5VpnV}X6fAWXfer@*UBqa1Asd?b*od$)YuqgwzIs+Zu4@B&G zj!o~07}^wKcqLmUPk*bbKX7;A6iw-Z`41~zwa+{~Lb`Q|zLPX`0PU@XD{L-^EEF~Z zgdjUyh;jrwF=!$ntPlK4kYA1Meb|7Q`$0jZ z0WcNxrzGHQak>e3m?MqgqJhl<@{3_*fgPgyR6Aus(W{W!x95#fjer&5br9_hV$b5> zy4J%60ZgRON&d-3N+o)51^P*Fio6^(w<-V`@+}#!>{jCkW043K6!>6%QiW zhM_qc!GYkLBT44zaoLnG(`i4rLZv#(BZN~SokL|=y*n*x35nvsLsHU$^9~fIF+Yj)ctG4HY%SAUa3e|}lpCpL0ZlawOb{^nZ;o7F9k!1{y!W7D zMzXMBX;L~|jhnvDYSq9Hx~&!jDcaX>7eiMnq@-shLZzzgV>}i3yHgolgsVP!r^5e%3`+}}5p+0{Mv9SPET@U-3bCFSz>Hk)h#FL00OSgqx z9puvG-xTTNKmG&A54PJ8zl2l0;kV&Yvv74P#E(g}B0-P;i_9$vQW4#v8^MeXONTNT zpJ)ZU`mUcEoj-fQ6lG3(NM@o?Fo zCI$8FZ|}BRT`InK!HPdpZ}V|Z0w%&p`L$``J`u;xl%JoU){$_o=SKYhYXNd|1O)|4 zN=uO-NeB*?@|RpZa-jvt7r}8ModTsW0h(vvOMevPKW~CWDRv=XSrPE;zw%&&U_?Md z<=wtGE`Q~=h557WLe3aT5t|OZy&(@KHbSej3|VN5W|KZgY@Qk^Q58j+NPNQfBb8Lu z5sNFP#e^{?*z(F595W$c!tsWkES>aFL8*7}kKs#;T&oQ;Ys}A6}Ao7 zWPIayIfL1lS$JzH3xY=EZ{G$J zzuaUybba+LDN&)nGWY`SPncQo_w(9mddb_=*@H?6?s#EIyI(l=kL7Ppo)UTQ*f_`= znf+VG{#g9(&aX+0-vRnJ=F{iBTh?ma$&O2Us;M*zk&{D5!aK+t0wd&$FL0~1T0%1ZS*z&2=B(5T{iaY z!6Xe&GDvT{y>?*t0Ml+nYAnHO!|5cn*00H>jn-C>di#m=P%8Khg{8LWT9`_5@Bp!& zJd9lCRJnYEPJ;8RmeY} zA5=n31a>TC(?62gFm+xqyOIhWT8n%7a{iW$IjiEoa@peI*F*6}gKpw0Ri_mwA7G;q zp}N;A{x+?l;AwTuf@Xg4(RCJ`t#OI^*Mq_A_It^8m#}pj;vZMHg-J@2PfLwk}9&#QbgqzXG+wj8Bg zFjD@ro&17DpFLrzqaK6_Iu`o~6dn>ROj!|M(K!iaaj>lIPGbN_hF>0ai$ z-0vR`Bc(PnX5I+dd|!U&qWmvoYidooOnvc=?y<4sIO}--zXT4gm`7`Vy4>Z|p?kAu zW&|#^YD^Q^48H$;Z~4Xj>bLo=cNaFvYex1yv+M>3GBIe&MD(AIPYj-kir#yLF?=A| zC>w1Rb{~^utKvvjb!wjeVb7V16aCd^gzjTeC8{+BP7_`xMw8`3BOU&~17aG_(94jc zB3)vg8$Q}m6Y0^35BkX1nBI$NXJ4whqn#B`{B{z@W)nAX)u466tSXMBr=@KnOn9#; z`I+*`JKA~YTXVm3%%K~ObqGB-zzQA61+OGf(C^l5-cIm1dV~I$#v01#RWTN$!mpA_O3z8k`p(3ZhzTOWyD*bHch(%8PQH+VnFld^VBrOL01CBi;IIkj zOo&Iho+i;i9=^V#*o72;TOWM2{)9B71uf`VH$kunkVr_MEKK4l#8nRFIkQbqPK$!y52ws2RjS4pPug)@_n@i@XWU729YwOeE)+jM^aH)XU5+t}NK~Yf=j^#5H zo$xRApFA{tGU)>sr#6V7xhs z>Ut*hi~*i#Or#f{*Rqi&8Eiisa7C+=6er+y(2aPttn$B1f)_y%liBzd^vWnP8$8f& z4h|TiqiOboQ!b~8WCv&#EF%UD<{z{_mGW8zd^;ltc3yyO|0>vYlUYM`4JHqvFSbyEDVSvPGNvtD;Zn)AV#TEC#whpxVR^$GoFXlGzzDadA+eN z(ZMS0RI6VVuD$qOQ}AZaxL4@3>}Uqds8?5r!RRl%yV6^xv1PNWQ)Sxyw@a_I5Pr_^ z>->4h{?s`WsIVqQ8uSfruk68ODn@y&+J6=6`A@#lZa=!idfQZ9>-vND>7EnlBHq_mEA4kEI4Yly|Zie=E)^kTV{Ekr@fzrNu79d4A|~dF6MWcV4?@ zjLd{beuwXcKcAj9fDxek_)K zg1O;ZJn;_m8;1V9_?=h8-y@{jlrqgWjE`=$4;L;OV_M^-LKuX4Z@!o$jf>(*Naeit z3NoiLtJ*ec`~JAJ<I+WDAGpWM96p%SSYKF$|Bt-Sv%>hmX?D z!6+b2-UlVL#k1$2(1(#HiC$dfoK`j^paxD}eCe!+*>vTNWW)K_PP;o;8*e=hP+-<;#K|iyXs3F#{S0bZ?k(T6z!|Z zcDNiODaP|bXS={CU1}oD5W~as+P(2Cll+E{%=#n$eKX7)n&8ewS&!bDEp(~hq-7Q$ zrL>PvjhDkay^*<;ykE_uL4Vr8o{;ib?_&Z*sSZ}6f0yk52ST=FXUi9nW8sOYF3+aZk_pFp#pWk?oLSbT&=nG@wL$1UB3D@7zeRyjd`A=b*RH;46Y8THKb#M@Il~sS@5-u&s9IYMaqGaqM8Vw93gT_^6IlRI7qPE%leVSeINu2$jZ-064?U_P{uCFWd6di0RoN@3pSfQ+cVW@ z4GfCZO)Wl}?ck#Re3&^2&5z6^(Vk)en51w27LS?{qBIP(+e;O-6x)h zigtt>g1+?tZM$3OhJb!tE#$u}*;=?lSPA?+7)RvupqN;{Hwzvrcp+Wgq98J=@|bjD zse%LZrrMI+{}uGcH^FcR(=Q+nV8$|gUIuFotPyS!fZlWm0klJrz;P0S1~U}=0Bb-L zG*Hh0Umv0tVM(EYRRu;z7&QR<*N8+on8Ux%F%cfaVsE^dP0a8gMJ@_AZpSFHQ zs#)P~vT<^L0#rm;zHQO zp7X`yuY<@N6x8NU&>6!D+!@l}GBLpgAl&=<+4X=;b38f-M9)~y#8h_J^w`Way`La0 zZQbo>Nh+0%Lr=jHco&7l1R#;1JBFMCX8%4(ggg$O^4eX=9djMyc%@rT<9Qm_MP9;~ zFh1~9#T3(<>u9Bi?I?#Cepold+RQJnPkWzhmX=LZnc%5Y0l1msAZyS$IxS zS+Mc3;Dpd0rd*v^&(EqpHzV>D(>xnwKOLt*A8k7;mLvH14dSOPEpE z!z|S{LzW0x<%CMwUsnA%>4#6RH=6%>RMYdvad#;@NB6)cR`KwZ`xc4Zt-M>P1kx2l ztJudRD`7{UNiMeBs~44!NG}b~EAvg1^cU-svLgZSu$U7ul1@>fSGzyr8|Saw<^zU{ z{f~KPHf1YBA3-K5wF62}fju|uVv8y(xtP~Nm_B`^W^X!V@U{a;781>MGefkj3Br~;~7fd=%TzBD_@gulYSZ$DVq zX1F2>*+?vOiXYS`Z=JtI|Ia6s3++<+NV)SISstcc<%ExJMe{9R-cPcx!|Akpqqfe| zk}vo11s8<(Fmf|AcwS!k@IcCL^&I6f`OKNdWEY)$X3;AIn+s@;OE2VxPNhcOMzzli z)p<;kTk$?=<+OUmKNTY<;h2g3%5dlIb^hvaRtC`*BsV_@cvUXF%Z&6&ZndDo+qUxc z;g{0cXqRS`IZ?@}d;?1fTuE)xDJ0bt=wjWY&y}I_zB>aZlF2cK(bvC7^al}Y-iHkf zuxJ*MQ7ZCCp4-tPNljRi2)i+$BCflFKcn*EhJVkRTO+RFx2qI-Es=lv*V2iC== z&E8nXup2pv)Nc`K8F_;}VKE}K_IM3;dT@b^*NyNH7 z>xo-r)>k;fS>4s!L_giO<>YsK9bkzgytd8cU)1nXer#i$;h$!?9K`i~)v|Bx+ci(v zZOrTK6uz>^kH3`B`sV%Yxc!N$jAHboK;PR5k1NV2k01GdwG-`?S{7-H&HjGAc+z_k zh_;Zw42Shxbca9mJOq5w@KP2bJ@wR+$49d)MDJ)N!~(-@Uko>NNa7lInsglN4&~wEUt*cG9pBP4YFI*GYPF zQ7eBd{X%_a0!Df3w`++0UIFVe>0`VzWwGxt&9fo8(REkG5qlH^ulz;sk2CYbT23>^#|AFW{&G~dEiu~{^=<+KQsXr!J4GBtfLG)h>y&r_bCa7p1E;YgtN*H0 zQy;s4ugb#pOX6@bFzo0C5^hSYhW-V>*dbEmol4_4IAnlk0gVMPEpVO%4FH6(S&CEG z)9TS1Po)waTG^25DoybeD1d;^YI}jVFc^>wx18a|Ml^gnLx=~^JTUgYpB&+Vkq!TV z#D%~ls`i>DM@kz&xdGx1*ihiuiSY+Skl>cruHE#Iz=z0SfKEa(sv+oi>LUy^xmZAV{3TyXN7%M6 zvuYfJJqi$ntRzQ5_Fw#`f+Rbv9?(%on)7;<1{744BrQ^_3vMIeqmV#ckQjNNgWUzG5`(EGCJ3R0Y@V>Vvb(9{ zs2c8SP%@i{v4Ex+Ij4i&XzDq1y8>PWw*~AqQicUrcwG#25p@l$nq~Azo(UiK4kbV+ z)b{_?C%~9Q1ha@;2ewya2lWWu8~gS5ZyN|hR)8n!f!$$y?reP&d|{}2^$hGIRex_e zcbL*M&+aA#nhdx)2#M&ExySKe&1g!O6kEx_0@SXNfF>C37lP%mMZn%h^mZtD0;x||e;X#1)SX#Pi zY8ZY8>!hqZDhrpc7O}u8UAAasEy%6LSSZ7eBbUAtnWc#EIyMO> zVy06a89G8KR2nLEhVm5KL%ZD5{3%NK|O#K5;#Anjo)x(pmhcCxxR&4@bG!gf8m5T06bACR(GgCth8jE*iyHw z6&(PY8ldcGCj@r%^O#4MWfSnox)02v%G5hx5MeV0sXBsoy1U2h4FGHcE0T66IDZi} zH6Ut{|3lP!fMdP?|KqpY9%W|lO|nBWZV_%2QL?i~wq#`8$jZ!?LLn{Lqhzm)vKq3> zO7`CTpYQYeeXswy&bdyDkLP1dXNFb~tbyWZChE$@KD>K_+~HsV&<7F) z@&`1#EC*TQ>5O12)jL&~YQ4r5Ukq;{5vj4C4uvcbM{OC`4BJNhRS5d_rvNaufX)~+ z%HSmpH^~>Y#)wZ9*2csnqa3!(6P`&6yttRD566Tls61E1>xnL`LV7wX)M%!zb?*rm zLI`3Q5J?*B{tx-WyBLxwwm6QOIUsMR;ZQy3>BP^4bo`VXxJTiYWp>(+o0q&jM%kPR zDl+KfFsyAa^xl%!3imjwTT&KZcqPKsZ}cZ@p(9~D#^)zzm-2M8D}l*$jg+~#iR2x< zq-%93_6lQHk^wx-98jMA^#PY+NilyTVZ z6b{Fb;QpZ;3FI~{Ny<1=Bt#R+>TtpIy%@Hk_Ffg!nR}Jlrxjw!?-V=A-rElISMoQZ z7%R0xeOd$yek6W69~S#e`-o(cp=(ZPg1+fhUPcgkMt@ZrEFQ`6++mH( z`gqS$va2@3q?Ue~wtNReBp~lS$FQJtZj`7BZ#%p#vAJXS7IO#_uj(chx`Z~m_lt4u z>Uo<`{ZRLSki;Cj4u6d$>j+XWe#**jdbN|%{@udM}sqhR(c6*Y)yhr7GIS1!y+p!VHFF%>t$K6KpI)0NfdmMxv+O>O; zNStza;5yop4<$VHU}M@sYw*eZu=Lzz%S<_q6iSJ($0?}9qwz1MNh{Mk?k@w)R@c(7 zn>U_0-Sd2RH2R(WthoKAUN1B8uKCwurm@Z@iGv(h-PL&~QDK$T<2171)!oEq+ol1_ z@>KV);s>n60NECdqYDF>{2vI+c~MkKM%rk3HHO*F}Be-{c3staxvn5|Hp%5)sPrB~h%EJEiiL>Xbj#W7lU-Xu8O|Nk@Q3>>V%hzbZ#$ z#ROcsQxV8KbeK|Q)53}DKg!_sBUWjs7C>Yd?w{6?5d&Hfz&C)Bz=n(*R}mX}sLqxw z`E{;pTJ&PSVZRgK|7ihOXi**>9yqxKPv|#)3Z+vB`wi=obtr234GjYzkB0L<`~{(6 zz}h1!$>6Pgj^E%(qA=zcYmhU^q^GbNm4{6G9^V*XXf&va*Ui806NS z93S?+yAN^BNg^iTb^0{~_sc&2aC!2?6)8T4l~+fsSVOe(VTE!l;)z3-E?MlZj3a4; z6)ezD0;EV7Di6MbET+K4zGqR8%XK+PKaEl=`L|vXw#%DiVm<_4;nKruNE+ZzSs$&OfNS&}C z)Hc^L?wH>CO0%DX1o42hsMwGk)Ypj88cgJ|pF63;|A3hds1A@rBev}S37w~b7(^%x z(8dBMm4&AxbY4*r@ELfurC!B0^}|mAx~^9Zyn`sCHU+FLG`kY1;s5Y~MQkQva#QDw zP2o7TU>s^%S{9Y`F92tE`KH!yQ1tq(w=)=YqNn7=I|>3(+gb1=+i!DE-2}Gk&g6nO zMCdUsy{ua4A`v>iX&6j{3fG@q{bDc0=a0pfGwOrnS|Mks?AdjJ_Bc66n}*HZ!{-Hj ztJl3xz@Y^c4y>1uxMskX1uMV5bYx9$ZD!G&X%p3(jz;a-qz=mv#gG$pbV!ErQT#2( zNG=ceir}LO+0i|ZP{hmz%#UNJ)wpi{LEXa2H<3PQ{X*E~`hwW`!C~@n!bOt zkf3kOI1+n_gXRmWLS#M<)FsJAs4JdO%<20L=gZKgdN#|Q<0Ns>yG8gO9j{_ZCw<}C z4cYvrVk3n=(XIy=LAyL1R6Z)(z;U;EI6~<#H^N+^=NE><*n9Zwb1hI^fVe= zpsK;i+-|MOcJuWFk-CqD9qj^6S5-a5O`65>J~w9d9^aB1cHRr2F1f#*d`W{fMgAl@ z{OGpvYJEmVz#Jc?VI|3wGFZR(C9P?O_KE$Yl%k?xlo}{0IPM?z^z3b-t5Fw6XGPF^t5r)Ec#a)e) zuylrd?}DYt)MwG;e&6Lsws}I16tm0E7Ds{y$i525HBM8ZwF2MO>(4wHX}>cn)>LpI zGL%-c_-omP&+nbpEa=*H^Ae@yqV3uwy<91%2H4HoLLclue{1(+c{cI|b6TwaCj%FU zV)-hkrzQ7;6B{;9R@klf6y8vpnj{+Q8Q%XntC7=5Oj!`(-T1iVp=Ey0k9Va>FwmyIvqbzX>CxJ-B>;Vkc~m5=&^Zf4tLAyargwvacb;ZC1uT`eQ_c>bBzXC`)#64UFi9r-{EFLHHTAHPhBGS4K?1R2I#LXHI8&yF*ff ze7;AliShFpFZ6I9=HZDLeY3NRqyD+It2=*SVlZYgmj3##PlI8?e5ls+32?tY#|Q{!^e)gIIh`hdk-oWB*uJ(MPXLpWI7IoO>6f*gwX5OSz@r zui1R8;l;;@-@zK44^TxMoph9yGmA9jTTyJA@60|#{=f_43{}U8&|0_k*5!DLIC%A| zgbBvwJ!=eqr(G@7+CWqanO!a+;(8?4aJ(c`i~`TzpQ9+tTr=adL8%+25EC4jT$DZ{ zW6?QN!gSBehwFgh=S9lHYULJGx6z$e)ks-ErOv)H%?$$%!gKFLY27BLU(K0nHf-~j z&b2lePR;Lp)%HO3t*ts?^bf{3^BjI!Y!6>d`t;WBl#}<+x^Q0zMMuA(pOKk+1tgm=ELieY}4)>K#=pB~@iP{ux3J;?Oe@Mqcmq|*>7@LThc9jzji zGsJB3b7vvqu^iU2GHuLI#d_Wr5A~fuheFJBL4B-gt)l8Y>8JSfrK$XyS_b#y%iN3I zC{Aw$7P_20VK6=SLJ32Qs_XkpW%yo-GLs~-$7xpSOv$;y7iuJRXSp4i8v?t>^-3hVnD#9SmuGB33 z$CL09I4t^YbP22%y9bdY(RaqiP_Bb~nuFkmELBZJs4W@X+sGb25UFYhA_b0hU{vrp zIr4{z3;rq_h*L$Ae*M(i)foA`a<< zDCp7zM@G>Ja$>SAY1DqHN`DUb^ z>b`dGEkIDPrGgs{q6Yv};K4?u4=f)*S%Boh0>cu%ct(*S4NYr^iWYi7fmFJ)-+dc7#s4QNLNpaf&-#Cz4BCxb+Q`&pfAE*f{%8UA4luF6 zwH~}!6HI;zG9PrINbCTjrg*UiYUrtW*@-5IDg?l|E*r8bi(D`m=#fx9utqb1sRdXx zfKp8j5tne7jlxfc=4Yl!Z#ZsU?NS zgG9E~Bc14kNAXF1DHVMtPtJd7cvp~@ydpCH5 zNU#r}1%L#|t_1d#TokHE8^$-=|0E+IveJMxC9HLjv^vmKBkB~u8~`{F#)kBJ!0w8Q z^Ow9)*u)_%5n!|y+W8D*z`gme&*23E&+`@7aKVzt_)iw@b_b)v_BR8+-w_NzKfter z>JOCPC@+o?dwEdqlDvGkjif~0fZu&6$U?9&KyXD469CpAD9>_@quDlR_Jz$Kz*j_c z;#C8LhTn9&EQnM7ODwp5KTYL_^mPS6Y)7R9l64bs7mVx0hJd4cKdR$qU|k0k9B^f& zm49I!2wWrl=45FQxelC+nwDuMqZCzyAFIFg(MM`-sB{DJ$oiPR3Vy|U)|D6Qzwi{f`*N& zpX=sdbaSsu8j<0^6((XHr{8hS;`Ahif}cA$%k@Oc_nWfMMB=f|>eCs~iChulBu;V+ zS0k9cNT|crLJHRW4x+#4aLlhLj2-J#SQEeKV0yiVb=L3C-v64#9_lmWp=clKnW(<* z7Yi2p@NJ%cJ~aj3+r{{7qg8km$#NJoF~5_i9>Ju3^MjFWi=&iWi$hMY#SU}5S{W9X zE`m4BiLK^`ml)2Pe0-qy%jV|4y`>LXVe97{NxIT6)wSJyHRVE*jQ>FnI5e1?o)G&Wbc9Ut{(z3F_~`gy8ai$jFUmO43KDFI7?Ry{cz#OYPMMA9HrcWPLrB8Nh{eMat5@8no#h@KdT-YK z^96O9?K}50(XgXex}Sc&e{8!bX;9KYVXb4;b@`17xq|)+YI8Xnb$`7#gLpL0jASIA z83mA$(p__T@`OoAbzL#3(cp5yk)Mnm^BSJeeIH@_2{z0slfmj^^qmh>=SN9wlLO-P%o{hUpZi}a8*?1-I`AQDYctfa0Kgm>l3KegMpvPJ3mEXkT zIYpcXh7Au6Ui?rR%GlX%|NeT|arRX5j-Bm7({>u#&a*x%H6#=(73bMtMnA8Lqub1^ z5BjpHOX;z7Yj*L*0gG+I#n+Rymu5aNO=^TJDGE-M?p~O?>1|G}v3-KwL$_bV$EaSq zEa~QQM#pkKQW$sr-L(i6$63*=7%`OsZ1ArH199dXwx=dUDrXAO4elRB_xVg^t1X|C z=WvteRk3AM-Eb4B;*@gU+c_6;bGmS3@-RYLlU<+iTg`{fXXByXKK2XuT+%$Ro{ztI z*(Y8Xmv}GxCVp*6!=zwNUe6~Hl3h7Px%;6muR?^%R#h`UU({Ca57KeZ>nCRM-kjij zBsQ?Qe`EW=?T&%VIyv!zL@!BWcR;|*?B?$eH|<5L54Rszdp-?rNVer6Z+$iYWILQz z(G>MbiKpXY3iEVRs~KIy=ULXFz@!RiBT_~3Ha!xmhZ4B66xP0P2+f#we>0G!iBtsA zl!u&YGhr3;s;|1ddFjBv>eKYrNK!5KiMPFy^knHcG_K=&v!AqoAP9c;aHDUh^_xik z+p*P)M%{aOhATn3CH_x?s~7x4G66Ee z+@l!*g!xApZ{*kvpQ9-8o?&FY0&9+JS@)5ep15X2KLH2W-(3Q^Z6GRK@0IGCI-ERJ z0{Osyf9}nadR+~G$%dcCh5|{SeaEk5yno(0;1ZA^VEcjV`+xCxC^-m&hg}bBCkPAQ zJruBP79haDz=tkG<)0Tq!$72oBnJbjo_^`O$ut~UIW3v7IA$9=Mj^)&SjkiSu1@@y z2In5MXbL-f$WdX2g$XQt7;73}AvmYHD7R&*Z=}PB?o-&LSea~0gsy9Zp$F49 z$Y>ysuNKm8p=%s?|IBSyus(sy9Z^6qGB&|2M5M^+I9^VAY~tgu7x3`lHUn6I#ggah zgyPcbsuUFj+dN~!fxrNMvk|joPx@^UdT{4xHz~pVLGT|SpEZ`obtJF&KVoS1b}(Vc zmPW`!?@ym|sTmCvbxrx?0!v02kARfBE@-wxwS$FS~Tu4?bF+cT-$};ZJdJ?i&$HS@!87C z$PCkW)g;35gC5#FaD z3x-Q>^Xzqb9CA<;@<8O?K9^3(h2s2_B(nlLOnL7EHg9Xt(#B8=*;{Ha86{hH=FkZk zmM5ab4Y`N9)%Zt5XT*8PwT}m)HeRl_4NoyW71>ko9%kyqy<|eElh-;qrkKA-wk-FS z>t*LDoR1q2Y0r||mxAUEapLcs7w8-^AmGhJiAo=J1$Xb`iI%@s@=vl<5}%jv!{`ij zr-u0%^B6u(o=Z)ZbTDKWrMS04J4+R#%Xl@qg*8mv8mmp@S}JY$x!H&4egVeQyOsNd zx8+yzGUg^Lv5UdF%GSxsZq`!5x3c=aKFqHN3N^bV#2*^1f2W}Pw$|LD)^PI>tt`?)JyYwaf$5x)LvrBoXWeX0n)%X-X6C2!OVMY`>xSL>M3+na&7WTOCj&vsIjp(qlv(dR!t~n8neQx=jOS?UUuzx^qF8#=F*|$J$b{}m}I=8r`oZJnc4$^qO;D!CANz?H&Zf~ zJk#vv9L=hzY;Me5-dDeSh{KC>Gc)MkzN}1CV1JH%dq$`EwjOhnQ*6(KYO}<|BQ5Wc zA)M~z9}YoEiT=H90=(}TKkzj=bdcP&Kk2K%$73{zDjG3Q;51g|vcL1khD$;Jo$}EAO5BsBdm}E~WS~)L9 zg*ac+waK;n9_C45dZeJ;SFKdRNsB zs*Vdn#p*TFnq%;cFE)lzU-?3?(lSE}j_I9Gs zhm}DVOVV-`b&VkU`OV}9)f-|e*cKB3WP28y_7%Ddm zA@9Ac{sIoYjs0s%5P-8If4y_zuUf;D---9riMt2bCEof8Qi-DdF4y-zKUh_n9G`C@ z645S9&ip$Z>nqP@&knNH*RI9)8B)%6<=o)*0N0H!+xb}$Jj%G|P3z$Jto#84KLwpU zh*c0fsu)=*eAvM`6m+E!zBcuzJr-QK|5ZF&mwm?j3nVgPrUA;Jq~YMMR;1`7Zm120 z(2?~PHP%s_VWEDgzHqxvDgYy>{Tl;YaX3tN`!%F`5eNlP#(vd2Hhm>9qMG&?8L1e#3=BW)V?e84_yN&pFAvq3c8>k36 z8f`pgnd}6v2fz#>0r{VN0m*uSjAATJI$H{bFwi|PjbPia66VRuliSCWU_&$ypZn=1 z$ifEBu)r0-#vf#_a7%hlk-DKr+;ClR*oBPWu{vK$kS8xTj=M=^&QDFDAn+9!5yW6s z(FQ*S7@qtAM~_jkDJcbqgmCbl$6|6IM#D!dIRe5!0N_FJJ_3(G(+Z0KBeXQ=H>RTA zSAh6d@X>H&S8xnAYDNf{9bgc~vr*KeiV`c^Ad7}U2v-hv5{UW$xrnaBBxokn|MIHW zSu89R<*EZlMKBTcIKh1j57me8yuG7&1eJ4iD4yR+`oIdRKWZWLj=T=q)&Z zfnShYL-|$npu;tVl&w8qd@6J=R6B`ye_n-agSC*ZM{CfXj`O*~XP>{!8x|Gi>EG_W zx*k`y5uD1feNH~A+Rpzq1-yblWeRs6I5(ucw5bWBJF0lyJqOsW7{DGVdL#8F;f;HM zevl^zbWh+5Ds5=^T3%<%0lE=H`}9AvJMvlqnbPzk$eaQ7LNJe1%Jpm4B=*+e6%Qhf zCIB~pUJ(O5ycs}F1D0bDp+g^bHeMZEfJ-j0T7XxVR!RERINRZc4EMa6Wk18HjzkaZ zlBp$xv}wP8kJQN{_isHhBn}+esYm5M~33#5$T-?Fv)-Q|oq9-E+ zMNEpy0Bi!sWM(QfPo8967Q%9X4hT@Ie%^g_yHd1ka-bpLm*9|_+>KbFN8F&FhnE;s zTHOCK#9JDVbBDwr@eavmBqCs4B6CSK)53h%10zZPlzYvHwN4`JL^7!z-RQ0UK#X5p zM+cLohHGKX){1=I^_MXw#vs%Z{g`?!QaNVtI*RSt-V_fZ6X94(XMv!&t6U(F{MQT2 z0i0QXL4QL{3@nOzrs)zK_^wfDG-j?O!QJm$Cw11oCiU%J{mpDf86@`nuu=t5AnOcR~Q)@jf z4BkB=c`ZXu1~bY*Tqj0I>^`=WIOkb!?Z)0CyRT&{PwWgOIij)O%kceMr~+{0gS4AQ z-7D%71!5f7c-@?eUypz)Lw^91PL-aAiUA?NiR}53v?YN`A$IkM7 zcQEr0`XCu95t1!LT!;yNgc9)1*$CCmXJl#pZl&NDdz4EZ8uZJaMpIyOO+=sf8l&84 zfkNJow4pG$mTv+SY?*OKk2e!Lz?s3`>%{oVveLj{h=6~{O+nl2RExFlrKNJ1DQVC(p|)ZvA}t;LYuw)3Y-RC|fH= z32`xsCGylU_D49o3HE|XrIF1?qjFx2UN$B5x6x69!)KXGm|pQ_vGHv(!+~q8IebvM z%kblMOUAtEW2&lfeROIH`mZhClW#Ilf&`6PG6IG7IXvGx_HB*0d^|3sDDdEZy*i=H zm=o*AQh+P0cjWA_rDk9JWwhY&q4Ltd>G2D1Vz7@?G}h+(Pv1mkFf^R~6I}32`{!e8 z?&;%&)tv`fmzM_WZS}JnQ#C%0D|*DCj7~T?{!a^FC(Zu=XFPJ+LovJ8Z3nJEl~w`vhxg{AEr-fxpF33$ z*eIL9UwW!~xGs^hx6gy0DSuruCivY0|CwBUp$YZ8QhHhX7{+Qo&D5>J?Te|zx&MCgPv1#pk@4Jk6 zb%IhK~)EhqZn1^c;Hz6 zOPB{u0jwn|R;dIX-~fnZngCBsLAr%%;-uB`qHb;ca#z2x(=!e}dx_F+eDqyqM?&lW zD;hxZcR?r!hygxyi5RF=$tB7_EDLHsXrxWHEJM;O!`ma`of~5;-OtKuUP_YQtV0$-v+wdnt~89e7kLA5af@bYlSE_ zm=taS)+CjD z_Vu&Mm9Dy$; z4GqO(*Kn}6_W)H9QOX4|v1!CS3>;fuurJ&rfF6Lx7+G0ued<7;0aOa?ah^j{`|l_Y zd*zLAjw956dA*1c`zqteR35=~bi*W#M{EZX3Z4UOe4q4O$-8%@A~wZ_HaON_%6P$x z+w$Q9kfmZNZJxon^LIk9xTHi1|9pHJq92!&gI;ZiB=;XR+y6%Ecec?{kGEd-W_0jn zz4%OYjW56$-eP!vDyGRS=gn_2cqyq5zWjD4k;75xY1haZ!o_lqR+Py8Gb5Esk`u|d zS@_+5d3W?PRB&ohB-cn>tsnAV$-AIOhLvBl2^F#;i*C_TDUG!xh(=!#OvZUn2{P6d zKVwbunj#?8DXT@1B{|HKo!zikpw%aHBw||h@~vOY8F*`5a-;m2Z+i_3z-Er`7Y*;w!>xyO#G8faNq_-M=oRJh?yKpZ{>9eyX zuFHMZmb;t(Jg!<&ON&eVrqrJh)qNVq=Cyh+3Nv0lpRU>ArMmoIop+;c+Og)HdLF48 zde>Wue_pKccX-cvw=+oAxQ_dfiwfI8Cf$sN5=DaW)J8?#TAH}!_l_K zzv}Y#i`VyQUZLKbeItGfhbwBkf%>N3ShWJ?!JN-zpKg85eBFK1Rv42RA7r;QywTfwIWZ^QtKB{w*la!N_ z#bfztR|b>oU%ihSzv!*aBfp~ki**Y9m9NVD8?LU6S0jzvJdUIvWhJ@JLM}Xn!%}$v z>8NT8>q%}yM+<3Jzr}=OE`^qF^r>(vK78JDuu<-k!*Nk_;xV4qpazrYu36(ZVzV=X zXNs3MpAL+mwP?@K-u2_GKK$Y>b?|tyVprX!I3?BIqx3W$UtWQ}-v8fyoz=~o|MJo8 z(=2!oYR%fr1Tu%v?5a*7Q?}QIqFG49xSQwDe%;GFF3Cr1qi@~$3q?p$yX{$Sem<6~ zt8A*qx$5FyM@t;CS{>3V_vzIn$)x?-i0}>?xWu>NB1h>J(VAFKH)^Mr?JMzv-20>nR6{i5UD>ZPD3d%ar7(}@Q!Bvcail~W{}GMX8umvce_+)%)Ie zH8rU+l}NMtnsB^@Z`{oKbg9OPiI`9Gm-x z)q~^ux1z_Ym?7fjWB#R2eG|%#q{T!19~mOIMb6~mhq`J?<5hC05kxam-7OKCv1s3O zk5PAX*=CQCW8_z&ds*ebH#kP_RKtGHlDInY@gJ=g>5p@~J{3f%kC;-DwV3|o`P7{$ z-W7Q1S4V%)%Q(JtZYwL{`OHGF3$w|h`JlGXjz!&ty-J;KH#`;f!v;+eJItq`f}_wRL)(MXqWd533jm$MKb1hq0o4_-JWWlU$+ ziaz{F_}@k&cv?0XAL$5=0Xp35qc@Vl3z?lNF1*=QpFU9(Uqq5QkbMs1iZmv)Mp4?p zpCPLLG!iI|qqQjIHrV2?!)cIJOX#81XB`u8D64=r09u0nlQ)!{{3}@lMq?Cg4SQX> z!D0W4yM>_)2mojn6`=@-)CF<_rG9W1bfe8d;Fc`pr(~0V2;KCrl)Wzy z1UAN^s9OI`eo(%8E{|NaH^-+S37;6Mf@!_BNM`HMFz@qBX!s#~yT}0;q z?7If&J{^=cnG|-0ZII|S(32qRm)&t+B-Ir3C`iZ)d>v7d0=W*Cj;!O9A)QSE9x51( zbp!vy%vTwq_L4gf5}_kZ{@>0RiqVK zQ^h5iK#xcKC8f>_=iSlXkUOFow4SXF(|BfgT&qlg7#aPpbn@Y^EMDt3)#K-fPYEb^ z^Ck7!^u{>z{VEJPW=nZx zN=E|pdCZ^*&Rp0?uK#;mVh!jS02u;yp*;+T>&pq6yE*pkr`fE)p&N5{Vd z#|*fPKqdXadg;fAgaA!b#!kxVVdu}g7r~8Xe~_J-IprVQcQV%*yK;#Nr*_J@xN>R> z@bM_;YemLPNuP}7Jdckq+IKMc^ib*TGiCPylWB;;6Y1h?n}IQ_MnCRP`8}mO!Cf~WWzse%_HS zp)H)m65TW+V!WQ?jQ3hF>viv+0+}Y_&b#>H_Xr*mnk?0O@PGPgdp4UUqAr8uc+@R~ z1*9-mdXxrzOgb=XPmaShD zGo~ms9~?W+h1ZSgse8icD-x}vt!a@jgTZ_`Sw6gk=~ax8DL;I=m2D$GK<}#Nsb-{3 zXKm=2htkqKjBye(FD{;Ux^pmKYD9z!#-7vKKw)}?A5r0x4g$XvL6?;_w>hcM7gK>uv!>D=fm-reicF)_Z*2Xs8Hv{ zvEXBA&D0;i3dlI}AT+E*`o1ETS44`+l-$tv^kGy8o%Ax8>Q|vao4E zGZ%v7bE~%+C{5N%THE}2PX#;lPX|z`xb&%7JLd6oW<%>sPq4&!=Hs|p-u{jq(=WwS zw`k*s$fyPrvCd)-5b1(N-q*NT1cza7SO%l}zzUG;HqrAJWeA^-QH)u_5`{&jWV#u|5;;pd9u zm|BUdx2qp_MXOOhPuD~G&!^py-BRvkU%qtn_6Kv0^`-@JY_{5cPn@?^f4#nwdEx#v z$DNq*>+70cr{`i$8V)aajZl|zer`$$r7so986gTL)FhX8AUbpAi%L$n0IOrxU3Ebc zC)%dL^5~YZV;j;lq;~U`Xxz7#XDJTd(9C_)Vtx2^IQy0S>pIH5JS{Z0N;~=c1_F0i zpWM?sUN3#+x|FxBc_{JYA}W4Wa#-vo+iBQgiaaVC#HASj&nnn4hj3U(PL(;0gWSj$0+lC+|WwY2j2?q`tSEX z`d7R)4LJ-A>UUM1^l0Frz2_d%Fu8r^Q(ADR#-{gGPD3ybvyo5_@4ceZAmdI-GV$N! z!Xql;io|q&o!P*NqTdh}Kfz6eV(_o1%{3S}lgOdy*YmU;9r>s#!&2X#?-ogZxpz#ro4FZ1&gUqXCnS# z9!pi3ag^uuNhsU!#9SZKM-DylfTi)8XS4=xvK08REq085Sf1rOSEEq0Pz_7xgVQ9l zQOKzTM4aXrPl2Fz{E(Y8#1n*k{YXRa$xHu$k z{&#EC^VAl_-LY1hR21UdBwYj-Cy)2o>vP9}3Xr?ftvm_y~^lpqND{0c2tQ2#F>G_buYEMY1;$0ALz>{H5fxuVB#w}`I!$>pMQP-Q(CJXqgY+bar-pH2WU|{~ z!vc&uB-JGV4$JsuiR7h%v=Z51%&x(<6FiY5q{L zgM$MkR1Xnx0-8uv*w74XFNSCPc@(>~I%Bd;&#V{X?FAz$Om`31uB=!tcr!zXVIei3 zGI*^$zFs5&4qNcE0@Gq&@j+~w1AFHz1;rF%1%{|N&y}%Dh+1;*`<>%kfxC5+?eKt3 zW^_*oV1I_REFy|zgaScSuJ7+OCIG+@rx*ZpG~xn>WfWx7!@vgQsSLNkW3_%4NG2%~ zSOs!DyMAx-Y#0iz2cmgVag`&8;OK*!o13Ho>lDgYg$kGRS^SkzJaWfxY{xgT@TzJl zX<8=g@V6$vsX614{+J2{I?~5ow*7aj#4lg&S;lPC0HUKfxg5AB9^M^zo{lU@AKIef zMFjrsag0ZfZXVd<{QdH`KeETLp;LSNedJtYtN4tOJUCt88{txwURspgJ9>F9 z9x5535EQg9pjKX*q>D9pO^3Xo28HtP20zfnBFYX(1MVF6os5S~;{P9| zf)GLw%a8cO0B3_!96^|Xcf}g^xZ#b22#w(0BitG!_P}D!T3zQKf|U{V6w;dkL=vF% zGM6>bvLJe?$^B=O&ENtHh6YV`c#nZxr*=Lk0QsmX??_bKVT5p$b;JkL{F2aqzQ(jI3tpBKae!KcQ5bz`BSrdEvQAy6U)FXbudzz|u6K)IwY+sq4|Kv|kN zBaaJOCqSG934Tj`yx9vZU7H7SZ+OSmf}Rvakh*9GF?zhSANNeceCr}4fx|~|)F1Zk z9yiPEkc5@tw^ddzQvcVn4A#0UiHf8)Fwa$qQ&*D&w!()0L^Qcb7V1+}?n!3L43UZtM`EO_jeM?seH(CH zt%bj#e%Zo{Ml-lim(p43(rx9jME=PYnflct^VNueT%EL)veX(`pB9T^8y229iCL)x zr}O7};%r`0I-OH_eb)M%it~f`xXF}Llh?wo453ykK}4nV+7-q!5(@&qmy|~MUH_O2 ztKFlL+ZX*^a3SbY$;=1o9#f)*Z-u*^uY;`ae#Yasr1|lUIEHNi?N1jPP-*PP^Xtmy zzmubr)o`h%U?L)xQp%QaFA4D`941;w&&d4x{Gaz?t&7<+r{kpP(*w<%K9}8|tGX%Y z=kMK=-D()!e3)C1cZOg?yMqnw!r!pM_ca+~zIwQ&T5aI?M!D`w`?bbC4Zi4WFXKBVFi|BqaSq$Gh^LF~lfiFgmk!Qkg5v8jWfTBA1az7@tFTVgWa za#-KVoahvX)T+vr~$9TjHJ0=Z~Fu&tGHB zXh{{LqLCzd_NkCzvry4OQqOd)_A$vyOzoi|J@>A*7%5S)UdRpUuVnM5Cz==~jYG#T z%^aI5$3ijO=-FpuWDT*yXQvi}BL11T?3~H=qoHpjKkv|mF+}gneb9Dr>&;(Wn@-K5 zw7RX6?`g5=R9C&5PV=iv5u(1?a#LsqoE+3UIcje!}KjS`1h5|4VG z#_=iid3{g!o3%U18 z{pd9y>3{DZ z7rAW}!fwB4x>q%+D03eV&y|Cyv3C8(WP>jA1l#q^*|xFPp!6RZSFM$wZVC2jFZtPw zzNx8UI9)v7xIfphMqPS2?ZZ*7RoKs)LOZmt#zN#s*5>6`y+}WOU~hMnwVznI-1VyN zXZ7w71>@JP!`(M4Ck`VgKSvaO1Dxl_>Rgpg?jPPL9baDPB$hI~OtoO4RJB`K;A|B! zr{6NRtJ-85j_$)QJlB;X8ue$f{7GWHn1GjOfMbqq;zAkFTizn>4^t;Mk-_`*5JM0n z!;5yjg)_v*vEw?Z;sR~inz+^cXs`GzRXO<*qKEnJy^iZGR9BWh;L;0kxS zJNnfk`;S%Kxj+#OO3YuXD@B~%WG3-ftjL&YQRO~q@9;wHG(S)f*kP)_a9lH7iZL_z z^eo`nW!Z+?D<;#cCjlkFr%fk^uDh&L$LD(hmb#R9+V9F;aaN1mD@OO$^i1r|~1L^Pun1^6C&=hDJPsGG0CgP)zWfqdD3oXk+fK`xsB2E&73h;uOv+sAS zXk2WAKis~3`%+A9&n(qdYJr&u@eL!TMOsUYn3j-zGLKUqgswrCr5rI{08$kIK!!W} zi#0fukkl4@>U$qp0dEySl2O{92f}n@y^cOG%OHzJT(AhZ7SJxhY6xi)u6TN13LwiR z`<5=087T>g$Cl~q#n9CaNLhs{uc#=> z*n6b_WUFU>gTA#nqw&ZN=p-25kT#2i=tEX6XnPUc)c+Hz;3Jc%@&_{FpbDzJ?E{2z zz~Asoo~K&RNec0Sd>YCKAQ%-vTHq{3qEBFSTP=J9Jq|?miQ_8GMB!OfC22k`sA~Xq zFyzdDghMi`H%BLAwHlJ_Cp?eYhwGdH7$TcR)Kvd-)x8b4G^LEc;Z8`yG!kfok2;xF zKEVgJ1y(^I=z-dF*zrIob}PikBM1#LVvy zGK&JP)njkX3hdKJ8#&Bd7@=@xfb#$X17Y|hFdj5aB*^1#I6YpSo(NdI3Na%ox=JyC z*dWwygg3nnh!zABfiDc4KQPdzK-8@U9i))a59mAVR>e(W6=xm|k%yL8UCv7@hca-U zfR`%VYv^ebgQz_Kh7HY@QfSNf#l?JIRWPEt*F>_vNCp@^*PEIYqay=RHoO%++gBiQ zIx^W;D}JfL%Oiha_?9U85B1t7s58p`Qm!M80^t<+)wsd$78In|tbomXFiBEL$!K2& z7Y5`WCkf5cLwJBdnnK83#tpNAgB_+p$FHeSU=7t?P!%!pp@Mxls-#d^(?^_10 zmCAm%s(v@weka-GJLEUMUHRt3^T_0{_tN~U`0Jg4E0x*y0YwqDLo)isp0>2cI0~IB zA|&_(&#@53$KQ!Bwt#(Sn_kBCq4bK2$@6PTkrVTD;rSFs-Moi{w_P^s|4$1b<&GuN z&b%6u+(YxUHuBoP7RgVJ=Xf4b2sXRC6cM#_TPmn=bo{EaYeZRvwR?m`W1 zm-zLmgDI)5*vDEdO}US_O=SoLZ}T@O+V;m>V`iRV%DrP!3TX@^Ep+;?r3V)%2D3y4 znKqwjIV5QnQ9pc+pH3J`c#XimuGmHhKbo^L=2?F!de8E*riHOLN}8TcMKN>*@kEzlcT_e|%t>>kkU4-}QQ-$$B0&Iw9lKgDE>}{auB%=0fQpN;JPV z!pEU=C!b&b2JNy>%AsM=kXqf4+Bc`H>3o@+tXziOTAxiU3+*C@xoEoA8gZ3HLLzp_34@ptg!#eGFZ)$CQ1kQrxQ zPT}p_^?4EkBzSU)bmVGOQDQ?59Y( z)_)Cma?;19t>f`3q0$wTdghYYlsJVct`z7yJ+xweeRHHimy6;GZ3en)mNbm&wRnWM zCJ#xkZ%b34z0cM2%}kw-pG`7ZR`|!8vk3~=u#QgmO1Rn=8Vb+(6fKf{8g{_3$*f=( z+Btp`k}tb%hTeZPnyK>Qh^y1CdVS^WJ-slrla>dvaAKgz5R}#^(?iduxJj*5qK+qx?;rdK{^mJ-=`b^Dkea|TnTQ077uQ&_e91-G zUYy}*I62jscC3apbFsTUk1SerH?J(&np%!t&upVaF+oV_W7x)6cW{P^KV70+hu`hL zL5U?9DxDsayGNy?4~uXA-gdy}mzp-AlJik}iyCNn|oZTY9#osOOK71#T}^R z`is2t`ou}T`1E}0xhM4K*Th)NQ51V#blUo{pbzJcQTs$I2mjo_k@ThO)cpel!3ICw zf)@h~1V+-?cy45jTUdSRw79!_(TYibpLtmsYg08o$6lm)lFz&mlyr2@#T$Kk63*aL zwXZP{ym#j`LWARYcDIhv{VtIlJ%%Lj``vKfpkBYF6`mF8&aIu^@!WkERkr}&=T5R; zDl{jAg^K=SoK~#{CfnkqE3?8IZohNmV7u4wYS~gqj-=tVsTn_DHU5Xo&Tz`#`I^Mr z(gWpjrYKhJOXIqPJM1lAwJ$Ec5`12Ti>xeKz~tM6+B;z!xa2#zwp3AHo5k;6P_-eX z0yQtU_dotC##cFospQpIuW_&Rs=RI0lOv1Br!u<28BCCMOl_-2e3Rh0jm0Bsn*MV9 z3)YTl#3LG^Up*aJRpL~mCGbN{llFvc_oPUSLz`p@9QjwS(T=No>oQxu$J*gNQ)L~G zU@W4VCMifG%y@NWisoV98SeW4pisZWw_nFx%X}%$jP-G@8QF5%nOLdK4UCrd?^PMw z^B6wy{M~eRX_;kQH`|}MX>lq5m*I4Hx$N?wBsgk7O?xP>fR|YL1A3dSJQAtUU<)Db zYJ{n9Q@Co875?j~3tuTM%3jQ=W)yrhnz-r&w#$)qs|}#A9cwDo&Y+3A3I{~wgic3> zj2su4Qb}+E-0d@=}#0NCO zdP?pQ0dg09HlExkYNDncMO;Tp^B@=kEi%4d^aZGHmYBj5KaT5$^f`nDGp%uZ4ptT* z0syWcJpl;gBbR_Q7{PD*|7iLSc&hjR|6?8N;27C^WF#3SBr|&^m4wV9Bco(H_THQ9 zm7QRpR2s z`NYdrcMr`GvpL8AY&G-mo?EUNx>FGd^Mfh=3Gz_Y={^Myt8-zDHWGs>Oeeif<5V?Fn5dt3qA07&` zd5j4x`X1ikxM!vEG5V4!psmKO$| zsVj&dm_aKcS{e%d;DsTK*MAP-D|nPSuoh5eIP2o?<&|kgD&}jD%ZoJuw>Cu8hek%y z7Scd7o>K?AIqY_UL&`rF=LjU)5!>lA;FTK{ro02jB6POgRmE~plXQBkboGAb98Oj^ z9J+=+{4FOw2J6)K=R){f3yR1TU0xL{z2D;1uZ1Kd&Y|>;6$E(P${wT2_=?28s&kiE zvx;3cQn<5B^H}%0HgjG&35r^gGdQ{Gm^}ZQxq=OMZSTnteji3kl@nJvz1HUH@DlYv9w0p_xaF9gXYn)V5rg4qTk(bc2B09R5 zw@0*vyC(E2Gv39EN+kLDH9f&+i_6>+YrbZVXVLhNrJ8kU?2%?Y`BphKFDyL4yktfh z^UAkz)#{S}J@3QDwEg2j?v00Iy7ss48-LZVtlGHMHuXaGK9=HwqWzu28XMMO-bWg) zx5K%Xy@%1v0Yl#}V9Z0FT{GgKX}_6l6`T|=8SyBwjd$J_n$FYGwF2>iZs237tA+Iy45?=)R8B7D_i;=^os>3fQr1^q_e zqd3TECn9+=*lQkB-XG?`fHx z!wVn3g<#L}vX2t?g@3!6)~`rncjjWaFWdJuHua@ujZvBpw|@w3o>;Nqf|WOwuYKvg z%a`Q0rs%TvLAxiW;6vcod2hp~9DGZDl?3Z+Wt4w+gY3`Nq8>?(KB?Qdt2a6B!c4#1 zIS{tm5<8M){=>Cca#x_%r+so7T{blEGVk-lIy^RI&Oq#WlAkF3s?9A%1(FJ7TSCkNry?_G4e>h{U$3khBY0g5Z{#*n%) z4>>0>C;kwA?_IK?j;E2YgG#=xUafL?`q9SJZj#7tQ?A806(TW)L&rk_zLhZ?B)2lh zw@|zu=4+v!n?<^`HaT;6y1Xt3Z_z%NtH*OD)#8{y;odW!>@Jk?`R9K3VptE#*;yg%aU zL?kRoBtt;MwHlUuXMi54htm3FgCmws;o7uISvnAQY2D9ieUD5bA;UnLfsE>feD4_2K{Pp zmZ3EqT5+Le20GG?V5jE_B1wTU7fx(*Fj#i$v}|re&-60&*;>#j-+?z76NFKZq5xcc%{M;f)+l zCh({s+1g{F+`&R%eUwN5W8egyJOKMiH_Ic=NQ}*LVVqnffDc&^7WWF}4|ot8_J8ya zbm<^@V35f``+zzS^BtZ@Cc_cl5Vi3mFYdxYLYZQ>_+^`XeH<45hlBe)(TwlRP}>h2 z=MRTeJkyrbl3_b&=Dlx3))7BW?X0bKA`PpXL2i)jfy>JzI?K}A{UnIM*PL_OQu}gt z5!Hv4)Z9Y*k^|07z6*;IU1LsY9vS}ZmyPU;5&^@(*a)j+1E2Fhr;6Q%UsBO;4{FT+ zdvA?^V9*+!%^yucAKu8-eU2(E#QcklgoE^nl=?cFHG8G};9{VscLr^)>EQ26DF`0d zeBb+8Di^|^>qCPS=pf1+P;6)-|AXONRVZwM^zlaanh$aA$yTWgqB?=-3%4@@nqguZ za@Bw;fZc(>am{xGb{mw@Azae057a;jAxs_!%Yf#P;_TpMgL(x| z2=F;76n+LNR|TlW6B$51aBJn{u%mi6>@IWR-9TPe6;#AA(p$Ebc?Q)fl%ZImth_!U2i;*sNpFdA-;N9K3^V}=jRv&DIBT@ z7fkq|pLaSnrRYj(QfjIVZ!FjH6Y|ATE~(wJ9UQaW)B864in~HeKZulOTJYLpE(ckq>{Jwz4>(dO17Baf~)(gp?B%}s454zE5X>ExtIDO`Cg zofmW7zFb&9SGg@(sb*6u4u1zTNJ-%E{&}g4K-|0+Bg2I`x?I#p( zL@Dt^y+Cz~{BxRNdwnTw_>sCuW*VW({FkrXKE5KVUZ4IDE6Aj!4Dz1k z$6vIYH}iF7mrxWWVp}pjykwg9l5P(h;`BkOAZS#Ejxey8Czwd`$$nGbwffT=7<@N| zzZO2Sw`!78USMe3#03pf-*@$yv`2NBpf^jOnvVGWUfVne7$u? z^&GC}oJG<)FO{PaVMuCxU$u1EXtz-a&Z-hegI{I&@m{A(r`SzfJU+{;tjOkrAyl#> zEysE)YolN&3tA~es&=zrv>T<9r+B>C9j#pMcV|@&V%WfxE%o#JL z!T#1&a0v=i`0M89P&GdUADofIj~vssTcg2+*malZv8H{gXCznA%%La)Wv#o9@UgWM z?Wr09jta+ya`RpGLMkKairb5?I--nJ-qC#3)zqk+b_g=^#ik;6(csAl5W}t|< zPssVEIf4CgeBXe-uv<<*ZeY^8lDyPow44CPav{1_cj!r$LdyO1Geg0jLyA^~gNcOi zDsW&#DUC;6B7Ud-a{iS)Mj>}dp=6q`vNlQh`N^|Ut48dtOcp0Up5T~tI&Z=DA7T*? zI`L&6q|K~Y{tP(QyI2^Sznob%d&npr`PqPG$a_$6k&UH`dgsF3@MA+U6Pk=ZZS7$~ zLYH0ZwGkOi3c1H=-@3&mV#`apR4;ae9$l38kl=gv6pdd^%VsMjX_BK8;OevG9N;-5 zEba8=nMlpQAJ@xKKLfs#fpzaQuq8Ng+{FO`M>~|ALh16oY16RTMs%Y%I)>7+0*l6L z*QUQ-O2lW0J!>}RnMt$yVgM67+Qxb=JG%{ZaDS|tsgv>-pgLp>yZk<8_{hhVZO0A(KfRKXAg zK@(tN5N89FV(?!H!2;8wa5ia%=(=ShHwzn^3dr_|U5AsQjaM6r)cZB5qo~YjYC&uV z7y*n1QfCLQ9z2wu{P9Kb!GInD2!OM=vw3$i3PRV2I~UFb5Emeq1eq3-9k3Ds{6U_A z5t}Z*FO23wi%n0t6$Dg~UOObqtiBE7i0~o-T)>ZeD)}Q(q!SIs=fH|os1{dXC^VCx z#{Qn6bx-BLY?Z{IY!K4m@?TRP_;P1pZl~>kej3ndB;EjIngve}7@z*wJ4t52>jviy z=S~{Lr0K|r1d18A+(8RD8hd@rj7VGqpFYhZg*4DnwjQD9gAcDBz8-e{6z@XBMR-Z2 zcOH}?IN~9^1;60S3qV5waFe3h<=t>uw=x5(aE=6@Rpv1XTw}zg12rH}4O0o3sLelv zV6fWYfM$N^46fG!BQHC`_rT_$rXYMvV0fTCPr`NvVG^KxEtW$*7CylwemzSVbo5_B z98e(1{r>%X?*KYdsR{9bg8=6gB$c7q2k8R>3kXO+zzP6URJCOU$2F|=z#}_+H1O2` zLI`#~OlrSKP%vs)8-54$#gDb(WVrId-;qX>|NK;l54;-$wUfo%6H@=ZF#m9lqiN#3 z5&z@cM+<85?N3`a*?dk9r+WSuIA(hG4&usrs69N9S@v!rk*A_E5CiN=_4#;d*jrc`lD3&(TB8`esJf(jhkHk~?!%p*!RJHrldUS!LN%cF};H0H{&Dkw?r2#fW zg%N=ST%dFfs3~&Bz-SUD=TETf6!?Lr1)>|`;sOUsEHujW^z_`xiJwJUbAz!y*$|Ht zJ_iAFqxFcBSEfj`W9yJBPErceZRko1KvMFhV zb~WpPnP5JPXjTw0JcWfPS;1E1`4t2ppPL;e}CQ^ks$$`HEn&-LV6sr zgm~~l!cI1P!bscD*3OP4=$Am9QC;1_LfH`9AxKf4#Nh}qia_ZBNQU1976-s1yeGMx zsyO(;Fbhq=h}j7=ROlP-$$-}mMxIJSzN(6t*w|UHJ|m@j;Mi`{egL1JtmKW>Vkw0@ z?Z_)GtZqMEeiPEGv}MhK-OZgYxc`t2p{M@4PZ19ua9{8{@IM=%tXM&KLIS%J~a{GNS_Ia`&W72WM5)r)2g=o?Qw3CP9>*2 zIc4~bYm}~8UlsozCrfe6<6Jz`YpE;!1T*?HxA$>`Yd2SPPh?OGtokT-3l7uVt8Gbi z0Vy2f;>rf0@rq=M@qri}@q1&zEhI`jKkXDDDco^NCr*@hhveZm`+izK7c_ zb@-BvJG^T)35U zzRdb-ipg`O`6~q#Xb0DC-b8u(s-6tiTnW}YOX;=V@i@Zp_r$gJORN9*qkNp(_!D_~ zE3q1HRU$@=)R0I#>45LavRpAYf$$CLnx{@H<~ey?x7%bh9O!e;>qY21BySWwMdSO0xXX(AM8?%J_!XbtFCE9mfgsPrq@odNV9I|K+b4 zvWYA8pjGeH(?#R;HWS4M)GWKZD@M=9Wp@@?l-6(xo;SJL)h8bN&P7Wll_>JBOtpeU zzY)EfSiiuFQM`$xCE6{`xsdf8QijVWkMozlPl(c8X*~Y&mDDts?dh^TmT*$el3ij> z2OCNfn4Ey77!J*d`X#R{p-MeE;6FH3=U`T&r%52^CjOe;d`!`3RKDp`Rq4u;rX4xH z?o0CQZ7=21c zo~orocH05s6v5YV${kl8-R3jKMw4swc3J#wY@d3NZBUO}>y~2fY1%OITx0t1f_3_) zy%gtt%NCVg6DOaEo2vc+K3y+~cA8x9iF+AZ8v8Zs>XepG+HdNgPojUhpZ;r@ePQoi zNu}{RcELCP`R(`S?yol6#@R{e$eKNlHco&3JmAo1Y^lUO^4rW>dnz{h^~01vZKmUw z%?ra>#mU}&t>d;7{3L;$9{%3WsFbdh2+L(NPGS7)AwS}=FA-LgvNI!>TD{WFd$LXX z2Fm+y#!6S#JrKG7FLj)aqOCP|w|+eu^0?<;=(%~#jOr5{LaX12Ys)Syy#&2r;) zs#_M&a#85`G)M4s+=;`1hBwNNqnb1@dH-rLwVGHkC3QGfXE+EQH5I5by=d9f-MDLzzFT zXnTn)hT0aRoKF(KjAOyN;wcblKF+ftJbwvm8{USSFN%z(Vdlc=)0WCD2hj;Cut8g*4yuFaOGU!L{Cpc&)FH@(@)O~er@iL z$M~(4?I%8d`VgLVJ=Wh7BbpNUY{e4vv%%R7-cv|wA)aYb3|PUd$j|EvtN)Bv`f1Z| zEl#@MP-khNiFD{g=^j#}0$-TA*PM`$5NtR(E~a@u=_=48|H)inE=BT4ai@E6NQMdw z6SJ_thg85nHPy@4SAcP1yGoGnc+_H%B}%}0V0;GWZlWg;DR5Yjx~KZcQ3>+tX3G%a zt7HQLfO8eT3eo?%=`B4#g;Hqzsar#Uck@HUn;*g;dl|`Hz$mARKg-SS0lg1G<-kGJ z%fg|y;(n-;iyiHU^XtvDqoX4i2|m0B#BOe3VWDSNb>$L1R}R$uAPO2B+5jq`HzneN z@1hn$Hh@$G=ma=A~H!1Sh*WAc6cBfT`fgcRHt&-fQh%_26gOzN7m5%6$>u zP|;j5v20xlt?StIF2|`;fXYza15Oq|FhRF=5`V9xrY%bz_?=CHdgln&y+f+yk1Ghq zg{l|CZJPzW-r7?aIp-a!({(B&8IGDpMkjY=e?t-wIhCRO3Ea(`!3rSIfIk`m%;47* zP63}Ulqdov1Y?Paj%Zr}cftE;lTKT8g$sWPfNDYTHNstjO9nU*@X`aOP1P)t6DbZh zhf9Hm=5&)*#!3y=49+8 zYy+i#yzj}<^;+~|6#C?C5rkwcw)oyR4r)-55h}*VbLy2215=7{i6$nUu-Td;_tc!j z?9l&YjokJLHws;OM#b^5j84tnD+@JQJFi2Y4}&(VO80i)UTF;c`&VQuxZtM~_ruGd zo!0V(#d}_UKz&JuUZ*#7@fJAFc=m-pUV1_4c^Z|BiX{kaTJ>4 zyYxncY%I4}zsL+zYO9i3-rzv%qx@W1B@-wXjPBk#^ZxWh;^l;~an;L-nKnAsSWb*m za2dAjF|&nCjG>GTirj*P2^~tR>eWVR!RTt<&rgcsCLm!N-Qjc&{Q2oi+KKx;n&ATi z67^aBc%ro2S2lyiSLNeAR()5V(C2e)-oueJ_ZZyUb$xY@UZzfG`Qh+yrbC zcDk?#Iq^h}FI>}sYj*8AZT52;GjQ5H%?y{(scRipDwmZV72gG*)h zX1#0sCdWOqA@)BgV$tI~`+$H?YEkr|3EEx*!h~M=?t}#LB%)_}#4K0%I}on4%3;=E1XS#W@oc`hkfKHq zDSmTzcz`WT$<&YJJ#V!(NZip8*l5z8c;&)j1cU$a&*bEFRiR;P!uBF5?K^_4tGL;apr0u#9Y*`TXg!Pc*Iole#fm%V&yY0^9 z$$B^EY!|jQ(hI*g0{)bK;qzPY8hEB*JpFPDrA@iayCQ9lXQ$zlO|Y$%c{uuBQ}o6w zqMu|})@TB#rWY$q@R^*~dmZZNb_eoyv`c!R>s%p>1>2d4e%ERNhg5&kp z6LPRn_WuV;)IS*r?hZ||1&KFA|Gxdh;rlDcx62J_wXJhFo=5keqJ=$|{y3w!d#l1~ z6AZt5TlkqCSOwyJIB09!J)g3dFZS@pze_J35rdskBRv{3hd&oGuXEjvM z(qv#^RxV}ZT4>>sb|G=>Fw{EVQS^>n|ypyaVJ zhEeaE92`ElUw2{oQp-e(9>*y04*@mR{d$*sD^xZ)r5>|nt^3k*dDwKZ%6fKOAHAWgFv?6Cxw!B3n1E-bwde5QLQ z)&O!yeb7@xYoeAO|?+AX5isRlqf%mi#JmX6*s(;aMev66A`+ z*U!Rx{`SxU0%!< zaCMjucT7yK0c3!ub|8O{_@9JC2TcNSaq7he!k23s8v0hWzud{tKFehz1;;;)<-}i^fQp|ED*0$+KO9~S@K&fwc&qQ;Nuzn<{jW;{73k&Vh5Qz< z8&FY{+&^!cSL}3J;-)T`;S$Z53zxxVwv!Z;A;eSyNAN_Q+kxc&!eKzq{dd7wSURBH z@PD1sz?dNEJ&20~p#U1?e@jY$Q4o{1mzOBmq`*)N#1}9_J5ivZdcloAd!pmW7Rm)Y zMUL;z9TKj3N3h30lM!qcKwb|%b5w_+a-tLPad54dqky>qSy4$O&FU;~#U(&jK|jJ3 z!;cypTOl|EhHf6}@SQKKKhNp!>lN>8Z@aMQ=;c!8bed z732d=)_rp+GukqB&_UI)_3hiP<7((MmVeq~Tn&+Tq_>HT2=Ip!}yA_$NR$NE#1r z_y4k!aARyRx+0TQuU>JdXjXll0~T$y<*|oal=3~e_~!I2{D9?c2Gtc=p8!;eXt;y^ zC!5IhHZpt-2{5sE2e=uKatEO9)W67(;HT=K+cqM9lhaXs;6L7LhHY>^O)HUJyd?kE zP%I7cD+tSD^vOF!Kab$i-mCd8{NDHX0MhG7@bu>shQo#_HGxSO`QS|Itq+dVDcS?3 zZpX*+`;_VwRUit0JUEJW5B1pe%To-*wKA!gcLz0|{7K6?IJknR#W5PzA#gkPffLa3~-!`Rpr=3eOES64K{weTV7xCA`U69(|_0GKzX!4@Wz*Yj7fW zML)kyFS1Z@Gr+I<`I_*t17Ap9^hBYrF`XoylD1hMVYVfO0!o!$|Dl2wL43f~tgyND z?=fWqjRv2bal$u7l2vaS-{}>o8!ST`<@2&B|3w+_y|)f*voL%r1P1^*MOqYYSEk6^e*Pf}TF{ajc*r>f_4b5OXpV%@a7e(^6{`fpq(|wt&tEpt&FH(5b z=lPyHygw7*n~c60Tj_`2_`%M)j+Ny7KGiei>Kvo_`yqYP zuMfqk65XS%J44T$v-$CwPHUPvJ#L&$bY=B8bZ|%c$&6pmNxi${-#>9QHk*SFvW>mx z>78?l0-np72U59jSZUFW3Oa~uOZk5>V|l-?H!G+f*>NK2U6XsnU)J3z*`oe&p4UHr zmr{E+Ajxv2c3<1tyJFCDyAwr+Z>XT~FbhK%O%t=uaH^BFkbb1%a^<=>nJJ2t-HK#L zDT3I^&0?;C@Qrn7YDBbAcYE>=U30s|ATKuOFZR?!ql%9BuN|i%JQL<6?=NYRDQK~% zVZ5W57?!sG~t-hSnex5gGPeCO=t zktZmUdBEm70nKb~D-L71N8`VaG5v1XBF^IJFpi^ZkG`mrJ@eUZo79nTxG>8W65QNY zP`9t*W^(&(rpxf;%dx`&0fTrF&TC{x&JYw0H-^E0?3b(O<1x02cR%{J zyvb$T8mD@>!QAiI7EJ7JzLxTnlykdcpj0`Lkg&~M#EY*DPvb1LdUP9wv3+WKq1)a+ ze`9+&wYskc&1QO{PcCLbq@=0U)c&LR69~tvTy~gF3>cbG@9%q=YJymDOaAV zO?^W{kjXq{@DD;5K%h$;;`j(;LOj?o9`xs6Yw1U>^U&H277^$>9-lgqH1k^IL;N%* zXYr%4L1cWhN0JbqZmQR8<0+;?yf2ksK%fGU0|h|{=>#2g-L!hL0iX$*wEAVYUIB>@ zln@bnumpX*t~mpmosX$unx-Hu_duUOzH!BDkNk-kpr0v$L=H%|Tl~)^tpfc8kc%I3 zszWfFZfVEJwd%M|A)a8wB4gB@=mYZ;x%_j#8h_%dMKO0?ZR%E-y`BRzGcUMditiop zK^_Up0gy0!``YQr8c){8S=!t^!j_%4uV;|)Ca_+8+#1u;(yI5^;6~^qKm^rxa1qpm zQpWfmNrFx^-G2|(COhj|j~yqTjF`fp)q5a0fRaJ1F-WN{D6YtQgoNtxR;fIZ`7bt7 za|JzhY!HL#<$b*E?bQ>l6^)U#yYEaU`C=LvmU8`dPbW^czdXV&3_qYNa9ibDsU2|# zGmYoLRH=Qboa(qwiFm_rrxJ1b7J=f?+?~j`)>|2$G**6me5LA=c=S!J_Nm0HC;mHg zhi3EZhi!iIn}a%+-$5lbUZ`KWDU5seCh_AjO3xCA{uqaOaoP<(AnL*>*%1G-3%q71 zd;pX&6F|(~28EMMoP5Cu1nxH?XhV7#!8;5_w)=kzYI*dXz$AQVs|2Z3_9 zJpoZ5lpNq=bc=LX zyS{rCzvBzIhDl#f*!l20YVXfKzH`3g=T!H{1y;X-7b*BU8@&41JAO?+`j6aJyZZKS z{ji`~?y%3+Wm(ZBK1*uXW}O{tv2E_2R&V7y)|<@|AM75D9q^k=EW+UQ?=Na7{kWDM zh{GAEtFPmUM(F7d*a_IAbKx^7jC)#e;+3V~dF#^;oDC?xsAX$Rh~itzH%}ih3DiE& z2*z0xt6Dy zA-w?QrrRkRWvJ_?M{@2nUvuPU{{TPsg#7&Zv8kGfeyPy&Wg27d!X8SDZP!`R@tR7Z zsR^az+UOTrXOxM!iVQ*(b%W#a0uJ%XBgsu>4Kj>I_brMUKZ z7oD5h+Fbegjan>gDZ-{-K?A6)^-OT4`R>+81~L6l;UTMCYM%0 z8A;ZyV4Hn@)A8HYx7~x+n$M~2QR&;xXY(}ew6lz#Q}dXKr>~y3zjsyG*hhh8iVzQ< z74!S}Z;sz>n@N>SD7BIu2>$v=h~qR`f`?+ z=*B0@--Yu8I|IGtwyQi|Eq}+hE3{#l-Z`ScqbgS}j@y8TmP}jq`Kup?)1p=7Uy~kR zD>B{j$&R?6-}#pN^XuojHshHKayR>I6hdA-zu6m!6;&8e43`rcPtd<0Lzw!x;I`1c zMccQhOj_^Or_yC3#&2Kyt5W+jzJS_Sq%UPmC_BOgL&$cvy%lkIlo*ICct>I7y((>wefITW@xgibk7P95yItV&bAv%FRd}v`c7Q)S}atRnEBkCm=D2Yu}&1%f&0l)PJGASufHh$=6aK_ zj2pj(^mIPNKF9L$zmL#(d38W%D5Z}xX(Rs$N%U;W;4hN}DPQp$4UW{je$V7i7A=0~ zxpu9NoO|aY;OR(}sl2C%^@)=F;Hl*gR#h6VQs~m5guzL8CcX6?>WVPO@dfH*(i*XU zw;qV=K;3j<}c($^BpO+lWFGFEhV= z8^CUC|G9*avgVWH!~cR!h_D6~0`+cxC=q|~?y4!cn~*X|@EHNw21Nw{ZK{RuM|58p zB4il6N^r1%cWlV^qB9I7AH2v~Q4ku2()#(#qm3)j#fGzQ78mVm`Tub_y1Pr_C4au8nQq|J@B3wZ(Q5cm zqw(^kODO^`3;$_9N~%cVWX1&_`;9g&WFl5B2VRHKhi{FJSCL&a7q30oZa)rJY=*^l zHp03@nOp-hAWJ~CdN7!Syrpw4;N*GSXll~zbp|v##FPztRLFQcqm@3Gl$c|X6{e=c z)kd(b^}wg@^s@mXsJ?Wdr2^%4?VSk{07UTat(Wizk(i!oL$IFj-y2AUH)3x8Y#R&~ zd@$PqSB0b;p)4F$QBg?I6;gK%R~NZw;gW-K3~6sd@HBumV|%#E#Xo2t3tfGc^FNsu zD#9%CXu{9vbckA?X#%8dDa&36u{2qBn0bZ!)$Dao9;=`)4GD#mw?Ua9ay$FT#r^nk z2S7eTaHWZuBH2iAS;0sZIIyJ3Uuh>kuY~U{XUqOHppng&w`5oU7C$)bHfVpYZJU)M~p{MA}^yE4b9eR}jQ7nf&D7 zEWJ(9jRaPTPoBCnbZ4Z$@4LxUru^>WlDI05Tf4EK<&|5tR{S^WSfnyv+&5SGdN=kt zcdIS8hItTcJkBsXa!rS{60h>FUCs^Ejq-`V8*(n{N>p^2qBG6BMhe1#U4MBftrPS^ zszxaUjq2CcMJ^W5uaQPaEPXpZ`Nrw~>`l<+nP7S$smk?iVybVC|IZ7sJ(<{%(H}A5 zO!}*E_bdCg#>~+^j!JX41ys_WeK~CyYqe@BIVO$cWsI1%q`PPa(_Nd^s*wKf@B%UA z`^I5I?sr-Cx%YU_3X-TMwA~pKe1>v(ewKt1xA1gJc;HFEHQ!FhZ?w9+i*&aqeCA%L z%Ul|jc0zSLyn3DWp+1g20o7ylmcQVib|6LOnWAMT%*1iA{oseouSf;zPo`guzi22z zF{3jH)$gOoV-;#hr5HO}xC1pw*vZ+h(UX4T9@7)5X2RDMF7F?wX_0t!5L02;(z4~q zFQgjbs=ysw$!*)m^Olm@DMnL!OUJLrh6GE(cdjGTp(>Zq(~7arinFg>k5%)_oanQS zw?=%|Mk`y3hB_QOM_r%hqdSH|s(w{V(g+m#%^yS?ta=HWoC|xm6`Wb@YE$q_M|sri zZ%2EJrdn{2j>+?Tee#r>c4ydEB(DkFG6=xfI{cek|D-tGePJrrb8E8hMZ(tPE^Lo% zRNd-|{&v=e@qt}9RcT?nQA^rpu$uh*SkyTcA?51r9i}_cVjH_#<$3#VwIh)ZB_YLc zS^7!JXVz2cO43)P@bc-IqpU|Y$rGw>WE%?hmb{C9feDV(uT4^W(QDIn{711-FlG5s zWynK{w_=2}=W6c~62vDO9~hUlO1+h@UTkNt^2%_l;Y%UTHr4MFgJ1)ySl_ z+w7ghbDj%u?qhDTSxwXYwUSJkP^n>kO5+~6lD|-DMpK?QRO4_?z{Jt3$#AD$V_U}J zz1gcngRVYll8?l*xpv{$TqlbsC8AGDr*T%>2#;QfaZ z@rN$n_GMbj_+`9sA(I%_DHC72*+7*jCu_@}p(lQKLwJ{(@7<0rH6c`v{M+|w&vnO~ z_g%kcCH^rt#-*>sWEF~s);*iM@KP2hV$J-I>WgYle~-+|%}SR9@!JHa*4W|~7j|#+ zhG(Q#vFXybxDHN{WjLTSwCQtRD8w-q*$ zG;FH(*e+as-zNC3Pr9i#x65AqBEvu5IREf|`65g;y^u0E5M(C3md@Y$ z8d*RR^d7fK7>|l1k;1c7xR&$!+rz2@VnrK37hr^53#t{oIBk2;5*7B<6pkKn#DsQm zvbkrwS)s=20X;n-7vt=w(GmRx{6p*H3hB3H$qt##)iPQ>nWda}_#MzOAJ{*!q-H(pYEhpQr5rYY0-GTT~!%q>UI1W7A zlvY31b~ncCUxVxc-W8w)&N->KWKHPm=@pKz{5x*m{B#9)C`=_NHig5B(=dkh(~05f z>co54w(@FbM+f1--UZMh$bKUHZPBVcKwlu;j&-{`I|x>T&H+(b! z^Z+0=dM8JNr>r2*{MSV7APJ+UE-=}N%yjPc_#deu>B6NRk;A~+Fap>q~uL-c!d~O>;(Kf zG5h}rW6 zG74G8xV2YQISR@eVmk+`GZb=z{r*`cQvE5*j`Uk0?ja*1+}a@{294N=;9l6hSr$mv z8D)BL74DRdU0Zm2O`Je*`J909 z9N73GePAY>=Wayq-gc=ph`gyZPw5=O0%(IKKcyj`r_xl{iRUH4z> zgq!2T^fFQ3dOz54NXH9D=h?ODOWk9lal`5^hu7#Qe#b~HZuuRN+qrs6556HNT1d!9{Q_hU)SU34fGGoGYYHigSrrv$_FuEJxNniVrai|V4mo?+QwSTztmo>6i zh0x$mp6}u(M(hnCQqy=L#xS89)6VKB4(0x&u+RrPw9M$X8j>oe);b}Z<>1Gk9+!Sn zvS8w|b?+P%HA{V%5LNuEDOOLXwfoJ5!e>fx6<6lSVs<55vzC}5e9ubXWnbWs*(wf7 z^T?8;jlFZg5T+lMIBz9vtHC9rGx6F|C98_4ubZAbD!*EQnTKw?$l<;=#3~ra3U>=) zE%)Ng&)_ACp%fI7e`XmH#yC8}#;%Ympw@V@x9zq%r1Q#r+3;WPHQx}5V)LpzR2#~t zpW?fR`NeB8o%hY}Hl;~%P2L;|tyyC<%PFus8SunMO{teG!kvadbK{*!{T1>-l_G8W z4()saa`a+3eik{NkiwO~q8h0Sd$*`e$!YwTxBEri@X?!j;FY$P?v|k-SS=1Tj@@eB0u?#S0tx6Y3YxpXbOiTaiLlpK|XOd6?b1Dbl=603`jr> z)SoCtK9X%P@}@`$)v(0PILqf->fDMYzvIv&_m?A53%{sgPLQevw=6ptq}RsSoJ_Dn zhi9XRksKy!%Y@O_HOlY{`wo z-~WQ&2vIhc_`6blW^nL4r*de(cqcQ+wlklOl#|w+GS2a$NTNZ8qIE%Xft9i8(C8mB z`*YactA9&3Jk;uz4)Vv7=N-l~(#eZ@IwR(NK3vw=xoc!c(DI3QJv7<4=s6XEzK8Oy zsG`B?6Y<9nSID-{+~VYQPFeDC)f_Mlju|ePD!KWUW|F7aR zwSq1w7QP;D@SA4;Ycy(P*THgrhMKRcfbgxtWO)mCh4o$du_Kk1A;jhE~B?g_OnY>?5t6v|B-xw=f z5F{Ghg;)gu81angtU2S>ewTx3jZcmH(yW!6we=M}^6M;4Gp zQEB^{cU>)95Oo7Lrgq<*xcJA_UzyC;i>XYP3T0DzmV1T%@{6ax5=?%B&d|pr)_LAc zjREZ8@79UlbgdXDQvwbh(N=ikou2-V*zhXIwL!y0MDJ(<@hlncUjP@KzLb&=E zUkF|NO>M!>{6wH!*@8*PDCl1Uj+yh;qs>_obl^PL>15{GT7wNWNNf&;h zl8Cg?k;)Id2L*UozHz;Jl)3)-nPxp?pU5dQRV%&Rk+tO7~}wZ z*R4|z_>!TP_`NxflSB$L<1A&p(7P#%Oj}Mto*CA!HlR7LP+uT#WJ%0n7>-)_ot^PV zbJNqf>^ATrK)VdvEZBLVRS!-pNVj==djs{fuzLu_J#apd_N+Neb;3iqY9Td&*}hMX zVmk5^4Ts}bcc79$@_@(etwUeXk<4C)!4fOjjb4v@UU6rdhWa9S>W0-UD73lA3}t)p zFWk^`gC+=F7ud3ZY}V?k2pmuVLf{sIc-AQ!Wf=SkM#`{ysOn2L*aNvJ1}SiPAb-dN z8{FXaT~~wc@8yZthC;0E&T#w;%Ad-H^{qUY&Rs1T$m+WZ=0T2#%_P zn^i`??p1&`BXH)WYPQUiNG|DyKY%1;x4+&%hA<%>4Tfaca|g2typHZUu`36V&dYzR z3J!93b_dfmmJp6Fg!X~wcx1c6sV)lGm5Fz5#K!iN5<>`VL4=ZwBR}IG~+d3YOdvD&XZe1YLorxR?(1=n1Say3eEnz#HRpymYSz zVYh(8V7TW)4Ijr|W9#7+fDKLS?d0$x%DqaH!S16B*AJ*81abfffDarDU_2!F*rq4Y zRWJdQ^q>zRd3aE+0O&!-IUuu-jxWIWB*h8_V4yFKk9}8fSPPJd!X?NiQPxjfFV=<+ zc;?#Qk>n5V`VS?uSeaeETswSz4M)J1H27cHPY@n(lw&J9o$F4`W@}d!#W^MO{!K2( zkrc&~nLydWVKv6|GEj#3ha~DulwlJWo)7lP_OcsrUojF&0aF`X-FDGm>jBpGf_l|& zUAYpL&(7=kL!V{)_r&8J*|-&M-?O{$2TdlE860oqv~b8@OE~5|)M@=k-hqX|5n^nI zHrTSg7aC5B_yc?4zL6c&3id2=`3sxv<>H=zQf2>r;DIO=?vE!DvqW0O3ydq^7ZUM8 zEI$ZBg_{bdG~B{1@vmwX(*Va-`Q}X!B(>m@AYG#H1i)2{bTq=|oRzm1aGQwWhJ31U z$HEq=3lt^X5?X#NgM6Cjgc2J@AnON)Ey$W7BQ3qwz-$6$HoEEn&@ShX%aya7-ZX~u zhjQ?Y02C(t6Bw(`wk$(Y0?Wg%PIW-vdQvL*K6&~yZG6{57HYGtySjkl1yBWC>3H3v z&1VtQQ$Ww5zdvsxaV<^mwf30M1G>2TIA+-xOGvAXUpmZ-qF2CoFRn^R#M~8rz4;%6 zI$i4?6l12!b~RAv5(y*e>0lIoL(U_^yDf&77;$^{&5&SPm7C;zjpa>#{H$dO!YeLs z-2yjW+Y~9M(rJAt8)TOW|b_!=yr4f zeROoGUl{><>r5PrN1nF&4bTv~0PE4?d?#r_A4^NM&pw++vfee!6cu$d8C{GsFF zo#5mD+@|;V=Yyo2sNyTBio$nQjq&e3mUp%ou0b`;rjgq*y-bW@;v_G;j)`3qE3i#Q z^)3`IzGfeHrJxRLu2F;-7B!zd6|+so^Sqn z+qEnC?#kG}*#AeS79|8h1Zhd>4(Se2O6hKpMgi%R zmQq4M@4M&TJL52OMqHME_w4ulPww&U<@X1_`egn9L1O;HEQGwJz>=zT!&pbxo}}7A zk9407FT6{uAcLa0u8*4ow^-(Oc>(QNZ~s_ALBER40oi2+X&OF0ZLm|ig?QtAtPEN? z4#T-2rY%J@N43K@b)}8{j01v#tACR)q%c@9?aQry&*ht5G*oXK>vN-i>hE#0d5e*4 z(1&AtjP_(rkC6(sMm?Y_t{0KHg*}ppWkd9-PpK9MdJ%(w6du7CmXy% z@L1&xxh{Xg7{{>w;d%7eX)ocFav(+ZfV{Aa_UP}{!G{GVY?>~cokM|6+`i>JA)8K- zaa}^jwTwOQKnuE$Lbo;PqhhMH;wqc?^R(G>^jSWRK9YRgnClfWhjF&?^_=56N`;~U z(T2##^Nf4>V*J{Ug^b9NM2uJpbBNm0sOM~_tm6&=R-m498G5B@_6z)(ZO`1x-5&%7 zL}=_cZ88QGG;bK}SWSl}?9YDZf7P;Gg)SAdc6mh3nDp78`gz}^VhZJB>`Z-4`}h-b z?pLB(U;eB~tc%<-b9R+z7*@AYr)BvQ`CenTa;dP}iRxU>iTBpG&aDk?Je zU2585h+UfwqWV@r(5Wv3;)$R< z$0_U-`_*{7`WccPe18MfOdDm)(c~y|G^xV4U8s~#3*R5z;zn;INJX$sv62#H zoDgBpD=kx){_yq4)q7Q8OB21 zu(lYE>~GDsaK{kgkp;{p?orFSZtqdCK! z;X@r+@!T6lQ|_SPISjKJ(4Gjp>D;%x$0}I1S|T51wo?8v%gWBU|LfXLSY4B_K*&Li z_L!NiG%L=^$c#hW?x`f5NsTej3z>p3)-Qq4xjtKsxLO#cy0ic5# zX+)GVc(cnLL}&?tH>iXSFu+1rKc4?(hqLX0Ks4Dh`{x7TS2(gf&_KD_v(}be13C!4 z5p(Gb7D&C(fvyNvKvm}ge2-k(fc!MFND?WwA&<}Oe^;9ig7=ZlO-rEQSw4SG^t|5amq2RhmHy}PK0-j)417gMu?>_Nq-^HBMzhoosvW=_nX`t` zl@E1`Z#F%Fu?P~t0)IG2fABou4`8J7AM6PNE?d(`N(kzokZT$3D|p*~IM*#q_Cts3Y zDJP^0=2U0hQB&>ot+PIj798jK6x_I%;`yg}`=H>1SM2aTKlc5Yd6ge&tsGBjCOzpx z8?Tn%npdwlhk<*ZIpqtijn**Rk|~wrB!AgJUgth~F9M*0ko+DP(LmdQw?ZFx=#!D| zWmgE$!#LYb;JyU55E!TcCxE#b+x_hfnM1g2uK$>fo1i4f(J`v)J9i=c1){nIW_CfN z^+5gE8H|tO54;;tpF%T@O-)~(J;~aH;S><6*1$^!@iWNNd;k0T5tbg}xIO&!MF3AB zi;j@w;Squ{VTw9RIna=&l;H*zIw1O5Y`OWLV0?QY5@Hbs-gPX$gQd1nSIk1PP5kbJ z&%yjPmrsMXO=7i=014MPS!B$+G**Q*OVf>&u*_ z{qY8^Z@NkuQH#z~Js8mXKQX=hSl{{y8|UEJiUZu4Jr% zHMW`(SWKJ2)Fl;e##Z)qyFlP8>nuh(b^xNA@CkN2mDOFpzlxw{eM2ZsX8l zP+bl->ZG*JEk!XXEJUsdQaOF?uo3Hd6F+*=oZ zRQmc8j)bjCOIbbH0s;S|DdFI@+B3^<-{v>My**qc{$~6T(ow_YdhuG&n>BI3pmC+3 zj78V=txlWMbyt72*5l2Ud7|MP27e;D&qxV0=Fkg%#{Bv8zKAt4BuFsrO@G9aq?d{- z`vb&_dH3IaHRSXO9=ukJKVCW6t{uM$E+SlNy@f6Mo0QveB&1MLUwwoBujY)lwt`ij z1Do5HOv0u-HxYKK3*A`8Y(ihJXvaZ|*w6-p-){svx{M4z72D1~(!JR271|@fH7l5G zs>=2ch|qn#XSAl*ujYSizsrwb6`GrWtQRitTX)aZ`1I^Le)ON3CIOd_D!UBjF6KW; z)bwQ%P z&%zt(K<>8ZN_Bc8j~|^8n+VgR1f@hiA0r1Ziu4m9@wV7d!$H)_CCj;bmk?f-F260c zOtLwGeGcm@FWPg4);4VIVE>ODTTk&5?#bs9rpn|k;$gL1Zq>aSpIZ!edKJ5XPvStN z^L^5I27}^0i-D8<@=vnLMFldg{208~4Oq>#*bNO$hd&mTnHZR`(VqkVj;eUR)!xNU zFqKz@Zd!1KWpT47$P3I~^ z^>9IGC7^5Ka+jg$(hYt^(T_P1GQ6y2OdCOGw~G4od6+&Yk$~oBZy9!nb;8a?zV^Yw zKTf*2e=(0=>~0dxsFc$%6o+bjETNau^82c!z6O=!^X~?%;ZCjIX`yEMQloX#b1A;k zKZp))h(i|=w&mxZ_7wz`tuG1xV$5tYu}2<+NPEXw>zOo`MJIpI!6lN_0HNu>ZSkf@ zs<8wpM0;+?GGHkB8+rc52=3F7E(j>ap>L#rM<#W#o=^{;@SC{Z&*({|-hpppEc@7u z6+?NNZPY4KzHJFPEHu0CzDmC?;Pw-G{&O!`ub3+Ap|lRd&5!>cryPN@ba{T}_wN<# zWy23bhPseGVi0e@l>A*>20?(FT!$9sDAZUebpZo$_+5;rs8tgN#gi88<#6LXxy|}B zh0(t_>op!y$f$e*-@BVLx8Hf@8=wp_)zkXtTLm(0h1^|*-KFqR?;k?{O~xaiCpcj|_CHS_E*$t$ z0;mAni0Kp1L%?eSrF-Y|n=*ZaiqD&mumYXI6Rhaf3eg}qAZ7oI$AJArOlkqjhrrd8 zbnCt|FkB;kR#t)Xm1=7CQ9!b36$c`RTS>PTZB*;k7{3>s^60<5Y>^WjQG$CEyQ4nguU`C|UX{bd zMRa5IrxxF_rTm|2W}%YNrj_vh-4u>B6Pk?<2~ zY63_ChzXW$t>nOV9NYm+5|-IhEx@ElJ$$|-NbpNRNhtuGfhzQ#7|2zv(6)@MtX`l& zfXRVeB21tJ!0Z;Rtsp%#K*-5CSaD+9i4uj2{?`4j^I;&n1lVeZhG45=^da7_8953xt;p>zjFv(_nnMd z3DZA#(saX>DvCHdG_0ICEwG12j6%ssi7Tk~L=7*FDzusPb72=h6$*AjM{uNIxfzzb zN0n$)=4EHv=pZH8@%S5S^&^FJOR)}K)<1+}FP2E|Dy!Ryv?-c{Yr!ik_E`?TChKO2 zYaL_r%T5=H%YuZ{+wPVUm{g-gw8XLQ=eIVK@A1h@J~qjTraL-%DUJxwLS@m_CKY6{ z!AFf}GZy zcd8$Sa5%)`7j8e096BTmuK(q;(oLTFR=w5&dok9^FyaL}d2{TvIH^_aR45a{!y3yWOOZU&#yQRO~H2HXqSiv}T;FJq#Qe}%w?7Tt=Fr;SD8RClUQBRX6 zHdd;Jk`$KDqL0zOw%*v>V;k9i@J;B=OiAm^Vq?78E5>Qsg6(^3(=6X|y$PPM^l=i*<=`7#lPGlG`+*R)tqiB=FujtkKXCR7-18doWvw`H{w^^8 z>|h!pK7BO*;9CKjyAMr!?%!vO`^!NoC~j0!Z)$FB9|dA*TWKr*-uZ)$8b3lcvOJnQ z+VdgoII!ORL8TN$)xP$u9801I2Sq)CJvfcBC+(U3SKhmHY%=+6f^PYFXUsHN2ZdVs z-E-DSjV=!il6hRKAI;W>=Qj8gkZ7-b+0Nc$BR;6VKdY5v-Q&!lwus+`gE&cGOv~2e z(r@h}P9v>M>+{6rj5@yOjg8g4{%h{0&ClpusrEyf#Ql>~>hMCrzvq5{(%bup*fol} zqMPz*b3Qtj7%-5JM*iY?yFPyuaQ~3$HFm-Ywx@5;(n;96tO)OZuIoTL&yi3URfgiV zUpdx${tU9av2x1Q3k(Y>47K}QzEe1F{8?nV3S&np_bz^;U+PhtBwf<`%zL3??u=ck zT~0o6qS*Pd-nv<}^I{#{V#+*&!3zE)(pV(YS!GaJ(cVS8C(gw~-C){%5<869Z!3L{ zNo1jGWk7B2P(-X85jOPHZm-khA%BD8)+)Q33%ahrUBo&`nP6uLmSd6m7zRIDp5fis zbh$EebxpzUUPSv*(rzN|E|s-`9W9Q(?z>n0)uMTrE>|(#E^p95uZ~zR(oLIAm2veS zT$RBiCqgH1&S7@&#Ii?N8Aes+DU>sJmf==K;asY(wWBxcY@s9af^c583+FhaSq-6; zpcw}oJ9T|2M?*Y(zk%N0p2}lht;3F=N}Gf4UmNbEOBFV#!->i%m+NnQG#vaXG6B^9 zql9ERD%XIltvT$;g=rx7qcfGdxER5E-nBmcYtfT^LR6P1!lig@m42pu2buJ>VZP)_ zYErsG3YeTp;UZ`zJADH=pRq(mWbJ5Aii?U`m9R%gMyeY_rl`T%3ysI+<)Gq$o%fcd z4yUrZIu|%a+>N;l34@!`Gc#?H7(ICk!Aj7_;77YTlG*j}c?(h+Af&qkWwn4A;PVxiQI3q2Vz z_wq_VNEvK3`S1egBSdS=G#^1n53=nL31PsV3p9quM$&y`mTk+4Ze z9agw4p?U>uBXI7mI?nQ?59dJzq{#t`hkPF7O%HTevxe`oy_ zjt0KM!C9*9gV&3IqgR2eXBrtCX3~JVntxPa1?|kf{+_)8$#LYkRV3tpR*;3xkpf7c z>whiI`*lmoU~fgni~=Dy<{`agc#=U8HlO_`xReV+vye(-eT0vO5}_I`T@K< z=dCedn!Y5~6h{yc(s>!=jRhGv$rIBKPM-N>h`VCR5ggHlHhR}1&Br)$1o&Vp0qnZm zu$k3Ws$X1LS&4jGAr~J!J=3~oegB?h_d!bSa76N8xoPQ|m)_@>?yuL6WS1{XZ1s4(YsV)F7 zpz^sKEJ}NC+aS=886UIQ0|F@<{&PCqC}rf$amFnmnjezhoFlX z2X-I8l=WR#{Vj#$HWW`KXI22xI)-`I-l-|0RS8v}s6B-ION^BNWpxf@ zFBk|wT{0iHp#338Ye5@*-a@fsZ4y-TwKiJ-=ce+2b1IYg@g1@9tN_c94OQnC}4A_8^e zE~7h*1a-*8Q`PP75+uJRjzk-aMaiuv-c59)H!3|}`#HCEz2#FqLMHjD@KVT-=Cq>a z%%G*-{;QTJfm=+KV5p8 z=85`j8t)UH<}X~TqC7-XPnhogZNGa*nou%q{5#Di`ppp(_u>TmOcXp+zJi|&A&<^~ z&X-4%H}Gepxrg)cf3dhdNt`yr?mtpm9am;bnkDvi2h+6knKePo%)?LN&p(abCQduA zFyK$PaM5N74Z%>Nt=BldFqnC2D7eIJ4FH-rsrp&G6YApW18&#-pD`=(!kQGlWvS&w zPy4t&^mI~*mt$mfFzS~Lvwo+unG3yS9_P60w;cPfItFoLtl}Ga0NFs*TYp|XmXm8u zf)Gq9R0?c@hzp}69vp`f4O!=9D)}d5dS6}3tc8m_MIx&YuyxF0ugqrbwuwnH`;%2( zmy_(roy9$7$Gd}?*l=cEoF>WhQaX=8!?peP9VZ2skAw0qPFkpvQ^j=B0tDM6acCP( zG!*Bg)0XSfRCO^luIEEidIR>VDE3?&HfUz*JbT4|XDvopN7S+fTv_*|Nkt@oGQ1d4 z?XWJD5Sf=|Pt4@#G}SYHjumki;WVOYklsYnO6gn0%(|fQ;%c>dLNT!3&okUw@2%`F zk&i4cEx#B>RqRyQWHtkP`kY1-?xk#s`lp^9I{)bPaQQC$iYeXBLComB(JCJ&(Ix4L zmeQ$~gTD3;`y4K+y%xbOCBBWs4g|GES-jfI>QCxv25yRI{rWnCVIq8A^nT$NBKX&~ zer9o+@)i6^$#W|Ok zHj=L&d8P&lCggS8sagUv2~kS_$H}Wl619_;bT6;EvO~?sJ|HBwOSf%e~BvzS`#bRZ6_pfa+F*E;JWX8e{&9n)CAT zL_ATDoa_y0**9wHDE6z@ge}TMf!n;AMR-Co*g_IS<~03IsQO+yA0By}%;^Y`=x{O~ ztK;<9q#hCYd!i`HIWp_dtKV*oYUt>1sF!@)yvg>r5qPdCf~jWD`)nh$2hQ~=y~OVy_-*9E1GgY zqcAz=*Eo4}EDqv4%qTqnR{_h8CFYp^A%gV&w3dcdq&XTojW~DNC>tky3CU2_b7O-Q zu<%;x=$KKgF7Z(BU^M4mOJW&>A^3%I7>o*YyRpArsHCkr*BsS&T%y*$wLdYm_`c*DTT}i1^=-ZOj(BS>IHfb%_BVt- z7WlcvY5DS|TvC)$K|}{D{}VFEg<`oTh#)ZD?mLl!d+q2iAl!$mJ~a+C4+R$|xM>T? zz+L0LwAluqzq!d!N0R|dNM{F2eSpP!L`CRhkP{TJOpfgMS#0qFBPM7caK8+shDo0V zJ+3)pP5`6W(%HCE-OZb1Zx+B{5GerP1wKo~`=nwja)U4|k5Xwxhob+JEIfg+ro+75 zndT9tZU7w6CiVcDj2<%C+{YnJT7_V3#~X=_5WGPavZ?F|bmQ z%0ZcDPtpS;6~QC8z$gNDm0y;BwzY$e&li8moT6uSB_NL-f>O#8tqvGzABAlv zD@Ri~eREvk*y!Hyj}^1v(<+POm)&?zoh%~sc-^dtj~e{JgDB4Cx1DKsjxBC>Sc76_ z{NMrdLIY3%n|2hSO|TF_MKOfsz}cI(bO8Qw!LUXcD+Bbsx3>o^PTEm>y4+)a=$nZLt#K2O1 zC?+?}vNEn!492IkCwfMac{spWwwR5^pXj2|k8Zp`SrrkZCDi346YD+z$NSI47JMsB zv|k0G1)SkvG4q@svaOM7osi;$4PDqeQ`9|sEnVv<`~xa61$Y*>-CzRmCJI+(!XEP@ z*I;+9maivs6&61z)~PKNFAQZUK>+4^P2iDuu9BEYBN4MY{`p#Ms0q z*O2f+a`y=dV@)=)4(l)#O6n*DlZmPkU{eI%i!b%HmYI^72aC3N_9TPn&Kl8d1~LEvTx9{9={2wpbMA<#%d;a98$&RPDZvk>zBZ;(o@+kU+zN&d8U|H*+vJn{E_4DP8JIt~jog6jeT< zRUQg3;5B8(D3J5ydXHE;j%I$Pg{?x>%G>B3()Y>zknGlmm_)nyl+6OmXNmWuJ`rt# zgAyZ{-Tl|XGSMF&o!aBxFG$aP7&K}6v%G+vY#PV^1!L%C7Grhy6XoQV_k8Wi8sXtN z_U@go>WNG(iM#AmH~Ac^-&EVM4#qno)>s@gCMyv<#3&6h{{5`;>(~MYKjZ|l)5q=* zt16!r?@1#bj4;V($I_e{XQ z)7-Q}7&SI#Wkqo?=iC$a-~15Gc>f~&iBm^%j^^n8FrK(DC8<@8aYphh8kZ@x;dHxkD_@!++c^Qw;T>6G+HU(wwO?&TIy7M>RD zEE*8telR@XnO2!OpszsT(3!`bbiQ~;L)XtaS30TrzCcRhL5Ui}AFWbESiIxN2qnj` zmxrl8EjsHVj|0^c%kJizPEwm*TG4E8ZF_efPxvyqJTK5H^2R3o!-ZLW?mEMtQY~fr z*v%?5m%Z2TyFu9BwG4)j4jaFjTs|BPsP_Q9MD#Zsm+f*ugW**wftmFh|fE7OsmnFe)z1+p5CG9N*xh% zJIAHv%{)2g%PF~RAstGx7sc=Uv&*|G$m0w>F|MWF=+gIClIur3NTm1@maM#$y%;+3 zHDJ-x{D6dU=FK~CxuZz=>v=?>(4%!q1#1m`|1yOb8vd3Ca---tabM_iKIga`o1#bE zR5Gx2ExEU$`w^QnF~D1iMPKN!3~$X8SJ6;Kl4r%-AO!abu?Cdl84z5-#8h{6ap|A+=MY9g49}{|o3{&pF$B+O zjVl(C?`Y=g{vVA~c|!Ukc~OgSY{F5F`TNlb;yh2)#Dh9@P_mp$-iQeCX8~5moAGdYOKI>S2oiti_dec`# zMoXozYpsVBvD;!)CA)Vw4)^>44xWh$1*!9FSr))nd~Qo_e?RsjWo z3AU#)Ss-MTZ8xNAAnXqdCdG$4$Ymw(%ekdqFz_P7RKR)x79g}gJ<0w@3-}3wESHy; zu#tq6<^C^r4-qIN^g>2)kax*o3I!Dfh$^5htZN>G;BGVw3}{a)4RV6jwS(z}>2n7M z=k%P8h)yw5;X1h2hJZHmlstHBKa3~(OB_`cGET_N(OexAc>{yq_`w2UP~5AP>%YYg(3%eCT}M}t>7KUhxi**c`e`$-+o+4MiXaqg1S_l~0D-KMYLO(u@9D>V z_uKv$UhTI1y@jL#;CMENY!$?M=4}_fPms1}fiOe}69mfM!ZV_8G*ZV%BEe97rufx; zn-7)DKx_LrRxWn$>_xi4DCa<}nA%I7q7~;Cq#`DRs=wE z#26?glmZ?gU_X=PCMdzE_3vWxXJEgF7b=d6Cb@H!P&=9Xn89tRi@h;fxLtV;VpsAI zMglPqLh>6{FRRbu`d2vTjv)LEj|Sz9l@Q>9P*^?~hX5z&s6&l4a!Ul{M(`&)I^F>P z&iO=2YY?&y0Pu5((R*Y80FoAC#Hqix)Z&#Q&oX-A44E+?P_W)WK_V6Zo!;ed_a7^L zFj5585!tN-zy-EDWZS{i4Q3joQMv-i7-U3Wj=1395~(yndJmk@M?*rR%aThMgrPgo zEnqIE&J_&97D#hA%4(~hvomB;`d8?+A^Q&%O$aL_tv27{MVWmu^aR-z32$6itnW|O zo0YhIog5w6_WFVC1TYE{As~_={o)7$e)<>zpi?=+jXmSZ1Z>`s(brAyy7&xQsZ!l= zUg4Xbnj+j#bI+XU=s*Ps4Fcro6ZQ?Yw}XmBp;ZBW+kOYa)I`M5SpLjoOx5NyIOD12 zRRWz=Hx!9Y49oh_M1T3HuJka|pJi}Iq=wSS*<%v*mf{@7KhX5?coEn6y0QT8!CrfU z1-)bMDPN$LM35eR9%o2p9;Z>;xGqlNmGQ+ug!vF+mXmX>1Hl(!0aSEo=1JJ$n~ZWw zO)5;|zWYN@a5!?0mOaxBIjLf)YxOnL6~ zoaG2h#?p1$JYT5A*5hHB;T%!oOs#)b^^)|T$!(`eH8u?N7kB%TQru>mnuRG_{1@2e z9BV~q95Zzm!(&_tu{Yip(lk;!%1&ctsqh<{I&Wi=6bf4&h~-4CaMoZQ9UYy8QhM85 z^!Tk#XeituoC*uTN#LZZFG_{-x(c_mm55KnCTaCVvogyM5FMO#*+mlSpBTLEVSH_u z^Qy!P$1@p_Ns^ipm%-uD4`oE3ojh6X;Xx6|u$HV1d}EcQHmV>Tx_rlecI)qFf!cpG z9^Bz`tvt{1@AsbYm8#ojcSY8Wx;^eC=A@vcuCwR18l8P*MO^iokTTgm&_R11jZVDG zV?TK(;!k|>N*a!`7e75}V|8YyymCSR_61r_82K&qC2bVzLHt$0!phVv{Iqh_Z$i2J zFJ`uFNV93Ha#Z*C!mfu%LaAKlnY`In!h}ruj+US0T-8TQ7s|y<(SNfdKGSBv!nqMy zk@=xE+jU{$m+4%&qtKbvd+a46|F?;|UU?2MSp3#pD#CIHXLj=FGv}OW(uz!+F_um( zUHXh~cYDQ(@0QEj8pYEGjB`d&DJGQf{@)8=|Ndv5W~W)b{pU>qHObNTTfvVD1z9DB zPlaBtbxz&tK2vk0T;z~;I^uWOXHq2YHG91y6Nxgvo@(1iV${7JnK>LpQfN7U-FRex zGPdoN(EDvFj5*z6-_gMUb)QP^7N=z0Bs;yv>anZ3cWIo8<|{T$&NG9(R|Zp@5piQt z!Fdkw;ZvuNX1(fZOQ7ee8ohFKzV*kynN+4Gwdln7oqPO@K-$0XgCs}cUK|<+vPi*0 zO{pcDwvg)IIVcFCUOO2X7ZV%v#MD5--vbhFh$!WpR*;V6i0cL>7B&L1v7B z+4R72bBg$PniSp*^nYK;-aJE3y2-X|N{78b65gcvNz`l0@t43XqQe1Y2F0z<{415h z%h!mrCY(NLI|AZawN`ARR@@vn3hp5^UEJP8^Vnb!&vp#=UOq$DQY>ZBleZGl00!l+|ncJ)59ujcDEt3Z-IO&Rz2 z1zD^CnJl&FjS<<*py@S{lwU_pB4-0MHH){X@`+F%{FJG%W8_wo4s?LKnJ9Dbh32N4qDSP-e$misR*E-=jH zn1;7nG_BD~Ot-y;@lOUE)f41e^7RlQpyDA5`@r=2l8uV_h*Aw7A0J}Vq05ALPgIzE zK2ITw22_Ki^gbA&b43(Zq>~0mNa5|M*L_xVJZRB-{ZBaKG$-*R{%msJy*J-vRO9;! zM>WdSW2BC8{MU3+h!Oxw9ChOJp`d_G8>XdR*g4>J5d*?Z1r=BB?ET|wZe)lIUL2&J zq|OCXC?qgR`k&MUL#MQ~w3V-az-t4x9hl6RF^Uae1OFHZLP(@cpN|{g0veF-I^eQ&=38BMAU(M- zDSfufYs)u-S~-JBfum6#JJou*}Sy1cyk zO7NCn_MgAVXLxW4CMa}-P7|1ry}gH4R+#cUJiNUfM&@2VLK=v!u9|V5@|>zBV(!0K zZ1Y<}83HrZ^vj#M4Gdtm1K>}3^4@>O9q)}ltbW}MTe7WDgZ!0^O)&6Okmh0#a|aX$ zE!%K!z-!jr504L3)nE)PvuLTaXCxX(2mIL)BMTC-iVSLpC$iyoTIQaVh4LIon zJrC}U!23VAQH{GzixGf|*0k_b(WYAa>7SbCzL|e>o+Kt5y?qQ4)T3OkEj zWWXuqt}08P-m|y6GfdB3=@#oVS=+tON?l@`HKC6alAWE1_(HD8kf+1Wf4@ZQhe}Rb z$;TchIku|;hRDN>YfkUN>v_=wrEq8~FAAMvLC;iMH0gV0tsKXL!-TVDT9W2~rY8qczkn3Z57ewC-6@BPD!HFPa+7!jI zGoD=R;k!OZ`v%n5dllX6<-Oc3GxWPZB@;fVCrZ2Y>vOYyd>9o}_3OG_?~2KQjYc0` z@Gwx?t#`TlX0g3!Y`+Z?V=|_jswC@RdGFtteHyEn?uA2kwyu}mD}y{eDyUtFNu#M{ z1$0ijU+WYeZnCei=T{;W=+xg6FNghA=hVSXU@3p=J2CNZ=U9|WF5xaZ_>>6o} z1mq)nRja8qp`(e-Y~@9tRIcWXw}k}yW){}+RiEuO1ju9X)9=o$s_740NV(6J-mN|I zzWKQ-e0Iuz$|&pY%?Od%{nqE+;cL5*=aRFL@_UBzd+!8K^n_>cc8tEetW;=bPgKLq zNNEjYHj*Ij^S7zft}?8R3YTAOZ*M+&g0Qon53$-v(-BAvy`#K$CtN*};o(!22fOTC zb%Yily64Gn5zpdfV0DvYj#Qn9EN38e?3>$`T8GX#iXH#jdp`bC_DiLSaOjT_+te>&-B<1pXXyrpE-ZZ5b~y+`c|=|MO`rXssbP;esoalmN&cMuePLe0@V)d~c}ot@ zk4(lCb$(LrYu*Jk{a)O!J_ zMzy`d8R2b~?B>Mswn-*}-z2}UwVkRfhWBWG*qFur%BlKo(VNlYu3f&SHp{k4sW*7D zPwGaQl&4g{>-Ee8|7fG|cGM-^AGQ=KDmKCq_sRLZUe>R==ILRYDWVgHC}9#nPiLmk12U)c5wt6JwQw9;n0u^M@d1U3=YjBa&xg;E3?Wlz@MiGn7iBLh_)a<+2smqsc$JO;7i$F_NDFLYbo)H@2)26R?d5# zr`MaGCgUYVMbEq}6TvM55p*D%Kq>-&0`4IA#18Ce7qfg~Ym4lbaiIlM6wIQC>D@}g zyY|fnI|OtE;aYKe4lV(FTBE&JJSp|>>V%eop{Aiht#~q5uM}B@^C%@M>IS314w!;~ zwV2p;gEkc?Zb=xng;7-ngAm1?6fW-6wj}z@q^73khbz~sy17D_!+_}u zbAIqp$7>bCqvGn68oeJsIP=`A>I1R^Syy-|6C?Xq3Hgf3iSroIV?U;O;11lY{FR>S^eEkcolZEEQG0#fLcP< z-2MIC_IKL*_xr~ilzvB)7f6%P-|w=QPoP963W<6k%#VKePWn9%?0P|T0W%o-axkUY zvWn~<5_tZanwm(G%%Zv>GK`5TKQ4OnaX!R0RUK{8Ts?mlm?g04s~ znhXyP;*}bN191ab4$2Qrc~w4}6zXt7SDtqMxQ97M${!MbxlS*TOFvCPCt#9Ug$k7M z@FQ{zN|s$Al!wfIA&a}r5m_BC}i}2%Z#iEfEGY#)`o4}fvKrvT&9MmCXG^q zRcI0d-4AFh8*uo%I#?_;dS6vj(=|RGhl*)!S~R(R_a6nys8RRLSO*su0n{XU90aVt zzjG&->Kqsh*%eQ_o*P3+hlkg3S|QVy(gcNuJ6k0EaOnERa@{nW)0ik3;S{; z^<|@4{1ga-Qf_&)*WrVy?b$Ep!J_2s=4RblI9qD+0r~{NK ziA*iD#;TL#7l!Y@1-+hxI)`iDr6B7hcNkBB|3Lr)f`QL=2u$R9yeZmW7rMxbI?T<@ ztAW~r-#qOmz#7~YlMhA>aNX3ooaXBTg5H}wdc>A6a0oWEqu&*N3qh~1DgUiLhT3m1 zBY`3ujI`v>H+xPFeePO`h2UExaB6T*@Vw_<#)mNj}1C2;H89@`LjtBfHbJ2vRvMS zzNL;tFQ^)7ZPkJ(oeS){hE#2$6{@!-i<>FTXx+OXd3e zeY(q?B>3`nxC3y(5ZMS=TeA`>g4vi(D4v4n0k(B`86Y+QByfH_ZYps$@hz3p*V5=C z(J@pProG22D=VeprKiRRZW7R|ZKbi#x+~UR;xQ;SvHN?dr?~v3e<=U=V&UuQ=U09N zA=e1*V-}Ag8f7M4mGLF#{Eis1ezXgk;6Ad#>h`m7l69)G&hBuG)r=Ur=;W^3FQmlR zqE$Hv)A9)nDA1L9bFn$oEved!jRqpDYo0z4M~iah`{TQZ5zX6L?wmT?n9k=mf{E3s z&iNQK&)4SpVRvHK4O-6IfB73`5@KCQe@?umyN>o5rNMPG_qS{fa{0yL zKg6(dVIdiMsDzP5RnJ9;$>sk5$5^Q%{{SOE#F3FPb81{oEj@K%-1=cE{(S!mZ75Gt z#Ny2MM@`xAS<`pM%Xfqak9(h?>GQc1gXhl6@b zP4A~~**a6k6XO?|&Og#El0CXU1tvZi8IG|K7w;2GEW}J8sap`c%lJF+w=e0>utBP6 zG}}pu*fYabuYu&qW!8ZELzjXhd#5qEBb8ZQ60SW)G)V$g!@8|#*Ak@|cPT=eJ}KN% zw!wY1Vl~nJb50GjTFk8^s8TqW*C#Fgig+hM;CbEs`FndmZ?XuA%$N_WRZ-4=JY$U{ zIlF=H8`;V-7_Lqd9GcL;i^sRkx?+Jkkccb4o!WSFc_^sPO>cam2rUoyu5DWi0gm1NxU!g@%NPQ&+l)i*Gb4tJY-ll-@rV~lKHMmDY|uH7x`Xj676jx5`jCyq)|wE*3mw zY8zV(9gP^o8Vp2VQW9k!T`c_c=oa}VI6PI@fqPS*Q}g)S<10}qO@{laU+UxbU(Tz< z#qW}(F~~Gt$(|p{zOxRruD-w4$eX4)br=6oDx1i*V^u1FSfu#M%%@=g*kal+WvbgXg~z2*kSlIVb4LF~VDN!LiOp z$A{pmPUyjwouBH;g$&DRXkza$mUTFuA^u^p3W2&$W2wko-&x6-`{6?w-&@N+|23-| z_}y6fiE)0y`KU<8ILEuS`)ESCmi-^cehbO`NM7y9@)V~c$NEJz;eIK+AanbJ__MC(SS;?1Mqspj&U!PSrJ-^yG zm;X`wm%=0O8v$q)X!%rR#B@}XBn35FgMK+VDKUF9_ zkx_rC*6?Vel)lsrdxQ3-*zHeq9cniQevkz#yfc*{Ux?jS!dsCry;XW{BAWDKz*Bv1uU@)zvtBu)c-5Q?+Zr6m_Kvhs z3r^FB65qDxUvt-AN@R*GB^^E>{i*%;8C_X$;p9`;`~mNWbqp~x_y?!%p^0Txrz;ng60FQ&pAg=w%nVrB;rQlOoqeF zLB!twrtX*c*9rWAT`T-6I20W7aBK?vIi5Z90huprGtG6^O#<-X8V|*9;ia>u!qm$5 zJ{t2(*a>T@cID@@EP8Iz0lVXQxnBns+aK`6HlYP@1DxVu`8wHu?w1Z`t4XK2DA&u( zSBtrm+m&^7eV`RRZ@U)B9}k1JBSIpg?ccAVzwzb|`zKFAVIj_(AEw4Te+9$COJqi) z{=92pD@;wrCa4=k68z5Sy;6f|kulFPbU`I(6^qNr*gk(g8r1qJ!5{NQfDO7qo)p;s z6?s!Mf|S#0a^;s9&+f1k;}DCfrw z=r6ZS#!DO7to-s-8&T}cRj+S?GrpZ%wObW~&Na_x1CufNR5=x*+vU4kp> zxcjE|Arhz-Og;q`30fR}z-tP2Fz+Q%ey6&*dqGW(b#qv$hU&1M_uA$NKg zyw^ym1;+g~Xi=~QhZD52gM;eGCmXJ>P%DJ~p_*vzbbk(HX?PlHg?ezO5FH&2JF>VB zjXB8(FxcGtvhK6)t#@<;RO$Cv#(_nB!a)Syd06jmhBfJMB4~KyOR%3 z{>I7S7x9+jTS|pWv`x_s%eqy6q6!D|@|u#nM!Qp3X*ku0N~rxx)|X`{iUQ)+jitaJ-2C$c&NQ}k(O(1d3F5RNyV7VaeH@0*Tlk>Xs|EIefo?z9H5 z5gIim#qZnErs3{zy!jJ$sZc(|j`F~qtexPlt-NI(BLxO2JKsmXOC}3>bibejqT4U) zEDY+*2+}a~&M87W$&{)Ojm`2Hp0Y}rmG|2Gi4p5yQ5_VU%adsQ!)a%x8NFZ;#381Cl}8F@GQe_+d#J`>8Fa@b7s$8eFH^^qD6<>9FQCXnZQ zr`t^u(w^fW-v7{a-SJfZ@7u}_p~#j!l99dl$X+3PXA>fOlO3`* zA$ybT5ZN+Q_9_y}9>4p1UcYaDdZo^Jp68tRbzk>20?c$2E^8!WNnIYClV_I{Yg>0Z zYX=f4IcPAei=z9;I0h8lF2ql65|5UT!)mkcW-UFvw3?dJIP9=;PN?a9Yt+P76r;ko z;#BytLfFuXM>JoZaUf2juI8FjD;Eos5%Yn-BhF<7+@$$sHwglkWJRwh8haBKna|Bk z?#VWK<=n?GFB)dzTiNxN?z8HnP?Wf5Z~R7*S2v!Ef`aNx>@wG^;z~=E25xlzDk(Y< zT$@C^yZr?Tsc}e_o9zORuvFOhaonvJzJ{}_37oDHsp%!ICwTqws$HVKV8+_*8{lsg zJ=QPqwNSldK{uTLfQ?|UcOEav*1Xx@{z}JUfDg|bi`siNG^t9$YQ*C0f}Zc{=o~J| zH--Y&v~eTlIU}66+{ZK-uZfW49c&0`(nXm_$t^~B2o_>6&I#W9yHoWA?ewh}{ar%8 zv3198^C)={k~}Np`swCXHw<&(J(r$i!%)#jeJN%EC)zHfO4d0kOJt}iyG)*xpLBSB zM3`^IJfGk~8W#z+H2RdQKYpm!j^VKZn(8^8 zVnKc$xwR&Kd!f6d(g%6XtWTXu-a{`jg4sRYeX~;R zoEFW}$R_lA-Hz9HES91h{na|@tLodYl6ceXTy|qzmdJkwTO8fWIK=$$$S)`;sW=y@ zmiO@fcwXRozQS!j_sZmKNzeD|Ee@c&_3!@T1UmeFo8iD znMAhRHN8ru#@{I}Wm?fK3~ykdd4eKe8%Lg3Lp4+Tl>+Np{^A`mRFsYU$qZ$_k@R{S zftS}JjXTfdGF623Jiq#`JfxnqF=Ud3HuzVsGC+HxS(be8#c%nCtx+lt1^dsbgO{qm z_vizt_sry8)M$=I)u!$)9T@LMggv}5dlyi;aekWgoKDvKx>2%@R4O3thqzyY_Z5>? ze3NM8!10pN87~8lMlmt0d*o;_d&a{cuEniY8Hyh4>_CB{TBglCu2QBA>pLiX1+5TI zSPDv~NvU!rFT!``VFWv#SR%6mgb)f2B9LCm&HvoqjI?O1psX~ohp0{id$1d|di=UKFff3Q7cB7c+wgFV#sf(91Ovz>$vr1K~Jya*6{-;eQ#>V@Iby zPC5pjb{yXIKY1CD3S5?5V+Ko7Y3FyC{t+mH8ZJ?KS7@^$SxbRSuRlsuSojN^c+Zbqw-s2dlH&pSoDGLNqfyjNg#;EsiNse4L)gba zxREBJ_7$Qcdu_yy?gJ0l`R`e0-@yTF{e&+|ZvN(;&gWj~Uw;9@0U-ne2|1kpr(npF zhAROUJ49ABb1|&^__yemd*K=)%<>ey>9tCBPK@17(&WV`AV|IPXg;)g}HM|=0ZWi{_DfL zY}F^`YCw4bs|f5T&!*Mo96@;Y*r!i2D9Nn%qPuoDmtX@3%m=#I6=y#Elj1iT8X@Yk ziap)ej?$X1uc(~W23*s!vMy_BwP_uutm~iuY&Yb{^lbjJA%F*_Fym^QF&HV!t>`?3|_JOjCxH|$c+hMsmv@nvoRr2~Kk5q)lv3Pcac@ezU6 z|G6L`kRe0NFuWw{z1y~r|7O?(xp@^_+1f@OSN+Ls6u>=z9+E^Z(y16W_F`=!)I$t1!{FMeH>02b zj-M=b3)?rg=S|w|LTN%@{>+=elzZN^f&s|nG`e);_9PEY#ur*nr1a?DE@K8|W2O;s zs>tUhOPB`PnAXw!k-o(pgx-E92f0M1csO3CR;rUvbvYFOX}%_2-2QS=&+RdR%Zz9| z^C-VP3;`B#Pd)Uv1G)oS&J^L3qfwo2lO`|a;WsZZ{8i!9t@@LvB)`QmqKfG@PxzaU-83szL9dm-92=QUIMh+Qy=ivo_>}29 ziw*;y8hxEe0kwfT$bVvqfG=7yD2;)#I-(^SjAdbk|L0ZqeB&lm|?xi+q_@uyb_xjy(u0BU=-aN+#bn5h>gJ@Y?f6|+J zl*4O{MqX$f+!3~Rp}(N$Gvj&Z^86(iIhAIWgtP8T%m;xwA!`c4VNAbE6{5ysSdb+e zHN4z|kxXteFUhk|&)#-SB0}r$0DJ0MPirpFfT(?i5lYKBVw< z4lShksL(p{LPS|W@u((?$v_hOPa!g6QoXKOCI;OneCF%bE@XLB)dqAI;sP25oAQBc zL9`ViX*+4zB`jjR{2nu}CdoNf^v@F$dXc@M`VqCmZ~3go?=> zJ1;qq=!nCF6^+ZXu8goz@DMDTa%^v_SAd#s~ScBT=s#M zj>SG3&+p{vzxk~R`?5rq#N`4FD!P5P&kJk53E`oYy39RKukVeyt>=qEKQ-7oHESLF zyvr43jzOOuO4eA=6 z@3Ys(DBovku;?byNMWh$6|3S}6K!Z7+~ktxCZimBB|h<7rS;9#p4qt~z2gjr8QDwS z0ou3z4yp!$r7o0=_Csm~MB3@2IC&$lr0qvs1UUJpn4Bw4O$R&h_-D5bh|t_9nFjm? z_{4tF?~#ppiw{ovitMbPCUI5b$}q<5ktR_1MY=v3I8%tG+$h7frQ0Cxk~@Ca>(OfA zo0qQq){ui(2m(^ZrZ#=8oL*PEYZHIqHgL=+PJJy^5piT9uzzdCa91K<1Z#nI_Jroo zeZ08mPPfbUZ@1PNuS7-X7AFiIRo&v;Dgy>|Zg<3H&8PzHmN) z;*18Ii@%HpEoI16!V*)rY$Dy{iVQJ7NC)>)*mXw!W<&WPK&+U=)YV6=T(I07VADO&m%5n z;$T>A%spqR5;-Hr@WI&K+pTMFi(PA-h^3kEV9C?zlBxY%NJ70a@gx<_=jK?XFFRLP z>mL}j^E|Qo1bZ4kYT~6UFGL!J9`)_K2sssBU*OLikxRtuIfICq`zA`hy?3!PdHpSd zeV-nt`Yi;MD$abs-xBDbFkpr?m?DZu%$6BjpZbIo! z;b@+FEdwbKn=gDgJ=?w$4Wx3uY-?+?zGI&Hj93+t9VH0mIDq^5;j^F48O`tfV?F-n zG#&z&5h=<*)a2g$p}zhv6XEoHwsREJLy`muswL?e8LRClKOk=!L_x6cflP0JM+nsv zky%^A3@j2u?AR5=Qtz@5s_4Ag1Eg=ql%Ue#Ra`x9j`@UcNBfp&|2<;r0+oon}wSCO(y`W^dpGs9!YLPnfyOZzIy4*XKsV(5k)^Y8wNFO6q>e(iyXm8Xe%_RXK zg0P_Jw*DleCRf|thW+@|=U{u-jSWAqbWfYW3)0O_#mz8v!QFzR=IUC*NPrFD#%)T|6tF{v!fG1D~%hPKf+ehCs_F zOMnJp3gHfXUqFM7$jAZ#88|#)vv~$?1A9dO@Z}~yFruZNN~NE{qY#Ve9PT*g1+)V} z8wHSi1&J3Yoi~0wo#0(~0Rad^qa>Vmj(nDm@x8EMC%Qg^Y8+(C=)J_FI z%+)EHiyeO7d>LIfis3T}EGSXnujd{ZOtU&}F$eT7ZbJIozCTi}f3#+gd+~3npHWo# z#w&^cCl8tImGl>{$glmdXuAH)&zXMgfvIvBE{JXMnVPf@fD0#ibA? z|4>YQWG&7!(al9QcYVh>)NdB=bx2t?PYc1V?P zH&Q#EpB?&OPzvM~s%rJ@DHHyDxTv7h!i(39I3q*YHQp3GzAV)XB@A|?AR zG!@R`znDa+>vPdE4SYwS^vCasq_TF?gInBVNt`iFhgmi>Y{-vLn9z32ONYBBRR5+s ze|2|XmfIuD`;Npfgv?~eR!ny{T7hzqR@>x&?(SQpU->;My0Iapb)oY`J(c>D1OloQ zp7EarDU3c3j1_*s4K8&G1{7JEB>UP*j%C<)Q#RN8oqw^hBlF1h!$W`0*Zw3l`48{> zQD)Nl+_Q$YZC(DkZ$&N1)cRvS)98TanUYJyzHBQHrjN=BS2a{-F`gUHj@g^r zvQdt5aA!p3eum79tSlQc+w??JlTyc1;9Zz)q?EE;Uep{mrNXx2UGWFj>S$NNpABuz zb-05tdX6S$YWqyXkG~?hur}qhx)lxlNwqT3xdas%L0ru>i^l`Bo9DdXJghD- zhM=)ndk)vDSelbI^4y5VOuz7UZ{YZ*;3U(Y%Juf*r9=q!pA>2#DPQV=16QMX8ihVS z*7Fj=En-R9#I-Mru69yUaz8DG81N`5n#;aZG0LnB-ru5+r+v3N;3%`;ld|SB$>eY6 zp~`#RyX`JjZhzWcMh~-zt9W`|7*eG4bffI!I+Un) z^hj7U`-*gRPfyfI_%H{B;;s~^FW_(0NHA=Abp6$8kT6DO)tq_kScDp^prXZsYn#+C zHiO<6M?JWac&jN+@;#rz+nP*^7oqJZ6~(kgvuG&Q=!q|eB#D-3UWCkjrwKjOnZ&wF zA|Tj#zh$O^X|0tLQ(>57P(79Yki0s+7HeGW%lfa-@3E3=>Ua2?dd>9cnb1;vefI8! z<$cATy*;ZDR49!(5v)g4PD-AEQ*m^%QSW6`=}{`f_@ab4Sc)*`HpShlZ^7d%jt;b} z8EU;Ra2hHnNy{F{I#wqOs@Tg~t4uNKd;XZa-cG6WXClaQW4CH;2?^V?tBmrX;5Ig3 z<0_eN>cN#xIaT=66d_iZE2G)sR3S%%)Abq3{Vs`fTNUab5tWAWW+vs~>1kE-kC zwUhm}G3$E7%s*{6jp+qznd9T*VU-!ehgigA+8IDiBx_PoQo4c=<81s**zFR@uyU(d zyMTgWtAy81>xx#I>r6+(4@Y?tALWZiIQ>d13=#c_;X`qPuKj_hB4&mqp0SK#bQy0- zdEIXJYy2M!*-PU%q}0cPlgjF&s`c6&>hDw3r*Mj{=sfX%yyI^T5yoUb5miEspH$HL zU6Sq&YRLQHS9g4_3Hl-l7_^Gq$)>+7@3Vz3FflW0>SOTl5!iO2?uEF~lAf1V#ry2$ zp}5>ne1KGETX(9hUdUP&;)rq!)wgAzdyd?#hNq}wI#^z_W;c(GPAOhFF;^wzR{@g{ z=U#Wu9bEoFw7YiSsiG-U2aTg>@kAeExc_OlxU95j%2p9-!z*+T`R6Sw7e6QNFtrzw zq@=+fr58Qcy%M-;nb=qC?JExbRj{epd3hngYIuYmg#8FR*>LR)O@cAW%EKefCijX3 zrezR(yp1~bn9Q+=&8&$>h-ETQg|j(&R|2(JNB+9U%B?|p)OE+vyBV@EoNBtdd5SQp zAn2j}^+BWP1KySY*y1OuUdscrQRBjStG9wb*Rr1U$KP}Z$oGuW&t&JmxBPBO=Ocx0 zE7B$|qP#YkGpkk&@c#0kxQ03IAI0k7_4lFG(UFm>9A=%!jCcuUV9-Fyi_l5&Wg^Zx zxk70E;2He|8r}EP?-Oky4~aJ~Y)t@;uPJCXH8fm5Jxv2X5A;A|Vi)XiAbtc(JDQ|v zk1(tf5rkSH0b@-ZPi8C$)MqQkE*p%Hw;U2>BT6T@ZXhsP(J|P-yUM0(}EIGr77tZB}?9 z;cwGJqe)8(Y-#c|%hcKL!PXBbl7dES-~l1p2})n!CqS}*rbkWu>M`VUZe{`10!kuf zHMRPWA06VrRgd7U@;Op85$_*x#o^glKn|owAA!0Yl9IYQFJ9inr5eAAf>?m-)koLC z0T<3U4^7S|Q^Dd7uL%}>UO&r9V996Y=a=2vD{bt1AdApi1Dgb3^Kz*A5)l@Ph&uxO zTG!e-2z9I8mj?q-xm%>k0=d>8Swe`7{*%@Kdw9Rb(!(PK_@(3@>#%4f*e-{KW0|({ zX9Z!9h50TGco@NZ5D*gL-kWo3ZUy!Ss5XRT4beG_Xn6g=adW+N<8wW5b4m?h)c@bp zfE2)72M`$=h(IaO)|hK;ZXPTSnOf^3{7XgCcK>CgB5oywm>oO~`1cfo!_(nD!$W|a z0!(x0E@)rSbyNciP%(!1F(bbzi3@rb}R zhu;F{17r@gGcT{Dg9Ee~nIns(K6C67(=Rq951EVni+0_V$BvXs#WC-8(Uh@TM(Ct)Kd*#cp>3jqD3J`V#N!#+*e zS~}E*in|-7o}GE4CbU-BOEC<+WQg4|s??2b&&kSq%m-St%%c>M4IUWHo;^dQ3jg5S z3At$AkjNTHkRb$s9<*KX{R-b4u12X7wx5QEl-xCz5m8mYK7cPc3iN6)j))?jDVPmL zD1PjDwt^c0Ua0Ty7rATjX+(4adFNmqo$l6;WpIvG{o>~0GCMzX5m+xP$yo(j+kUp{ z{}qG4Rf9eeA>4;eH6q(>_|hHB5dIg<0hu5Xq>C4UNO^R-s%bm;%ye9CJUSX;t9Cg% zv;x)|p6?CN1NQeX!B{mGaQ)v0A1VSs;|A5d1!bwQMHiwp{s@mf{3wRCIHm-`L)HZT zzG@G>LK;r1oVEjcSNG{tkSQwtJ?S=uPG>7H7O0k3Y@Rda`o4keRk)SFzaliB0;5UDqS!p_n}C<={kAwNY}}M$WrJBTxk?Jn)JJynpuIXq%!wksxA&x;>?GdJoHSs@)JWndOB6TUON31)esD} z)DvyPPH2j2KYT~A%B7b4MBCpTEjgVt=Z=E4q*=bw{AZMQU)1Ejd`|g038WD<%Ha*l z&`2YKyUR2Xl`I=0mGMaFxez)&A?wpbp;&==)IWta0g~&6@jA-x#GYJL@8>2QoSo=D zh(@vAt1gdGvotiYvk~&8WJ_dOyKKtmT8cJ9TAH1p(>@|{p}7`$PZEUmc*4G*)+$9S zSsV8+k?^2n8{vDxFeMq5*;r}h*TG3{v2Ge(ezf_U$w96~o#v8^@6OS3>U*E|-*H^) z464gRGEZQqLD^ds@nyr;5XPzS5B$DS$z}673iFUBv!{Qw42{#GN7Z13X;1jTG4p;z zX@i4Da&FfX&6g;T=ged_Xgh^nnd)5_JjL%>aW93lI_lKX2V&*h#mD69?Xc`paAB6P zV@lGrd+kO^%Ln4#4LgXDkL;41vA}&TXk{C=<)|%@%=;-BtMjM8U_$Z=<+|rLObNyn zw!(-|Vja98#V}f)6lRGQS4stO)h?SMUwN7edN1qw@Y=r}-`-5@|2y@0EBTb^2YLA; z?{~ui{r9jq31_X=6XM1A&6HC_UMg=p1d*dT@Lhe+DYv}t=Nfp-P-p68;oFehM`kZG zpzZl=p4Ph9kK(A6%@ZT6GLk99Qi2KR1DSL3IG>(Naom6o;o_}t?lj)d2BIY^EPcL3 zq#R>ns1Xv>1@V%fCbwsL#no?x)V6+7>yV2!NVTjWv=~oT8`y8J-dD(W^N-?xllf=x zH|y3zaqWW-vt7P}-aWcxNiLt=>cgEyQS3V?0&-ehd+}pftLNU)OgM3sk^~RwW`1US zPJMByCTND*&^t%kup3cF%^j~G9-o4A>*rf!+OV8E&iSqtM=#v zR2M5R8L^XmH%R=Ckh7PkQpDmoQ~TpGTG@9W7A9hZ`n=z9U)U}4f8*qJQJPg@&bG@% zR6VuU*t1lb^+x_NRfUV+#KxH#JwwnGb?3=He9>&rHQ7_KnM?B%SC64J3pU4sQHum& zf8X(r)Q_}GzwPrXTE(*V`|ur!zczlWLuxr^}yu zUrrK{%HA}VKRA; zN7m6Uy-|L2wdnEp(S&Q{hNkeCIHO4+wN{88c=cx09lcZFLA`nbzy9jDVlDsY@k6%1 zEJ?a_*z@%j|b$pKR=<2>5 z5%VwR?gLVU6c2-fit3G0F=F)zG7wKP+1i>;2vGJPJB&D@CGYf*+mSE6Z z56kEfX`tR$qoqmBiZ+@>DDG=&5O+|eh_qGX>MD?4Lk_mFYZLO1fa{A-!_)zj1VRE0 zK*mJ?He>R>O1^t^KOInXq_@8TVzhxEbVwSKG0-Ba@>_q7FPdoSs-b8K>C!8g zSvB|X+38f)`iJd8RVTj8E750y{df-pK+r|#Awe3{8SuXWlZOy@LsI3;d8n3d*2J5wmW+tXCdTS-driob zyCSk9(j7~7jeu-pVeg zWM({D>I@KfRdtJla5O-!N%8FFFr>tboioFl4`k(F2!zO7z=W<4^8l|7R9Tyiv&I&W z$y}ja4nQ43a|athuvvny1d=YyI7t(fih;d^Oo&u>p%KVZg#iW;cm`Z9uyXKMxXe00 zGjH}2464ABfd>MR$I41RauE`+mxwmqMGYlb+mHMLF3v^ZadJ~OAZ&yK6MmOAcPvx! ziIh}TWhGoYfq-j~o1Z3EYzTG_Kq}yIu%H|QX8E&pa}mIQF@ zEqCk%xHdbWLK+sTAitASRFirIR>eX~eqLUy1%6Bvr|%#7*4K-Ifcx{=Z$BAs1;q5? zVDmx@k$ws@a!kHdewXcIC?QT5u?B7!fm=B%314e49(9{0AU%4~3VAABF;C0BfYuPI zLb0-0Xo~3tBU~A>0N&X?M&z&x;K4~si|+CeR_v|*~{X*YgkChr)j+rjh_8=x*cU@TiL?-xRd zkwMg1ruHmqSnPMp`LtJ#rvDC;d1v3ug7@pnlzl{UE~euwB#CtQx^vHSrU#ZZWxS2q z&@JzC5l{|&UNQR%o)UP$^Yimu`A?Q0cm+7(9nUrZl5qPzTi1Vt`-0SekCK7{;(G&s zeE>>%!htV#y>`nREURnYh+tmuA0rrTkZ*!*2V!Pm%0$qv2qqqqQ6Q7e9|COw8_R>h zgXBI)1FV1C39Ntt6NV}X7^!YQCIjaZ%xS?i%TSs9&WUC>+WdxI+oFD6nVHY75=0l^ z29B=w|5uI(!$FtQ``RS?rli#6wUkBkH!yI3iJGqL&}9#dFi|rZkc$ir74S)bsknY# zX88xi!pyDL=nT5GX4PJxY)Luf?mp(>vB+xWb{f#iSEqr0z^VB_n~#C}bI(zlAW9Xw>%32#jrbpjby{n=w+` zqs|#7uwc@1Xyn&vm(#BoN$4gnsN%-zSL;ZW+OFeRy%C7}D(!WNnWu61P2f=wGojs6 zltfwV7bue6D46G-dQZkmlWrZ(#`iq3TXN{Y&SU5biyIw4vX&W*l+oI5kt-Hm&lQ-U z+w$LbXIlCEvO?u{rj5YF49?pSPnCCqxpWTT!xyuYU z^F!39N1A`BMC?Dg!gjwGY{}h0|LL7PN^mXTRIzIDEIr?p#gC1z@&uok=4fdgEwa!Q zsNROq?1(nYy}xzMAo5^l)-kMfTOjBbvZ7br+}Xo?mn3W}ESIjV`gIZ-)+e$Nhri!IhF^K&4MT4%v-f*_74Ia6lqmL|!oJh>u2_p!pU` zqW&K}6uu|lS2RD{W{xnkB3JMo&t=T@6xi%4xJn*$G3q`iw2~Zn^_$G9+$HNn zoP8HL@+-$YMeVlaAQTE54gy)GfrcnjEgT}LE(%m>8HuR4Wo!-RCow@Zc+c;v@vO4f z<>6ZeaZFs&N+rm+xL_KbqD5XcA@O`_neTdHN-0eBCD??tCC0Ls^vCBIZhKW}ijQ2{ z$)V>(OR|nEd+#dvNS`wEnC4k5Abq*cu+Vpm`q%E_(pO?S9XTD46mGjXlXm^;foz=k z1*vXk-=6HE(_xbU``-RH6Rn}){5Z{fxEyhRw-=*+2H9qtIT)us+aA-1vLO1mM!L_o|RSXkO3d=mkL4 zfY3qvf&ZOrYGL=@mjxcu+8kJG_7coX=;iduuW%Lbp9*L)66w^@jN6I_*Y0*OZ#3@K zW&a&aBEJaswb^a<+)CwTcU`K9x9@P;O}_0raO6&qvV@Ovsn9*u>;TdS*&01G%lL?B zK7L2E1Hmt~BN;szS_8Ctm4yUJQJzUnYoAV)>3v33L{t~5NOMF4a~GC)#^;K$ zC!`rtf8x);RNoZP^VHU0S3cYbICu6}W;%5*ibrJ(nWKH)OW#2)=L}On$d2o0E*|$- zn!R>R)t2;C5$O1RZR$ZBhrwikI5JyuQB0jYA~OL4oX^xwu<@{^)RPTWQ|s?2xO`(Qq&Dv&#B1a)*E|1#6r6*UZ7% z{4a|60B}&ke{0BZn<_3YuI`l;VWPahX{6C=~*Rx%l+^yW}9`TKUi=}{^zCMO~ zTdCgb!-6@!tK3O_D6E*6lgK!~j*?SfpQea43pwX+oeL0+Q}Av7ZQJ$?TC7oeO{mYR zt;EL8UIAc$(zw$Q&Y7;rU}N8@5xO&s942bxH(Bi3R?0Q{dy^ z%6W7DPB1@CJ6sRkDW=H1NiQiIw$b<<7}m!fFWNNP_wNP!2#4GCt~cw{)H_o0Vp^G1d1@u_N8y9H5AAgQ#``hC_C7MeD zZDXozdx^$AxY@HQ};Tsi(fS>ugfB}bERXqM{;&WYy<=~(zX z<+zo_6jIELRve^{i48z1|HwkR&g2fR&jkiMJICR$nrQFQnE2S_2jEMLub5i9zik2L z!$*&f*g6jbpkc-vQBDYgu@|`)6bNRs>X+NmrjNtE!!!PA*$=y71OnV&15BfP`@mvUR{$qpHFnFV$S^hb3AyiqO~>acHSrOIWbD@mp!MK)?ly$K zx*EqU6^P^h^-cYAZ}*X$HT%|)H==FF|M!-E4v)=Di~rTDo)W@vvg!VCdP&C^zw^Pl zAGr?a14vHd%HrwCpvd#ev5`myfCnM*2>+-d2lzHvQk2kVfc%u(L6>5B*QIA*5A>3{ z(tY`TF9SfofZ2e3C1*y@(`HTlvH=i3*xQ8hShLL1G!Lp6VEY=|GYTkr$2|jxLy+Xt zGEgVOkf7|v-nE|oWdk9Ua$6p)s(bb`3F;5p%CeZD%EatL-u*!6;K04OR5*?3Z^y9V{i zutGn->Ig!HZfrpj5lff{o}_XdK+RGrZ0jKscnA@=3yc;(y^|k4@u2^k@>F6m_FB1h zy*qXtg9zYHhBrGMhz)70AU!=esMV1Db%Id*0mMmFr?-1dhFB1M?3FccSth#0p}5a9 zqR)O$<@AZh3uaYmFq9Y!qN1d145DKz%;ti=Xr=u@BEQ*|< z{80R~8z0OmYw0#Qk}Q3&5Qh!7xu++eD+f?^?>eK1mVReyG6D1rgpyh*TzaJzmB>e$ zfG_VSl`ses=VzA`ff$1?Q}oX0gsNLbc6K&VE+rLJh8Ua0ilky5|Jaf0Rh1EX8wdTo z>05~^lr+i10=+=JK`j=m<$Gy;%*cJi-~{Cw92%Fczxfk34jmeMNC9Khqzu{ui-uHTR>i?C^2x^C}pIjNk~Wp zJ>A;e#7!tqHV29TU?ZZl6OsQ?NPiCv`DwMW6?jdcX94Wr08TAHb^tX2`v`uLVMwcd zI;Ju!EzJ~uy5a)50yHS@>|=HX-2{UB2ieN$m(I&4V0ePdb9wmah8yAal_dCcwI4t| zb_C8K-XSvsdqnm1=xAIz8+yneCvyFg$e$K`nYX0o>L+YDMMWKZ7H8~u;n{zh@h z-((~>@;1xbWFV=lxMV|+it%Y2ooPk(0MqlSW3%&ZP!Fudz9IR+=w3|XWQj&6?(X7^ z97IBjkwd*bK0!VAn(I)+t>GDMvZb^}Il;9gUrdx?vVlZMLMk`O$?9V4P$`;-lq_va zkBaL2Iq^X0o`gqoyl$eD_A;T&%PJP}(BVj_M`0q;4J+i`&%_9g)k3f_8$xLm<7f++ zQ(Oe%O435r85=U2Mg>_T&?{r)iK15MO_K%CYo%DQm+#5s6I=ALQ6T)CA12h1uiMrKt8N18#cH{;?-u7OcLz!X&MidTM}=+}|S?`*l?`U zzF_C#s`unkI)80&w#J+KB zE*_Ko#)CQS9Pbyk=mr=glIIeUAGI*iCHCDt0Xkz(vs#DO7+b8|5jq6x%`pN zTnXJGeE*;|agQ)e3Ty7C%rpfXiI9M8<#;IV?_^JQQ`%&<`ZG+digepT8Zsg?V!?y6 z&<$O(J?5#B^{erR)FCESYh}`{NPZ){uGVCA==)}ibhcEk^WJnM)zb>u#Vy5 zbm=#hwxac&)dg#;Ww|b~rbA?*q6{@D`B|lE3_=O2R6H44!-jYLsMum;HflC0P}2>F z^dGqV3Q=QKoe(MYIK-K8Pj4V0%R)kt($Qb5cSGe7Pj8GXR1cDqxtB~t>R~uutHQfw zG5?mv74h2|`j1Z?U9v@&q|Zcy zEp}9^>aM!(k?7xCzlt4g0;Pfd2-ed=+t|w_<`p%u^hUmeSF@@@HLRPxe@$-hC}(K1 zYL`&Q%H>abC1ibbeqVp}c*4?z9*?e84GOn;i z^vaPJ%Y{DVHGzC;!M`V=tC(R@-HV?djgvCV71Dlp!XLx&i-sS`g#SFbfE1EUTXr`s z7rpSueda*`4nE!g`41hwYrQ(;^9khMF3h!j0&P52a3J;7c7W^6^*uO;A+eMw9i(PJ z`6@uAw3Aa#W227YEbjyQs(MXvhtn;`=>x9i zbj&`xO-pnyv#hP#C1%o#+Q<`r;9^cn2j`7N(&ndrm-JcwM?8{!XJn6)!Y5z-(?e_0 z4I#92b|>DkPntoRO$uF+8gy!dlp40YgPwJk;Zz)As;@rnt`a}Z5$!!c=k7bkeA?)$ z<);*;$Qp({AEl4oN?5*yBeKHA*DTj?+=OL|^7>G{>u-gffm8r3m= z)`8aZ-#?yh7EPN&$5wAI9k51QULlAjLA9f>{c=Au_RhcamVem?7<{@KmAZq7?2B7+ z^74WK*C^C}?q9HMK`;q8E+Bxq*d3j7=_EaC(#{l`G^O%Q`@LT?zsbtVN)x~hd;lK= z)uITa2Bk7gl**o`tSL|sy7F_nJk$)Z1BE(!d_knbPu}!fN_(+|9n?_0iQt$4TL38z zI#U2?pfrF5Fs$82tLOIRH4Bt|pRjDyJwD4B4R2^^`8=pdG5BD?$hFK({=-V}WZBd;)s6b--qaY0*HQDXDC73q4-MML0g2E9F$Z})s~eXcw9 zwJLSz0ghT&SeWJx($witkpI|P8;FN6oZl_SSrwl)pe2JKg!_2WVc{c43X(OU#(k_T zh>~(A>N#9>aA$+$5+P&g*#D25J#MT%*uVbX3FTDxi;1BHeM=2AuBRhQmntu_AU7ph z6GCbF2L`;sPGoomBs8oHAXE{W(J7d%F8m!F5LFuR0*n?Ov;6yHnNpjq36NOGe4c|N zY2Bsnd&C!*Mj(#xvOM5lHAEk60;)pTlcPINqhsRY5DMeen?n=GBZ9Yp5WeiV{|BZ4 z1|oLmK(PaNc>w7_H*VeTZ32#s1_&_;B<2WZZ(g1q0YJ+H>bEEv*7~h~t>Lo3uHta! znX@ZQRS?f}9f{Ctz&`<+4w#^XOm5C+SyI0M-6?jl%L6%0f`Wn|j)(+(DBN&(;@~ya zfu{A-r%MyhYsoS3!-)0M{6TMpl(a$$f1KRBADnHfj9G9PZTPPvY%sw#wC zf-1##sRZiU+uAO)g&~g#UaV+-I3EuW57PQv+w%F9*oNB~Q?NE%MCM|OVcY0E`SG1Y zSg;}XG5=m&l?7&mDP7kw>|op!^u;~7SbS@ldwnx+QEz7jW;gc$kv;$iio8Sx`n!!1US@tizJB<8%FD~69!)^JA#9D{c5!oaOMw{?>{b&K z8ZfDU4-2tt{JF_jUZht&3%A$xr-KGDgj``<0#WRTVhoxY3Vdp@B7;goG-No#VBmz! z!8257QGvGzPY@_Ys0raWM(I8>;AHFQ8w}1;wAg3UybfH zeP}KYNG9RO&V-Cl(9ek8lT4zYn%`o3d7#~gY=%>a$tj^xac}j))xf@7V$+8zhkB{( z=d(b?IpL>{p$e$zTy}S6pX94cJqSboVi`(&N6Jg#j+CWV&AfTAHp+vGMJ>jfst`xM zQ2TBY@&IkuT|vBY#$KB$WL#zQkXJdCt?j3Fs6RKWL?kH$bg?&*2P?=jZsnhIVKPWR zNKtt4e7Wv3>$rZ4a=Lpl$4DXi*ecs1N?Df{N^!$(dwfI!%Et4&?jv&#n(x26yY@xN zmDS7{k2y9z&xbp)l;H6o`7{4JvNnqWDR3>Q^lDl}g>i7)sHSuirUC=Ljv++h9GDSkct~ zFos+5w4t#3I5x&4Q?-kgXWq4JNAxPE?#_|`$6g0Do5FpC?vMML&&2YJ%(ZnbanS|R zh8I5GCS(d>waz3UUoN8@CU8q=n*=zt0QAqS)LwmUMO}#&3n~;k_;|; zR56Y`=ktCdB~*TFRBVNMlXT1+A2LFs91CjEN9aiOny79=Zl>ILt!z&sR{A6MFn>8$ z{36F}WiWS%N+AAVU%9VbniN%pogVai*Q7a>l$a>chRXC9S|j~iTcNddhkS8ZuiCW30!vO z6})U)=P-%1)E-$sE&!+7^8 zyG(d?JoU)+P=)CwrcSPxSyZE+tj=#4_>)7jjizrL# zbR}=>ESCGsnu?Vl?gibsKV|V$?txgqzZcPj z|99LJTanzWZXfFfMqo0ETB#oIOpm2?_S)s^nk|vV?_3g=_*)ALRXihxW?R&v)eJLf zzoQ~gPS&wRT@6+5*ZazAB^ zek`67?@x~J6)Ns8zUQYRj|y;AOP_eS8cxD|Tk4yqZ13d4y#_xVE8i3&@z?ngHj><{ zCq!epDV-gMk4fb)UOTdW_(3#2KlTi;-u&ui1!ev3Ug>@DV&?iKJ%;E{3-sx#Bga#m zBG{6TW2yt+uR38$N=n$frl*mX=&{51BK^+4 z52}F$dh8huo^K2})Y`rmOxO~j1))Be+Ib9Ff>ui)+x)$`>@HO4T=&~EF_AuVM4jVl zsrC?>UIs5ylRTpqS60cWfrTjma|mdMpu zHtBOeg$OZ8aapx@QJ-lB3G>4w$o`Ri_au^y@4C$SlhU!niXz0_GiI$P!Y|wQLW(xC z59e-Xu?k+@9j1;58v17n^)(G$&rDuLUzS=HZSWX9BphUHt)QV^|LpaAQu1xiVWgc( zTywK66&2y}0;XGJg+xrzfjk{qfox@fjKR4&W~s88OKsXl{|ZOEF7>!*nTGHpU9Jk3 z!Tmx_cEZ?jPA0|dBLWgyq1oR3$Ad-v%wxvp>t0wo`vg_aE_EHUYk6`E)tq;7!bK_7Cc^O)8{UE3`P~UP zx5uR$-s}$_LbrpoSgy^hSK*pvh#5@Jz+e>--c$86hA(F;QK^`eni|8UfDiPf0G!~Y z_de(&0a7^m3qy(9<^>giCqqL6u<~PfS=mMvL?$KOlaIj2YJeceMLnEg36lXHRy)29 zQEu)Y;7r$^6ea%-f1}I?`8?F0=gfJipcf2iSI8X(9t>0o03G=FHn~3`f-5^atJg@( zfPYgg(Q#8|bxFKe^}Tz0YML_;eU?zd!(wY4>X z?QLU>Dc;GNK+o29bo{=@d@lyOcf9y}Ms_ws?wD5fY%Y@F8znmU0|mk$e~2u=TspaL zzsj)pKP>wr*HB|8qd1etkv(A)M)s3Q5afAwSkV8OoH75w2K=IDku z2qPHrA`LEbpysPH3vu!+Gq~AXg-s_*``JaPpcd~4AwWcGLO5bj^OAq2 z$<05L5_RT35do(W2szQ9<>@AW=O7HmpCHHxQF{Z~iZGqL?7T1nAq;vy4BQ`loRI1N z%dGl)aTWCU-3(q5C(5!!9Yj|$b+HMDONJ!f>j%jUBn*sZ3BoT3^_fp}v&{56A_g27 zj#yoiH(#d5MN?ng1jvWMbwOd}6z@v*=lOuKW;#2TEkm?QV|pn5!>q)` zx0g;(gpBg0gz{V5ytrDTJ?uz8XpwuG4p14S6Of5ewNxqfrV=7mJvu%aH#AE`>1ftD zatjH;T7e55T8`<8ur*knK(>{q>CowE%ab;2wc~Qp@PAxVm>68aP15BBAVledHx6*K zL`qqAZ=6-iVEglt2*h0;`E*q86Dlk`C*)}JyWq>cx!ejc&%FMay8gfmB)sOe0!Tgv zR&{cPEBE%{LE}*Q0}~eTEhHws6UCLomfRrAaXa4CM=Vd;jhS-Cjy5x$5%Mj#Mtr$4)~a^7hF2{`#rVh{$M_K%}OK2TTs9nn~&y0l!%wSlbtgm&4#)B6*bF17KPwQG!f}@sABco(9bd`zL6`)<&i5t%~7g# zvz0MX2e6_zInz;x(6@0Y7u}SkZPT9E*`b+f{~t|n8CKQ)bqz~MNjFM2h#;UycXx@1 zgp^2$Aky6_Ez%(&B8M)KM!E!~JEgnpo%?^k&o_>T3)p+Dy?$ekIihzua*?lL1Nkd` zGhLgn`vc|jy~KO4OG)^gWi1?4OQ~aa$yrwG^L&U1Zy2{0_PC z$W{CSKISWX)X16Ou*Q{Sc8YQJ(7vvjFKe8GD)fUz@fvbU-*f-j6EJBx3MBB{OZeTC z6d1I1`u=fJDGk|U-hl*hSMmg5YuomB%JWlI)k>v)lCJjAvwkrbb+X4@S1K)LU9>gG z!ns)^XVaCQ?%h%o6(eXvv673JR823^#XHB1TqPeeu{{VS8`4B$jd^_@eP8>%x=+{u z$%03L?OmMA1-~m4&c3v83U{gX784Srlvqu%sNd|d8$8&ut7+F5D5koZOavI^ie?HZ z6*C+p-S`-8HLu)bab+vMd$MjynGE*-%=zLkZlTB?D*PGez8Lx2;q{T_o1wKA>6PC-;wy}P9P!0)uxE)n-FQ;gGe=X4E2D8w| zDZT{1d+JlPPlTfx@yJ$-bWVXDH(`s*+-mD= zEm8MrJ~T|!GD1Pla<#@R0qu3!a>(P6Z0(^4_pGV89KCpy&5_PreMfaUKS#p<8uo<~ z0$Qh~nA3?GEjqTEPUBdt?mR0;jk=UFzQgmO+=m#&T4cqQ)rjE_E1sHVaiNyd!)KyI zGX(BoSvd4rBYbz_1jbVLg1a{A`kd%YGU|w2%S?lr#YMc-N&_ucigT|Rp@ohm7wz(Q z0nK$S+dGvtznO#3(;%_iIA4Yp&0MC0sKAt0!J0Yw?2h1KyvR(p0%cMEb0Y>)R6^z6i+X|WfiT*=naEN8R;mk4ASqx21BCb6Bvg`44IdSpV$d%qfe*pgu6|9< ziov8Dhr$B||E;@}(x-G~s&n=~Kt+NzIglRk)QqALTRp4k@9llEHefX0+k%{+m;jhw zYmAtMMJ2A(G#0ugz?<*ri0$K0D_#06p-UL)(!FlW#`gWM#_(xD`i~>?n#QPN+S+De z8w;4hVht+ZcEO=9jj;4p7|MP=~&x`T^8bKig> z=Cf$l7*meiCau39=Ds^pdN(~QZ5P49pY4wYW1leU43Gy)63Jo-MH|MxK2ZFmnmi)p zs#!}BUmQJyT$D;rw%nO}xy;KZNfFy;L7tH|U;B`3?+W)Y9^*3H@e;>uBuIT@Zd$YC zYM#4V>?}m>W{cbX0i7|+y_|n;2A^cYgQAHaBIVkIN@huaAq_~E%<+_MmxYj>*I$$K z$24=K6MM+WT-SdmvOaqL?fIvP{_Rr1vhJNL>TLB~LHD%URxVz{I={K~n5h}rnd|t~ zV4C5ZBTkm6WV2RLfxj$F?kFeF1l*nANny>-+d^o-z&}J?W(zzHQA>UZMsYOWm`!f*Xj$1ohgk7CyPp?G= zSets}2W$mrpZ2x1P_#TAQM8KF;^0WlGAxF*ysqBQP7r*gvw*r|;cJxWA{@EQ?KXB> zp;{9l0RV{E(Ze+dS=I;t{zy4FJFO>u3_7m%M$b#JSb2GF&E=ch()xHAs6$iUWS@ z56G|JgRXhXF!2Xqt085;0ZF$IpD#7Lcx)3#oU~!L?&w`>Qy9*X-h4NjuC1F$p=^Tw zJTnsQJf;iG)DTcPLyz`k9K2f#;*jH@T0HilLkP%2S_5Jkh#~lCAYus`6i^PiLY!8u z>tUY1lIYc*6i~MlHc(u11~F4DKuH20d^+cyf#CVq^D}-P#Ur|XAe?kx43X}X*l+|w z7escsh4+aCYp(uc%6b#x_83b2lf|n61%b7hlEb6MHnkXLx!EV-7rx zBr*O-j`Z^Y}mz%K)FXJ&o<*y3VDa0 zXY#2Mb)G-Oe9TDa2MTU~bUby%G%PQs?a6dG&3%sA0m-cS_F+KyO4i8%4dPssf@%Ft zwRW&PIsPw4GpaJqY(~|;DeQN4VaCluc5}+`5UO4!FI~W;K69MCLub{j1b(X94`Z5G z8@oX<#$aELLc_7mV^|jSq|Z?^Z4!&W}b1~mKwyhr&}la1;!KG z^@ettTtD2595Py)OnLsUz&yeGu}m!ge|hwI4=h@jY{!|4B6W?7eRT?*C{U4r7l9fq zSP;PN203xm!Y<;q`iMML_}IZ@b#r}*vf%&>Kjh8wBw@q+17%R7kx2-EJ(4JPwSb4X zAJtD0gB*BFVZ0>(;EsUQAen(F3QCWJ-Ht+FL+dfx-X5g%>?JIDAc-C_%MkWFS8A|z z!aWG1%mZ}zP{X(bS7yawLc$KhhMTqIISzCw0%)Ck!n?zy|g09rDK#uZ0QFZMJ6yF~udNOuhvBc6*>ig_3iW5BdiOq8%lS znyF8r&Ho6C)a+)BkP&~2d~mU&w6_IhQ3w74=G+HlQp z32$HA!HFFA6Mke%zs4_zkI7O32VeUH@(JTKw_!2r1h$KtNwY3GCUXAGR+;#Af$LS) zZKhhv5sUea!%9HG#~4q~-7;CpQA-`Z9ZYq34q zjDnRyPm4*%)LNq^`yO2>Hu8OgJbv#Vv8oKHuVx$25Y7Y5&(R7Z>RHB`-P6qy8m1JrNI9$gue9yx1S&%n*Rna4&uj zo9vr0e#-2N(9YauZOPwWQVM9tUCL>M%?{{;*wP1&)br>FkxCb7OqvW$yjcmSf{<@k zYlS)jYWbVAaV8_5OW&``Fr#_+B<;0lq{{9alFfLHndhW}+T^rW^JYZbgadb-e$;Hd zO60PM9=Mpy5wUD_awj8AS9;6fLby@eon6YPLllC!@y!XCbge2amo+2FD8yas@rjGQ)Jb2$%-~b z|8AujSG9q1ucvD}f49|h#+L@|HVoY{JIdY~%iNcT1jYP5M;VLlD%SvSVbmQp8NS*d z`&8W%<(dj4eW)Q8B+Z2CFXtk%SP#;=^N(!qukg=cv7?zE-!S>fU#f_eep0N6(T>rP zNzl6<=4C@#YIy#x2#J7jpy`gFJtv0LEqOVStnqWESaGX-A~Bk+Oy9Ac?Y6ju;(x23 zQPcxwIE9TjNTx=J&>skX_FUA|pS0@ek*gM=E^psSo7p1@6I@ZdYV_YAV*cXT+~TLF zN%5XMKXqNf*1N^W>kHprK*_zIHT_Pvn7O6n)Jq>656S$eW-K&Nu8HtS>qY-w`AXF!Ftj)@_X%w^}vfaN3)viPGNbC;v6wb@84Jf6hlqei+L3_$Jl;WNl{{i=MI3 zl*BoMBft3imOWgh)N0Yv~@Uti!oveY46 zav8@-TT;?~L`RIr+!{QNfzQ+8Aay-o*^E$A9u%~+-<`Dp)=7hd6qEpvj|l{xu8|Q7 zA>NiBJh>f@;0xY_@>3Ej+o5+wOE&qRvw z?TFA4$7+r*nth1O+rrOEkmL#_PP6&!q^9X!qiB0er@@`G>8x-`M_+`YiQh@h6NX{+ za&?r}J34D>lW0)FKB9?*=#6@1bmkbXj5MvgSwaruYiU{H`yYQDGmE^;XS&D{&U`8U zPM#;yKvq-KM0-fbRx_8{)-FoVBI7qNgLc?324j&^8f0FS4FA>&^Qs=0TnhemczeU$ z@l>K*z%SO+C;N|Osq1@j``du7upAzv%v8?zlvD@nOPuI+=+m$+*DHd3cMyaI7HX{3 z<}!JmKfI0ZQu@Gg`uTjnS&mZnV{!p?!U$@jh0)qUFBy5^0ATckiFlPZje2;xsSQw6+zo$6$2wdu8b8PxS_jwt_@YM6cd=Pad~tm1G^ zc`o_Mt8oC@e~ih2NCG1goYSy&fyFUc0?HZZHE#}WX=0NmKI~7jSPzJ>C*wklMUp?+z0X(#19a(pjY%+D~?cd7=i;5KzFO@&vwC)Ir{d=^qQQk zEWfZYrM#8}nZ8bLjxGlx6BUHuwLZs}UBn*gYoM$E@NdsndIv-y5EufK9+=LWfCdMq z6#fHZEA)T%fJy>CzH($2nzTEjyp9-bE=m=1TY%(_Detuhun!ee0QNy-0S$=YzXTIl zfwsd`f~G1O#E+C#RkefV?8Sfj3!nvut;c?!o!4-)4xh?8$X)QLh36xm%|ffy0kG1D z2)E{3b|F#G)o`OLdiWbulMrUJ{{^ZrW(*L?5EN*4AAjJf(PkwE`FcN{MfpphT?rTLFYQ2pVn|jjrxNm;yY2Jgzs5fcqTWJVp?u83RHIWVytU z2Mb16h;BtlyrJC`02-vvf_eydr%xKmr?-SqY}KpB_`u01*qq7HB-URE5%l#2$*;ML|u)eDTq3r+wkw(2=ArPuvVh zH&c99ZEAg{Z(DCGl-OgAUZraUG8{^RjA;we4CmS^TLr%dCm;B5EDt`k4%pI6cyW-1 z%NOiAlwQIY@M^MIVTB`#bo-Ka1esc=3-7(B9(#g5`!Bts)y$e@-SPsZhY4X*M&v>L zw=ab%E-TpGAvE~B(9E5hnp#l(H}x2M)XQ7bQ}Zau;eb|v{ydJi8?MxVHCe;-Q}q6I zRGF9RdVJnE;8F)L4bWS&z|jh8e4!#FNg0g}LJD|9nBLx*lJtNgse+M-TEswX4*L~a z48$h{Ov%8btjW|-4P#b`e#CK~8p80JIRBMjeDtiDJ&2*ZVL+p)q>szyWJY4{%W>xn6+@RVx+Tpy3KSRp`G5)D!&P%#idC87Z=Ov5EN54L}y4~^t!~7gG&C*^KNXP z9Elw0wu$KU(JwXezfr>~+F2k-jxLpBq{p{se|6V|^UFhx20I@b1s_y;ExAMeb#C)r zQ707(zcTLmH}vmFN26r}I}7fxRV=E|<72%ZjiS~GWD7!4=j$!rG+8Ls)p&S5sA#4! z!h-ctul;dELe~@ZH;r64uXF$Yr2pz<`qe9a?e`j!k9@v!*vEK};X;C#dz6-`4~M9v z&4z|2g1Jy*b{CFC0yL$&_oyXJz4;8;=z_X?TMvbExRBZo;?5SS=SyRY` zJu=BIWk(?(&k{|+?Rlz{BSA2L+FiQ;!F)@n4eRaDx69vo@h;TWTd&E+`JOw_me{6f z-Xq2R-tW@#tq#MOxci5<6ndO6Rehr3B};(XvWy-T+CW=uV?#G^H0cjb& z+_#cR%ImJ3jvZQ~oGlaBGxmC{cg*6L60Pbx0NUz|6;&X zRi*0}S*zkt`}lR5d(<+LwDfpf8$>eH*Xl+U&KvelHcGx+DD)J`jYAT0-QVMx2D%(m zcVuy-U4u9X+OG3D(%&(-v(pQ#YPWR9s?Qa?SS8xUJBl|ICohT4-(e5xSJu(BeTNyG zvna7W$+uJO5^#pbsuhZ|vFRfC^n*vRyUjh^2BnI|=NE)7(&=)`9kfXehHs3`MYzU^ z%Grzv$y0=)7y}qeMAa7DhpwKUEOm%#6vkxJF)^|Z&0HuJQ%Pq(RpDasFmh-x zp0C|zM{i3Tnqp1Zn~42%O-L#3Ta!WV{t%~uOsZ5-r+lW4{=M!^sh8uo z$jC<0Ja0!Q`K1p1WW~EfZcnd0Lz|w>{nbxR>JYKMT&>xm(|w!k==P_KHsU& zvWnSOh|$ZGb@4{kgRNGqI!E!>dR}<`M05Fp)@O1L$5+x@a_Dx^pX{9YKW0L=V09&< zH~NjuDdzswhsjbeHz`q^bYWW@bI+kUZ4Jewxg2lzNAv=uXi8;V$3KPOjUd{`K@pQ;e_$n85<}Y?8b#mfFK}EGxyT+M3;wAue7=a{2 zHo+;r3>7}cPJ5d1&ols@v#ta1+n|B& zT3p}i_|(h_!tn$vSwzfI zI)avb^9Ewz%|Kcico%2N^Pr0bykp!?Mf%nZz0*tz0(RX&uJ?W|POa0t91_g(^76$o zPEJquqXUYVuSYRiF6%0)`1Yzcam5@mQ_ zkWEIXVm(LDaX8lFP7GcQy07LLq2`@y(wR7p%B7GXn?YlLTsi`rU*E!ijIqh7==o&I zNyx^xhWv3#+pjkWLx1IB<@%fa|7igV{aOb;?dL7{AE1Jf_7a39cj( zeO0gK=$znqDW@E2Up4l^ve;={Z_3=xn#Kqmk|bE=mVBe5@HUw{xCNQ~7x4BxgeZz$ zravz%;&HPKr{aPq?`O#g0Idxyk$$Z=M!GMd%yGRQwkzhc>ZKtC?YCq z-@5U{8sVOU3k+mhCxqmKG?*E9(PnfS#IASNZS#@g&l|$bKv`IVtUCt9#1N$M@L|9$ zM(2IiF*grl?uaP0$2^)~%u9t(F4zJ~?a9XqFPBp;7TT?~vJtL+Nynb{)*Ypkm%QPN) zNR@hhY!;xmhR%6q7=;1rzKh9;ceoQWlP?maGWEs?)Ec#JQa?IP4!0+lbV(qpVoe;o z4zEzteAsBR>AwW4ih{yyRzwcjW9%8DLS++_2>?yG@k*Dj;KCr5!4)s-A5#2w(Xjie z?&r^LFwP;uw5M!A6#^cOwPt_x0OQWiP7IjFLG}ei`-%e^4G60DJ7_+Dq~PXU>~;-y z3YqbXAny=%+4F&qFwE^ukp1_+1~IVcfm#B*}slnU!Y71t!OSEQ?N6;dS-!xRS1q-LR~h?K)Hut@cb+ zJ`}`0WtyvIa_t}G+_JElVrqWzs@N=pB}>&ky{b5_J3`?>>73H&OjXu(#IbQJ`-_v0 zJ^&@5px=uvY`DhF-VB#c-~J+5yi`a2bDUH}P$kiHwGGHFO>vl%eoLODsy+S5~OQ z_yF-U=#z%ftO^7-oCt7GfNTuD0QJhw;u6s3J{dZS0trvty>ysh4$h8u7%Z%Ot1nAuLmfO?sry6Ii#0${P=5yvfk#a<#||saQNKpTNXW8 zW+{?N;e9hL1I1h|2HBwk-1S;{idSwaFwm@g_)PRw?z(-qGqrYs+c8{lT6k|Ax3MM`I#PvPhIv zW}gAuJwO9HRwm~9S767{O?GEqZG26IrPH>FUpzJQ+YRIv=E?ksAAxpUpC2}%=aMWe zUTnU$HtQESLN%Nlj?Sz?j&tjkN@}Vnq}ORDfBR0XiXjG7riqbzn3haYOfI=9jL_CB zVfrEPI{7dHtw&w3CjNHgy`o2AEsVSIhis6hYO-$Gs(FTFEpZ9DowhixV6=|9P+1;+OOToRj$9e+i?$ zn5d68k?a1=*JbNJs?(~ClL~Vlnh4iaEL^L3LZWbo-FQmD{n_8rZDXT{@s?6rc)T$a zM>Q>Pf3q=tq`{YJ8@+wSL|ee&W7ZKo>-}Te^4b?IJSR}aCM{%*$Gra`wn)D0=&A5O zJm2he+6YPExn~XCa%@rZ7Z?K_ydB|MM#)RH>4a}Sg?aj1M`-J%$Ya~mY&rK<9Gfk_ z5IO$)IPmd5`&h%rmakAMy3{#l@@g0{eI}X$=@*QaG!~iGh*1hIs9DwMt^hFBjprxjcskS!>3; z5*_IHR+$FVg41a!0%6w=%}u7*)=uL)zdZhkANpvg)<6!&1w9HWV@K0=YV9OST*~at zj?}~Ki*#2iuCD!n79z~ck{LejwdG^RXWpIUIZ9rlszwF2GgvcWTFGxZKZ1>_z+_ZE zR5T>x_P3q-u+PfCe@@=KE5(bb=~V-b$B`cu6|QDWHorA0eBZXvNuPb8xKNgL)EeDn zX8dQVS^pJ=3H^RF3FvWhro={tS^9tWQ2I@LkrTYCz$I)42;2;r4!p#DXcaBia}OgDv6f}sQk9R^z8^N8>s(T72-^SutSH)dwBI{6*5lcp!QrvxmIHInGJNytrOHS*M5D63x$ zYK3Tje*B8|yN<@NmKnP_^D1dlPeSO1N*R|vo%f~IsLsx?HQ)XvomFvrS37gsDnS{h zz=fI5k%i|*-N(-_bX+SQ2c~{=h<{E=Y0E9j8?;fi-h=VWhc-pxTL|mcADp^xtc>z^ z9q&_(j*TLOj=bf=kZ>H`XMPSX7@d&V(F)z%U!Vd0H<{5gqQjNq(@&^Lg<%CE)9wP2 zZGx=@TtV&c3^sPQ2sUzO&dAs-r#pmzPX2*?3>>*}U1pHrN^kx(`xG|xKuT9ma#v2W zpZ{8AL2y!Vs6Kl)J&&kiZ3#Rau@W3zcZFR*=Smr(gFMlwK@}hM>Ytq0;*9g{$Zyl> zNFsKxch%Nnte8^U_h$M`HUDfLgWnhSABX!L)f3Z`^w^ibj)s(g?nY^iFbMnEvDwcSnjgvz0n zOkB2Hr9PGbM33yATOeZhyS-95^`eLdviewLLE$JFmVy znFFtJ=kzpXhSvofq$1{M7VuYQK_c%y6zn3h&i)t9Ja?WpM+X{ofURQZEVlvP7iza` zw--jY*6=YC0CO1NLWD2#f4~*L!snAnHN=PTAD6;PVPqs;sn`PLua3k!NO-Z~Q(}%= zm=#gsX}rC;M96MWcMK3A6OcK5evsJM3!Jqg8~l|BVRqx8P-E*@T=+uhqVh&d6!XdfNO;}n7)0$x`@Ucj>> z`pcl7b+vBpniB>S@T)>87}(RAiASk_xDA6O2LweRn8{{!2)|j@O-f3#x188=D*RDZ zS-JAo%3ZW-JC-l)2UrQV`OecAqb)lufpkSy9Xu~G{nm71@9?Uu;iT5n+ul9~6a;u9 zPhXNXRr+6BM;V7x<+nQTk2_WTre<)xf?_jJL2rBMdB$~=-Z0k=WN2@>!i1n+qywFE zPTNTUhsA=l7TnV1D)m;DmzTA52T$hq<`zWdCDRfV&6~t!}+6A;e=3~-YHV-+C%5!2Ldyk6xfI3Cy*?dDRyc9CRE*Skj>Mqk z=QLIHxl<}Lr-c@Xro;oq2Dv(=QvWSD4d7ORYY$dg6wB&u3ka>5Sws5IsIeamI6~BK zjrdZ-M*9;X{Duy-NM{q%2&3j66AKFqL^i{v9iN;O{HW?P-Uu&4sAQn32f~a{Cbv(w zg-sG(*-kN?p8vSIA}Mg(8@^kl{909kQaX=A{f)MX88HFV(8$Z?bbk71_4WNH!gRvi zd+s9bIX0PE=t*eWPbj5V1xh%AMoco5Gqof)>J@DEdVJZK(@5wgrK$bi<0tGhg^3$A z9eW6iwP=ZU;?LoU=ME-rGKwN8p6^IHQ`!s{FJ`8qD@ti}>n}gR{&s&}iVdGTGGBk0 z1Bq5Q;Zfm#<_p|k`I*1sQ=G)enycP_%@JnuPeID;Vjq=1Pa9iIp%9fg-=g9LBhv+^ z3We`;MlI&o)>&9M+UJv;%Iut;I)dMJl5P@q7A$?R)mxg((pAv^WeL-etZRQ}=ZPev zK$d9FROYF%X~r)i&ubF*(NW;Qa?itAs`wnU)zNLH@#9}!^?F4Xu;)2l+B`^cY^HVO z-=tse4WLOUlp~RO=#2WAJQcF0w|e~pTV~L9a7^~+%%Kp`496q&#-LQh+*j0dvvKd6Q#QsGg_0l zfw-El+$+}16MhBY%hOTCKe_X+^UN(MUY2PP?IKVT|Mp!Ir$7Pdi` z^pXkBk9TH?Sl8Fx+?f~OHSy#UcOR!oGiT4IE0{jJV~s7{Cv(-|UXbFGSD^ubrC&5uR)f6J_>^IWJb@53X8m^jyrv?R{l2#T2mAmLHB;xdo4*F?&x)7{ z1ZC3krFq)oL=BgT+^FeCEPXGHr^RB{7B1;D(WH4=cts5`iZ}~s+&JTc+V(ty3vpg4 zU5))JBIH6t?Tl47IIDltgVrN6h)thkvc3X9+qI3Ga68yG4mv z)uu| zu2z|;RR%cMqw4t{TWoV5yj2UrkJ+5Ggi|v#Yw4WNi7M2Tv57AQ zmj2WK<4`EOFgViu@i(n>VAz_h^M4y%<>e<&^($)I=XEK2!^Z~vH?0O(pC^C(@yhx& z3zz2>DvR9<*Y4i2p^-7(J883xXdaKwzI=1BA$#MxsBKOXYR`-PW&Jq903EX&EgExn zvK+-@y!C42X5*zmkv#enzZ5oN=GJhF+48B|tM(hAW*l%Dm$EJ`Zw<_um0sH!`)34a z$2Yjv(F93njUJx#_M!M(8f24bt*AZyw88iM4ksg!d_yI)$IMIA@~sB14_Kd#|d>pcY-Q(5oXMm7$kWnaNUBl4e}u zf%gMWLXPb2;RR&Ky5LJwOBlrvin7ru6oxdA5#TR|ie|;4dWkb9WdFN7yB5u!`Z|2L z-c5{8OK`MKL@>mXqY}*gXfo$tjO5~nY)OZD+$@ZJ`V8e~QaTD)UP1A@fBMeOUhXN< zt^c8(DP^vwmA;6bUVaj1@g0>yoxSC7I3gjy{{ie(gQ! zvewoFoOz5k0*UXk%yV?Fg1r9ZPi>TxokS}ZcP}ow8rGfM^SJrT_4pZ|(uZo??yq`O zYdI6f6td_qYK>Jik%Gl~Ym){0g zL-TaE)Xv;R$k#NgpOyEI6P~wdW9{Zh$x4dG25fU`6!)y&Fh_mj6R1Vmj*oi5#(O$+ zs7&b??Myv1Yn#O*P-dB-%<1209;zLNA(8i>wA#68-#AjA4~}i7SORdB{Q`&sBM)TZ zvJr>nXj=Nw(#q#5pCliNZ%NG2W_w##={*9f6>O|1#B!AkC#R>d!G;qJD=<6UI`~=? zR5r$DW&!_8cQyN;S)Tw|?0qT9176Ap4@|AB?hhP-m5UflhLh7^dF25YFAq;QI?Yu` z_1ul;r%$+PU!oti?(1E?(w*}m$~VD9#u**m?0_T*gey)kt?CBHM$-;W!iNQNVZqlA z{1({XAj05m#puQyhP=khy2hRiNENR9%HY7_?k9w+m_u@Z3V~UrAZn zqF?LDr7`)>_ynB=U?w$-#|#vUVXFa+Z_ufSvLQyAJk(!0udQKY^&K+n;PY3hXPY^T zU>EyxRfLihb20qpL&fV=>J#)kCy0&t_CUhWzq*=NR|s_(TI>n@qN2c%BMR5Z8qZ`B zPn}&~a@BxX1SU|(z3>P3)7Z)96ETQsMo`IP{~0Wed2Ns3OCmzhG9Z@%a3~OgAP@j! zSPvMJK}q`Sa;HvJ@D!RRuE6#u3Nlj<2!L34=6(1Kte^n=4(s531HKiZPO&NnPB{%E zH9TTsYW0SY$=#Y(#}xVK^=pYTGYSd{d;C7wZiC$r-j5p00)5UyM7ImV%E+Cd80dXy zcY^~Pr>il5+UNUG-dj8LXB#gX6+z}fBvU@&Xo;khO9-JCfOlH79z+8s=*fVg%zBjBAuFFkKi<4lA=WS}Lx;jxpX z90X!q+H_F+z~!Tq|J<`853SNxPhlH{c3}%G+mVqt4z<&F_`meMDcv(EWAv1TaFD5O z!4=`c8y%>|aTEll5ftG-2qG@73hC5Im+AP(r&}6#J3>YU2N>R_8BTkA6$LoyI;f8O31;61-q7?0Ad7zNc7y#Cea zq=kPscsCEy;u#ehmaYRo;tX&6w!fm<)v8j8U7i*V9!^wrP2V^e&}rFcG`F$Y(zlXU z_`rr`{P>&dM+bW6r0w(gK9DOHzUqUvZkRvFE)Wqrm!9BT$$+FHSI|SlwSdp^(7Wm` zGaj%G;(W^_@e6dz)ij1w9!Q~iH~Xt=VuB)yT4Zr3R|(-Og_uQ<{`h1BSC0Olulf4I zjJ)P2>}lYeOdyLMuB(_gNPCKzu|`irFBajGWW;;brgnwexc{ILsRt<$bu(;VjL#(Y#Q;IB-30=0L{BK`lncXyad@ z#Z*mUbec-V+rcJ9G9>fbZQ`Z|P#GUA?_Vk%!?dj<1zmV27zFZsoZ^``&$&2KfO z?cAgi7LvyE>l&~va18l)6Mv0(?#wM%hPO0C9$SjU87ILKBjR<(IOmTux=E%_XMvSK zjlx7l1R7ONtbx{3QACMQKR`{~neQyrPYL_f_ui%qU|iby5X zBz>@2>GrV%Jwf{ATe`in#bodMr;SzH#6NJTx|H0nidL0yO8aYe3u)a=q=8YpqWf_z zxdM8wg0?iF<-J(T$k69j0*WuIxOh&grtY}yXZjF)QTB^1wWBFiU!7DO(!Cgyuu}K! zQ=U8V{}!w8U3pBbopCm3clC&9yYr6%c`{zuI)BlO@W)UJeHbc{ z3#sGdkR^<52SW*sDaSfK(kO+BBBJqU#G`6IMR{Z0lub8TOk>*~9#g~~O4MeaM-bL& zP#q_Vz@nPB9T+wv#d@k*-#ryBjQ3pmPKa@5ch2DWo!6xO zkGfuWOZeX7ZqE15&7%* zE9m`yB6jCOGL#isWFygjuN5-*LkCM`X+#pC|k?e-`yy;j7%4EOkxt)&E)!-(tYQI7kzqaztB_53f(2uMUKb4Bx{TI2fITkM_BUgx7iSiv9 z9<;tZoeq|w!5$ywU3^A%p?mma_sig;vr|;o8=a1e&l#@O&ijeKo`0WzX!UPXYS+l@ z9A&q*mS=`9EiRBmDRHWR3+L4JohSYe4H4Zu@(UpYp`MGsjikZsPR2hf!wtSL{&k2a z9x>@DkYv1(MP6AgaTHh5-g~WV?b1IMS9ulbGF@{;+X(kw0&0 zdua0`${*AfV}g}QS_knL#B4M|<$Fnia-%w9=eb4~JU}IYy~!Tpmf#7fK-mHE!@2o~ zM(0=xv3u)k-pO3ra;&6eGrQ0FAk71a!)3@1fX5+G2lxLq$7ej3z0zfl%L0Sb+b5yf z*q~)bG+6=Mnw&eEhH5N$^g^q|$NqjRkA-lf9AV7`L`B(*6=LNFfT0!wph6WuDs5ry zp7QWvxLK^|*A>d^b#8|VlprvKc<#TK6Kj`OH|K&)#l*Qp)&uao#(ETU*+Aj|1PrVEAIyL;+;O~Ff>dmY%1*F zBmOM;U;=EB`>8QeruRKnSh|Kcwci$S=F9$hVc?|FD`EEbJ91KN-ZQIza-MqE)E)H< zPHN6IleIw`EN10l`r5A@JSgu9yPZK%kVi(FV~yL#q@-F3zVw~w$e+>|#9vQ3S6Em- zZxCZ~i(qf7Cdz*8OG~_A&$#T3I=m<>F6Xb6=j$pXvq(xxv2b+s>)IFi9=BAX5@(nv z^>rxkzgMgd#B8xla=GzLU!TOG-=271Ya}s+4>N z5*&!czzcP%GXP`VQ-CWyJw33k1*bhCyBP2n(8i+YU1}x2ezgImSP1EUsi|i!y^ocd zpW#nF&?7o^cG&Us9a_%@}kMr#4LIWZvlXL03smz1g}+Tef>5{ z3w({>XPxIf6T$5Tpb0)U5Th3bvJWW908IlT9s}?TLZt!`a_4rp+l~9hH-8%!dyH-n zKM8?hp-|=yK!@{@d{G(ZxMp&x>Zz4A2=hK;xn0gcm@*#%o&+C)%k}XX2q6%4fB<~p zYF)Pw%!7W4+!Qf8i-TT4$>@Tx$tO);oAC=2(s|;#fa3TQ({(WzCtw|M)+%--b<;j~ z_TZ{B>I$RrX0x#$u+7=p?N!F1(e0+UIlxs2L^IBYs}akX1t1r4hlYy`8$6N_RWV?< zL^QNqnuaU(0dJ3yPMXt0^M>)Ct`6LdHW<} z=?j#`0Hw)0oMeDH5peRz_Xbe&DHw5DiHpdP?pRn@+z6wx$H4F)5>f)cJ(JKZ;yFe{ z_S-vozvMNnYcQgD0Pw57m~bYRF)N?2*s&(pzITf0zeaO|gY9D${pom+G#5Lc_42!LvCuO1ZIW3Sge|6x8xvloZ0h zH2{gXqu^}tr%#_8oScF*fo2e%x4!!WWZCd$gL0i;NC+azFLr&8Yhw-ZHRWZriGQ!& z-HRD>=mkSSNr^}LhC@k!?IW4VLUmS`PK6O#H8nM$i>a#u4owZijwGt5j!oswy5V0z zcTatR?aNcLv5cS{)?;qF;!CQL1 zPjhPzQv4Sl#NrR*DeRuyztNWrltZdB(^tH&>>Fo}4O4|(ewo_2F*2V@UIfBnc*oxw z%hv&3`HPAzM?nb41fk5gzgDo2Y}|#*VV0!^MWRRZmJq=T1{T&ZwAbSMLPPHc4y0N) z-no`BQGSr39u!_JrZlrz zd`)}jNfw?&Xa2GhC$IY~ZiNwxb0hNY3oUJuQ=8N`)J>#v#=p}Ff9}+ZZzBIzt^Ymm zSKsaVNj7QRml~IqSJj}+tf`GWPQ{o9^B2zD70=8UGUVpfWc(^j1k7RTp*VYCda-To zn)uD5U3un|L7kK%@ok2I%ITi>+wpn!*tkvaeLjEknUqgne^MetwZCvuK6C0WzUSlN zNgt=ZbcJ}ezC^~%=UXkSs%bo*9=Q;PACMdRa*Psa7!fg?r8zxLV*b;8TU1|*iTc)t zc4qu_?Uk28i*}~MmdzCV(HC9uvYk81Z|Lg(^R)GQl7(dRCU%@H?ymYv!pl-RrwH8y zbPLA53En--uljC6zC;GoFOl!5BDF{vKE~%D+v=^UBK7J0L`3%QL$hA4{&&p@oyAr% zv`vHS=X>V9xP($$n$z8E%nQ~GmhZJ_pZo9@FEe6k?_3WC2lzTjVBi$+B#GlGO2x9; zc;UTLDQaeQxAFB{7T{hl7pp2Q;3P85;>jv)JC&abZs2%Z@MN(6eMXMxz3ukE(Hj@i zcf*E{`rj@+@7Q|nr%l|)|4-rQnvjs8z{%g|r!zzQRCEr0q)eJT#Ui9z-`(MG`6~Y- zES#Hjuh=G8c)vrm=p_~j4%+R2KNIt}x%o>r)J0<$Yq@fmBQQ@Nj|_SJhmnbkr)cb1 z(Vp*3P+8;XUx9w@sz8N)p+8HxtDJDoC5~7#ciLHL1{2RBnEHDy%KEzZvi$QEVae(KI=JW58pI0e+*# zUArOX);X#$1~Jo=g`Ado!f2ddWrXg@G-8eP8JRCXtkR^P87pO+)XP^{<(Yo zzoRS*qCbRo4P5Fg`%5g03M~l_`IxIqO6E;#S}9(~w&8bl&093@Do$VU zhtYfcSF};4^r0aP&uM>Q$7t?4(XOsn#Aj{2`RlM>=;)GrX^H5Gek%AyAW>8m^u2g_7i+0x=`@fD^|%%HeGB- z)vC^S$;O-LPb(P{$)u*R5|Ps9D)BB0R=8NMtUoXNV{au>j@8eHsXWcM;!Y@ z536h4ws{2V#o6jQbEBLl3fXW|2v{inEr&NxI==}&eE6b3yCXE4Co}&w@p9&c^Ic&uDl>7Q0TQPV2w7#*A|Nm&Z z?r^H#_iyjLvdYX(NRnjlJ)%hV3|S$2XJ+q_y%R#n-k}J|&fa@ukKcVh-|P2ZuItb_ z@8>zsbKkG~HRh`wx@GOIu+P{Q4*K|TIUj8s&wo<+H;j|7*k64@nEl7p?H~Jv>L01;21DU%yt?~C}nG3JTM?D{5E&ISbw8-Jx@IalNK9~V(C8e3GBP3}j(N)33Oa(ODq z+24PZpjFBpf6(cWDbZ%G0a$6y%$p0rEVka)wxjLR%kFC8Ke{Cj&QLTp<5WU_pqRjI z-*|b@ukV?!Z)X_sAr3_C2WO4pv+RZXE(#DUJ(ZFFjH8}rOjS<^1o+x%+NIldp&_t0 zKkGLwRJjD1%@tJ6&6jT{lNF$+>*_@5s|tSLcZ$0CunS03pi1FS5J)M@zvOa+*g2@Z z+|G|6wK&*DVAXC1r%LN;E+O1I->1sp9~7T_FZeQ4dN9?{b))^JEcq#K-27i*L`{^X)d(i zNQC@yshnq#t+!C}LIPrazy8`?cqWyym19`8B{{qvR2~$Oa2PjNmiHrm5r>UYEvj)A z3L~+9aiV8&kVp+|j83RVIClmB0orznUy}%i7bC-m#1p;HC&?%YTOmCBeLzqx+vo zU>OL>chsh45eLWtf-buR=fuBowF)scZVR)gFy=-)aj1_GTotx3gcbo6Vg^Ch2ESKXz-}ST2zCKM=lJB9b{Ngl0pG~IZm!-S_g$yra3XhiUa`<8G^V~ zn;I%A#9&Xp;36pc2Vfo?S>?3u;u2WWf0-<0wgA&hg_E5{A&S|5%f=X)030N z&=9byemreZ{tL;02zSZ!gnK?WS10Q(4e*o@YRt8wD?k0x(aU%E+ZdEDl6-?U+K;hT z*X+}bimIlz`M|qQ^j!8PB=c$_^ETzC@h*7x{pXoNQ$#xF)jdDY5KHX|Tx?hdu(tpY z=tHY^@FW3)L&)H9p7Z|&;3~99K%I(X#s=uOnJ_6a5o2YcKgkwnrKzdOPACc92*QgA zTD`_^w0Yjonw?x+x)H%Tm#3ApEvLKoPfr^!ktpb@doT~YkcPdHJ$Zz%6w;0+@EW^O zsjQ-f@Ws!?V#A%!#BPuT&B-5d`}a%LDES*35!nfzl56+-Ga%jHO;z(iliWpzeJ~5T%To4RGVVYt3L;ZoJjXi;V`{O;@e82G*SuEYf zlPPFQ7&&NV!~7)_MsZFRJSn`qp$@i7t(Ag1!?%bA>rP_1MZ7GHHI2G+Hddy12z>c4 z;~xKND;cGl4V5A5%QMiT)L8Ybc-be7ylE&rvAK()HE|<#Gf*c`#ZHQjrKytfy}@!w-G3^Bu)Z!AcOxh$T_E=ZSwOi~3T?u5KM_ zL_+`$b4=@-gV^Dnx4djfdm+>(%59K(7AIa9A z;l$OQ8BFkoY)YG5`q@;W{hj)m#=NljpfUQZg^7Ax*G8$k1mp5! zs(pDDIVi2lCL?0Fax#IM^i>|DW-=ap>n`3ceg65A`O`-gr^C&~ePm^GJX1tkpID&MmKAy}i|1>xi~tXTzziVXH*TM@&@ZKgmuxRxcVI zOAo#V@+G4Y>JZzodQT5Jr`xq;kx#1!IQup3>c4a5b>(Ssk@@piviX4;vI@EH$nLy& zl~b^zHO6xC%f|t4@8H)`t>q$v8eAaCz;pvf7b6S5I4ll-kHBZ8O0Xd zpW#@T%9Vp~fbrSc)zi~J7-k`ecJ1xL6IXbknAJ!AG`s8M=?StK)-Zkroyrev!%L0= zP1A7FHgOU|A+%I2FHJ<#vu(1(d&QH=W(4cbQO%S0<5cj^A95?xc z>kHj;rl0Jah!zMMxIgXgm)|Ar?vP3I$PQQ%J)mxQ@}vQ@Hg9~k1mMO4y5N_VT4fK5 zfTAgjH|B{niqBtsOlBgbA>bsZZXzg@eaSzitTdgQM}C&_*fF0t_SCm~1U3G>LXDD@ zOJsYeV3$Jg-|1gAL**Ij<&Oma&YF}D8E?<|Zm&?KOjAC1RIWL2-@b0t?1U|w=bMz< z0(FMFU$?%*bRUtE%x6J)Z@wJ4V9y4buVc9*%9gB8yJfp|+?UM~TlV-e%4*#%k5pfj z*^Z17U+Kqq=1OkYsT@{E7QbDysG_y8JDh*A>v$4CXjMDud7xRo-`?}tVR`Z{#dC@j z%6q&|9pV(9TYq{}TUYDeKC?s0M@#COmCnAuf6IVrgzZa%)A!?3?j-ZialPi2{Ha@a zXzh!Kn2~ez?uA#^vTqJ7iTB-E(6Or}ncDN4yLU9&RnYyK{rUNij>J&n$2AS^Dk{WUq6 z>+C2oy)(33yXGo%bRuN>EOGJ=MFZg-o?~Ec`Yf1f?|7zmsW!duHCwk}l94TaCevqG zHaSy$zugs(#ZdbKKVGzU*=fGw9n4AJsVSH@`T`SS|Yl9 z+V9teB8s8oO`QcaA25JR3cCW3^sD5*FkbcW2#0F+qlj1ElwHeDs2(^ulj^{A4PhK$ zaF$VCQD3v((-2&%l*;m?afc>sGVl>CK|ry*vF8uYFvi;3)l;`2JLJcI4!o67UJ+23 z>ib+d1H4rD9MztqZ(a4Hy>EM#{g>e>A zEiPB=t_z-zXejVLdD0)psw(WsY*mK4sm|fMC_s z)invyxjm%GP4GY{>LWxH0!G+IuqJ@T`V1gE%)n&vKaPRV>h9(3>k*%G)yv89tJEYf zJfrpsuxvxrIFLjKdDccCBAq=in?10)Y=>MEFsw$ydZDimGyV4v_iYao5AP#cpLm1w ze1io<)FaR#E-!p;cF(#DE~SARd^Q(A2of|z2ZJC^c>6$a0dE6-AB@L9-;WR*s;H_W z4B{|!sFY(9r#`$u+T=in*& z^)HNnA8`364D|ws1(aEI9|sYAP>y5ck&!TVVEx6*;V51sWr$J8!rbHgin*`dbS^&DI8J+Zn<=RG{0@CooOkL0-;T~hYRu@aD-rn?*nHMD zNV>@@8YsQ;sflW2ebcI0%nqxCT%Sxylo$L*sgoR4S+%qAXn0gF^fhYhaeKU`GGh-k zhF_ig)_D~^g@W#o%c78il0&T#{?!>vWl01S4C zxMnSG#o^!C0#9>L`_gfu#oYN`#A~xlhEBi9lo1Io8^!dk+_3J`6tZd+z0{$=c*Rv= z8IX5}z{$_&-i4h1ez-V)Q7bzxH5F@{osq#Z8OniWQf1FRy*6#DiHyzYyOTLhd7Qjx zH1;Q?@?KO$foI1GQS3|%w0~n`iLBTSe3k<=1DXL+IGRh8*Sv={y`r^?F`Y*3DJQ1O zk)`KF&W34gbs{Fs+*c4UNz7I~KGr?a=ny71`B?6znc}X<;!lPlYTIZat;2@t3}Yk%dyeP#5*)7QJAyz|<&DW0w&^bxn~ zEk`8A_X6y!aRm;_6XD2n;_UV%CLL;lf2eO;5gK6Q`57=35)~*ImoJ$|-6fL2!OeNg zBT(TKp!zuW&ttE9zRB`ap>vmw8*%&2q#@5g>CqFQz4&eA^){X%jIYyyu#CxgMs_m- zJxsa#f@@J@=e-E~!`)}0A;@cN8R`i%dJFkW57wjn?)zYxh1`F9GBLNwkie&-DHlX* zx;~rqP3YGT%Ep%JL|bx{S1VQ)4~VJL_{bPbJE?R$Muiw0*JVN(8-?;KH%xJoa=z@& zaWYv)Q$ADjzuloLlcI{h_E%k?CgIqk1ZB1yYhDYVoBVUTl$EZ+CX;VOnQ8=o1MeYAp`W_2lHuf?D2kg z<2@BEjh+4A*hXK`A-VGM$xQ(+oy0s#VbzL8X(Pwfeg4Xq5=X7`MI<<|K> z00P+uqn92zl}0WAZDWfllN8mlSdoJ8QP;FrZyZ>c3LHCwS=C^lZnM7`tODn ztk4SN$X@ieFbl?hQk_0mY?!@o9K2)4`Ybtdwa;|6iv%e^azF@Q!}|f@jZe#W-Teju zzo+*Hxw`e{7Eucej~+DNpsF!{#m@F2$y`~fxBGH*trB+g)0cdtVhkGVP8ujIQKZB!T{x9L8$|`FNeR#O=lAxa;cS+XkvZk`S?)m`dtr=_8u0xV z4p7@1A>nFgx?U0{gru3LXt}v2lyPd{F1enc1b$5aCMq54xu5|*x_AmRN~+ssIW<5Z z%*w@sED7UEIUof*<2c)FJg&7>YMBL>cqfpcz#O!nlM_PM&K)wBG}_N6g&<<7I`v*R zYj+!ESQlfyV<>A6YlIBdn^!GA<%})q9=(|LP@3M%bqqV$B72T|-{B_rWPEmFY3Y;v zFy=x?RTagF_E>0`+2@~wd|qxbx~0-Ld%oUHDh;FNp2lJAr~Kskp;eD3bu}q7=enNz zBqv09#a>yaUa=P1h=@ohB^LjfH5IP?F_bBseR4#}W{4BERa6ik%Kn?L$UQ@)Ry+W& zOE1*aGs4m#Okbm5G^B{sWbn5p^{l z<*<0H6~^S|E}yyGbnoMv-;agDQm74#Y!)!W>qY3gTiR8gs=jADe89OB8BXTJRK$!c zGi2pFAu6Us`YHuy>PxvgUX?(Ghp!X6jfVAjH5+V#MoB+>4jk%!t1_e!cB z{J1v&Q)59P5e%DxT8LOoy2{`6X(%Z1@&fy$6s12=#WsKZKPs@pD01daFxzmv0(qvq znXPRG*xUh6a`ZKMK7W}uX+Hn5V-WCFL4gJ(72L-08lZhU<5C8O0T9TCw{`QI5$3ai zMgp+(ZaLxkX*S(C12_kK-|yuG?=EI}&!@TH^*Kj%AxL`Kj$J3Zes=whe?>*|#RuuS zoof0N)88a)&aSReqSuR}E8x=i9~&?8?1#m>f1_g{$ywN2`$Z>-uPQWKdH<>C^E2n; z`d#nm1ZTDh7NgdChiwn12!|Ul8ZR@Get<^-z>3~2g8(6VczEcKLIO%EAa~{M0M88o z00lka9d8bBep6DaXlMxklM1F!2;bJ)DKMK$gZ2?o_=4*bqzqU9;SZ8UfZ6<5P!JSn z{v92Xguqs}0TB~au7J(D+e=y_Qk_9{W%B0DKq=|=&d&MUpxoSCzyr_35vdOlE>Gq1KRfKaLj`g{1m+f%iOv<*Zo1Y`;=9v#KQiU7L; zo&s2gLnm;GVAz7o8ANlIcbJ zTh1Qcyl?qedrbj+i2vMK)XDZsTh2=XpwHBO@QewNWEfj}Zxnim-GB)&?r!tN=jZ;M z6yYC-Z#maMY$7}yq|;kB3kG|m<=zQUPVY^%TulL&1X1t$x&Czv2Eyjb3JZdUy*X+W z*0mre=4EBoTbP*+3jo$K8pTUSkSy8>Gjh-+K=B9L71VAJY7ql#1F8gsf&kVSS_2L4 zBup{B%6~@AB}B~q=2h^{2npEo!FlUWDz!EnXM%!0IXBwF_%CkbAlp*+>ms7ZHnh3j4+8DE|K@FEfU$Vq3)*rJa>sdj(MV#=au@iz|Kx5 zFvuCz)4jo^;i;Ocd;lx^_LAV0w~v_k>p9xg48%y<-8$h3Ov{Ab@QO^c~>6%wH`6 ziD7mZ(n3@XIM^M6uWA!Ao+5e^pa$$>E>ptn1p2O=cw@j-!69yUMA}yM_uBiDhp^v= zhKK=m7x`dNZ?h{hIXep(ALV4v%g59eAY-Z*kOycTAd%+*`~d7`1ozkFQh0RPRr`HU z_9?U-%d6GqRgZbNr5S7}WrEtO!yq3|YDXW86XDr{lknO3SPOW|;~^#>h{W=nqs(hf zM7IX;EIf8DF0P9D`t{YtOqfWlAW}pS$3x@&7I0Ln(ft7YUATdeH#bjC5D+ua$zz$Z z;lOxPi*WFEJ6OU-NM7MQ_)B2`f$fmtvD*{&NwfM798X{#XbCI`g2%`u*XO`yL4i9DUJq)!k4d0FF3A%<1#yzo%WoAhGN#NU{z`k4c z5!FnzPFjp8LK#1}&1}U9NiMozK!Uf}J!VR>qRN7n8A}+O3_=R#Y+pyBU92V4a;GUkHzSy0^hRQY?RC znck6_k*2(*8S0>}bQWV_{31PQ&eWh%QNdk~m%YA1NAz+6FIYWh+7zrPO&I7iC`sskjC}nY^I@)7@GDYsC6VSQ ziFfVqu;jAW8jdwEfY`h1b&?`8Bxy55U9in*k(YuOo%KP6st|7pnF3QS+E7l@Q-LO> zZg*1s*|dAWZrAYzGl85UN#-4XFBQ`YL3ENzd7Z-`HIvuHB$f$C6^stYfi2%x#N&BF zxcu(l{Uw|FhgVrEvCi3b>4GB8pF{yWeNn9s8A|CGnyMQ1~Xu#VTWM&o~DjDB< zZp?p^zIR|Xt|j#5HTk3J+lzCPKP5x@Y1Q^Pj)%Kqx9ncE(c-sm-iPvzcbE@JEEKSi zFyF{!y_}c)i-8&P7+nJQgRV1O`Ofn2%w3fPrS;B&g?~ixRbF@56&#vXnn@k8xTD|L ze0#Ay@Kl@$n6b+x`u5$CJ+YVXm2LODe{xRN;g-jsE_bd5Wd$58K6yyJ-?8vA zB3EAG``>p#f+sIkkmL#-DN)$2E0DzshO_68zqAdupH%xK?y`RL=Dj2Mi$RHH_Lk3Q zCaalN!H2rRNRdCD4vev@$uF$ZsXjup4V2&7|4?OR%QVBG&34zis@2@|(ps6!HS|2@ z0zZu*@_a2XScP#RFG__Gv!lC+S)!C5y#QxRnp!8wo8|Jy$+3OC;P6@5eZ^qgAmb&nz6WI6MvNw>>q~C74yNHDdi$t>Y`(*lhV@D*YnZ!WzHj;`_g5yzLjs zBh>bU#6U|jZ(Gl->IG}8<)1t1mbX@)Da}=D?9GhMisHV#$5Vp(`q|R&xd{2Zyfe`M!1P#at-+1>6%o3G-Hc_aTI|LQeqjk*#SIdAWdH~YZKBIvWv z9Fn=A>+I!K_@kT8iGGJ_??Q$IeSd7?VkA7Q+~3sW74q5GSfJKt8+U4>r7Dr;m`=|b z9%2$vL(<#5e|7#+gmsS>IlVOhqc)c6SL~O6cKe@?obgOCd$+`#T2Nu);8L?cusl&P z5`Q^1Ad~&pc=cQ7_}TALag2{0Y*QcEpW4l;Qey2rjY{*XRUE&bT`cjWk={HikWORS zx-Xu8^Cc<#&*5y&gf!XwMg8S0;Q~#|*O0|P-R%gtUcOXU|L75MNrSTkyg%Ut zF}Rqoyy?mwLd4!o#%(y-R*f4eI$sNVJZRmQFyrA^nJ73DxI8fBI;(&OE-?v^RP}%DvQ|=iYwv=$cd-8%EAb^rvr0RD;Cssy z=@L0^SzeXB%4Ts8fB2ZfVpXvDZD?FKRjone&*=lM3)uz)V%c~GOt+hvSCLVNjpw16 zO9^9d?AP<@7LMjK9Zx=q9ai`MJtlT?_iL9+iP1=qvj}jQuLP7-^ z#l!2zdIsh^I?7QZ+i+)hMM$GlGwE!YNWb`K-l&$Je2-7d?!jT(tAf97nLjTGi+8t( zAL&-V#2-j4Oz*VdA5?j4{ZX7-a(l^lCQj1PglS;b3a(lN<2v)SlNItV5IM9@pGt!% zb$V|drDLKVHwe>=mxpn{gxRor)jZxfiPH=@0eQ+8X7|n<(>AY1$rwx@rYqz=2^5o9ir9qx;Vp2#4@M zF`4B#zK`totjRUhJ^Ki9pswIADR>H2d?_JN?}!*cng`m3^&g*!%7jCl5Tq0(sd5X1 zxnOS`EBK~T+)4t2mATR92HDzA{-qc-)0CL{#EeCE_>11UQF%1GRJFS7cD8aCFg{UM z@fFAy@GEw#w_)vjGginG_cjP_?-thL+i}eEU@_*a6-ZK11PL2u+Rzi50PYKeYot@p zM#cmVoLBO(@37T%1QoKhhMy~B05%QQ8@^g-By(WQ3+hy_Uv=OR24-t5tYJFQ9F)B% zTGmgA-jOdysV&gkIr;i7F1qXm_A+-bu3i=uATU!wTL<3xTX)JI36KZYXdIB1n z8-E~v2+~C|X&@>f^lxR_hkM`Qs|#hs!+e!O$- zK_~#VOX2(o6pRF4#(#koX!(*s<%kpy^Q!ejf&MeBh$Dnn4!+*kGc6acu<#Xt>mn^Q z0f`F14uyIT!43ud8N-*glD9G(>SH*YlDJUFAr$iU z>%Q7;5WV$pdWvX`*T#iu_+RHFvl87F%h#attwGy@H9+Nfu4_%GC!aYfeU4S8-5+oV zQx@4t36_E9%=nh7@`qjZAY zYH*&&9oj2?)Zq?)enIeE&VJ(>aLo`06wZKN<5Y& zlW(d-YVBcEP4rBcF;eZ(F%Cesu}D( zC8MvQ49;|I8d*o^JT>oJ(!o+j}O)L0;?Kb zM3CaZfUqEYtASuk=-}Y$A%c<)QGDs?c|#Shm!Wn@83|S29akGT)!-pqoDKSTx zIb1C4+~|0l4ZHbQ^B1k`=ae@>_!1eKn}_8NQ@vBjRHW6*JemxZ?%2)lS*v^4;lJ)*SUui^2|qLZ-(J``f4K8uhlS628U|#K45>r^4iP+E53d^ zf16n?Q&&e9*AAl?41nX0_o9z|tZ!%MvRz&H2M@>Cy-f4hqR(Ipicy=J(>E`cwjx;UZdX7Bs#xzFCGNM5DJ3Bhv=#eM7w1%NfiPOKl>zoJM#kI3 z(p1%v-=$KJN0DyVyM!<@s#_n3wG)x?Y_U#1c2~1$9mG4|{8eDujBQJ9=1Er=9dJxk zj>-5o`S`%N?nnEb*F0gxdwZ$AJSaoG$A4v{w1!csB==G?ONV)BzV?gVP_G-Vjywx{ z5^5)f#QHq*_s3aW8SsD|@0`1>&!gI1&mU+IlX_temYM;g?yr1`1 z3#e+_9{-X$7EP68smtXysMAfXyT8v{kIYNm*pom~?2{D>*{pFaWs zB^Y~o{Y17&h0+#$?GYH8`((Q*fIILa_`4t-&sJjtNT6nt{ew)LN+CXm&+TvEv0pUC z%K~zhFEus2GYzg+&L>cupQSAWA?`}~uuH#?e40va;2tDHQzhi;%IEcT5mXZODLb`VOtSWgG5u1ICd* zziW?myc+w)fAHhp*JDbhoj++g_Yn5Fxc&O%&dB(5ZV}&)56V13q8-%&Zw0j3qvtg< zZy3*9+GSM<+%|LZwOw`jUp{{OCTxEnGM$be3kjoam^vvZCUSUgY@pN@gjKuHeetLk ze-=`IC0VQ1|M#CQ{w8CL7&582rNDblq2 zbGAh26=q!D+WklKdg(*0+lBQ>ovUkH+0Q$qCUmQl%QRfG1C2E#`O-1#7 zbyCt|ssCahlu~RJJFaH;yVvvqR~eVuoqNNNyxfmwT9Un66r29etsMo9=zcIRmNLte zhz~8Q)fINXOpX#cjlOUd&C%oH)xDjqLB){!a4}cQynrPoBQ+=b=WtX5ZRVXXK6O29 zy~saR;`G@2*Z09@1mewY9VUz7LdjA>)%iwDqz*O7l2+Nd2TfQ?(#aVknIxIg?l$oE z|Hd6l@tGI0mJPO{rOW0c&ew=hB70nc3#zj^w?lNmYUWMQVjr8^*%3zkd|gmsECi}F zV508~5Ws)Jt#4U0wh4f=pj>s}AL1a1JNe{gF5$4ZG84GtDj)rl+o}M&gfi{kRj0Q? zwvhx;04!&Lhbau&KZ?xESsQqS7pgw8kIZ$kQerhS|J)8v7z>HctS6 zZ9YgS2f%qXNCM%Mkq~x`;p4Y*tr~8S`yLG24ku4?@TSR5l}its$~O-WlFCh))k@ZbASDZ?}&RV1HnI0CFBg9`Uo~_C{08L8 zMHmzP&+E{TTpj3~P%+Wc6*`72bfW2|f+Meo$CM;3iUm|#fDS{l8xT_9y)~7@jjkIYT7V0RD_=2;u;57Sw;fZO;rJ+5KGtPheEP4TP(1McX7WX@Lk0ZvY^2 zk*jr8u%&o+v0Zy5u>m1=U=B-&3RoaSZ9u(CmhQQEecfzV3$$2>w-*)`5Eb1;-C?k2 zveytuGXpCSXq-h3QwHsU_&nBp{17qA0*|l`LQzww8==mJ>d2ErwqDHvUI2YGaHcK? zb}tD;FFQoHD9q8J%6Ye4GlqcJfq8s+)pB!kmIUbZL3qn)IBXC{PtP9+%f9d5Lkv8_ zIAU7aP$rGu^- zYiguLGH)U=!^BWwGBPtW<45+|-eIyElyl`s%y+AKsjT6NK)@z#4}aQErxNk(?V$Bh zG_0`2@m#r5rijPS+r6RNz|&ht|2qC`th6-&|V1Oi;~uLQa(WH#MUF>SeJVe!e>m|gDRplDXetJt{~^AB=5!QjK3{! zSk7~|pxPG896mDR-1};a@y`G@z~rDD>sEm`UKCYHb8o%EOFT}jAbOosuDinTkJhV> zdG+4U(tS?y6w$ly_k)`w$EFT=DuBi!m#Q2CGHgg(#2Z+eccWYOr~a5=TmEZ|gB!vL zq6KY|VDw<=ouRGT$|(pZ38VXIbxTJZ>CU=AO(F4&RP~m z7kDF(_BZMMqBS^`+*smi{t3hX9>x0D$K;3aV4NGz5hg7B>X!Mt$anhQVv0oZN8+PK z1AXKdsH1b5KiHzji>V`78!{A>eqy+^XXqOCQ4HUFnDkM zNN?|9Bq=5-x*-`(8A*I7PiRw>GSvs(KK33t-yh<_lldJHB=*J23xWa4l;jgfi6mLn zAv}}6qZD*%7|Uqm^K3Yj%Zy81Rt&Rvve-&Y@3`!>Szz*G=dEZYVPC!v__1fNi6bme zvyc!jb(am_urLer*bX_YliNniCW=Nf_JuT-yhDoN#i(m2Rikir#fBD1h{{5;l$CM* z&^Nmg)ExPE7Im*!W;lTvXIO`x#!8X)d>ver$|jYjMHP1!DWzb-RBF3#XTgI1J+5=T zo)v?n>6<<#uJHY6#=TCYxwB$~-;|z|~RHrE#I&1-76`ODO&4%YJj3caPstMc0 zB7V?V?RA~*Xa6=766!2zUvm;O!H-zY_I}V-^=v$?RDN4Zj1RdZw)6NyUKf8Tg9;vt z3dUc;)w+s@3ApXSB8$`LmCR*|IU2HgBx*vwNq7XYXu115FJmc{Y~+?2a$;FpiE)BW z=Ou?w@C5EZm+loCTWF_BLREl^-y2$`Dp|DR2366Vy6j@3QgN-|p+bFKhES1#0 ze^xLVw9c*^?}+ddZ1L}WcHF=4YeSz4Ji=0u?`2zL2y7LWSEr^jDdy8k)wRQ_qvCNV z|M5IA`q$^D?fgkZd2b#HJk0)A_J<-t)AZ0p%l!GH+3(&Gz|Ln-KdPb`{C_Thc1K@P zAhSwHXhz1-`jdB`W^0=@>F2#gzh3k0#I4Q6m~KJr#t?7iaFHNN`mlN4FK$~0EE{^Y zA3QTmhq=V$T+8t>!vfFS>b*T~mHh1T+P_zOU4@F1eP5Gf&mSW~Oc2GCJD&&;l#A?NR8Gnc4^x9CAK=*srcD^0KzLz8&=Jg_D0FC|+;fs6&R^)3L4C1tZ&ba4n?}Q92 zQmpgty`OY>2Utte(S-|EX*Q^ z&T_~QKb~d36245Y+c%7N@y%~9u@Br{80ax)R%zom8z~E)zm�_G(Ey+^nBJ7HRo& z`IoG6B0QkX`1zo%S>5Ht`EJTKYw<+ehr^>s5shb!+c%erV1N(pwjJaYOt<)CY7|R} zWXirlyTuSH7-{>hu0s++qMrXN8QTQiHl0Vj4L^*qpfbjE$sp=+nelk{Zpkj|VYh^M z45}r9tA@aOO~e@O87kYnTfkiilERW;QVX0|bao+BNbYUj=Q&UTuccFjZtx%kY$E-BfQ}|ivzl$HeW@AatNL%UdBG zO0Ho!Q%HPCXJBsqt$!m<)JU;RGt*|coI~kRTPOB*t`KXK>iA~V{v4NL!)Tr!_mFLk zpk&j( z;6YlkueQEt^VxR6vIS`e>Hf|1MND7b+_(T#Mh=JF%8mb4@M*VpnM{-Aq$K2SE(bey zoQc2SMHFg$?~Jpo-FVkn6NyPUD^up?Z_gFBUau3#g}bedD?7^fx6z3-!5Di&ibRp~ z7S99GU`xJ8DHr1URqY}7J*@3Cv4_89xrBnZmdM_lV0$hODANjTu(=4aeZ=DGfN_IT z2VjA1;8#ohp?mLm>SS+kUJ^JB>}J&p`TlQe!$CK8yZD(xS2xJf5QbnNmgkTzUtHt^ zDnYbD{$3yFt}I_l`v)4k1%wqX4DA6C;(7Ea_yt!ad^wITP{9jPE} zlW?t8_ukfSxWkvGrn}^|N?lSz z&Br`velD+s2MZweW`j)NgzbS;A-P}Qx|=fuYqrLKT6hk*;}d(_=NwO$2Nf+ zExTOR*!amCH-v_iqwo$-zI!woOJxO2h0al`ay8yBJ5nW@L4uA7uhWpT-k27j&5;`* zw@`p!1$S^nK_yHVvH;|iWDqkAp|^l_Ii7^n^p8o9{yfCKWvsi zFE^+|rBDF&wWpQ+*VYkC=(RjHg|~My!$!nPLd-S|oF9#t2^Qq_M zB3+Ni?1es}LWAVH@5_$%w3w>{867|h;Odvi9coQ#xitIlWe6djUb80^-SuAZJ}}Mk zLZu{n>_~GMpFVH&Z)g+`ZbRyzF%H8#&QGAgN+O)Y&}?vwo}P$>Z_2zq$;dSffWb6{{WlQ+qYv=zAII-^)hKNpQDMQ`Ca2^(fCV_V*@e5JCL`d;z0W7HB&W z1R+n6a>|so6QQiYEi@u5Ph&P{irT>s1Gck@d{ktjbG7F!ZoO7O8IYoEBf8sxa)Ag| zit4GXuMd4E{Mi!~*%WzD<>**MQ6&E3`EQ+$f!8Bdt){B4$98Wi6|C~&u(`!{&aBnQ z99|n8Fu!NN-6^rSZbec&^ClDJ{kmp~}Kzw*E_D3lB z(+jTlFIz3WPFxwl1X07|P!Qj$6Fhk(2e@bn=_H z3PRC%dp3?dl&8(P0$?%%R)H9+dVbH=op~tPZX}fok>Y2wgaubcGP9>1GzmrKQa=A@ zIwb&@#{0p7^OAb}mb^X-1Y^?-R*^2d+ezy|YtbRX8X z@Q>rs5~1xSktF@kL)DQ%^WjC^!c3f%W>T%`kD+tK&;6(zP?BQ!3o=Umb@3RBN>Ee9 zvgj}a8Hmn^)TGf;*5+@~F$E>YFMUK|Bg*=rWynXIZXw|k#>?Y{`%ksxX>5mh>NRuBd~a`j32 zqy{r4QsojB1{>;Erm2W)UQz*?^A~k*pDd-~6Vu0_l$ zY&Ak@T*ukwLA{3_=GI5Ywc6*n+>OU%h-La@t;|D+o!(be6B&1y>EfeS(f-1}q_G|D zF<+aK4Eo3sUTTx`kl%iIy4TMzkjDewmWmDH; zUmJ+W%c~Z>y@o2bk52poTdCLkTLdQ$brL0kh=%u|1yP6=604;RE>B{1P0Ot{jWGeV z@lJj{2DhHBfApx6KMW;M{y1Z67Wf}V)DPdnl2s7XAQV|JQovHAM_GIyy=T^LQg@() z`rcACgQ45-j^Ph7B~ywfUE~)9=>2%D{9Ska46Wj}o_A`SU>EQ?I?=YT@|lOYw~_PJ z7{BH8$hlDA{hM`WI&@=-+g`!n8G^w`tglW>@{g&_NY0=XncY(iA9-VcE;d&q*n+hr zx982u83%(^Nrqx8gNiR7q1vhfTKML-IkXq1IX@}!tVZ-ykf=}592YaNXSiEmFBZ-I=E!(Yg-9!p3Rm-`UPKWbnKk*tpN5u(I`UeEZlE&mPa$A_VIFQv_ue32G zFCP;j@iEx4PyMnt(%@0|?+!dbkzeZj7cNEaFu-qff)!%Z$wfs!ag2vOiKd52kFU7H z$D_GY%#e~yt5|S}Z1FjM$XVL^eKc-fKE`O~gK|uCwP=s)FlvRWxT=fjvnPuY*F??f z1Ytw+%dDc98yIIP-H(!5NDsH=f)#Iy2K(J#zShaSHqMK1f4KJG$)QwVvfFZ;NCauC zPI9A4cm^7l%s!WDt_%LGJ$DsBrZe$?V%;?n5T8@+!ZK zor|iCtgZLv3R?W!Hbi@qNasaIUl=@=(%Jv;a+B#Yw6gJOrn0AGA3UO5n*3YJ^lF%Y z_Gi|@$WZ|EuD5!cruV1bm#dL*7<@e8&rr!3yfpcjLGoPX{P!c>g1?iKhj-C*PyT4B zwwZ~BF?*WSPDz(fNi$JO&>I#v4YnDwT^3ulItL>OVgxVa0|saG2b zmB~dQKY(6`OEHG(afbsqynx7Kw_bjlQ z&(rO2{cIpx3Qj3oT-*lUga>Djr5K3?Bg4%P(IT*|#4##W??m+sS@Q26UtM4YOUf~m ze$Uqok>;sw(STO zX>nF;3s7$QA2Mu-({zXgkVi6zP+|1T%rS#^G*YaSReUaMQ7uPN74{>3tj~O;JXA)`X3*Ag!^hE1|*V!c8|+04+w+N}fwMmsp>h-r`r< z(6&jTWlNFSVA+UFcD7u$7_|SioAvFw7wFHRv|4CHjd!v;(=&FnZC$tD?K%$?Sr-aR z6_v2-GS1&``z%NV-pd>;J&uCo6J0G{XQih;*YmqWt{CqI6Z%i*ZZ0#EKN1CUf8ETP ze6zT6&h*UsAzFD$q#$P0Jf~;~(*kxdw8?fmJ&I7`pr$j)F{y|hCIaY4a({kD0lBN5!4YCj!5xOG! zoFOboDhryKd5Xx201Y1pLWl=M4B!PVOx9RK{n!C~SFr61ovPh6{{C)F=sTt96yf zzvB0Q0X`(~6K5CYoZ!M*Qb00o0RSTCa=&{MI9$5Beu>&Y;a zhzq1?Aw588Co)@ySAlaH3o9!OhC-fkPClf4LDgsvoeQ+`JyqKDm;i8ai((eHkUdS%^8!HHK#mGUM zO}GD!))$Mf{L?2x7&R1F!5P6RQ!7UAt6drdQb&*uYDEDe2`0F}=bj6oyQBw%Iv~n( ziRs<(gvEX~p%;P*aoXQ{zG-ZETd}DZJMt z>Dn(Zg=u@*9<`h)149Ji5eGaW5kF6nC{?cw%~RlOa{^=5m-l_kSz3!YJ^fMNAkHvp zG#3#T;?t%((LEUj^dYP(M>RH6D6v5uMnDVC$5syYRqRy36yq%;mW%kT>LP&@ z2`vOn4A4-J?>=yc>||6d65Qu(WbI2!dApMmr9vAfe@n+UIaF`65k>XD60cdO!9%kj z(7Fu;^#Gc&bgnx3r(xuKKwAcGkTALoeQUfox4hHwg%^4&eRSZWV2M833*;>3yTKjV zC?ANT@qD8g-gtP>_#(a3$Q({)$dvGsTssCb4m619%p+4Yd%mecNQu6tzL?SZo2doG zlreIDos5ko{Io-|!O)L^BoqvoInLCKH*%$}W7l3eJr*b5{KgGCa8zQG>qgnIQ;8)& zx9mN48(W13>AG z^*dj7U)O*S{s+hUPg_!Gfhpfol$c4Ns78d7Z#ZY0T*qhpP%N-I|M&)qagiqsy)UR; zE0bRoJxWu4h%u15>P(jtFkF;r`LUJ@H;PX5y_pWovI@taB0E$;E)dzjTHC1?uU>V5 zaA0rJx|}`wH(2Wf7 zFQjV^w=6P$|xbP1nKJ8i5(@<|~4Ie302EjL$?@m``2Ga`8J3bAAS z%F8X_fl>)PE7ZQtR%>I84_(GsK@!c!@XQL4TzyZ}#Q3ST4)ujHw4E69)hiB1jvgc* ziOtI`Oy2y(FToOeeDov$TZX08r|MI4;h-KyA+xVPub7|Zk!TMtGf9P{%)dIkcsD;* zLP`ldUhd%Tjh?3yGIAnxl4x45B){LInizxH71`dvKW5s8E_}WaIdU%#b6B{W zNp6MwUdX3^zGD{$idyo7hV)2;jNLomqPMuNm3@ci>Rxl#Q}84s_t?+zVEWz@_=Fu| zfw!!yk>l7HQv3yJUmfX@;G>%Mi#Ah~@rBkHzW<}?Dx;!mxbDy?9Yc3M2tx`;ic->o zq5=-x(xFI)AYIZSD2NEs5>nD3sUU)Mr-0J&9oDH|)n7g7bCC8%r6#Hn=N61pAQK80@Vr9hd+)+`sgYz}6QANg@n4lc%gevDWy*Y-#iKeg2xvONbxPj5Om}5t3<3Y_TnONL=?C`o%geopP=4&MZ=}W8u zDGeo)sQxi@z+6xRapv1r3xzD<){3wAt8>rzJhyRqEpLPL#6YzSbU|9bm20LH^NzE)!|$z#T9h#kaXkf z9{%B=i$~*H8WwBkACZYB+fvOX6bz(bbp1GFl&^!%%WC-&ZBP(n>leOEc2YEF%&_jI z=lUSA|L-+lzs{UZqTtjXVhm1pRO$vBo8^p%rBD0Ol8A_1*MHYVId%HOOfwSFqAnQ! zS<_1xC0e9hckUvWc+Z*CqunEsf+j6!k@1tiQxS8)`63C^x3}_G6^p;6Zo5&2YS<5BWmLaL)U^@sb+6tCerCWPbbh3 ztHl@bizTy;T0qxdIu;6SYgFl&(cYgT_7SISWWlcGCev(Yk^QhKrpYiBJ^}ar(YbCa zg00j?^$O-q!%+)8mKKH6*-|S__vpVF9xF$EpSd}Vrq@cGTV_ct8SQ=~p6qA$)# zlP?=)o?;8k3%6g1w8MQ(yU0l=38;x$TAX}~DahY4&$F$|1-)SfZsWVj9^@Nv;;x#*eIMj0?d$8J2xL%e z+;hVWW@uA;4D!vET^E9`E-ttW|E!5lOr!^=c+?9&=E%rCh*Xk$70OQk4HpxG+}};A ztl2-{)|(LEJ0UqlLt}syNytG(7~H^kiuba6Nu<_!m##g*g&5bDF^8)B{6My!HOTFF zzgsX1>qIk?>Y!|Y*72e$QO0t+jpPlpdO+6WTcrlKxGh;Fv#=Iqk@2jCPd*Z9z6?Gz%5`G3Dj-+I zIxCAn%ZHaS-2RSlibjPfDc;UAHN+so7!9&jCS&Z&t9sCR(q_!Kl_I=qX?iFknf9{- z{f~K*k9NZCq2x^Y@aEXC-8iaj(#9*Gv5^UU^@y}0f%Ha_lL8`a+*NFcGBoXS+}wME z_J!Y?4l*W6{0X;;b@5n!;dkW2(_Zi$&sLJ4>U938!k*Rw=~md+DT^#Hql7~^$el^5 zZptS0@kmMwaJ&v@WB!J=Goy(xq~CT9PfL^fa`g3XDl$j;jbXc5Wnh!}LYd($(^Ev2 z6+>`fuvKAf+a5s-gQHAk{j0tr;!J1c+PrWWqM*R~Prqm}&{&FvqaAQR)GMm8xb}Hy z>+jI}8wQLvC?tE9mbsZ3g}J#DltzTKnF1yPT*g5kZ3a}>`2_;pk<)T<8+qd!AfX@w ztVeMw{LoAC`mmaL2Os}0SQ6hs4U(gbX@*uI z{2SmX1ZZ4=QrMF{d7_i?v!;Y`7&074y>B5{G3}X{n2rrAU^D?)HjGga%*;vAx^sE4 z1EJ`IkO`e4^dxLSlAl-epQt7!e4{MM*m;$V_vZIgke6ctQU_dECO`zSYJm6492tUJ z5p8p1K<@)(3to?1Z=)Z9dnNaa!Ega2`}!%MCU~|or<;}Vz$<|Qz^^ObxVAPN*m1B* z0zLzn4K~2J*;xggiJT<-DoSG9rBQ0=u6wBHolsFFa2F%*dE+!6ZZi+pz;O}8KIH|| zsxIrXC>80ie>a4YqVQ*i`3a>n++E5E2)kSyHHSXX#PflA|~i0oiD8t(u! z98jp25-=lyZz0Xk;xks4KQoGyw9m#HI1m;yv8zr`5TS9O#$44n|8UqaFe@c18x2Dj zY(apAxk8*k^~1Y&H71R${pHJXd#%mIO2^tc#9PdooVZLWOKNuE%GlNAZ~_gRxAS#j zLI9YH21Gw7e<=e~8dgi?{-crtP7XehY8q&c>Ywk8J$7PCRu2>|kdOn1Gn{h{llNy0 z)TM)2k0oVyR5@MM!;(7nz$Ez3O@QX6C2hXi;o!+H?kuhR`^7~WrIo2vIR!bsZ&Jj zl&qbJ1BtoRI0@toS-7GIlG^^zR<8X|yZ^5RxE2>ufF9cmayIi%qQ7%LDlGu(p$R4K z7fl@@#Nd}s3o=D3wbYhtx;kv%I$P;5gl6#)dk}Oy5`x3E2Hao$309@1mSL>^5RB#rRFWB zBpL(JF)Por1oI57%f} zlBs3rbeq5FSvCs4b!zcx;o{!viA?iB(>hsrOW-uJO!INy`h6ZU8-f|$T1lCed>1dF zuKs#Y3|Bx@pOn!{!!9E}?e`dcjM3CXa}-l~qKQ4xN?oK+-TrCbIL_&!!dHu0e8!P% zw9QbEDeCW~+genj|5zbw@zdw=`zN@sF};O%Dx1hVYuPOCYtB6;7Ic2^dKp8hlt%B0 zO;71eNw|nI3kWK+?=)HxNvq%zHVM6H8e~a+i#s(JLi>M2JnT;j5Mgs!bL^)ND>AW- z*6K>--cq&9-y_c*a|$tOCQ}{4O6WPn9@0mP2%$QR{h!3=u$P7SC(Qj~b6iBNk&68Z zPB+(=^en$shPgZw4@%-tZek^q z@mzEevRQB?D2uv1t~)fxwUK7Af-ihroAE$8(B4ri(7o|;k!?n1#rI%Q&wy6fFa2h2 zM}+rolg@%l27Rg>=`)hiy&nVTCRTrCNBM%!qWB#yOB9yS!D zoL!v!wl<=>emLpy-+eg#5!JEc6E*ooRx-c1I z+TM{$yf{AXb3540(b!w(*fy^nT>hd^dGxW%>u;m_KLmvr>-_im%7t3s@ZRdF!9A;` z0=pIRwcsk0o$kaQkAkABq$*<&3A9&Cd_=SLS(v7WMd9E=_+>PV{eTqUns~)WKL3jk zVI2IpXRx6MP70REBy-N#=H?5q!v%q?_e`Wv-tfnT>hY$)jq&FEpS=_j*cB53n1QT$ zbG-L+o{?P^E(Mu%)^fl%VcXXpzK6?;S10ulh>s+G5xssvk4X@?CN z0gn)G$?^ZDA+hiB{&(O-Ud`?;)%_>%hm4Vxxvyc{zj^a7o`1+PqJ1^A2NzmX3CyK} zw>8MZbXDXtly79*mSpPs`=i)dS~lrk?4Lh2SW8h6`;=^7tl97ieWPv(M%zWUmIsx! z5g5jcvD>gC6ldcJ!(5JU(FE$?l8&YG((bf8MO97W9{gv#>28K!DidtYeXEo`o9M)8dzx>Gyo^dku)?ZfA;ROD2Oq)t%vp@ z`?OdoV%W%p$>dm+{p?6eH}WPN@{LMz$2S(1A3MEyRFpTlIluTeM(-GVWAYSV*@+`1 zr|qs#Bk78u$*q#%kS$l((?%_In$mL<=Z7u5v+UPc5k?Zn4X%`bZjQC8jBu93>_mbt zqGEzL+yCMj*zWE-@)Hr|Ces|AJqo2D&OM(x4M^@%{kmpKAw7)H&wovcF@<2RItcz_Pvon zk}&>BWh2Au=CBe?Rrhk-JnedNAKpFV+9}){?I&<@kmXGo==e0d;sq2-&AR&z@OB(N z{8hP!%6-cJLpE@skw@8iMiV<283s zPRwhl-Oa=2`h&!YcdKKBh+^<1%t?}frsWQz1r?{t3Bb^0cm58PerV&UjjoBU|Es^1 z`UGAsKvO*&CI*Ikdj4u*fZzOd20&7-hMDoq*UU?pj3M`YjKT7oZ+2U1s zadY7)z$gQvuUx&N_pTd?|C}YGK+OWY8~it9Y{1V`JO9AigU6TLCjwnV0RHCo))r8c zS0D4&mH-S9&Ho-Zhk~-Xxkc!FL}>0{YZCZ3;Mt(-L7hVe<`GFoe&sw+BDAmqP9@Y( zW|g~j5UHl zRkPloE6)~i@~N4b?N?!gvyW#^Xs!g`3$d3+vAb7r8AyD7xy$3h{0WD7h&lnt2JyaE zg(M(YcXoCTAfgp)sSto9Xe>C@3Kx%Wy&(f_It&Z|y-SVif?(MJj=9;dp+rE6!=vF% z1Sv{l=hFpXHVIv(wmhlHRt1i4$qrlO;Z3#8p%qHHxULXzW5n6%^CVEXay^=eS4`@kDQ`JrVg6BYunTY| z1W{A;1~8_?xLD9>bA=rtr=@h`gIs=1#BFvm?SM>N2JlORp_Rp1G+y;6AO~CS-G-j; zy&@{;$pHyZ3pHlu>Va%}I2|fY!wiMYH2a%(FxIE(K@VrgY!_U(Av78oROm%#hNL@q zPOhd4|6HWAlqE7crl+$%HL4_;0uZdm65aLnf|)o z-7GB?jMw4S>e_Wi+f-!fon#p4*-0X4{d_t3r;5D|_lvJIAg~#mb2eN`8(e`c$MBYC zvV(}4mU6x>jIgk?GKX~o%jwT99RZpv4{V;1pt+|fO|-I-Fx`kG$MVpeb2yy$VB7pB z_6UXid%UB-icmOG8;}AK5+{W&TDJ{_VkG&2WTz2MUx8$32p5TX@Wj_ZI2J-kz{`=- zJBlKPS-c~!Q|f_z5U}x`OR#gfdW`g27}HEmG2mdrP4Q|82Z1v18soGI4eAEev1`E4 zXrNIB&E3JREuZBu+QYP9J0zV2nbmKEw9|#$EpgjPAYQw@t;qbdz;=gVo#I7~d5qrdM*!?A-fxASdh0N?W#Z1IZ z?H`F}b$u9#ZyT|lJ5ZeM!NRqAHSu+N%9sKU(hHc7ZyZn8;!?1@@1#*2W^l@-uMzwkKG?giTWD9mrESh*J6wn z!{HEd^Hx(*+ds?-eg)3A%im!X$eh&M)>|YJyqs+rRs4&E!bY`+3jGnoWZyjr?4xl0 zG-JU-+5PhFV@h*7&JV1C)EXD}?JWk!{t7?q%y}>L-G`cWAA=sh`(0zGx9 zVAun%@g=oSUJ9)ZFl?|1Tii{aOWhZNV{bHeMA8N4%I9qF>dlOvG{vlN z9LN0q`~YvuzdGhfF45Ye$z1NgaYu*0hfNitc4kX`bk{gh9!0}4N$2)6qG>q^&&5K1 zzj9f`cuI%$qTlk@;orxoPa0vIj{zM*1Z_bjGFE7Q&yZ%oIb2odm7z#re>*Y#HwluP zvQ>I6-+dgX1eoSR^LoNmb+UA?<6dwYw8J4j1mj;Je2G#)wMuYpC+sc}Ix0vOU_x0fQd^rcUtU)#kLiWt4 z7Lrh1B_`P_axvs`VWG2}Xz-KEqs!10A^AvWPV5vnY!1^!?k@6ccyYFtrr5-{6J0{s zO~D&zhGJ~-bP!9wuA!y5z`=41Z@h6!>l_>Z55lKS&xm$yFjr`3;`%y=2&;xR4#)_) zghi9_M3FRBv}KKr(ZRvKQ%%0Kq~j9K`qE*+c&b*FC`?78dUt~3Ge*XNVY`~Lrl!CJ zGlHwSI!_{~&X9u*FO))pG+=(J&JDB(_MjR5`RiAZ<4r)604S6sGVbtF-4dh6F~_AK zcr#))S)<2L>Bs<5>Cz2VWmgOuqR?CLb6vpG5r(o)`<=>R2IiVwx7LV5!U==`6bgOc zN2`}7Pi!PY(v3hMK0M53G_EMgcwYlO-IPzzMy9R{K(|9Weu*w(vYx#Q5QzBKmj2?N3-kZL&<|ViHoAmpp_J@UsUOag+)6?;&2K_JgXEXmJs0Jh*Nh_46S9H`uj(tBL{pZ)ObkYtje1pJc#}7f6L20U_uFQ;# z0dA$Ka!7NaWdS=k?Z1BtfDiGk`Vr2Gk=mwimhwdG$$1lD6$>L{cj)@8Mxj+Y_cSPe z=C3~809%`Oqn%i3BIlrj_^Q*ez;FNGCx50!6K#xCNcg6XByH5QHsGhOE!{|*ycyXM zf!PY~QOE<--NHmbughUpLuF+!07Fo}^B}IoBrpbmqY@GHY@6kBm&FAFJ+ET2xdA7G zy5>)jwlCpTF!;qE(o3@D{hQ6f`zwQOE{veh2QeF7yec**oZt(V4&Va4ry&%x!27TV zwALU8hNgCLMY#BYUIFl+c%bhb(UTU4GofBxjJ;Tm{d3jp4YGzS1EurD*)tI77e6OQ z*ofU>CkHNCj6PcQosb&gmYQQR%V=vb^=64krszC{}P%#F+e zT>@`oo#@@9_kSc(91~=D*j8Or?khP(?a6<~3*dRFj;4@><6r$}c+y8KzWL3}hQlp) z4JV?3V?H!}^c)0kFpSo3#S7&R=3C~;^azbupJYvYx<|c`=s8ZfrZ+9!$A%&Exa9R- zN9o4Ni}Y;kBK@F^`rd>0(cR;YPoG|ONNc|nRM9IO#aKC`qGX!2#>;<;)joh(rpKP9 zEW74+>vJNQ9de`(S65Y;DBYK*uLats1Kn@uaQS=YoXN`CdUuZ0AGxuy0UL}M=?8-; z0c!zF2)j8Q{zOW~LskDlCxCa?1yxN#w^yF7-v=;Ut+y>pB z=+x%7%HBZY)$RkGX#&JkXG5S8;=@v{Yw`5;TKn$BdlQ7j*^6gUtB^|8 zJG@;mnE%j-^Ij>`t?`qJf9sNF;YP0}G5OChi!`@uv1uJx>9wdumj^^~H%qaCZw8%5 zh}KR8^f{siW_uUM*gXlL-6%F;I;|x)lofz?nLFu;*bho!@UUPc2uZW7JI9k$8PhM4ZzC zUo)CkSnhUIMgwMT+cg)>W%^rouh*SY2~*b+EI!&FISkv2UPIx_W_}Vj!C?N`PL`|6 zCbU9mC1l2Zvx6r8nCg1mC!T_4k%C_;)&dJ7s#Edb6fp^q4u9*jvFSOS)3`%{=Z^j& z^)@H3W=sZAXODT-JBW?sEK5Z`$!o(wja_nnl#dWbbmBN;{Had!)SY0Ua3?0g)qa(z z!zZ|cN!2AQC^+L=U!_PN@j-}qf+h^3vwbuTePU?Y%Z#0Au#dB7zT}Vn>&J?6V`3WP zAO7&-oVPD(@H`I!?*0-kU>a6nQ~w%+VE^UQDMN0WzM?geHKt>|^VIp$$L}P?oo3X3 zm*jM-w_!M<|8%v4+Qw*A;!|+XPt~+@+P~Mm^joW@Elo03ee{&F)J=(c~xXtB$ zDzu8D18>V)yV21(!bZy;p3~P9>v|ghk{>Xw>+JnEk2F^I2z}ryq}Dmx_L28;R#_R&r!ScnrcV&1=vVmMwMWx> z-}g>4wo|!r9}{{QrPcrS$X@g5V7^ZDPwIRS$2qExkI5n@iC|v?{^jr3sR;3D6pRx|>I+b6P=KBT*mcBvjQ zw!Qcn2mgu8i`y7C_%Bzp`(j0eU7!A1sr*@eW_dE#r*fFg>B8B`F#1bHBzE-d569C; z-60IFaS!3u!z89PR_vV{9Q!yW*9TRtE90_$m*%gmANn#kjK>ZtPjCGlxN|wT&Sgky z4t-8{n&n%7wX3Q5+?wj0>Stwz3yvI>!qGdR#N^IuojPL_H2K1dVMF={sz}|Xjp42U zLP@}{5L9rrnFlrt(_Dkx8THJck}wpF#06CY^rivmXdw=B<_+1uyMmIF3xi=@j9wfD zd$z;@Gs`8+SE1%$EnsK8w{bcNa1SASchnAg9V zZ*Cvz@T&ZoKb;N^eJ5=Al<9M`4`uB5*pQ>RDK~~QB_l>i5Z&U)O5C7P=jM@&>lBVq ziq6(J*_K3$04EQ)H%@1oNs%4lzkoo zK@RWqJyr&cYfB?RV#}Gx_cJC~{Z4yFaWcPjmIOrvCqNtWGR&XT6QDv+6rh1Dgf5pN z2yYOl+hAsA)`smh_{lz(S64>>i3FQ&h%eN{=$FnS0lh;spq-FgY-)ZKa7uQLj8K4P z09e-Ynwo-+qMP1-Z8Sf$PJn-S{s(}s0A*MI)jJ!LAIeKf>002=n~YtuPNGo? zCHL=<);5&B(0Muf=*4%^bFt$g7T<@yhaZ0#GgULlqQ0@E?#Y2ClMw9&js8SfGdEU>`3DIqa$RL zFmRc?bd^BrLeBKZk`j2MPlJ9yu>`=sR?zJN$9%=Y@xE~jYGrkp>;zT{sC3XTQwI=| zX~-n2BF;mp$qnl zS<(vxpyH$CC&$#z1G}I7Pd~qkIk*b2ze+N?5~+fi0-hKMXdy;WK`^Ba42DBHht!Ei zpT^rDUqlAS6Z@oeERiKc>-#Kk3C7@~4 z?1&H>v(P3bB04J7NmWk2ncMi~-dorD(qc|df+XuniL0Ymndql^l5J>*&!*-2rv2+3 z5s!AlLebQY1((!oC--M{`4EctqO8I9aKY6rBc6m5HGgcq#kVLA3hYLzXJp) zhN*FTN6Y_f0R|qSbtat$fDUf0^A-s`i!?<7$Ise3+KSHYC06*MG&oryU~sWh{r(LD z4Q5=l`g4)a7w1aE9x)5BG=hag?ywE-SPhgL!rHK-VzFKjICJ1=sTb&v<;}$VmR#YW z+sy$h8U`FZAb;@m1__73&w~Wz>fyhia-{U})sz9Ry7v~+cnt^NUw-N7x-G*jKk7gF zB@Zjc#*OJuaBjA`@pHap^*1v+|J5`Z3KVQY?BahYYR3~U3IfZS_5>BryvaJ-^wf-u zdo6Y?+V@KDeowf3a|ja)EV)M4T524jf~Nyld7*B?0X|20Gdt#2X@+`N#W1NkIVy0W zIXRJriEK{=&Iz!3-h5K+^@s(VIeF7Y4deJMfcS;|0A`t$h ziR`%g(12&be!P^A?0oQiY7q3{z&hvu&;D4tVFt265HlTT!ABjgti|Ff8}+a&QSZ%I zS0$3ma!If$vXy%)^Vbh6H{hwe@$Vg3O?k+FGhgC=zkO4Jb`;-TLhSB5@D7`;WWuPfbuO^17W+vY)w_$Xxg*T& zC_2`jd%OIW;%QYx(KWA-DEBd%2Yr1mjs#EXPGTs_q8gZUH4sNKvl$7z`Svyy+0PXM z5f<*MojsP1ZGSs=az_xNSHq;!k(L6_HL#x-9r6bBRo4tDSk)81!S>ZuJ?pj)DW`kDQY8G*`$cxyDMh`2QYuGEj(jrQT z3`Uip5YF0u7bX;6r5%zOR4n4Daa4=hr1NC6jMdSFY&@y0oTfBb8f!w`*6(vA4o{_3 zGjdsz4+fp6{+O+O_@$Aogm@)}dmEvC5uP;=>sFs`{e-_|W2T%c@b18m#J0Q*nNu>Z zp@7JCX&$;%#uVg^MS$a5e}z97md=>O-L)3hqrIw5brr|MYid$ByC!x?S)c>PyB z0`RhTm$9-+zKLn#$EDAmGKo{2i>6{9*D_88Oz{?$-)7}3iB9%8^nT&)Nxn|%ap!#G z`-4aM?*-DVRrJkbOS;VYMUcTo%ks|zjl&&QKi+Lr+Ix-7e72{?<8s+`@7a-@z2mKY z!qKMvsUo?Us&c9HeZHJ|%jIXfTe6xTrkwuyEmEcIhv4OLDvNCYa%N=UoZ0M^3NL=} zAeztMk(69`>ktlH6m?zk-b)7A;x9x(&(5UW4r%dfJ_Se7o&=D zg30?7Q5?Rj;ye=r?-vT54OeoJlC@SZj9lbk^WPgS99OPy&f9sjw6f!7ODi|Ty8n4C zks{gWtz5l}-Xy-jCa(aYwRq}f0}pY^F!wt<`J&ohQsl2A?#ba54!)i3!0x}|btH28 zkFtus%J8ZAvkMo(50Jk{FN9ML zh#4++><3MBM&14re%z`Jk{v^RKfGn4c~UGIy_xmvRdnY5c};O1(KWk2oqMUqi^*3pQIoQ2O|OW zw`Hpc(1+SSvXOZ7K1o}Lmr93^CEw%|DILJ@s!b?+~A(NC?z9jq7uHr#mnB?3wX zzWkY9DX*vsa$v{GpH?ZpryUT=!wizk3=H}WGG9sTe9*eQNG8;ZfE=J8LHna<^3 zxF`Pv_tN;VZ(&$;cA?~@B2%(`$UUs_|6}er=p@)w*o zmsBlutqbwXC6olMV*U>MHvQ~xNboZ1%*a5(L48vlS#H#a%y3O7nBpTQzEV$F$078iUu4r2<5WeI)i0 z7iwK?1J)u0kp*QHGLa4vAu+$PCk1kSDk8P2U+Vl&4u2djilsO(>?BcEeLyyTxgh@0 z(J|NQTDfysxOe+)c6aiK2y9G&K#h^Fi*@+xOSmLAymX4j$TN^#2?SA$MMarx)ZFF_*!xQyT6Evy9Q(D;)z zRSR)0<=U#fSB}YVWbV`D;PTaM93rWfJ^nNasvnY?XD!uXJ?Gy z&4UD1&=-UN9-sW|1oCA}P!6Gpm3q6Z%BreD;I0pm&kGqdFRnd)oFOUsvnyYP^lFd0 z=8i@ZgNy+*@weaTC;*52MyCaY%p3J^cZ47SyO_l(pMd1l9!XkG4)z0qGqFIY!1#ZE zN8P21d|0=XgA{*@M%p+=za|msHEsP>85vfzbtU{8io<{&T& zCLG_{Oo&HA=mcKah<%VI4@jubM|;4g8OZD?EZr4` zGc2JAV4eD_p$Y+*@2~U>;HrejL$OQ;^xJ{p6>JY+Ndzw$Q77`sGYzIeh_3@0pxvxo zbmG18Jyx;++jKc)8oSszXYUVA`NO;rei$CArQM#Oj0n~$#2WX|<)un82Cc2ZXE;UO zrAv_es#ePf#*uG}%Nh?hW4 z7PZI$+-yRZm?q_G%Qur->`+TJy7oTfEI*&aLo@3b^1j)bV~cSx)ROd0<6f+xQ95Yd zz6z?FnYQWpxWR>-{}JdERT5%+<$;1e9Dd4Q>sg{)LMoKiH&&*s|I4R%6(x)#rU{19 zm#dz6D|93;b@`L^S@dQ$EO}Pc9n3QK@AZ3O*R$7f7}rq!K_+!;#}AIuEx9)nw{#_7 zAJGjXc;h|_cBy~7<1Tw8c9!82dj4(!+lY&sf3ilm_{Vg7U9=u2#cuV^LRT!bSw`;e z?&drzy4#pjbltXe=pD0)r4WYv>FbSpxtpd@MdkF-%D%8)yzTc|0dVQvp3LmbOc4DS zf4hSzY*qR2Ur2N|lqlgVlx6(}vCNe}57fz!9`%Xyk$rV~ufHVYiJy|%;nEdZgTN`} z^1t1(ri-hX5U5!=3J4bz=%1QSKJ1Z#y5qHF(MG&Bk24QOFnDBP)`nS5k~Yd8H0eDy zqf-}PDhw39GC*D>!$3wOL^oru7=260bjz7xQ{Ynb26rYnk3q!&+7JVky&36yT)N7m zJ08uwQV$gVLLQKXNRgpp&n3Cx0bkjswbXI&$$Z>r(^IV*j@H}pu7r~0`>9Ev#ZslM zkO8KI1&H16>5`qqE$EAH56-Pp>^nGE(@6B#6o>*J;7`p@(pr%nRv2O0Esm~G@hm6s zML{<1!SIC<$+)v=Q~TZQXsnEWwWVY0uyBX5(_{1aRYUCTj4! zx?_v2Uyv_*hNf_8%e)ut`YYt6H(M=fTv>2iU*PRJmw+QPu&!N2L~PC3yQVopV) zu(uZM{@fh?czS)B1;J0HHwxqx@Y2>e({>B;X%aPL!Ykf{r5~Gyai9@m^?}n3^$qn0 z*Z=$Pupj@DX)5QX%6;)6QS7iJgiv2^csD-jlWh4X)8oy9FZBAA49zp0uK!z5$H?Ih zhGe8f~z^24=$0mo8 zE>do0jc;>0`jr25Mi+%8^xdz6uEMvtv3exm#dc>g<~>&koEct`iE{_>R7 z38H$`K`h4_eb`~MS1?MvLsPr(lM53o4nHVd@_xJSZHtGsAOo-L5bf(i#S44=fi4aU-@zLBGm zhTxz)9@;Z`a9x=Hb&WlOhkLNxat;$?ovYui-10J#={?Fcu=3drA@yndLAL9J^Ay*) z5P3I~o{izr;E(1Dn{m}YoV3R!;%Pv2$QG`OO}X`A^z`!(-%9F5|0KPqilcQvDy%21 zJ|U4S&OgS>MO4=$R`?rpz9Tar^EyYmp5Xa>=k>CWu3?q~K^;?1osT&WLk?~_&wO>~ z-lO28;IbRTx=C2;DDrLX`OV|V4NVW}=IOn|h+6KxwsVPR!B0XF$LQ>19<>XmXO?<$PY&vY^u`@Zs zaP&77OciqlkYgwxX$etBsAH4_ObKYiit$8>_@tTL^Mn9k{F)W z?j0)Hxk9QVpU=$VpSB;*>i6y`#p^d5VBhH_IQ~|Jcjl8lPFweP(j{TfLS@flM~(6G zk+jF&Y?9Zrox}Z%vyX|pQ!DSNosKL?Uj!J=#`fJltaI_fG}6$|CjI%mi6*YzTM`W2QH+;nOL0^g>OD<4uSbLY zb4VeL^XLoT{^fPW6Qg(i%1eM$VO9F=-^O^+xIM@f6Z%&0m9XsUpf$N|E)HU1%PK3| z>fBbYY)8L8HmDWp=MCE+a05UYLgqyE67S_0b9`CL1AgjKlg6(TqSkaIVX$z|IF$F! zffU^a+gcDWro12g4m8EW@VXKNkOF15JhgWREPuVHJMy`|BM9`f-+%7g`zrTFPW#k3 z+hs=v?{TcRw^z%%NZ)~vN#X7(r=;V@f0xZ)9n%p`@cY~}_dA%T$zW&@_})M~i7{~z zXXmAGT#MDlmY>i4GE^qbEFyVb>{E#HYate|v>B%nhT8%poy7R5TkhSmj|=q$^}bp1 zEs36;e5KGH8#in|49{=yqVxMBT)ic0_amS!$N#Ikq|(AXc@u;r%(*d)& zntnsvpVa@JOm2Rhw)S6;XdH=Sy@`gF#;j<~uQNwXxFy#m7l+fw=p}Px*XFD;fGp z3De~i2^e}%!b?2x&ai1xG?UI{M&$> zX!_`|%1<-3yH{0YXf$2RRdxgrm@BD<5U~Z*)|JE+C{XoxB6sgb!p%|c;>g?&^3>cw zLksXq*J1fIEea#hT7<4@3{0aWq!~6xmRu!XpZrw5%Plm{LP5|;QoVpi(BXi@(O(gA`9$t$Ja)-*PHX&Pgtnud|Xv$ zI3iRl=lDaD=@N%5{EoiyUIPy`s%m}9Um zy^A^p5}L#TQTD&=X!yuLOf#Mt1{SgR@lwjeCr`WrQv8~o&j0a4p$P1=!Q2QYGQj(w zGLXXB`Tm`1%X2bNADRN0CL_usx=V-LRtD-0gE24wd;w5_%yoD7+vSGtv+q#ES;8_g z=1^S-4Svv6xbdlZpfJZzoeX;b*#sfVkot^5qUfUmcnqjQUS>CFHbFBypC2nXe+Wq} zbwE!;kTMLxA~$ZRfQZFjQzFBIcOGcA3*e4}pk@$)l&=aK?d)Dbi6Y=$^Lx-|Xj1|e zIFNn}kGhHufu;{wKLHB%Hejit5pfC90ZZeVpnBueI9+s9(9S<% zUx&g`m!#M5j$IXp(_caf_2aA3xQoBqmsIcIG zKA789qApw*p)5NsE$z+d8VH|T;3fA~+mFM%1ap0Pef@fXxCr_Zx?3`*m{?fu38r9x z_(TYs^KOV-wB5PPXD7J;(0=mHJu79#37EyA^Cf#JvxC)%U51sZT9|WReqh)8#n;9K zZyC9{0t0)^$_aOnN4yuOk2ZQttB}bOa&9ehw0pF~)uM&*Ty0tm)g+Q1Z+?vuJ#cpRLcJ3{FHmRCw_IRX-3u$G(dw@nV>V(iW5|-PSp1=# zXw{(jFZmVL#jz#4mr9irZ%sZ`LMp^xFDO%-y<@6%+WF%h0d%Gt392x5eYdN=_j^hU z7lZxS_t`r=Adx{vXZ$$pJ6&SyryXc2sD7k*?I$M0X;|xUig#(+sajt7~V zRf&F7H@RnNXYS0({4sDsYtC5x?MI##i%zutj)#NftYNtf$7ih1nzfBdYsa)i0iu-N zU24bA4bs2Y83t?b25@Zu(h?%4n4rjS@M(BKRMts91>P`S8s`((c$# zDt{c7i}@CmpJ0uzSFyaVK>W)uT`SQy3mL>X+hNY;rVt@nv1w7G{5D!DB`IAs@@_ve z=bDa!rAsf4RaEOE8@xXnBZ(GsA;iyS)Z5jHlAgBGwfMT+U2kD2q~}P)q$cNMtyp3@ z7NU4vM^+Y4p+I@t@POu;>8t`Z-|zR@y`{Q(5ifW|1T7hO4hz>8l0x;fE+p#jNIgUm z3(*JGJ-jDJkP-h_TI1cbicC!Ev>XGpusuIU;=@MU?3x7yF4pPWv>hfd)TSw%3%|@H zhkxR@N2fK7)5#?~Q1Tupfp55o8PU5ug^K6X6R=2M{3#cYU`V=2T838Q%B>()w~P|3 z$wgzw%`Z)Si`)z<8onm{X7`20dvWO@Uh29gVJ&It44!z~&^<*{5>AP#ox#Iq?LKrc4uu2G{GPJ!i^SCnTx0F$E&OG}$-=exqq; zR3Z3D(Ql}5VnIYWS~F@ubCk5Gy{^u)b>EO87+ZDuM30GKHnmI}rx)=J(|kxBYw-H2 zDj!cysYf;@u|B2BcE5=T(Rj@heah|1YOO#}+oY*yCrei2Ik+ljJ^zroS%Cek@5!vi zOw-YECw1uP!ycrbPsL(1)9)8jJxMnRWlLrqjx+Z%VK;p^6LC@E zU#egV-;U>D8lADw^oh{Po+|id^+A!+G}S+G?be4|i9ao0tQn-pb33oyM;=#;SjLE# zI|{YGj#e}^KI2q7xwRMk>0v6PE9b1pC#L3>M~awoA{*R+zl$jEc%C8O{a%rgmlYaV z6|+q}n0$BXQxRc)YwTltdJ}b(ga%!L@$S4!p5w)`!frD6OrGyo>UW`<Fx-iu#5ei=MmW!Fj1R+xvm@^!0aSpo1E(`ng)h@9Y7RYXnAqR>Gmv9c zhaU|UOGa`~&cX}|Ke#+~E|hcZNyO0P7t=}Cz4jAEb34YT zLS>$xdXGaNh6~2UinWcAkjnMBELE6!ddB>yW|%rUBCwC0G-@~lfjW-o4a{x-`{rJki9fQ4ou_dNBd$*t!3L< z%f^g^UhpcpJm%NmKT;=w(EKKeU9IM9Y?tDF5K7oI$tNCV~_t7wY9)zF*lV! zaS^C7BYduTzo_^9>@QKsGzU>1`#_mcHKG9S{9HJKlt~bl2MOCJ@#9JFKH6#caB7Zk3Cx#a)*R}#!^DUi?iXO0ff+wLZS#nBsIc{w?K}sseDcU|KisK$`zBCQIUaeA;X&@m3Wmt$ zSz-6ha0ta@WS^6jwGHAY00n#|<##Fdn&H0ow6a#X zV(aws?6c~zOY+>~cZ>13jwrGYpgrJSpAY<=D#o{yw$M;pH1ns{v)oqyVgQB0E8YiP z!+v9b{$#?Af@lFuiFgK3{Gki(z>ylrcjB9er_Z`qo^7~oCb+LA!4tTii~^bLr`yfg zyK%SnPs9U{AS00M^*jLh2#Db4T@Y}H{+F@KTsa-!S3A2{4LuLgAO2xHM`Qv(j@#(9 zTeR20q?VKRq&b{||I-4DfNl}Hq7R{3}L ztpO0QOu?#x7flBJfSn=$#{q*KK20a^LVzsnannp44&RywpssOj`s4JG;XD)Kh6xAI ze4}6vpHpabbTqEtW^u7pNnW5vUMX5Fbq6kt zBA0DlJTuXse@cG>7EGr;h{1t&I=ZrP?XC&oYJrWJmtBR4fbMSYYCJivRi*_Mk08{= zRFHJ$;7X@O2VhH}D=5ST(t9w=fWk{%{ifR5UQpf*>RcR~) zBqb#xI;D*OVMPX@zPJ<;_B{c^a7gr2)D#!3+VC z4uN~K@T;ta|audPDInV@yn8{$r>LUlP6jRd>y$Y$86>jIH{P@TV565eT zTOv5C#;Mh+htS$SJi(S!KIJ#&hZjLTEMZ*(#&j3+h!D+AV*Zgp6k?|O>UnH4)Ux;7 z7u%3`ZMcO0{J-f+@bP%iSEcM<4lHCHT@;{U4>hEu{LT~GNM{b0 z6Ru~j6$wyuJwvva7pSk35tSxV4!!y6d3;n%S7ODc*Am=x`K`skP>mTy6k#`h*b7GN zvmQ|)`pkBo%rx&^7Qs3!1r}+;X+Z#i(A*v?_wOUyD!J4iXBf)J4?TF4{_G?Iq3l}g ztOI!dI|M`1{xFD?IHBpd0%^Zf^jC2V*iChF^H`lvidvIYlZ6=UkEHh(tZ0i%GaLV% z4u5_pns`2}{b7{P!3b%7-(1JX-Job8k*?+AY?c&VXX^Ylg&Ox%uS;#c|B$$_&!jH@ zZDf?5Ytl{pqZgWXq+&JaU1%1gx=$2p49-CEH**Skjr|406QJLL-039#o5H8w#{P4Tz@PE%ChGIyIRr7p|+8_g0nD z&hLe1|EOv~fv-p%JS%Ukt{5`K!g@?&gB(dtTawZ##v9}>N`-1F8{RSkImHTV@2Z^`Mqe4_*9%v5u&*qO6^g)W)@c~}UP08@XpalkIN<9e{!J!= zXtMtx@lQt7KQzkFhCdlo`wj+v928>v$%d-V9-2?&R)?g8hBbf1JplRftL|a7umMB&C3NBVoNz#=jyUg)GgucS$FfBrRvQw4Ura zuq{WwCk_wN3x8B1;%6JTJ8keB%(f?oasT@h_1CmHnv=NV-bp4&Ll1SULwD}#4hF=^ z`vc6@AA2c8G_H?{LuLvcKfdE(?wv9H(+{b7aaN$aL;p0>Nkw8g*@M#i49}xbefE^M z=%e@Or_j60fT8LvOV@8~ysWFQzdM@7F*^FY$@j_hmF)$z6KHf3^lb$Vf_QCuIYw1` zt!W@F7POfXpoZdgTC{QsdDV}vt}+9*C)EEVozy>-5(q%W;}3xg{-%Gd1(i^l=%msd zo5V2TwyFs^u^do;WEXe7y97}8tp(XQ2X8h7KAwSnwB9ZZ#)$=KM`_dZw}1)Z6|<`; z(ld*6?`y%aC;E3vD7DKY!JhI2OgQ~tv|DUE8;-l8F_2=SvMTi|*qrVtboT5$cqs)4 z)NHQ}FEDGVAFLD4-Nku{Sz|slFG5|pCpmEDw$*>UNff}{ zwmw$TkoP^b6vf7Gpdrrkt!2 zrh@Mz`mgoqlYzqV@c3~0;0CDLx9>;hRb;DL8srLf3?0A>#QX|_EWg@G@J|L4kZb!C z*&fCgR@Y3pHIoFgR=Q>i7ABl2x_W!dS1CJRJJ;|@_eAhgwLpkngkm=7=<$ zt*u2M&wuJ~-ik5fVvn90S>lEJe%u&Q zc;VC}vsl5S9hn7Br^9*z9*K`AnkjU!+=f-Fe@Lbuk%+2x4*Hdo%E6}o^@;*PwcZ4w zKuFr={nY`$G2juoy-?lFN*QBpPW%=xeW)vypvwnRO3Rw&j)XI5RngWD0OOyFglhny zysdJ$WzH_BLYG-NKSy7A3T^*q&r9rhcW&BQS@smrF@B5>6WdFh-2!Ho%+U5e}L>#4+Ij zngW8!F|!#uK;8{oa5_c^=S<)Xuz{z!pzq@XTN!R-AC4%YA=9u~4Z7w!i?k^_A>wBk zW87EIlv+(81u3cEdVC`+6)R8Dd z(6yD;WdM}sPX1I5N&7A6kljA8O$^)Mb(L4{euOh)%^2BMmF$)wOwPjb&EEQ&4R}iQ zOLYL%yoDzfJ5@nNHhBAh8kN%khz9gMfp+n#_I5>TE0o8cpAi-E5a0hB0T&O{F z#eX*s=$NnP3IxIdl9~=b+`wNBru4wI1%O*1G|2qbqr<%GJo)@A3`)_VhsLvoM$XQv zyp(<@+Z#|11woqhV*w!xc4DBwM2Lw;wVbbWWcM`BMUM|qI?KAR}$-VBylix3c(&dbklBuJV#X7>7Y&^-of^4DJk?6BYU#53XS zwdw^=e zqlfN^hJOi>fT1um2B?$34T5O>Hd$R-G*sIPAqZOgo%%5F&Va~5RToD76?2Su^3F!P z?s>sm$u9h~%)3z9ECR@MKizheKunW7pHqC>NF|45>61EW^~3AQu2Bzf;xjyEClA|N z&|i=~RAc{mg?%vY?D(BEX^3(jwvtMeZNC9qG$^L74~~w-_T_<-HEnlix}6=`pKhSp zRa=M>RYaH;G3A<*z{=>2?=b&I$JlG%n`o~IWOmXzNqMR(lbSN)XmlGQqYpaB(y=)E zH#ob)ynXd=f7DT6>x3H9snL!gPOJbHTPYyfL5fjWWJfAi|tWpa|nnho1O z8UME7ZFpTAEqze+wha2gk+6IoYuxi_PT(QWUPyM9Hq<+74MT}jnWjOC{&NQ<`{w9t zQQ=)d>WRq};~oE^a#UtO6c?;=71fa{t*M(8{bW2lqv>@MCUgiPxn?fsN2tvzXhU(? zpf>?=$_hkuHvF|dq$NB9Zb^F_Aw3i&;l}fLYHQ5g!6fofQbR7pVWZGORn^qwSX!E{ z$$EET)I<#k16e;2m<xUVHL85^&Ejia1-d0kiu^Kz!KNV-3oV)u~o!}|Emh2y4->h)2 zuYzV^DtJZlz%E25lK7V|D=oRb$E84VT>OPbw2HtPjvqRlaEH!8BkftdQ`?>F9ip3l<4!yZ*i1RW_%V(`{YCl6`(<}9*ZcL(!kCv z9je7Uc~tV0bpE`|S#Uq-?C0TF`hEU7fh~`N*;9$0;ghV%+fnb2bUf_|&Q>ANdkE8d z1*yMz460dBpKoU~U&NHW_!kjLgw`fA;r72%U;VxC=Q~4A=R;wKRMm>CdXN9YS-Lov}82YH+3hi>|5SskDd&Xj(6-x|LNHud<5G+Kf;60@1BPCCnoK(4+m$mRc&oH zM?SDdEe>tVM`yQZ^f}(=$YVS4E2vlrV`hZ0pi5Q(9UUF45ly;LL&V~N+32;NyN-XG zTLXm9c9T=aa2fZTY?dyY7|x-VKJkrW!cjl#a7zgevx;GbvMnB_>U6QHOF4{+#x5@L zn)w{1?vNhZx~Sl4>1Y?}(ABiHcP-5@eHIK+#SB#oHViQH>g}2R82=w(Kge8~*{5Dpe6+kIkqUC~{+ z%W{2c0jKOr?w;W~4Z;qu!AlEqQ$aIz_|efZ>`|qzpCi|EM6uW0ckkAo@xE1cP3_Rf z*4JAIuTrd$I+?N>HK|jWM2xv6M(6v?VYm{Y4+yR-?kujNS0EVcef>{OTg%ASHwNs+ zfzzh(X^5%5p~I_vfVOD>Nx~iuGTB@bD=bud~u9 zfiMVu^^z=Jado<9MWxfGu1QLA!j+=}4C&wlS*smSa;zqJ9sx!R?1oYntx3TZlI1f# zATrpn&eVJG1y@2`1!PFET@1;;Rz|;4fIz)see|XT&*z)K%|ocZ`mRj6lCTJ$?c*FFxwXMBhu#iGeQYi*J_l|Tv-ME=8^YdUTqB>!=#Q;b|Hao=0{}{uX2GJh>aSV%gR%y9P}1vue_6s&bPS4`kN@z2HVRk|Ks*5v z{hfDqTN`ln2!eiKu;m9E{W|Sv+Xgx6L^h-)qj>NYbBZx50VW(YD9$j9Q zsoen`xL-0=v=_MG2sjBT!QOmyZZ7##G0H{C7HASa#rPiv26+x(EC8e~ZyaD!&3$~b zK<+Fc4}lcI9FS16v$GI^9>53++*o(xsWak{NN?*u{qpMr+vBVUUT6jdB_)Bl&$tq; zkLM#G-K>W&iYg0cj?ZalG~62{Wtrc6A!haiwl=adEL%XA`RFP0m2VJ4{&48BlkIs+CA^sor7GqFd)_dhXkM% z*Opfa)GO5aF7o*P=6EGvhgl#uoM8MtTMUX^gnvpeR|>)35IO|=Qd{3sT~*mkpxb~( z^S+61Ka>^(_;Dx|>Z@cv768RjfZuCQErlKWenK>3o)W})Yt2dk*vOsf>W&ToE~T49 z5;=vuZ$ZD~#zqo1%?Y-8gYm}(t1KAFFyc3^7Zf^H)W|%DTSv7Gb%5?;?Vw{u?)=pY3A%ZeX1>j=|*x==Lx+748 z_)^wuej~esTAqtwx!*GcOX6-auaigF87MUekR3=fjx9i{Fz`8+xkL!r0N$TO;7*r0 z1vCx1c7B0Im(AWzf6?<$cP<+Y+j9zca)jD$QGv_%(*G@#-|A#;KG1aY#NXVUdDv5+ z5Y~RS98~)SSp~OH)ZKx&_%aM?hm*X{{PXbm^2K z6M!O1e5IFu?Ii%~2&|=#7JU*gFE8i;RIQjNiDOP2TF`ZTi%0kA-P z;6f81VYpZD?~7wa2bq5ZI;mr3x=;64wB_xlhks$;q)2+r7JT$j1arMcs_AV{m4@fb67Z zy@`pLrHW4e!GKz8QhGt5mgA=d%X4rSqesj2Dqnnov+@w-vr`bY>F-OV6~&>et+XWg zlzKSGTPub2KM2~_lx3(hpD~vOHE(14S<`PF)~mv``e}_Z>$cIyPc5E3N)3it$-)D; zlA9;d6Z%Yan=c0vzKc^AmKs-i(MDIJ%%cO#v7_D!_atfqw#yV9WE?9 z+LdO0tDvxvp~2hPGRFD0C3Jm`^L4!l1N&le(0QZ3vkG>}YuYipcCp~r`Mhw8!6gCm zL)JILx@$j#23n0emzRyPuL^of+#xFBEt}a)NJM{cfYx#ZY#2-p(k?-$kpwZJaVxqa z3^n$rdpPSZCn}ot@&%4Ss(wC{RQvvWlOF?qkya+s9!Lz4jX&i6E&5Bq^dQjflcV8D z&j#4UR#hk!64fGAxG*t#=Jd{*;!5GMIwh2hHfGH-3Bvhb&Hg}td1|XpleAKyaqLjOZh%Kkkh&+m5r4RNS?bvF zs&hfdq@|)+z!l%M8XQR9u~W|%FbL7T$n+%)7JIGgUE>8N&S$w|DUk~LWYMcs_9uWN)3!rX9Jw$+iU3o97PkAIQT};WV=D$hR1D7o>~`6<2{_ zj?9aP*NcfR?VSs$p06mr$HRTIn**n1p~ORQG<}?7HGOlp&R(jR;6&&b&det6i>x^? z-=<22U97)EGb*CUvzWXAscWOBx1m75k405%^Ga(KzH@vrobpg#D!h_&&Z~fJus=TL z<)WmETuI{eSM+)j5h+j=`O&VL;(Q+f*IS{uGe1(|6fKwDro8wpx@5NDD!g9|84P^) zfzlYUaFk&57dcD7&<{w&HT&+(qW?j0;Y6};7b2vvx+40A;=Z_g(mBB>Bvh2ITc;(Z zOXEZmJ+aMvEtmzBg<@>N<2;3vb;Ml(YR?E&gs|fU-C^cKzjH`7=Gbl_4N`AX>*y8a zU5meKsE2Z~t42q}x}9~PbHkk}Oe-W>DK!IXWV9&LXILo_1MjiA+az=Uu8rT}uvwBv zUV(EAKRowOjx`+ngwXD>+CLGr;9H8c97?R)4k2mb=&_24fB%dDsnZK|v+f{eV_|LC z7(B0lUJ6u}0i04h=iE#J#@3NefSlF*#XWlHD5c;=v%XN1E0S`%F^fX z{%WJ5AN!=Rf3X6HFeTW&d--tB#aNE!Y;Gj+;Sn*QKD;NhTQfS^=Li#HU&LP2flmtA zp&o4+V%S%i!P~~`8^UvwXlhN zXHg&Z_z4CCsW1FJ^jbxOY~(36IJg;6>{8Bo#?AaYxhdQBpSMzpKUJIbz|?(8QFy>mJoY_3fdfRtIz_Dh z0+Z?YVC*<1Dffa%7$31!|2FegiSXI)RHO3o$9EbFWVF|aQp9D^3nWTT^3hl`)@nPX z5}tP6-|zGv{06sDlou^87b)&l(YO*#|KsfIL)jg~Xn{CI82rg!JHQ&7)m&TJv0X52 zN#0K4a5?WveR-U@x!wBim?fkvLKj+dJk#e<(AFvGL-hSXb&HC)+cWo)F;jm~Ej17&zm zda(fgOlewF`q_8pe~+boD+iG^jVR2^`UM}%PZ{w+S-AwFrKR=vUXDejM19Ytlgw2WAs9-o10sB-mSR6v(eM-Haw#H-P_g!iJ-N$)OKYdH|vB;hEvnsE}PMWyHsut zkGF6ppTp?C4VyFICX1c(PaJRhXulh{jQMUB#1i_0|8p0zYYoc>`ElrvKQ<}8=>#>x ze6tYoK@#XB2xQw3m_=kub7A6B;*Rpgd3Jn{^w`u|c|pI+PUN+6(xEmH1g$CqdZp2c z-!p2iy#htE8or-gWErk3Wn92W2BuK&}>Lz*&m7*7fJ={ zbNjZF)7gmx8@f}J8&##sKJ51KdFU~xC>4Aym+|P3#>~2ECHKI(!;AaArk9OhR8*wr zo^ZI^gIJP)b_-s# zpFAQW7zDahEuR%<-WAu$O^GCa6pg#{7A}mX1jkDFb{!Vfi@Yi~Kp@YnTp6t3L3*TY z2@XGS`l^Ac0wo{x@9S65eE4}WZ)@%EL{kD90o zf5cP<)4^x@af!M{6g?dskh3szazk=pS*8w5zAafiiQ81W+m2}fuj_mm5h%3H#y1(g zRJf&nWbZmMs_B<7WOqQI@=|gftJZdxbTcn-0A?Aie_H~HbVf#S(RENF6o}~wR>-L% zP(i5voexZ=ymdHaEkE~)(O8a(i{xnf!!K{Pq>B9_k4*HcKkzx<4B$9W`_rY&FSrGm zMosJ(mk+sFL#xv5kYQXV`j7HL_qyxxKJj#%E3QQ|n?AHkAhB5%uWk??6nam>B*^Lb z^>x!08H4Nz?EVx7&gxJPC*nn8wxx%GZbj-SBbZk9$nkJFKAMqoAx+Hi2TFrX|KOE@ zfWWxslqfHDQEf?=gtJ;f%~P4JCNYj}a+hxb#ttwLIRcyBw_m4=R9kw4Ttz!Vu?ee0 zIUOST;_Go3ZD4Q{-KYtbkRe_xa0awj&%e|BGRRnPPSV1Lth~x^bw5E=>gY1D!rbU!j?knjVvKnoSy@Z9Jdym9(tN+=-T5|)>vr~_ zPt+yy(gU7HJy}I`qi|nG%8=*ha&K=}c0_uoa+VM#Mmg$HFy;@LIhoY(IW7VLSd4Xl zW8j2|lL_O@N9GJ5KQHb$qRC*O99R@=vW~IlR^m3!9x*$l$>2E|-a_kS98IXQL=Gx7 zWga2GPZ@4(=0r6eZc4wl()XAT#66`TnQjYoTjAL#@~0gNe**~@JherVPb+Hw;+XwR zaLv^{N%AoN1v6KSkB1D>YaZhx{)Gs8cfV=DO~i6VO;Ux3(=5Pf^DNH6M8x=lFdA`{ z3pxckceGIh?=H!A<5E@eK2;on#^0NN>gt(SW+}7LRx!GPy5Evs8Pju9V3`bI?rkM3 zxq^Sx^v%~5ZjV?RGMav@#K5g5=XAF2@D#E>ap!CzA;ZfX{SVc2r9Lzl?29jvF;}A6 zs~+F}tZ!fZw!QKAi*l&o>lQO#_jmREK9VjeoT%BQf8&6{pKT(y#sJ;#=vn1)O2b*@ z7?J{}qgxEv+sOVbJgd2EL*;I9s9Dp-7OGFdmv3b{42$7*aQ;@|ZAxR>-;~T`tnmD0 zK=IXornrgtDr5NeJRsZmG))6$pxW@#09V5H&!faia+Qu}zGAmC)&A|5mPYyhD4A7W zHa(yW9YxNw7`5lE4o0l9I^i}Ak9lCw@?$@_*=_NCYLn)Ds!ufjD3ZgHFw42OkpWdC zk7}UieJ zFc{oE-}oiEt$GYBdem~ivzh?h5)fb2NU8t&0<2EM8{IHTvT0&JM9a9xK+xxmni>#_ zg2IP|H4*X%iike;iwiWoZlzt=+$C^?rg0`im6{mUA`H4^hTFmz<;nm!Xp}V%L|r6Pg=zyB^(qqGCM`Kf&o{5WgPeSU?b8DY+yb=exw1kb* z5YtAi^?ZY(Pg=*94jBGuqc8XtieFAsEG|*}WdFdK|8pXDZEI9DCZ#-u&#PX(q=3)b z*6C#2=6G$TaGq2-tz@dvGvIy}1y`LY${gi#B*KtX5*i5D0wNa2LW#dbz%fMPvM{T8 zn1*n4JkzK6ouJP9KJZ7{mB*EcogJd?uKH$;-cg}jQO#8oy3$P+g%u5AQDvK*Kc4>V z^Yg9j%JHrrcxjy3potX_AX)TPE(-+-ZncpGR7_4d4Fqs!hDD>-gweG#oTm z{CLaa+a3GdK?ayan=oS{CnvxS}8lABmS!vCkmD@DNVn3X67sk<{evG?FJ@K@+nyn{)O>iTqv=+p3C#~$j= zyK7wT$(PkWTb{atFjra{w-0b)_7^(}&+{+$SUJA;bil>Kv+5oMlx1Tz2eKW~|8$m? z=HW3>Wb_%i+24P5KNf57I%c_0A2Z3R_!IhX3mqbRP4FLP5=L%OIKEL}U)-5~+b7g#m zji+JVD#R68r+jgI_t(b~m8?xJOb%e7|>$%EW zfaJ}7V*}0;;n#5pusd?Q=jV!p$K)LDNjL4H36k=4Oj9C6u?jq-) zI~%PWAr$)7oHh62;^N;~4gGDffdpLwuXi4>g(LS&CiN)!p5wG%mD!ywn&-T>NdRO2 z(C$UKPO!_~RK8S<&4{_f`J&R+6AV(kBldirBXfDhBRj;2?gnW1MDC?t!u;-7Ua0Ka z?{<*;Q{2{kQb0ZgD{1Uq+1fpm?{!TM@Z*ExIx}A4W`6gJF`heMF`Cq#vEW1s^k2I# zTQdTxKr*0qoq&&32>c8+@Eaak0C!#I&3%VeSyom1%s#K1F5r%0-jAD8B~~Xo<)B#r zxn_QTzFGkB=Gj73$L)l4+pPnL&E>^oMuySx4`#CABm!=)t$&3x`vuecEl9Z6{JdFM z@=I$#3;^~1r41$z(@YRqSYVElBVo|CNk_6X7tn0k@$9DuTeZB~H$!gHEBCf@!E^)W zt^!QAClGg^P~ncT+xtOt+jp@8CGOrHnVbpo{re-~#0}a^Jo|zQ^;AG%n6;$n!v~%3 zL}|OG@ayE8W3{}5RCxK7OJ(nSMq^cV_P>F(&)IM(GMUrN;B4^;3Oavoii7%1xdJ%Q zp@tl(csqUWb_bU<5lyzaqbdc*#zVs z#Wz6Ty0Xwi<|fS-sRM#$fqhlghD6akG1GctE!Yl75U-Y+esCnp!EnTfMYpAZ)Gq^$ z*tY}1+_b0oZv`{XOAtV$5#`WEojBH4b=sP+_o#U7KRP+^*sAQUDi#N#fBaSmvkzrv zgA_#@J#Y9Vyi;SwF>^NjceWyMfACa|w27y;@%sX%D2&OU0#75rR@gjxD0v(3U|hIf z>lCqBjBSmZOu|2d%et8(i_v=KSknl^Ls&*x;4^FvjY1!EJtW2Km_B+fx>(LrmdoP! zOXCi}eLVF4EDN98FHWF^A~Y$L8!adH$H7A9_zpqVCV)zn+TDO5xQnUkTsAGW0oh-C z*-=`Y#r}w*YKt0*Rt}{+f2c6__YXRe7XQsb$KKA0tasI#gacW!49>Y-&1dqcaznBS zu+J6_DalZCssrlf|i-R>i-_F={gKYn*!cVSvze=l81Jes*>;GG*>$ zI~4MFd~s}FY@aXrTg zZhn7Vac3u?^ebL@`2yGQerTKqHJ8QSsx!d9-4Fhw^MCsOmaw$mU(onVBJpvv@sTEe zZFVf3MpEuc4Brkeb?vqg}$JyW+$k-j%AqMyMXeiIni#4(cT z_oUFD@8Ma-1}2v7ZkRIJWOXV7L6JU-s(wXeekb^ya!3>R14;RjP|@ShPUkcFdHv?@ zB%U`>`47%H!p59j5?cBOXJwW}?Iaw+EuU!Uf#z+>=Lq z!v75ZLNZT8v(tUs;*J^i59_ z{;RVrDz^Il&*e?Bg^{gmGKi0#IdUD`bpm;wdR|XlAmOK{%l}6o4^V8y1ECW8Vw^Rz zTt3^xtd$1pRJ1AO$aZzFLompriPK?LDpWNDfXkX&s$&gU0h$$H#0uhvOa{$3wj8w_ zn;3!71-R~oL7XwjuIF_-Cic6qdseWTZ`$?9zw^XM1u8m!LFo8Chs^2$#n2AoNyT>+ zFxLxFT5m%`Rx+;kd7*>gT@`44DTk!0c!XsKDx2@83|yjMnXr8!G@i4;{V9!AblJfT zYe8b54hKUx=hab66FBsOqyQD1%Ynd%_vNF;lnQJgMLHd>7d4i%w9(v<$&_El9L{EE zN4d}5%VJl9&mh75g;>Aa7iyHZvUETR2PA3Z1fXeZEYFpgLquc(Y*+!uwF5+tKvc*3 zq1p}-8hj^NuEb4C_)`h&eKl0sHF4`Xkf-nDGG*y@^8i&hW!vz&l-=74D=efM@UH`F zR2>ZxQqotaM$Xe>PE}>4C|ENCF`(b`#0wwTdy~Fq`oBD{y?E`SpM#tFV7|iXV2;UL z2M@NE+^3Iq`N;KdU&&9lVHvXLo4Z(fjdi;8kJ=!cFrb4kxsS z464E~1+1J&zWFk!RC%4$z?UZHn}(8+>a*Z90$+fO z;bPV6q{;L4Lgd8>B)$T@ zwmwZ$om^~Qxh)Pgk!|Tr(_Q^LK!v^@Y=ec6zNj@dDVmqJocXd_oKfxYWL1;bHo=NB)xG)B&4>@g$OHscwFi10gcR4Bq z4vqlN6s$V1)m&fK&sf4dBYa2{CQxu)2-AB6odSa=Ppc;&Rchqnq+z~bq<|iaigRbwb>JK2QZOA=hT75v+|Ls{Si#mTy z$X42)8`wK)vQs+j&rr&So#58L;JT@Mp`cO3!i9X^^^P{}fwKR1FI0*@GIoDBr$96t zJ*Djo@libwG)KiO-d=An9G^ppp>sNSlyHpY$Ed(_<|9J6QqoH(BG3wgdm5W{A`s+g z5Y-nRAR)X&h^I0nT;+_W{VDU7fFf;@MwDyKAR`&&bf!XWR2zo!!g!hpmU1SY{CDsY zdxa()+F{K{iN?+sB&iEW~*L@L8wQ2B}vA$_MnOvAoD66*AQ ze`shZwl*KxepVd+Z`9?rD3s$cvvt#2Z7qCeJmEnReH-z%OxjD&E+YY53R0$?47^6Y zI<=7K-d3A%WB=W^tVd}Z;Zrhd51c<>zA8O6P=r`$NWm7Hr%$!kTjibt2*r=?;a57S<4xjav3v*62`RZ*+&$UhY03s zCYw7(HP_P&Nr&CZ3p!yian=)5Rppn&b`p%T7%4P(^rRd9&hS5mn-z5N6JKW}xs~d0 z-JRTS7<`mSKx8USTqW;AQ;#}OL3t~wgD*g`)6DY_Ns?)iRe8=wNERE`|Dpfd*xwA# z-)!Jk#ag$s+4xt!u81MW;Q^Aq2Am}|BVnw;z+1D{b!ZW;us|-`M%c|}fv~a`?XNch zBp4PU5jYL@^vZZv<|C}i`)6|h`6M75SWHN4JJFwt`$RCGJ@n!C+d zZq>zYde~_9yO$`y(#)*;+n*P=R^cx-6${5JC-FP&r;hfAJ9>OOw)YX0-!Ph;Xs{NlJmt3|KCHfOI^rY5M;<(dyth90Nq>}aQvL?> z=T;~BT7j49k$xVgcDAM+Z7@2>x+7yRc!mc*V|SW;GuBOy^XE%W8;@7QR^zykA1PLo zT~bn7oyJv!WInz>)JF?Z?B=aDh~*FY`P!B5cPKkrES^~+M%kB~X6$K0l!+$O%5G8V zKg`4cK2vH z4Ant5*T-%A7AXdi(x!*hfL}Ah=@%l5CraAMv0f}w4h|UA*Jq{^vI|<-RA*O~#Y3XI z#g@fnUj~Lg!IO#j+@5tnk)Nfc3okzT5byKt2Th#~RZWxeXT6H2iAhP>L`0ikK*&53 z%=zzkz(xJM?Dvq*Ym0ldGCnqzFtO|LH-v#!YRa;qMBQqSb?Y2u!olp$AF6o&zSxC`Ez*lH~ZQ;nTMPiVj)81 z)frq>y6J7s0!}5Kc}vEuzjYNpL0%ZK3(I8jvtAHKy8G`We`+TpE84nO$o_1tHx9(_ z&ZwrV3z#gxH{`tMsgt*ShFL^#SBoS1EX`#mQz-P`OoUE-#HX0}lp=6Tv%1|;6c!%T zrdz6$nJ%vAb#7DC$nDb2vz(1T!1~?>eVDtJ)cJ41sogXCbDg463tR{VhX%{p)d&aV z7d(A5dyq~DwwyS>hyjBKO3d(&_DJA`+_yvzVS+tx2GENlt9450bm*W^^yw2T4Yb5GK* ziJDfyiEVu5Gep1BhePWVWyWOQ8pq_<1?g9^KLx8l*|@m+G&=72fnhmbBu|H4g%jAb`8u-kHb zi+c*?Qh-=&eXi`QMcM0y9yr7SAqv(B9uG$i(4z(wkUUMsY=envwKl!tj|0!CpZ!m4G9ut3qcnE(6~*)&CcxCrqP1ibfcLW)YExiWUOt06x0m{{kt~+ z0D?>&VAFYJvYt0Zislc_ygF{YUbEKcU4ZlVHDnDqI9?sUz`f;uzJ(0BM_&yo0D&5? zvWjK_s|>Jmf5Zfl`%$Qx)QRCGejlhIYrqOmjs%kpdiDU9_1aJ64n!u=kX^7)?|6CW zh~4!7_UQD3x@DU;Auu3;wd@1JPot`^T@PRrpS0!%3@gGZyO5BL2|v7+2m$J#2|GZ3 zAkfINPFoT|K5!rbh!4P76OfA zsu6$fEryv;1wLXD$PDXMm=7~eyXQ|?L|GPUm!&^o6OM}gFi4FB(pP8{X>vbTS0LlY zuC?PNLJ&=w*d>gX1b-J44;$Lxgpv($B_|M!1dfFa=M0%mm(L9_aW28_BUJxhJq= zf)xeWJ=9VPxSrU8+_*D@y5fExTq%ytBqt|UhaE|0LjhtT*wEsihD97S$6wh(Rbcg> zq3#AMg93%#c2GKTPIFyaX9hme7Y;^8qv9JN=V%D9U=RV;A8T$of>1D}g6&s`SeL&z zQFMPQQ#hLNf!%-uIHMrD0enZ6?!y3`0ruG%2mk=oyYVNZl*DJRX~kYYIe}%5VHlPB zs4Xhj#EI7|D@n)C)@_T{jzANM=(ZJ&L+R`Q%3lzysI^6T{ zQDoZM+C;|rK%Dt14$cIL1>k2kKXtQiZKvp)fe{c~6eka6zK&oS0CEGgKxo2>ZB1jN zG<{MYm?RIb?1{gFg<u7$=bi9DwxSSd;-eM;{D(fcifLWpi0TX9526>|Mf_tTD4_ z{o12t7hRC;3uL3KEM zFt|2YROOnmz7w9SdC45`^Ng~KQNEI0wJaj&hwUg7)=OExzs|MUnfo}5Z6yy2O#lWA zMFy(!2z3c`2;Zjj=`aie(qOl5gGdXvK-gybd3HUY9e2x-!e=<~5NLgZP&OO`bYvqB zp>X7{WC`oK-ce&>RCgnib;#}iww8!cC#45Ix*+dGHJD6?ZZZlbLZ!w&bbm81y}*(A zvc(H+I%rOpNK^xLp+xZ=29M(;IkWJiwN`*>i+6qS!9tyaGQ*;^(l9?(mU_KHwoX)z z5fvMzXl&g?LEG|6WEIU37?{}TQ#4tOUz3z3dFk>>W-H}Vm{+Ir+ba?-|a}wS_WIWWPVk>HAi>})6x~6VLf8)Zw<<0 zx6zX()+_P4Q#UFB)JW;U*?L6O9ecz+>GiVThaWC|Vxrhdu29)spqB0lkWK?tII7kl z1ntdon>to$wB8qrd1nFh-}M_}7K<_pZA38G%eUmgE+Lg0Rt>&`+8=3c?22Df#@vm? zCAdL^IGB=>b<}m|cKn=?4C>Mo2ewj9ET;8Xmnyw=l2om+h*U@yfhpG0d*8+IWR~Kv zgzid(GiN>mCRH!sTE|INH=yU`DGSo#$?sMRCWrF`+Y(vQ& z@x5#wWV+R2KYPOiDKH5F^AO*#%Ck!lg9u5}#!$M%8}>8|{|#(JOlFu(H5ZINFxg0z z!{)W#e2V;;6UF*RLcrcT3|aZ_ue3vxsN5;1E}83`JYp9b>4K;cks^Z|<>ladYgzUuCs=NcX=lbJ7|UbRT`azAA13@jqFbBXD<&w~iwo`k8w96#j22 zv~#b~H=*yg!8tI11NVC%Z5jD{WA&PTR(?aE2$S)A7C zA(5|wc@M%16WLDS4`;zbcNTdK|2B>xkCBGI-+JE-P|4rPZgI?}iGMb0Vl=TC7L|*; zaI)IJC03bDYhuhGrN-K4?W5CaglU{CQHB^T3%{TwQplmH;y0*ITEI zAa@q?m+v+&Eq(9Zmyf?{rygmA$w^?Gr1q<&6)*j6 z4>CPswWA*wr+rU3LD3FKVdR$xx`98Y$2hl;kByh9I?kPn)-N)@0da?LV7Uioq{T&2 z)=i$fAWjqQ2$c64!a1cTHD7JNNeOuhznmpafsVsS zwEy>SyiVuguiu}M#j*T(yd!(7+9Lriqn)DUd^hd7xXgWAaEx6@CA*^f=tt^y zYrq+;M~sdq+Dm@^mc<{t?l*sls^SYxCf(hF$XvczcDM9)bq^*`bxo|_3oBf`=uENZ z(!7Lcy3)yfYUs=8`)u?@lPM=m{Q??y_v&ZxyDXo>)ve<{*dYalKlSKME2LRvOhp8* zFhA+_jj6#VRCU;h)5Tz$SMy|zoyac^eMJ{1+;&q}H=1fV+|E8lxEBc7x{Hc#EF30Q zX~3$!qvv4x7eP?f6}xmxjB-i@+y(!fW2C_6?!^^yh;qz^Lz-U4e{mZ9&eHX7bKaHr z$z03D)i1+`A%7p|`Y%mGW_*@zLGLXJh9}QCRv&`9rwm>0LdzV;vBK%D?+`)s&#(Oq zLecrn-a9mkzf_tmX#hQLfn=q}45idf!pU3_l`4~jh0m0OfU}R2&xydH(*CUG0h*;a z#4jj7*ZNcpg347uyhw`+aLYmfe>w(~#Xvm_))UhQ-T)0&*0>x2Y0J#s1xso)ADNfv z6vW>@t4t%${oOl|p=jadl?ti~fG-@qUomGl1V`K~&`Io`LtFOw>l%1M9%z6cId;Qe z#Swq~aAdwd7CcZ)z;qtlIQKD@U)1CG^;2W6NsWSb;0NL`#lGP2fbK;7y$nO5t{~YK;2W%?b-+`-&oBvBMkx^WpiBO+*YHd9J1s43$In{r^}>gSt3 zyZ`~M&nNZlr6Id-f&4a)BBUOjNIJE32co<5(@w^oT z5@O$Ezc7nHr(_@U0)W{hR|2Bqua+-Lf*3INqA3H?&KoyZWM{uOE3~V+SM{24F)FdJ zODAuG`NB-uQ2vDPBU8_Cnlj!wh2nL1&NdKcXuQnJ0qPK_r55uUKu~b{nE`ds8WuOy zk+KLNQAOj|Y6dI3qXZ+BlSbIBQ%GKDs)}CJ2Wr7zIH6jalUXRPsbibmd33%@{6O{V zC`n);!hfl`|19~s>6AdEPO3h6$}-uneoy7PWMSHpoCq_l&S4R*?5|{qPR)(gkMG38 zV$2krrp&O;`6L@Xz5Aex?c(JD^98#%OR&mnb|e1rYO>>6Ji?qMEwyjdOXb`?BW8p` zrPAst!(?HYHy#%*{W#w2{KdrufN79e5RANx`cC9(Bi|{eS#A5&7ea;PnA=E*xQZ$T z)(%WS$=lp)eL`Sh6}j|f#hKg?xZJ=Obt-gYZ!5G%p`SpxpD&oNz_0-rmAKDuYfd&s z@G~b$>$H+234@t}pVq2*4{R-(1E`XzbKk`iuiqLb{;GwfwsZs zn&P+$Gz`ajc(;`ts(Tbu3oH{v0>(YR| zHp#1#9>JXZGQEEIgAY3<5hTk3mHMeAUbt`})jVquj~W~SrR`zI$o$lgu{}kqAr?7x zyfoAf84W%YTJWSp3s-n86sE@Y!k5pmXoA$ zdg2F%N-D0IEctd2F*ym?H3(k1NTQOJ(A|8+9ZNKi$Df8eMl$iF71VJezG7haF7WE) zYO7Ofk6J8qY_Gd1(#^`focxDIPr~=SJQ*_7zzaoMj%{o$Zskuka&;$GQVVJfxo7>! z7;~^viyf~57lJ^k<`I(UZTY=BxIX+DfHQBBpehiAD$`+E#k-^D9HDUaBA|S`6pLjV zGq7l;Ip#*4Hba}qX|*Q&IBw;h-N95@suU;Z#bNf{@-IRBVy${WVq+FVC;9u)K5jD$ zBzhHt5$C=E5ym5W!n9xt>R%*`6X@Cd=|XmWb14Xn$q3~e8L`M12-B~;xZBJthoD2} z7tR*M)hhH2C0HTmc&^`%MFr?Rktq6Ax7OgkDCQ{A?kkqvk~EN{ABQNs`mAwj%1n7H zmzyQ7IRv>`(NH_20FNsF+J%v!>$o}YNP1bz{&bLmVKzibPv>nx$?XBFFRA@L5>VMZ zKX>Rx@!;tg#WMBIW~R)jmq15AxgD!!sl4*Na$>oH`!dOB=E?gR86@aUTOU- z$W=JWKJ}qCWgWMyN0?GLb(|(c?$Qv9pU-zXs&~5jr;YxEZ05fQ9(4WgjPtsO#k-YD z)KrpRvhN3*i#7)Oz8;IJ{V}|*y|kjtDf=x>)1!YgsU91~opV&(?T5X|+PST^2kVrfT6_{Y}_9;oEig8D84XRasVc;vYxSEN}+ zs&5i=ZI2dEQgN{}JJyNj-6Uc}t|R95h9i?-6a-V)surlHKrsLEL4A8WD1nWlibkD}gPMQ-{G8d^!66H%L&=Ne_+3sN3pff(PQIRsLswVT9 z_qS>AKMx`z8$q9YEETq+f4h;F)f1!n!v`d!RMhQ=>2MqIO+TCpQ&|?TcexVP_$(-gU43J_rVBmNy(Xa5^F) zQ!}C9kI{x7&iNy5mPN5$+*(`YRu6cv0+9$teY66JSH5xmDL8L0HdrH|`7Fj`9zPL* zc6+;}q4gf_P=nPL@at851tv{kDJvoB9f!$uk%8(uG4^g;{_@^*Ip^_h2`EH(<0!gR zVnCAQtq^LSsot$ow*33Db>i#9Gt5*{`!l?*qLFe^)+^gCN^D*ViUbmD?DtS|f%~|s z3F8#^#UD$BGwDNATZ+Cqv8ZCX)y{6~3KGALT!}eLT3!EA#CQ;=S8pt=?wy?GNvs{O z8>5Ec3ZxEFN!L7`u+H;#03B!nF)Ig7AWX%IL(B)1$By;(BIY040 zx-QrOEH3YI;VPV+vQ;KF!NCd6H3~KJ>uYAwdAA!(0NS|y{h@zyMd9F};k%vV18_yS ztF_k|Mtl*l%u~ZgYQJ2kwEG-BKG%TJ*XxWWe{p#^hGg3B(Dm@AF+giM&cst5$9GVG zRUSh^K?q$y|{K;X1SqV}{zI3G2=)5M{~ zdertr?GLs~aA_5YK8zMFhNCF2}m_iFIApmIeXMup>FpyLVdM>98K#)Jy zscMP#)o@QYN*`KC??PX`CNl{U17hdnBm4YZb?t33xq~Su2)O}5M({8Pfb}r&&_C3C z_~*|ToZYuP8o8pq7lDrwN1zM>>GzfZlYyFG&?^Kqjv(GBr?Ua z(o!bkBrx&=vFmdT)&Ju2C2krd)~6nBr>;OuyFiNe<68{AN()A$EjxXbyMv4#pT9=2 z!wJmvVIwHCL%4>hICyX?0BcG+I3e8tb!1JzCL16}@6Svh zys-3|o06f8(=4&ZP>U#=xjM%}fzurSZK2EejFdwI0h zi%e}%t8Zus8d8&#OVm@8=x2ei2XNp3^*rV?0c}NK;0lx{GWolfqtZyCE>huOK0{h8Y0lfPo|3{id4h&IX>yeX_QzshsOwI8v zi7(KfhV(+^i_Cl6z;YD2P>m}X&#fw1jVGC?-g7J_gIlV@}`r0iAyWll*uUy=3*W2{+hzRTDooQCs!DixF}9JDwbM zkjn(`vCI>wP!Wm3X+R8{&7H75&6u4{gvK-AkneyTEkIoky;V2SNxpnZ$_sWj=D2KW zV}MEqtY@p+Ix0A_#YO!WVt$sn=wF4C+l+wB#l|KAY&7;wDyk5 zHV@o(rX&U#!pK$BsP8@`#CT=UtBmYdD{09jNq~=7f9z?`H~J-sd8mXz@^d6nA*G~-Ipg%FnJ+03$3Ac&5RQq2M{7P&n#2z;)J5qdk09D9j{7Ysm??WdOE7^XoY}18uBBY` znjrtJa5apJy0NiC_4QDtZ9#J}mIk6G191ZKm@uk22%7q>JZo^`YT*NHtMBX#F(6>B(@~=yZ8+Xyh5EX;-53Kke(P;|Z!y|Lj~M1V-tVE!O{a-6>Xwql zrA>;!x)9XsX2GSfAClsp$RzsuM;=_#GQN+erxlZ)nNw2pre?%1#am=hLyk{J>s)biz%C08#j03SS4w2YumnLZSi}|w8LcT7OHBaN>(2w-g z@i^1I<}E+x-^;16SR1!oGN&d5$EWlNjXUq3nm>zK$WNi;$6HSLJVXjLBCJcmV4i@U z;yqB`83@ssugODs<{6HRDSSc?TU)u)RS|qkU*JZmz`62#tBJW|2dV2*h7E=sEuF_D zx6l(+7rwFQ7qireMehzcD6oh|9oAN=#jCQvo>Ycfo>(EVlBYGtnv{(hFEP{|tPCt^ zcrh|Vr}%P-mO~+)w0-F*3n9s{5)vLJry);Pp)V)f$rjj3+z zPTr;0NI#ddKJ`=h2_fF_{EQ{-($9IfI5OP$O$GID;@SULmo_Lzo-lfZ*;YnbWe*ak zM+;A|anHPC%G@5%AY)s_A?3Gv)Mi+-yYPD3!WI+w=?OaL;M0VfktF{3?i#_wl4C#E4wj|IJO8 zB$?(wk5z*zSjs23w2+oEu<%-xI8EpSORY8pFGUIRsqQAtDl)@8$JRCVlF86QoJR|p zS;Z**mD_WPBNep2VD@CiNFVnSYv`tNH=6PzxoJ?g@4ydG_8tBA>P2AH6(l9d_d*1t zlIlVH{MaDt0%xp0DF5{f%sZ=M6i4FCyoJ!++qoO!T?qqaM?+9WrO4^lRdqnwaE3xQ z4 zdFU91SfZT-eqvO)cyju$r&8JDc9}n`bVX=uX1%?bmxaT`XruFDl^%;QWBhYvjl|Y{ zzsNWH*UCDW5zoU;pu4EWymWnf&%PM2xLsY1rMPb^a!-XlWssJzgm~p__0o`X7Hf@7 zm$zB+CQkH?$4(8#aKxxY4>G7RBKO~mPxKpqQJ|Ym#R_tfY{3u?{hY>8aJOpd56Kzw z#GG28t)j3#rTJt;Pp#6jYR&R$>S~Dg)E?1CSgll(R%hJJ75(9alfxk)OLS3;8vRv4 zx8#GboOSWESXl74U#%@8we!-%$c^h<|77~a%X1YNhjqUCZt3Rg?Z)e*ibAImED1uqVTRdEt!idiE z&yS{ROT5K-#oQkfx4X-_VnQ6uXCX+Ixe$VS-T5LS;<>LnNjQM3Gxp8nCTbwk@@NfV z-fj2H5A4^;Ha`N)=DgZ9F%@*q3)mCD#}$8lbPT5|KbiOPy}jfHF*Cf6KhWDNRT;a9 zA1cLn=s|IQfg@@D;@$H(m#705N5|j3&yg*0Q6YCEB*=P9cegMGr>d8X9YehE`~-oy zfG_L48)sNW<@Z)d`zf!sQ^hiD=@jx`8`!zh@TL~kbIJMAOiB9eIyOU}Gn3d;DTvq- z{w^jcCK!lL<-s{`?0eR$MWcKrixW4H#_NPDAy~~&jq5uzJidZ zq!t2xm@cavpfnd9GpU_$Q7EXW=-AcDoN{BbVO$Z}sKU=(KRh#ASXp7fk^!EV4A9ng zdAWd)-8ctAm_h&qaQ@jbGLa?Vdpt-yV{mHNeP;N`UQ1jTNfZKU!huV0)+31td~x|H z7Jhz9wNLJDwlJv$E@+DWKlk%xp{#q;xxLcE&1jLCABaG~^z_CN1 zoB$yjAXOezTm@@1EN+030)&p^A@Yu!zwMPZ3g6N|v*%-4C|G)f)O|qOg7gGx%y+>D z4yNnitvq_TBvDN8kK&(MBtly!8fmFtrraA+{J$1}T#t98kzVP;s&~(dwOxJhb8WP- zv9a(cs?`p>K}xyaotTMOc;{Irv3O|j{2K={aV(65(c#m+lL zeNRv#5#*72>JAV35fEVclV5vewCBBZr!2bPqhrxq)x!`dG}=*P8>$vBSTdWs8o>eBD=p7xn%9ZSJK8wZuxhnBw^Ojzj(idN-X-4PT>jT`5{0P)jr?`8esKFOsJmQ4Q8al!IXJR4HPk`mEP02~btvQ<~99;W1nNgm;m3ugM|^V#_P7y%HbSTJN<(rk}>7 zKy;&*635RbWFbt==EbJ(7j_9aus~Znc-4aVWW-G=YDnPt;PNGG>^JkNCB(E4;s!N^ zOEykhFv+CTp+GHEp6mY#LVky2E<7Wgl!BopD5%vVnzG&NX!gTW2==a^{^2sw5-t9T zE1o?QlHP85iK++@iJbo7z#(^}Rs{DBYvl5P6t}bNdao?Ie#@l~#ODn)r6#u^+c$Fp z3L?fd%>pl6rxIJuB{)Wo9wR#<7E3<|@dbqguW>%1mcO#(tEglLwQSRG`~`Ekqk$^8 zqnNse2vq&&)**g6KWI20l?M8(id!affgmv5JLX z9ewF`39V#C){vWyV6_d@R-HW|9s1WX>ua5a8d7k*sej)$3vy*qh2L_GwZfx5$^rVf ziwj?s%rbIt@K?F7^oK~D9&!-8hmyk-m2SfjO2pZB>jc`rGC;~>DQ8gMS)g%G&v>~> z$L-lRlDj0cMM$;@3jZ;Mcus~FS!@)s3A9jUw z{?6>;H7UW6Ho=0cVgT$lTdWn=j4Q0E>WsxnWM+pc;8x+)qMclP%*S_>dkx3(dpJYji*tlX%~lmj{}}CrjLs6%O@vTzo>ZW@o@~(R(0q?6Miou9aZs8 z^p)hVg&}EL3CLe{_$AlaWFdL;FAF@)Xw-GZ+__u`BjqeN!j|RVd`}*mq`H1;v56n? zZe?bKa-;TN3cvG>3adFVx(3a>FKzo~M|??p$ErJF+u_YDlzItB{~_(>zJ{iclX~HDx$Dis8%H zzq%Ok3w!q?3Xa5-+t3;xvgd~Yad-=NQ!LXd_H0b(0Gs@q!_|$eZBDn{Sq2cv4Hmdo z9v)x!A?JR9r(8|ja-lT9Cg$0`l3q@uQlV>M|4F&YK#nECh@U(uBynK%Iz*f-uV_oW z-QQ49J=~;5Bbcjrb&s3G(v4zbUpk|vm;T*D*MIb0OsGqRm;Fu}FLoH)@fIhMmfy)o>feM+XQK-iJe#};0!f;{^q zLUk=^^h)pr3Jo-7R!G!+r{IHlv2L_qlk(yeY^2%FM&aKV${n^2^JqJP!8X+l;%Ejk zIqGLAtl4f;r`KbqHZ~r4{ytP|VWg;(dCm?!)Fj-05}2*(2|fu?paaz>YJ9@rB%M#sg0czN`Vc!%?kDr9ry~GG@5vHqW7-fh{x|~XMECRCSV~_NwQzM zH7b5V0N)QQFV$srySw%Rqzx#zc@!Xm6>(id!x%^s4e08*y`@;a91?ik>6({cl?7jS zgC~4$ukEl*gA{I@ffVlHvv4xXu~%Q>Q#j28De&yk`+F+e;OBf*Vvz|r#llwj%#&mB zISYHU=nqFDTXs_?0uQ+KyxNJb|eFvJE3=H4=0CrK1xd-lgB`;E^o7$0y8O(7#Kf*c@v8 zyc}_}wI`6zpE(z4dF@5WSEkvO*i$k?g209BJOFU$<^}3G zuovdzNqEFj!jwPXtv_@A(JED-$+b_FR9a(mpPQM<6Dy(2(l5x^y93&_CMV;~xnYwa zA_)!_*~%;+KNFXmNi6U>1%Nu?oOtu626}pCd}PPV-FM626(3)%&1h?o*c1#;Ki40l zH!mLp>j8tg_~XZh%fq=##dmw4n*{MzV_=26t`x$vZ!v>f%u}DzZMy_E;F5K#w-c)y zVD%0pi-1lu|5Gm|l*VbgbvAFho%e8+2Zstb8B8FwG|r(SfRIN`R*RVB)m5gf32k;F zur{RzYuYd1X2}`yGByb~mJ7Q6ng_O~$ANhu|Mc6plo5ff2@qN@%b&IR7~VArdQ%_u zv>+%I5K^Xh-%a)L>p^zDhvR$Va2i12f|Kyr+643?H>(dpqQ6wuZ@LhP74Md`Lx8zw z_V<$NnBn@eeH5)8m1x-VzqB^Dq z4m#>nr>e_~J&J8_faITxBt1V4fuVk}QfgPF3+9V?DLYxW*jcPLyW5ylnBu@(Qplvb z$CrvcJV5QLTSxWo^J@X7;uD~OUE7X!RrfRLHqM|DVAc1JjU9WUZUi8f0= zGxJ^De`QFH#laxeVU$j(E8*WdIl#Dp69(rg&%Z)tO?E}4{=ksstl->{SJs+`lmaf4 zRJOu7C=p2oNXKvtT}xgG5EBK4y=M(Y+Mp0mq0OlD>n^bO%K_}U5fDH%@0Ia*YukY< z3WU_vrrq)Df`Btdn>xip0E_@g{80h)Fi?9xuI^m|_YA?6dQ1!kUSTjcJXTAP3pl%O zjgtZcVb@{Su{-GS;)=k;Pal7b2>^Z95J2W{Zdw671dy6qt9HISrUlJffO-I==X>-> zHugNgwF4gXwxQOrdD&^57|cn)Y7FAxkY^S=z_TY;)EATq5bt;j@9*y?s+WQN10+b} zI=32~t~Qw}0Kfb(rcW@t?*>xwq;J~?#Klie6r z3sE%7qEEy}dzsqV`jI*_r%d>u1XrBk)L0ve51J$p2eO~zT_z|Cyl9kHpYIyP*j(X?+M@tZc)zCk9;+yWm%P9wlad0o(r zJc7j4Jf(2WqdXEC=0Q#pBt7?hLAy&a^Z;!W`8Cle$}jk`#yqLZdn5{$8}xF1Hgbz5MM7 zS>joGp#2fOu3O`}0m_wf#nDy@-PYu8czauqhz*e>WJ-FcdmLEM_YR*oXxH{so8P;C z;SilSV~)gCpWds2j>>MdH1<1N&nqY+2`p8I{)}Ng?6bvDI=K>?FYO{pH+5+ja%jO`&XB-+^Ez0z%mrex2`#NY!gTFW{lE`aBw^u9R zUWS@OCsf0e3L6nTF)K9;L&ig-pizh(}!Hv42JlsZb(zV+`g+`A5?} zQ{ErOF4S0Z-q5Q`k|Sm8jSOS|bfft*^}vlb?-Ns3|8-o{A^c{%fe{lHyi-^6qz9IA zxxw#svKYRk{=rgF7|%ihc2Y(YU*xvZTJuHAxRrY^=LDI;Y9vIZWGMLQ^h^{(9KI%L zU93IdJ>u~tu1wtTpiHbnBD3*vM7#$_`NGy1LDr-e3K{l6D$98MNh>Hmehh^(>s{!%%>S;8ZF|Ch_Mgx+2Zfx0>9N=7q8zf z_%7gVD@99FV(1Mv3kjea2**P#L}z|BjDZBft6w+|sow2_SEt*LyC=|i`pZ?Z?CY<~ zR;BLM7zm4ZZnf4oU}#{-njmfFi82N*g+9%%d*^m7ezB;TDcf9R_VRR!ZJ3Quml%!+ zyQn5An$AZE^YupY!^I8SPz*c*epsH(pmutPH)fV-<mdY+2djJ(e~A^pEnWNB5$AYg=porEj{J4CP>{S z_>~_+yfthU-RhjFY#&bHd-6%OIk8_&WXDlbV8wc;?5N>JaM4)QCX(t)s4z7;4LX4x zr@|zgHb8c*Jv zq2X(>|Nd8zITXsY8E!rwX@hnSk#@Sw8@ON*UDxgJ7^7CcDbFTZ8dHldw;ZawHO3b4 zRt*kgg(Uce`LqYd9Yx!?s2x+-`i7=?=65Ew*Rn^|qHrXq#-0m0om=P$l1cCXM7!bqb6k1q}^>?{0Jo$0~lgRk08kY)eB zY#%!RGqCw4Jwlh&Rx^FLo(Fkv&Xo$rT=|hoM8KkNB`jiwAeD?_v~eR2%q{X9v)1Fn zAO;+8g8&BNqR8KC^@xCPJPJdLR}VcvYL^LUR|FzFAheW38Mxl-zIWg-=}>H0epRUp z_KzR{Yh4g5o9&x2%}J z;{|Z*_4OBX83+C>R0K$fIWX2BCW5>oP$3W6qU6K>0i@l35eTeUYEVD$PjA@bOgbGq zd?e=gFA^B`K;V%eMP@U=NuaPDkn(}}m*;_b09G!U^cW*?k%6yIO+B`{Qezgr{rnm* zwLo6$$nT)n=g6ha2m`lQLsOGn(M-=pAb{ig<&Qh;L!dlX2KXG=)lg55i&~*B&9Bqh z@v|N~Pz!);1W?Rb-`S}K1_7|ZRW7kWKmx_QqLh!i+5QL|ppOKeqep*~nPLtV1w}0| z?Q{dz;4T-1d`bmU2d;jPdKsAgA>dfRbcTn52nO)V>S{6!;kK^Y`?H%saGS?w8#gQ# zYgdr$3bnNWj1D$Ez!`=iKXn>Ao~bw#6^GHI3oS%iz&9(0PJ*cgC@UGK463XhwR;o| z9IUOaK`$+j*H`Bj@LvY5C1@Z5Xo?y=_Vy>J1Z7TD2LE9osuq#qH9)U8IAD4J%r?-r z0#F772;eK=*MOM~*v*o}K#&($djrXa9B5?#M?r!G7X0$bCjd86qXRGq-eukWxl-M!<#w<_9Sq@9y?Y&9*`_Dfz)?rXL$N>N$HP~UVX8+BX!1)RnQme zdw;dvug@L|b-{rtP5HAFD*P@`idmTNNSdktXy`OlOH(5gp3 zKtQ4C>jf6X*g>!$m2-0lR;@ZzF-swO$GRA;8ZM1WBb-k1{ymX+;wS_qP#; zjicsu=CGACZTmA4Y5{tlzT9oMckhP5rvvbsu7NQUT$}&2*c8}{VBrB&63QiyS+WvW zBO1for=@`)0)?+6jz1)D6-F2(pl@OVLFxjQ+>n1*jB12Avy^>h6Y?7MoFT zvW1J7f4-`CQOfreH%=A>jEL<1zu4*o^feQn?CPH6K*>^a78jZe$guL9!}J%}g%TG~3OAyrO6CHj+w}AF&oXFNilT6};+0nPf7_RQ&Lb`=sV1r9Cx?P*A-`j;MCrO(T$$R0a8kN|#1_ zLyv;na_-K#TaHRv%+IE%ag83Q64=L)JLS(eDL8+D*5iWhqI6@R_lXSPU$mp)E%9y=N4sp*|?I_}*=nb^9(E_DyG8=_T7j zo#2Z25r|SGxUJ&mYgyMRO@**l!G>ucQm7v?PARaqiYph ziu$w9Z(XmO;q8^Tn(h_P;38zaIr%%Foi^hm|5Nau;!n9MDgux53R5X93?ATF9~hwR z7dYzwFYCwp0AcK2;}!v{FO3wb;h%4AbUk%*f*h@GM@kj8&VS2$5CV$EVa;{hRG>~% zb-W<)t_$5c+CBNakx&coV7BJs^{rV!V}V z9sNmt%c5d1VbjX_rg3)!t_Fcb);13v(%2H>g}XtG>(hjw(OZb#S1?l2$nEKq&P;^# z=c^P-VzLlTPfEDE%o{D(Xd*Xf>=x;Hs1(h5net?lzm@2=c04~%?o5ETKH=1e?;!E+ z+spy^KESFTW}%rpC|G2;Q&??WIuhMYy--C>6cvR8c#B&5{jzV zzoi_y_{B1nSrqR(V=8rhVfuE<=p5NGPjq#lwD>?gBSY-QtYiq0kSeI!7~5*A%bKGU zFEQ=bsm2^8)QS&7y%dapY70OB@Y{g$C_r~SCiOHlG<>u70-vC66io3Gx=Lj_im?LG zOmc1_^IkxWZv&)~?d?GEr`Tzt^1A}@-woXd$pXa?^RBq}nJj z*P;tbCHPNRJhy0?bg;bU$R9iQ#PS=KFEO@oZTDYoww}o#McjYB_hCGnw0v3cANOlw z=L!z3I&@n$#6s->xd8FbO~58McPjYdMS<7mFi+=9)hdm)pG+-c`QN>@Lb>grv}1fv z%2XNiO3Gt4p8C$7(X>g2d$Lh?O3+d@9>ve?cm|Ju{bF%GKgEr1oSj|xCU@&Pb#J4C z;NtM-*2rBu%CE$sJ_^InhPqE*V>VIjrVNpLxm}~>3%5$4b^E9)pS7Of^02&S%6U4x z5!lxY-3p3WIfFC$M6%CS<7R?v5L&3pm1zKNVTqsyFN>El8ZL=g_b|2O^R zy|xuanG8wk5%Ll81oQNzR3ugSr4(+%kV7A}U!*@D8Pbv&!u4Gc1@HWEzmAD2-wZJH z7wQ(*HUrZy(9weBp{MYKt6(Gqs`cZcFDwRtky+;!V1k#0a?G2dTCQ;5%*Z?7MSw-) zItxL2yNEm?2YMd{mAm`?tS~Jncxo{YtvEKj8b|Ezk^yU1T%6jMmH6Hy(Xohy^;qa3 zP=Fc$qfjwsEUFRjD%OYNs1-OV#7W}cq0&tH^=|AQ_DnyHy6Ecb=V}tl3gf3_anX5S zNUo9nio|0HLUi*Ah-Js2(tpXmki14AWnE7IK--q$86svQvCf0SUc`<$pX7~frM38s zPVTV`q_PQ#~Ys=qnDR)}AbvE+t0T zueR-6I&>t!&rJfP2Xxv|3ef9zz(;50)7t**5R^kU_`ocLY{|8ve^R0sRMH z-7moIY~TQ5xE{5L?{-Vl9%YCaSTWx~+&j-?Gr+N+1{rl6psnN)OAzM=rg#Caz393S0}-PbK~I^n@G#`E?&KvIkUD0BlhI&Oa(V;Bxzvco=m?7GCG?BQ z2}sw`|E6ykTX9Gd$<2r=ak-T+TIH)*pfAl^lRbcDdKA>TLXz?2St(+VNT`2>}56Xu#jbh|~!p-W6=`Dw!-9M?*sc zc@4;{l-LnKa7x~jRC^50It0koe%#-S16!J_tJ$A72#Vkp7eeQjYMqpFXM>CX(rcLW zCV$BQj0jcqZ8d_)6H$iUwY8prmbyCgKNZ0F^oC~j0@&TQgaPJzquas6^P*P@m z0djDlf`}V2TJk)Ih=>r3@88-g9f4m20>})|lyi$iPuxknD%aoxfR2C`9{K}hq-3=p zUvAs4w%=B#@Ms_?=ha%_Q^L)I?jInB6S?#v)i?JVTb)hbuf5(LihcbmCSuJ+Ed@nU z)XJAt!tzaW43jR%H@)3CGF`KIz&Q`0yS2Ru!)flfzGcoRWX4EQL_$H6K|sbr{VK*Q zrgG^2+Q;c)>yYMjW5RF+8Tw6nQPx}c?aE6R4kitb?W|Sa?Uf(lCvGWY6#fD~Y$mgho!mghtail!i2VRp3=D8}zybgVF3BDj}O+|lXKu|6qT%8J=Eby3tUbM;vL@xcMA~6g9^6QLomT6(qnLT z9DP8G{=2{bIJ|*5uOCOkG9Vz^y=@;6boMRp>F$z0`G(p2Y|Le5v(to=>1iSHKwM3$ zo_ca980m6dMQ+$ze&&Ul=HT)eTgvyCX*<6R##%{)3$)^r{pEoea9xq}ROfvBm<>us z?8Cw(;P=TE8GKkjUE@qa(s+T8#~wrb@d@-v7F$bs1@F2AIuH6H+sQ}ii+F0Cp->%T zUfog-2WLbHLPiW&ow9FQ2ck%#4~%K*H&oZ|kD9L#wLbbim#;UW1D~$`ccJynk=HOb ze@fjuxW3Tqdm~iZaiZZS38tqjOhu=O#hx;fgdj ziRH`PjM_J3d9tLp9#!Z5f}iQh3qhNG`#?tGS@A&<#}6G*Q00|kOeYF=F3gGb=2&fr zXqHwvexr7E`9zfPGsF-YLG|1T8uajx7Wa0U842uHeoNA&EySNSjh{I2**?6u#czEV z>$!D(qQAz2Xl%J3CguMTC7m6vf8)`OF-tVs+Wj$v(E4HXXFg%pS|;bIq=wyy>9DG` zi~CTZT_jo9q*zvo(6kEUvJ<=HM?S*Hgwai%rH^w<90shud0d_gCvRl-P4!;{q*`6T zz*4u^-TLmiWvDBmpH0W`e>xb(m)}9 zKx~UE-4T7*Ds=HBgAy9H>PJg69(^pI-IJbnX3T|u?5^X;!$^tx1klmO_$W_=Y+WhR z=N!W}^{l(1i+&*w)ph>);kR>3AtNXm`%+fQ2v*gkFjTV!b`wPUtJb@$z(WSL{cpIX zHv?g2g7_4u-MoM6f8pG>KxAK&rcbtdht8FMLmZ(+q+!EiNzyL=_F-6?a=ERA4a-g@ znJW$%s;s55v=OSL#Y#hHR=7Zw%!-I!gpSfRMbiQ}TY8yp5Z}jHi z2ss{sM{3Niw!%j1JXkCv&HIY6;!-SYQ*$sjj|K!WqyEXt-s`8{ja_h#A|bg6i#<_H zMQ$G>>EC2!~z>{nJPa@|UPZaZi3b2n6Xk>yeaSo1?}|^>H#?`XcfCyo76UGA4HKFDU<*f^ZV8 z7_xulVr)=A&*T|!?eRwiq`P+ru zF^_W}Uf~gOe_CD+^S$$ZZ+YbAJ5sjUc+(eU7?f*`dl87C%<{VxVPpA=_GQ4B5&L+I z+gf;15*heZIXim>j19hbXY)~okseQWgoVsQwlWlh1ekKsgLq-Bszu`JG#nt(%J`md zh?!rY`O@@ZFBnG85_}6^-6-$5}91E?GYGSXkNuvfm9R zm%C><>w%M|>1E>A%lVuIDw;boAg%1wg+L3%ZN}^y4cbA(eiMggxooyE`wU406ZxL! z7c|*HO!6#v$JzPC)#~a4k;n)uZ(3HsW@-%=H@|!dF64LmWd4*w!lA3n1;4^(ph>{} zyk0B!(6&jgjm;hgJSWt>X?#aEHOf~LP0q8XFCRTj`TeL~)Tm>UREzYFzjz0XK-giw zm#9E>8{2e8*cG&eLy{w;(P@B&+_28;+NIIGvIUp8rV058JsuK7%W5YOc9k4oGfPNK za6Vn@zt|4Z#Fzk@`O&a3*i@&S# z*y|b~im0!C>*-Y6>sksrvn?I4hNC{0qs6pclC_UjoR9j)5gsXJPg2YhbyF;_$bePl zoyDY)cQT_u^=MKAtY(YLs&&ARC0YQBfhD`Ls!FIZn(|SS3IqdJLjqmB8yocC0fh7) zkEfWNBCvXkv3h_0u=UjR63O)L&)ch<)hnm?_{yv~;1%%~NoZtRhBJ~t1QNac#W2rk z-`1FH?wLLar@Ds;{0s=myZ^`N;PAQFPQZ`~6`kKknFQ-PWvr;<@;7mMc4H{wVfTYL zK%rp&3%Zyl_G-E(fyxk6X8s>d-yM(T{{L?)gsjMxtZb6K3E3osWbf=flRe7bGb0Dt zD`aM8W@coQy?1`E`}2ML{yC5H=yY!G`@XLC^?E(0ERtPi7_j$O0?iv}v~&%yAA(My zi}buo?CNV>S@q? z$*@@gWky=Mt71^7^3X=4$MC_abFG=Vqfo3K9f4aG3gKJD`-*ps|N9haG|HtYcrX32 zldTSlC)25aVXM^eN3{b6Y076`UTLpY<_v^HY&48stVSk@Vi$&Ji!+rqpFTvQ_C3#O zsc&xHQJp8eKJOMgmF<4}C&8cOt6oFra=^UQ-96)*;C6cJEdM z40S7g2~S`?u?K(xX{>+`P1aNd1ju4HxNavT6El~E=w2aJSsBimo zXb7PlMZ8J|uTn~K^1h;4YzRbu0}s>Scl-UB-kT=(kw5~OOf*xr0Vg9gv3nJ)E+i;U z%Ag(9JKj~0s?FbbtG{xCuv~B{F)%X9$AY*^KkH+;GF;B!fBN}TDQj>)bJ%ACV&#Mz zqxB|ry$XcyqTr&|d!GEK;--xoJNQXQ?mbru_Hz#g`B(~nmA>cSrBscQ@p}CI4hPEz z+AHt)_45p|EbQyKi>tU_xjLz4H@yih+RSZq{#dO%!`PN3cgONFV~1uRb+9{k(1QD ztN9J_tE7$#3Ok+-Q%WjwV@Gbz>j6ta>_c0*%p^hFfN!5pjN5aQ=d*?v!52>+XnbOk8ggyUA}8T_$vo9+QWZTepo?k>g{~S$W)S_R@w!N zT89e88Jesr^YeGD{Ye_%mwwQs+;EHTSYl8)ZBZ#ON7iaN^eZMBkyWYh*|E*OG;h-| zYA4FkXmD0IblSwQW}UR->LwS(oXF0pHtr%Ys|?l5$1SIg)JZ9t;!7)G3ya}9`Kqwm zbam_*8Hp8|dr(fRKW7mF)!{AG%=09IztRz%#?Q{PPw5|U}{U{nWSM*T(*bR_B zO<$o;#RcHfKO6n$9o+mcUQqtV?eAZalO67RyLVk2zT^M2Z~A)8EfUAp>M2f!OY~Sa zU(YM9gT}7MKeWgJiBU);;oy6Dtj{+qG=u_KMNL;_E%vk;}-O1 zOmxT>KT;y_C^xr1mtqe@(khs;nxbqFWb7c>xPMWZ&$eztv&@?3uSKey3h2qL|I?<6 zm^Wuh-uH6vYn`Joi)AoKhq<^}qU9wO=rnky5C&Jbj^~s7(OwZZ{wkbMUhrcu!(!zq zfZ$W?=}leF{hZkp)ytJBlhx%mliCvDa)sj()Ht$y2`3bHQ&m!P>2jZZA9kC59qPY% z&R_g`C8yr3dX_3qV(30sTt==XMMmj8`dT+wl=f@oqmT93#Y?TzYKfE{&o^ z0*##@@xzR~JeGsQWYot(`o$Gz+KH;m+F$ehUZ$|h_nOURT=5y~TygVFd$l`kbO((E zhvly4T_cHU9U1cpxUM$|z22D(y$mSAV$nG?mqhMwP^$iO{p;lFt;o06D{3*;XY7v- z&_)$VZ1F4ayuTkLvSUiS^(a!P_N#6F0J^5xLWz1){|k=SMaQ&<6D0-PRbMCa+%=H` zaA&?!?}buLV8vls+e{^4t||-{7V4;ZEr|y1xmC(C?JL`)h4ae3=G4j4*vfp3_s*oe zCY^rBsQaAtx&wVRWtYcz|E_u0EhqEcZse}>+J~;zg=Z4f)T6)n%TOp=QZAMw2iu%i z_jrY$+%z<#s7P^A?N3%+UYMfwn^<2B3k%(2jD8I8bGT@a-dCS*pPKg`jMMh@CS}}O z-cvJ43B?McljjCm*x1zLtb3&WXZZ|nyASRa{z!SD^eK64MPY?WDQ>o2eMwURT7?`9 zxtWdgiGWk(@Y#$2by)_?8-?EIi1UsiO#-5eS*9r|?5m|mIRyFMd+q~3sH~w~YQn9~6 zodX;j-gA*~dj8tAm;SiCj2jedWMmZ|gCXpGp8T~z+L&(ba(&P!*P34b z7oS?)vS}&PtF6w8t;Xfn{M)2v^c$x7&gn?jY98*icb+fWcy z;eO|TA@bjFJi`svNsTWfqh8j#|D!V>id17ol22N*i0OYYbU%h*i>hdPt^DQEtVu$~ z&b{y-s0!mx^y+n2{*)_}-scj`0beq~*{;pe=N8?!UVHxWEaqurP3P^{k$l#|y3?ze zV&7z>Q$l0O8=hP6yf65W>#tt1&|^AXv2)HHjqRJk5zdRS(L1Hfejc2fB27@3uGrU6 zzk4t|VO29VJ&h<30G|8vh#`c=LhsfQB6D@qx!!3Vb$6i!{DKcae}Kq%D)T*=oQ61$ zjg91xCwQB97)1JwD8esNrYIEtS6JS(-;NCx3*74DFl;51mMX>n6{JkyBK>`uT=Sd0 z1`Q47UC4Tl(Jk!)3^Q~Y1*D3A0YQ|l2zf(Bcem?u#Ov;AC;BKZ*D)oE=TJ}!I!X_S zjFumZZ@EZoIi+VQwEJ-R9KZdaPkk9)H~)}lR~Bju-)A)o<3jzg_nN3NC{c6qiMZm0 z@z1g1y<|LhkokGilppcB`b6BpHb8`Dz`K_(_C!_)?0d>7_TgMN6tT!Og54Uj#T)1-)@BeR_(vI zcK{1O7im{_HzErOkYFHasKk6BoZ&4v)T>tINXf~KIZ21NPMWX_;QksNjdgp&$etO= z1;Z^j;A}t+BP0c7WkL#FRBA*}9S?P9pu~ix*4En#vD=U#pIxV>f0tYS=;ozgzaAnC zZvaz6zQw}Dpj&bl!dM0`u&htq<)GNIaAvmzJoEG7amWcpM1I9Fs=z1=hW;UKdK-Pn zK44645oL~yiUMd%1m7BF3&0G)hlEM;l7$#X@TE=WEC|YI&@%%d4s-^4EPMG$21`N< z7q~F%f>_#Xt=h3+01}^?+sO76GzH(c8H&T-2EYwKKR_Zu&3)bIcedB$a0Ngh1i<(n zf2KYF^qNOdun!Px7-B`iEf3{i9?x9hnuL4>-~B-9^Fx~&U2y*!_?)~18XqBBf%j%^ zYWlca9HIFB`}gl%8mvD7CT}^r$|0_>rzg~W6xo_$4}6x?)Szo6gVFy2V@n;UWaJI0 zIsI&-+Yst563}D9QW5@`G8o8j-q7Arw|E+4Tkv~FH14guWZ~F>VI=e{h5+6OJ3SdW zIYctF@}vcz{|*yYR#vY3{(V;h*WZs12aj4*_{6(L_vHAGf6@>5^dl>FY0>4FCx850 zg$WcO>%a@i$w+@pS%q|z_lR%Y+Pc3AzYj^uL~WE?udMa1xW4w9zuV7gtD4ZsS*ZvfasBUW9E0r=qFh`zO>j80_zd# z#8XgQoUA@Jy)EAOTRCS3U*6v>=~)J>KNgOTqe*ec`ftghBt_s4RJXM9tV+#%LbKe0 zyy7ZR*GBz?v(Tofs3?c4Q`^BTF}$ho4z{-UjByAF3E`#TTJ1oXVZjFgV6^BwTp_SY zX=`i$S^Jr0fC1MvEUsqIQvx9*aE$`AUs6)C50U9n2myy{<4;77#z9rq4Ng8$61%<; zWJ186gIE!vXoA}37*ZLA8iz2fr}XFW?^ zj5IO2d+0PKjQ>Q4oPnuaA;=J)Yf7l2-shDs3hUXbwv}Vc_;7#lfIBkjqqKUnIO}{0 z{`P#OFl2RxHX~=g5V@|D)It{e9S&NQIc_;n~Tet0RWPJE0t ztsEy>O8&GY`r>DFsi7bQY#J4@1-`ac9miG{IRr-aL)hdvIr zGS$&{G{nZE=)>Xt&fXJwYCxsLz%yS^DsH(vdr0=KNLgdqa*vCwDmuQAbvWW+hQl#m zz^lZickQpf(4RzB&-_83ROKC`#Bvpn3cU92(mkB}mEPa%!?}8r|1`g4kR)NsL#jNr z`E4CPi7n+%jyHe6YLfHM-r)}|vwB?Z9GNx0VidaGV@rZ^_g+RJbL7|4-L1|x~^1T~Hv2I}Qarn%xX%hN%{ zwY&3VwO-g%8pz~2+sU1Dl%F5D8O&tWcRIJ^|Lm%0eAYLs$5P6Zl%z)FA1QTOU-C~J zFQ7Mma`}R0N9U0pI}~P|mY8H-Jb}N56`1^#&fmNZ`y{umH-y$vytxM;<-Ij^)6GdL z{|D=O<+8W~Br+9AlT1jN%nqolt#(?B^1lZ!X@%>1-B=}-AI4ImW9__iFfSD)*-u8+ z{A*8#!r~M$zI4i6A!(70Cya-6wj7krLHx+|>mDiY#rF-Jbz%DfG*8g3*nH2oHMe58 zVtP}cu!SSOmR0MLl*g>ly}@+1bvZhwqdw8-P=KJI+uQT{&p?BUmLY{x74o?xg}#oNS^PE$Q4V88MW{j`in`C4WMclG+lYh&p-6MV!Inwnp z&3n-_GhFPnS^arKHPbBz|K_2QUL!tI9mj>uEQgQ9*Eif<;fWjhG>*n45@FeX)y7m_ zukv<8Vlb-5g>;#nrI8ro4?|4$$&$B|D6jcDp9m9P-(o7=Ej+_`D|PkbJr{FefV+5% ztFxnb;^wtEOI=H#eWl9v71Gxm{g7FVG8#F*RC42+_lt4jzJ>Xl)k?*?e=Xm+%L;cm zn5}0~`r#LI;ly^9JxD*DpVelpx77~vQzy+V#0@FA{-tWb>p+p?G7=?5a2e>E88rNJ z3>$sDYpx>6vQ*^097Q)AHSBM`e^BQX6$Q@iA*}vkVGfY&ZBg?ZL}fhY(k^1;n z{fC8d`gDo_Yv9bCjL)JfSzoKZRdoIvk;09p=HzpUCg))1bhAS%C5G};81RDm)p0O_ zeNh~W6ias81;g*v6qp&Y%Ov43@x2-z*IzP9=-Or-4=db0%e3cJMHu__NSBKb*5wNC z)kHj98&bl5*@*Lt_IWoYRf+IY$CcQ!-4!L@-;ZRoTSq^K^w*x0eIIaN6i5`iCZ8!q z>At}YV;OmvCoHJFy4K;wG(=e?#BX$Dk!6R6B@(K^WIrH&5~?Ygr!M&1)^m=EIG>p) zd_z6Ju}HF1Gha?REL2yMp=e^m6>r*>vhs3+su*vVfRdVPrethpHotCi+2YLq%+EDK zxto*Az}VS4(#$FT7fz^i-%2Oz&kF8*lwVs|aTZtycN}=1=S&sovW-%3aP$0zQV49) z@%$P7TrvLK|8#%J7I*%L*JU$%`wxY~XYq-m=tgde+2S?Do134-@htXL<%6%qJO&K$ zKZnZ6$qCTO(~U~MRS%lra?qn^Ckn+z$NGWdklwHym75&%_s;V2GH)8t()ZxWxYwqo zW+I|aNma{<0nb3FH$9%u0KLGbb2MTY8Az!DQuS?Q&Hd7n?N_Z0|6dDGVh^oips-Cz zCS6}mYUu%0$n)p6|EB|;FNi5%ZZ^nj`*Vkr2y0?O6rQ&5_=0$aw|03dg=qT1F;n;#rf`1I-Rv6huX}jqWT@o%XLRchf3hjB5`;Q>9ubk9 zoye55L7Sfp;nkD!9fqYgkH>H}zl^y|ExhCxv1+_vAP>PjqEddN($CA1NUZ&2^iJcM zh5%>E=4VX>&B)Ncnb`N1+q3jxY(go0fxRYv1#|SNMvhyu+?d=`lugVN#HPrjD9I1$ zT@(ca7Afq>Iw(}#vK|@Y{b1Qg%1_F6$J4~rTu@@7i}&vpK1%su!^Uy-ZoSO6Mn1U; zp1alfco?XNehHAju3Cx)MXitKzW_Zg_$wU^K?5uT434UTht%r%Ie$B64GfWc*Moce z9n}9m@kb-X0zgbd8*DmlSphUnfKYK;4=tY&b9_f`b=qS0L4lqrVH}0Sw{q42f&YtZEcu>F1xO zGj(S%LgFuCbb+nF9D`65Qn8i}mb*J02HY;aWJ$m#AWV1(*96V-KqpE;lt_~pC46lbk>H^%8g@eSX zHSv@4^Hi3pYsqDOtCenz&!Bi^UGz*Kmi}OuMCHY+JJRRX65=Rt@90=}63^IAzqr!| zwT3zPO^;yM5tjm&+=J)&>b(`0p~cb-XS|<&GNL2k|5pr48 zX3}veLSeFwXCj_w-rEqL> z#?^3Te;kXas(;V9bo31eWIYgIWjt3iZr`(BnEq{0PwjJ@4zCjur zK-hv3E6OXLCME!vEbG5e$iho3vVmm@23f?e41A2Y7%vxB09WwHh#Gvx<_lYASFku$ zK~!di_Hq0Q;J1f%HpmEZ5L6XH8n;F1|Cl5Ik}vi<@W5F4{mlcnpYR>v>_u>ypUghFZ31>qkL}TL?gU@LL)Jed0w64<@$pvGx zJ@irF{W35xC>XI=`OCUZj{PyOi#6DFNCvY1DQYRXQ+Hc9HdlIZh&e#FQ=hs1o+_#!{2Dyza2dp~qw_OKIGJIF3Rd(kbeD52eCk2yqJw9!< zC*uB3UN9)*xpr5{{gK{}gS&OR`M~ZL9c0t2n#y|YC!acB#-Jveo>&UIKaRhT%}^yY zsr261&7s7^g6O`&v`mHKcgc?UgH~EgZIomlewyd1@0NU-Umfq#yzD}@+s=)bayvhy z!qvGj=f-g#er`2sQTYu!@_Gh2&C%w`F5%S7(VkGu`|T#O%g6oRDayTcstt^RhLt8* z{A|}ZDwgOb@X8{q@1pRXvt`NxapS0+8QW+md|K-P1|;2^9IA`*X| zdcGW=V@;*UK*33C$cAcSVoOmb7CbqwxIg5ZBCgU9!HmoKyue^Io>yLuVC%gD=f>+- zk#_f|^Jq~dJf;box7%v4_C$XLW>PGRZ_i3&ak8K}1^*{KV^7qWF`(9JwWdd5YR9fG zEcojLg-QdT^CxrZ{p`10os8&AIL=FS+^+tWIEn?7Jjrggm53K^k^of zeqge9uKsd*I)FN#+Ev)K;6o|Ar{l{2495;mTtt99JO8aE>?!x{>TeQ=7zP{z|NdKZ(|F>9uEEzGRUj}(pj z_{FW>bH&`)vbsBddawLc7jHPmb*nBw`OxEq{Bry+#UHM;Nn(P=@98EXpI5e4dbl^>(S z`m~1fx1hRj9BCXkO|1nggxt09ah6y0S7N)Fe#xJH{*+YJ`TOO+RiQnSgR$-mjt9%j zx1EexcNsL&|JC>P`d=UanV<(Bo>bx3$r<(?nahR6v)|uEau%wn?u7q9fyW*{yEciO z@x~dZ^EZ9Zxvzd@6XB9Ma{20~*8Y{J(|ZWH9o02ycZD(Ws4tHqZLJ|0Ck3?|Ld7>Y)zi2&yffr82p=AKRLPFT$D{BkK z#}Ovz!F93Q+>ETeqO8~Pv^_4yn*3#Qe$tUbbc*qhYxMTo2O*Q_j+mawOMk~UkFlKHrgp? zt(io{#1NEr_~7a`Dh@?S{Q4}!Z@6b4x7Ki^*X$c~(68iqf*j~6nXgH&{G#)lVq?wF z;WF{A==UMQ+9|cG4WTo+E?n*OFI-w>hu58V&Mb2pUvG<*R2-Q^onTVO*i>(nxmXgv zcCHJcI)0Vif?J@`bsTYg6?}SnA8)TDn_XG0>|+iiwrc0sBQy`;q7^M zS^n~erO9^!d*=ax~K}Eh6ft3ce69Fp`r# z?RR&2?^rajF~tOqHb8Qhm?|CB%0~F@+(%OYSp;gjIjWn~IK{EXblAG?HxT3Hz{oWkJo+!{zM(p0rHK^ZIpv~%;o6V~P z$_Yq?3REt9(KtsJZuBs!a-o%j{7d{O5f+J|tFyCWk*H!E5eruG_t!a}XiSYeO!TaIzuXA~7-d5!SF~gF=`ZZTO%P+04l3Jxs=U z50U!a5qM;BvLQI#_WW+I5b0}yfv6CO1|~1a?HEF$!-9xgz?7xH#RsUH_2kzB5F}?Q zchkKJD$P@6+K0LGa}C6PM}TY0%~3YSob^7E{6>huJp3$6-iN=oT!z@4VMvC}!^_Jn zvu0aIf@ry%e4x$nlQ9>HJD9|vTqN2&Jry$GZq63g!CX3T!HQi3I3Z$~fvC2B<1Lr3 zt_yFEv%nUID8>Nj@8b-ycw0};9T?GJ)b<*dNi9J9mv_ELX$S=fqHF@8yfJR7uOr~> zyS^5lvrBSqRLWOhMAY5E__S~L5A2irD^bRHc^(j?<_<}79x!TySUhul2Z9*@tA^!#Y9A*E3^bwLtZ6#%cRE2q?4;R zpe$nwcZ_t0!MX8oxe)1gGoa)M*t&RJ*quGvSoZmIrvW2ykituYj2u32SjG7;Bf)70 z04*SqkfWTA$xScc4u>WjuoV?tc=4&JsY`&c!-)u+0AS^3?0@Kgx-JSr7(1c>5C%o0 zKnU=in4E-^69L0f_=o_3752F#GRA?BGuTgtG6^e>?h4IcUJAk;$|(M#o$h6kCcFBhHw+^t$9L2 zyHSN)54#O~vk190XrNY~`5iq2t1-e=a6SI!h8WS(0{QvSa=7pZQ6!Df zMMb8Y@p@1m$uEKv;E4ISedH&3?uwDg?Vqb^5E55xCw3=@vsi!-)0BZTcYG|jkCcq&ot zv>%xuN!}qzLANoPM3xMuOTx<_R`2REx(2~hA-XMd9Gg;}iEJ=Mx#H|1dY6-YfVmwP z3a5O=;?tHFPf(*wTaI3OD5SkoKV)E<+-^$VyOD3$F2i(Sa;szga3|TaNBnI(`co$3 z3=UH*9rPj|jBi_AOzOrS4%bE>`zjO39MF%~NdwV_b3f2BJJ}|1A<2K^sT1-q?(WR* zu6Sdp+U2|be(F<6j@sZ{{@uUi3(DyZS-fBT2&*4^7nCq5e2+}{(Mc9H=V4s=U##ON z^P8t`Wu)rp+Dprijn6r|Xn#t(QpnM`oC$GM`Z^3IX5F3fsKsAHrs^;vVa4t}On$?I zy~51+K1cDATV~&RdQ{zzsBez3@Mz1eVYP(QeL!xP-vaees^laYFyXeh(+*vd$%3uf z4yH6E61#Qj4^U%gx44Ulk{2aiPAt_M{WLHi8=0u7%J<`$jBe7uL(<^$k&pevK-Q?s zg2X?R$fVobwV2|EQkObkYDy%)$I+NfB~Z&T#IlC;%0OBFv4Thcpz+R}pw*CiLGD0v zo~xZqJnGBoI~1)0fj#N3HAeE=|0~Gj=tu}cqN8&rA{5f%rtB6lX@wKRchWZz|t-1F~ZzeLNBX}IMYk0ZKFm1+E`%Af4YpjoU; z^-2b=+m|a1Cz6M!r#)XDiYQ@jYJ8E;x}mo_VizN#T|RiZR$_bct@lirQS$4(kR8AC zx{VqfE)q>|q#0*6wR9-AXkS%(J#1vs)=4E>q<-70r|>YB3H5GVGkbpoWg|C2hpZF-k|Lu#(lk+aW!w9!EBK zm(Q&5SVxESH(n9%CxJq6j*9k=)}eRfyp&+?*ICWL>7blvmgq9m6`0^M?aqqnLuzvr z)jDlL&)6)f!-^#}N14@=P z7~&|HC$qgZCOyd4)s-$SH-FOqSH3ssHk;#Z_DF)+{FS;d8h%415mE~JfsVj|e##S# z1gDYBK87Ff3O?Q9p0OlPrVlVhIxVnWj@`piXSGfr9JSIDOaABW)gy-Ory_BghLet( zHH&oE`s8ZoE80<{N=xlq6c6nA!vm|e2UvvxN!}0NcMRXjpuE!d-K{niAHDT@AD=+! z7JQVNgNwTQZ1wv3!2Fw1?y#WOnLTOZD}kg^@*W??OyS30x4mQOeVxiD-~kuFOUxN0 zDB($qRNiLjuO9B%+y&2VKx&MQjM_aYHY=bQ;P8+D@$4qIfukLA@>bzsf+O@&X#^BeY<_vkka*cr-zQ7BKe|l$4OZ z1`p0Z@XQB<_FdK|H%clh!L%p{nvJDr9vjn`|13|@4Ugf)MOt79!IwYEn?EjS;^-I) zB?2%UB7f2BYxp@4Bsl;NYIw*3CNxSfW4VL$wBDQrus(1`b!opg$Wd)gjt72|p!hu>!0_+=3{^1hJhExwT1gwuyK7Mf?5_nNiKpkG@3lhG9QWos-`h9i$lDIp(qq zDC*^5$|rjl&BevjA!qu*;b|ZX^9;qv&M~Km4BOX=%<5@dw<$p@Cv7=_zp~qQ6qPgI z`eoOZGIu-mI4rxeIGk!{mOi)mrp<+b+i;g_gd?`(v9y8&`UYxowi|Z5U|eUj+GT=McYjzJ#39Qi%>RyD@ld1f`11Tt$9Qt~SLfuGTf`<%Js zEHU)=Z+t_H@?YfZLYX&-s^DUI&CqDW?!vWz<|;-+L}zBmw@nRByZCjH71r z&S`Q2;{x2|q>Kf{4z0+o(s5-;Vw+r%zo9B4bs|qdq z3=M6+mwms)La53?t_uoLC&2sRVXuElcZu5X$h!MJL4C0QRfg00T1sjQY z5(Jr^x)R>A6(^5Up!xe;`XjRrcV)2xKPVvb0Z>c!g%;_ga z-J=De3bLHNq+J7XjsfukhG;TmGMH1(t3r$j-QS06(axaH1=H>)zj>J?FWUC4`0l0Y z>Kch}X)D^zT9wvb=F6eOS;mkzYhA&&uO;d6gOLkaCls6^V6a;s`d=~< z%!_-8;HSZ)_7;cT%Eg6PVxjK0Ek`G82|yaac#o*dhK&c#rI3Z&n}zkyA4Qj7wYv_v z-KW-m{rWSkvxXy8Qz>YqkeM+6Y1ty2NXp#uO3KOzI|`zav^~%v&*q11KIv~-V-HyT zL=$ATAOptNpJm7fJb>OW?ksPgT~Xbzt_Mq)5J(0;x{K0ucgRJM(vP+4RP_Lu73w4; z&JRk;yX0m>Tds`;R4clq=4F%p0UtZ><@`EpaFo%J=YD>J! zj6uAabB~r(d6W>N=m?05y>D85lJk#qptTu7Z|Z*kTs;EP0}z<$4}UN$13M&0-P*T6 zx@}fMC;+}@#w8q6t^xC&?MJ2_x}K8L5B#S%_m!C}@(tSYQPgCVCG9ntt~!uj3jOJy z`qf@Zj6u(w1{(KBE(1(CgPqRe)qVzf0_vgibg(TNMjl)cHpIOP(@4&vkDfH}0ujEQ z`-32aULWKqqP}E?!JCP^a+e)^^d33}2B(IVx0Cw%xIEKgR5&gju*<+Zvo){3DX>h9 z`>p!M*3RzInt}^&~(CK;#^( zrM=?@MH6gY3zrjhaR!@O<}CAx#|iySfEma^pyqA;{4ZaNDIoq?Idw9{B@7 zC2-v!jFqrKBV_NlD_Pfs^WbmTYv)taKnQsd)YlQy>OtR=GI%J67+W?Qtiv0N{@2hw zlbWxbg;*1rWbhPPaCLqsi8^?Akmbi?>H)~Q+vuzK%ZBfwzvcP`@X-Um-?d~ESCuzO z-OwMvgYn|K{>;k!d}dj9xqjc2Y!~B>t5CPq$aMSY!82AB|GR$V({;d{u3v2kmG^{oG1V zbzgUUKycF6II{up#B z(~YQT6186nO%8Y+{JD|iO#f(K=_PU^$C_p{#?EY^s)w21>Pg3H;6m|q0 zEaeOKIvnD9QdQFWnEL_gHQ=E}RGm$<|Va6}qwZw$s$NSdih!;_Gy(_Q#R4U1jZO`9r-d-E_ zMCdX26=E`K{kvLz*|PDJ?Dc=*Z&t-OLOL`>ut zDsatIa2I?PrP!cEw>%`{nHCGik52Go-=F;S7o%voJnQDTEq$WrA620GehGcBf0g|W zZ_{Z+kl&Q>Kij}xi-w<&y52GLIG2&m?l6R3r?16HQhiFYWqA*vKapiD{mH;9Zrp@> zxV{|$BqTkHL%r4B>T|ud}qJ6^x{!jo?umFbuRiQ?y7VxG3NC1J~ zI~eT}^h{KA5Kc*kr_Nsb5T3=z2{0Y31qa}?au<3I2q^SggY3cslm;}ppHKjJ`n(e~F zaf05XH#6CalR48HD~8fNA(S^FJ*JiC9gpD(4^s1NMl0>-eHhmnL|3Dmpq?MiLNtsj zh0-7@@ zVL&a(kZZecAd~HWk&Usvy$jL9DzSO-{f|?lFdDrm;bRfd^XzK~a*BNVoS6jM(9p>^ z?dmMaot1Pzw9m&kB&U&n{b{5?^Nf3J`) zS3zW~7-Mz>Cdu|5xdhKU*cP}ZlqWZxA^r>k-hc=I zVHM2v3T+>Kj~_kPwwZjcdZlH0AH|14$8;zL9h^_`pf~vyEj`Pl?e;R&|EYafWOW7O^ zrIJU^xg&vh=00-X(4)qa85*)Cv$_nJ$gqB5MY*QZkuh6png9xJT_bMXQ8{)%P5S~Bi&OwH3!xm+*cme|iFX`D# z1x4BRqQy@^@lN$gy-2f(>ot-AM7+VPI6|r-Nc6YKT+!k|a2=r@4iffe19L!hc`WZ? zpbp`<=)$l~rTBnlkP{^7dv+?1`TnLk4ViLarj_=2yv;wZ=yzokiUccqYYY3AyXqIh3wnh*S%1f>xJJxi#8q- zuLj<$<>J|GF#PI>=w%oU6`1#eHJBT(-U8ms;djvwpz3c_;?8l&4Gsa#;aE%|&L@}E z@1JU8^UQJ@o$0K%FAp~xxa%`-RS7#cGw${%M_~6;4MG6fFC_a?T=-`taO%~ETb_EuIb>yBE7%q5lP*KAknPlg8^1||T61LXnjKrMb*&*t3&0mOczB_Df^ zT+w9A?{g?J8(cjhfWKH4TilOtNLsrLTnU^!2qSH40dRvri)gL_p=40o>9Vx4Vxk<3 z@EwEn#^=rargL(7`mtd#&LTm|e~Mtc62Sbu22|L2`-AVT@Mvp((gWW# z^}j`G&(?!?*In=Sm#J@)L609xf9K8?T+ndl!1XQSHPJZG1S@3ARbxv(ga}=fE?lx9 zQs6K3UBOg~3^F^bE&{s0aO zIF;JLWdXwW`3yIxn)$s$Aafsh9k{I!O9j|Hyx(ZDB!F4f0JE3W1a1eA4!xNGZlehv zt_TBbu(Zywd~E056eJD$HqjUdma}1{eJTHjdnT2Gy{?eIM0Pi8b@#Yx{|V`+#^u+6 zhY4A3L9T;(_8L+t!jGt}&!bVgI4^qI{VZ-t0<)SExyq$uNdHpuE1}z99RBlfdu;A} zW;e8L!iVa>?@IFS7XuPmSTQ#;<|1KH<#hQoMfpXh^hS()r2c}(&+_bYroM|gdl92V z^mH}&HWgQW`($+&=O2{V*(UdhT3sk}0$(y_Gy z8GYN0PxAM(7~SbGJ^g%^8uneyB@=o)mbd|h45L|GujMJDQQl%du3VIy#W%SlT@6;6 z{6^F=e@*5eevB&1FW*(w5h?yt7oX71rf6CBdXxz}p68*ddUXX2erbX^L)_otnXb>( z`X$_%88$uArQ9^rmTT5=LJtYJ1d1g$`=!WLZg)sl#y8J`Y)`BIWD)MmsXmw{f1j9W zU8W<1=VD5wN-$um!aK12+bB2wTyVe5aFqtn7e_pDl%)O4%ZxjQhp_31lWD5wq^kjq zioEW`*A*cw9i(RKejIU3=djmD(tsXm91x5`q46D$Y64Zz#sDL&fVZal z5y}0a`+u1h9+<{3Jr);O)sxlPPoxagPB{`OakPooy{ybWd+IKpz*a6ktoZ%aN$dvs zS7RYX4fRLaQc-RKrUZD&lSLwolailZ>kDX+s(6*cocqLOm@b)4ZmZ7B#2od`rf=6Z zU+#ISs0=AMlHi`bjAxyWjpH9&qrpbGHXxNiLF;j0kM(=}s^RG;Y|PL=nu<3<6&Z51 z*9w)=It20#8H+gPS(`eZo^Spe+*|r3@bW1=+w}DIR0yf78?1X(zC(vTgGcrM-1#(V z6oTu|{kczYH$M_5;;|n&FJS#7xU(v8x$NN1LKYeFk3yUZQ$0jizh1Q6lql9cQ9X() z##fOSZ48$TN3ea5S{=hCk@jLqF5}$k5jKvEGO9rk)q|6prKv2-su5oKTQ~0Obo<1Q z_u^H4R!A-n9T`seYDnj%eZLIa#klnNW|N2Cc4FV&UMudOD2W#?A}B~MZ%Mt+dR+WH z*a(?Gg6Hga$UbAAWa*1z;rok$RR_qX-&8J69w-#@mV|uaN5dE>>~csTTOGJEJcw)Qz`P zm3BFQK5E`?%s-{C)-)0CTNIXFA{m*ml! zYNPiAuOdbh>ig$N+aX}xI zWN?YopqCgGb#G$wS!nliy0Ay=pS{!A05Xm>`4`kaATkgxe^_XK%n(I5+1vNrT;bLG-BJ}QXBatG zhnwD=n9zcd0XmWhhvlw&1q_Adlpz^Alu&C8PNZEng;?N+%M>iW9-#6v6$&i zOOnNK@z6^Xy9br;{jOk2a3l)9YvdXkKrAH}_6UuO{KLIn)lnNNN9{6blkPQhB8p(n z`yla#ZjPvuqxEM%lIc_u??WZrt*6}6^g&Cc71F6%zn8P`?)VZ6^#vx#hGL|+hi`Mr zv&ZDGGbd0l^Va7>|26KPvvP_U8aR*K7T(A zearRp$E!CIM3lOiY`b&c`@7xtAl)}5J$0oEdot|t(y!XO29F~Kc+BOESt9zH&pTZ% z1L^zwBfR1BZ@T86wpCFbQP;-f`R6I*8KVNx2zGIkkTCC*hSrSFLSg zQWC(o1(4O89=u-m_=J|*hg9i~1WN*xAErW12#BUZ@3G?Ov9`Xh!|xQ_tQ%ER;{vV% ze*P)OxL$-L7*R}`Ayfyw+uZ-meuh~<4GA_pq(m>D(Y51;X z7uv=s7nZZ8Nwj?2@`xGH-#PLy^T+>EBbKR3WXvx2N_I%$UfbW_e_Lbl!xI#XCAM4= ztMA}WEUL&JFJ=;r_R}@9;&l6S8B%TV#j40o^PvlS#uZYYDVPjcpqZmJOeTm@x{Z90~0ZZ_-9jG)NU-KS3q^@VeTMY%Zi1o`=iwJUyp0F~+ezie9;p4}KM z6bG<@Jpzf`SyV7%P=la+5ue>Ul>43K!wZ4J@1H$S>F(U;yw7#LrhOrn z`IaGi9bB#$#ju8k24&xE34EE4la8QY0cHVebp*5HD%KZWDOFN4g6C#uh2|NEB=~Z& z@1*u+c{(!AyNU@T`c~b$ECm!$-_Ilo3ngcyO8znpHWnLp%ur^99D5Q*syBU>l%=b_ zrV&Hb3>2(e*BgSWi`o5M$R^*} zqi`p$`AOLc*ko9=&SEJ&b5Yf)=&Q$pUarucI~JLp*%LiP7S#9WeEj@bjX9YyTit!B z3l~~rokP}g-s>GFn^xbl7*;JGhrOckn?6WlUCs+lSzwN-Cyb4~|C=o9R69Q=v zWUiyy`Q=AD&nDLynwW^7{D%Js&S`?rGe8$;G`xNDrU16rU-=R$<+Cjrw|SxA{WUOT z<9tU^+7fxN6ZR@Qhgk+<4xWr{daAeF&DDS(nH)$MUM6?sA?3ZHEAB`8RG9jKk%t(q z4p%y|e(3LCn$H_zgc&xMqz39<*GFyiwOI$sv4CX^o!6A7oDy1*~{$OhAhbkE~Yn00vEK~}g zYWmMx+`>%Xm_K!;kF46e(TgV;78I(|`b8u})`k8)ZL1(k*5+9)^Ik+A@0q(j3yZNx zvyrES2J6;KRNPbYWxzMC`H%FcOS$guR@ zlOzg_x3t}htDl%sxbbS^2P#)tGGXj@e-!StBJcO-;pC)hFGHr4!iXDHGjD~UC1wVv zX|rwxi5_j9WjYGT9t}E>}us%(&G`&4e6^n+g zJ}k_y5OJn3G7D)guSTZbe^6xnoW&fQin6cpkG$+VSF`AmN~|1vzGm5-1_!L0 z3JWWlwc`*mIqF!II^y`b7IJ@<`d^X-D)htY(jn zr9EWhW_VY4o;Q)sCoe02Z6SlMY}@AHt+=L>ZrEl(VOz)l-oUa4g;PrME(Y89a&g6! zx%$N4p}ULijFNii&WHepX9dzBg9nm0q5Ym1$yX(_jw7S#JPDrE3YR7QrvANBF~V^+ zS0V&r2Zvq*b|R@HG^KJjc;p+g`}e0;B2bqVosz2N_!ra>ZV`3euV<;gOHa09M1}XK zyc=$*90lsR8qa>ZsUP-M6 zA%t$7TK;beD9O4 zIgRz<)i;fze_USwFbt%#20H%g2F)y*-JMg%hzL4k(jgVJdYczP|8_Qfbyn++dw2AA z-)2Jjbmp=;T%8DNl{fEwIHI#}1&BHuB^CwAN2aM#e8ZC+vkfX%Tgxo{DMKcw>R?^T zGa%?+BO}hpomFlBnYoMoV#SUh1D|8;q)}KmZXL5w{LzB~$EZso22a4+Fh;RsdwY6n zoO2=JcF}?kG4&>pcRSAIpumKyER%35wQEjwU##A&4V8FZ;eh z7|167Cy-<>K#c!AHZ=6@7#?oadRzG8Z+(8E%G7u?N=Jt2x$lDq51@v~#@+oT8T)HD zlg!+^E~JUQz$zdG(6`J2k|B#@xtZ7O{Kr%PDNciTrG6z~g6MS{p3Sxh7clyjmEAU; zD$${0g79USq=4r|HZj9YCmh{UriTZ!U%!(7@tI)DLP41^si8-a%=jm69h6d*BswJKeX@%*%l~lN#6^00Kg$ zH&j}|XYp&1201miv>$S#2&{=4G9Ouo(O?ZZH&78q2V5N#Af?oUgTtVrnUQJgJ8r!W z1iz`6gv8R;94SO;^&l zuD`z@Z*nUOZ4T#lWY{G&KDN1dm=Ebon-|@M z51*edTz(dF%N4qDVC}Jt!@1#g`+ZM{I#tAlZdCEcd`tf5X$Xew*ez!uhkc zyV;ZscF&&ahu-m*@^ZaL!BQ|p6})k_Mg18R%IfM#DrL$&OUj6n@$E6Ox4JT7Z5}4> z+1vu`ugME8I)5hABuQH+*Uy-Hc!0QPU}Az52H6%P0xebeQfl)k;a4z>zKkqpT0>@2 zw1;EEQy_i(36XvD{6EQ0EWnV%C)dZv$H<7~liuJ9rHC3ax24j(mOG3_{U>}bbIsj% zTTe9rU4Zif6j3U z`UF@Ced>5D8V-hyzJJADZr-7f9ewuE&@^Ze=4df7F_5#QS5!D~54_gqNb0l3UyNE7 z12=|%pkPOLES|DAsA7! zn?5d4E2*#4(AZc}71$Kk)IRV&4)phvpi!s{>77=TI z|A7-@&r2g)^Atz3v9YJj0omSCxJ2JyWXRY(-u4qQ6%%*@j6dG)4B3mKkfyS%zQgCX z7KNdv?UbySeW{0nKF@9<=+IwZw&G5hmdBbSt}B_|Sj3oc`(s;7$qAF3DDsN63+2}u zpB^$b|GRM|4Iw>O>#8zp?YO}(BZ7tp{oPyr%HO{^(tLO`g$h{^2T<$!#jWXoeUx#! zV(F?>|9y}9r;U2NXaVKrpQ%JrU5a!(U~u2cL@FcYh_uqWQ=4 zG_=3M@_1V)=1#gQcte*%=s*?@76h1k-QImP;(<*NbWHiD7w-yDZzL>JqG(9c-({>^ z*6}A6I}$Np87)zQdj<-Bpl^Kw-!Bllld)@3a#r4Z{s&T@_$VKIg1zd`&repwL)1U_0p1r;*}sj09gb>t+W#0o zH%IeH>pVOM2_U!x;3BWQ^rC|_27yQYd(k(avy%T#KRYJD7_LwOUE-78>hSI6=l1XP9`J9CK3e1k$0oW)v?FXeK%quGCZRhP?P$l%Umn z^I0ynE9qD7i;rO0%MRc|AZ{G_&2gJA&gi_AQSqVZ%=}7EsH58X>Q?^mi1S+SZ(C<$ z?;IrN5HDp0e;q8ZSRDWR$3c#lyf01fDdlMR(^aC=ZEGE}>d~|O^%=x@eNV$2W-+d-o&}hq%u34c1oEzqUOo`IR_8 zMMOza16v`uw?W4b1PUebN9lGe17o@W(*hK4hMiwZ0~Y{WfYU6L3sYrJYnEHJ6~g`o z#u7+XI{i|t*6OiN2xfHnh{!i5a2f_?X6)&zdyvq6fGo~MVkJo5jEJl^LC(Zw{oFGM zR{|hFsLj-b5EfHVFeMM!LV@WLpm7En-B5M~t^?T#&5G1Jc*5DrtSFPug~zjaWtcG1 zRl6r1!uhe%mx_GRAxld^bvw@2A^HR{bQqK23Y>foh2z$_>sg1lApXfj;AqX#h2TX8 z*3LVDgcag8Oe(Rlu)jY2>khA6Y+KmyYt-sRa2F$FEvY3LNBaGvEEMOhVo=^KOn>c) zaF*re>T567saG)cZo?u|4#(8AhuC-BbhT95Rq7i9#xFVv1raRJPacsg@^T zPR+NYmABx}_9LL>ikf^`IAiatI^S9u(QS-?qs2pE0e3vJlK>N6cI3nR7rF)?Np@=R zXg^S^m(gf{h`hgjQE`@zXu5hOl~>>x&bbnhd14;6?n|OTV~8dEFAlNcb1_dz98u)A z$Am5&n<<_5G{o8>W&o#+5#uTG81{hudJC5a!Pd)w?=gfWcnLNSXZINA1k-E?4B{vZ zg*8de#-5*_4;ss&2&Z>UKN@Is3(!t?#&oixHnt71j>=P?t2E;=YaIK)Cx@fGCNy{2 z#=YZ2!Sq1TtN3x~Q+|Bwx3ZC5w92+D+`S>W1sR|4QNA=Y+(7dd7{E?-kTq<3VT(Oz zoe^K-j2_mgxN(o*6`qI|I@iCp`oKcfH(VWUl+No4QV*w`?1_&D#oo8EiORuR9|zbVUd$y=6TWf>xAR}q`pF$``JA$)N`~?1N=7(Q5eah`Ub0oEOPB|7Ej~M zjfCL#?fTxuT6*4ZJ*%zZqApyK)Ek#RGxW|e_cMCX~*)8 z>8fo3k?zSbN^~pv?8U#@!UT=SqQhY*o?H#&Z_6S7{ce|+vm~PZC<@Qm)^MxkFfN=0 zO;2>Ev*7x~Yll!OShLLf8@6rLYpvu;@$}d-b^>L!&=E@IYo<2l_WDQv!atP= zJIiF5$?b#{v^z}##-GsmxBy|)*-Jo>9_oGh&@ z`WAm*l=J7|#B0Pj710+_t@woA_A-gYv-V`p>|n$=ORku7+O`?ZlcM$h_JFq5zJq~* zkFD)`1AJD87(&A56U(WMLq*~&#I$Jb``LfcaINQxC0Usji-@QB)#rtGWL3wH)sy{- z9_QUGax@_!=9*nnY51C?-!yS)=ci=`R6#Y71&a2_TI5VLAc2SefkN03?4ut=6e z)3AqZ04ia$=PcnA?dT<5n zL9FnoJs`B=UXD>yrst9sfcf7B{XxCmFu%CCjX|O0=AxKm0tgFYi9yFD%bZ*~{}@jy zRae*elY1nLS)?%-jm|;>0##pgUzrC47+2t*vfe!M3m=L%+252R^uDb{fvI#Py6XhY}WsfTdrJc<-5{zk_^`LZ-T+zahhto3x9Zt7oWp zs|~8Kv|za1bLf$B!D;b+DR(Dym7=ChX7yi66S^19>scE2^*<)RE_bD$H`3RR&X(uZ zwP_N2EU^kv(aRVwUd{bYeQL9pV?yZdh@W#0X9nHEqTH&ql9SX*iB;EdX+J4w9vz$e z`3qNU905f^b4C;6Gg`Wx+LnfPr%T%K_M~U!v3I0iYij6bR|%3U{5!r|LFYWaeU~^R zwyhIwDVtJg-Hx~$3L9{|f1uKE&vwL!`{;}@aLhMtH*?Dby<;^F-HXBPc?%AUV#maM zw7X!1yZ@V?Qjiv(3O|bRsGUP@(Cu64I8u1VoBl?>7Y5O;M(*9VMsCttu^6AQtevce zv;>9fkCIbmQ#*Aqpn^(_k&330xoo{UbJFyt4)t2Q&L>59IYN!lm(w*O0}~S)+qE>N z`q8)SaF6JzT3{mSGX2;GCG7wNADuB>1|i-gaxhfdDVxJ!2h#9Ezd-O%r&r74+`d7T z2x_(@ol_w&BA#^0TqwXDR%;OVH|Y3tz~#0X(j-_i;3c+Ayd z^jW`bnhz$=XSV%qDVmE+QwJIfOsLQ@Uplp&9e$OtY<})flyOtpmY18GAI5f&skcE; zdlw|&-&C7hVMRjGlaFP3!MrOjAz^7_6A4)>%XSm~?d_qsB2{=rrSUf+!O&s40u_o; z_Pt&vV5``uT;>M(w{?JOBagyqe1eVY>*?Fs>Vo&~4M4?xU+FmX7R-Y1cy#CA#U(?- z>vSK_&w1tzJUESHL;1-zwj%P0bX&r_%9wr$17gex%-GK{_08Idl?z8?n2a;?UA9GD z{Xjfg5ai@3ebVE>z9)vMj+)A$Unk|{O#)6$9B<-(ycu3EYKVx7imiAQoYPiTRzhwkvQ?_Cv9Sk|R6$k-qAv(D z1dY>l;}DI@mv&$xcf4~!pn)C& zBJi*G!S9L8wg)l)^2P=ZLE+fGJ)B8B;xzebo45(yFQB4mX-^C!^<9g;^nip@65bDg zYfZbpz792@QJYpC9;qNkYA{*_&H-eQMI;S{(@KMVwIfS*fI(-P1!V`HLxB)-X5eSThzII4moIx*@PCkg zR3e#+B!~%k`hZuj+yU?pP~#xu$N(!w>amWd%-HGw3whieF9!uZQt5_t)#`C!VkFoM zv3fymJ-wul?0)(Xl@SMPz#n%&pV2vz>L^ol%gW2~(=2mBPcH zYX`oxy#iwnpNt7PZv(7?RGLCKJu)3Mj@9tJzEE9oNU}d<5C8nUm8X{{rmY z86fRX9aw#%#|1ur=~4iYGuqR2%iTyAP27c^LS7^0rhpP?h9&14= zfU=M%yU|ZLs6ovN@*z}wlzON?bC`f+Ar`y0onVTC)?HZn01EKAI1$KSr=oZTr+tel zO!QO|Bd}?KJB8pN2`f5cwy&cj%mOP19RA>lS7)<2^MTmbz`#6M4dA7N|JeYD1&UZI z{zz$p(u2B&2Ajji%*;%JT?hDZu(HUa+CXY)hK<|S1ScrhV6*2xGT@ZF1p;~LHpz%e1f ztSRVH0vT=!@qhen0|wj=J{iA;tSW8_5aofC8Tk+ay%H~3jg|bE>n2h|2)B{h#nLU` z>&s(MMg!FaR}ywZEMf+%=Ua7?3zJA@a|KWWxR`)1Tpwy(E0&BRqom*-y!CY#^H<=p ziB-MGuI9j}9(XK%L**?pv-#VqJAA*jZ$$Ng5{2>vw#)%!48**)Wbomr669QsLsSA> zFRX4w=JuG~1EEb98Q z{X|?LXryKwalvpDdtc5r$e8+Dks;0qA-e^QYuIkPQHE^YcVMGXR(U@rNGG%$e)ti>2uR;YQ@;}n@x^zBRW5`D&8)Nz= z7`Ka&ku+aM(1pwS^gkrtSKdlprlx(^k>O~ibW)D-NJcwXBtLrI^k!xDE;j@1lFNfAx-AS%t!0kmT{&yN&e6`vIN6?L zdbDQ``tdsR%OA;CMtyNVH-x7+ zIq#BUrIr$d-X2LcM6Z-f4d#&kVeX)8V4M-Op6ECVm+T=Vs|)X;^uuFh;Td{EjydaC zv9P?*w(Mln6GP3b5pJ0}DnW+IFBe623l)QULw+}aiho6=;{4;<6A3JRK>>&F6b;!N zH8;OajUCfHe_@FFLj9QUPSS^osXVK9){UsSbarf=3(b1Lhw7~#-tj9KY)tAeFb`eb zzVJsor{<5cFz6~a7gX6bS83zEiNZnN*0(>?=QN9*e(L0q<26`!k&0mQ79C1(I4=|& zz+)9d-+h1+Li$V#!x@v{H=YR5lKem8zb zDho_6szxT#p%L%F#+*wB0%e`e585WC(|+If$^uLFsw)0{cE1z5*c)Y>g_raQd2_*m?hgI^ zyszXjjdVU7)_J~sf&AgISlQWbh!5=}S$03X4x5L+W?bQ;_c5Elt|{7|SCtyto5v{d z$_~Y9+77*AT+Ef-fkG%8qDSfAKr(%)jkDf;gu1q6mV`|-*D9}EzQM}-EfYs$yu%Fp zQ?%8716wtQ4J8+~{2WtOLEy{69!-ay5bZd&G4rb1Lq27zkM4hX8DMD1Fj2j(j-~#( z;)hw9=-^Io@`ftKmA+@`sY6XDyuUg{5$CMCY*xc2cd|6 zkh(Zh26;0w!8yRd96*OB;`njL#RV;(O}2?<=pQ-?Wu}hgMaOQ;4B4BFc+hfAGCiF- zx_@EQRKRQ$Q7z)g`{9`EN*kqI1>9Q-Qp^_NFWqJJ~c zk|tJk1^_aO76FcJ5Cr!_v5O)w)(#HI-jz4sU0&=11PYTlyyL63-64Ae3=jaRN#KdV!H#^Y9)qjV;?NPh#w+gAWnJw7U!$WI{?r)$l<74nW#wp+GYQ;PX$x4 zo|}f90=+dzw<7J~wHxguz0)i**aK-uys^#)K{^Ej9)`VcNVmYxPxZ>2;7|~2bpBqQ zzkbTC$%%Ow)6D^nlKg^l1CEnA-EB?<=V{` zov{|F?Q9Qz?tLqDwiFek=&}s+VGcbs9w(GANt|pTkUm*pF+Kh5%NBkAH)U5IhWy$t z7OA*8OEiT$&ijOc)G`W&VC{0#0bQOSP3V+OHT5$~qnGTZLiOaTZhp_Azt?DvOBI8J z!hZ23YOT*Jz2>&6$>rr?wmynO>sUYA0u#ga8jpyl_dpD#(}H2cr!dRu!AR}o5h8_A zeP{FV%+op1w4+0{r)E}w5X+z2ncLm_T5v9*w`Z7Qpz`S}N&lRHPs&=&KHo!r70P{n z{>^;4J=yW3(Swle*6YnQGBLrJZzzpjFXbe1;cetTVb550IAtvgMoO5lsIFHICxkPc zg$_|w{i>h%(FYc&%U|pJJ$yY4lil0Nx8ec6{vLx(L^`Xk=i~&V+cHMcc*mmWRaVaN zNdyjQjPs0jo#B#Ov^twc_0&*8Fq(9C-K?;eb zBB$B#P6eld4mbJzxQu-Pj+sFR1>1#e1y$4=jTwLF@S_YeG-?f&x?;#+6s1;CBT)2s zMVa7IZ&@n_UX(BU`vZfg1__s!=rFm*YYo5tzNE$5Q4>T zZ25L)^yOKY)K@^jnMV~ zCc34C5$u?&)G6kiq*9uz&`&#-EANiihoAKC@nrP$Z!{VMCsdJ$M+yef<{~7;*z)J; z_w8F%6B`OFO}zu8m9^~<3CpR=6aE|5H$wzl><$hnCw}rs+&cTvj*Bh^dsm}#eM^h; zVd2M*9|608cHfB!av1S#(e}%O&&rVrIE)m!+!#tl4%!H{K*in2}=uLo_pm<&vn6+k{1jWT2+StMV6N)OsN{S1A zGgwQ6FXZkIFgbp3;iiBfRsk6q7lW^|Dh5540&vw}GzS?Sn0_{n{CbH0>z6{VQOHqH zr@|H3)up|rWVMO?$4LLW0k=CaVVe1peP-83W(OaG&p-ZuN&nJPF{+w|hQ=P~Nb4X& zlq-D+Y&0Maf`JZpqeSVm7vPlx?IAJ@NJ-|51gPgyh$`dF1jQ&aUKAKfphIUQnb(ztJu{cy`k^aLjkS&J2hJEXvpIPbD-YczbcN zj4mY!3V+Vb2)H>qs0=0C#4pZJiGGj(-ge+8=Ks<#YQgUHTUKItnLW;vDxzKFEU@X1 zuszdYS_5$0upmG-kvTslrQeFRU?1F}k@Be8WVe_w;IRXp+|vBqoQO@jGAllZZaMHK zic1)nL16S)fEI_eIT%%uI|ZbffolSw2_z{W-i|Wmh5Q|$YJvqz$N?xvPYLI&R8MJ` zZt)j1&`S>MQ~OxqO@LLsTdFLSAF1WFNnB+&_b-1+ROCidBWF(WBdxTWnV_arkGzS9-!;VXW}?-L|3@2Ph9%P?TG!Xb&pPMJ7E#XT_~V9albHsdZ=Li+r1~ z!)&8UZpO!P=OzPg>Q8NaL3^>t%rb~21NjxK&=6$D(_vc9>3JmN$v_bPtkc;HJ1|FX zz)UoE=$mbljUm=V@iKQbU`^(Vi*1f zWfy#ZSV?aRn97jZ0=;fP{zfD_|2aO#Vy(DKq*);C+}4$&p*OV-uQyooZGTUA3#6;o zg4PVu2q4Z4UQ0vYWcc{_glGvtG-_#K(f+C~rgs@QB&6b@qXP{dg@E05>?oC8@MQ_N z=@5uc;lHig29;Mc=83FSk1JJn3l#_Bhh+oj+(l!+*5=BD^4W#i7Zr&WI!)MeJs-dH!%dUfE28%clPy}7k87B&!q4V8E z1&O=_i|J8(N6=j-@5#?fwuEAa?r>)!E0HOC-C!fdntp4j)0t9lfql%^$!CjmudEDT zjwbE7E+b~ZLT1@2D^Ku4r%mw^#IwTHu@8DV79q8RMnYS~ zHyPyzb(wucDs9ukRZmPGINU$z7a)EWL_q8Da1GBQatX8aFMj8I+9;xChq$Ior#hpi zZOrbYWJBQ;2CuZC+Vm)`*W>`C%5D&uVwye-UzvR*zJ zjeNyE7b8+k{KHV|jL7v(QKx9y--}~6!Ys`9(AJy(JZW}{Ba?nrU^Q$Vd8tb;wAj1p z`|^*e)m^<*LQ(9F(JZ_3y#cFWi}HXbsc*ZvyV#tGbHu}k9#wrC>kJ=xJb&(xB|M0b zwl`m{x5B;D-1?UY4zkI2+pGdpg~pjm|EB+v=H z3#QhyHOvry

    79srO4qC=<7!RxQg;1?R|NF44Iaks~8@tFD9FMw%w$m;FsVR|;D~ zGWpPU;>Mt`+5>t;IT?9$TjA}jRrJ1uzO|etbSxo}DhE+vp1_Ll<`%i^mk%noCb2(c zi5v3UQuf?-R=S-$Ps6Ez&X$VDxF)o=*_1@8Ro@!D!ZY-=$$}yGmg@L3j1Jlztd8YM ztVBa;u|DM|FJ+%k>Yzw9F#TbYyfaPvksF;gwL{@#zeld+?Ydt+R_Qrne_Ks_;qtgy zz76!#+Y zN}E;#(P1y&N2|{2oca?d>nNKo19aSmc@$*|>I3;9)j4Xcls;wSAI~torLFxtt1(8} zUH#JL$j?j;@1;sn8QSGa(lO8noc{)?A}n>GBR1yF8ZA-lk{pGiIip9@{AHh?`_PVc zlMecNnU=(mCqHK ze?Gb#J0Q;BCp4Mtl~e1@)uG@*P*6zoF+VVp)(I)%j*>Y^m|2!NwUH%yPP=VzZNrol z_>X}v!cFkb=C1-LGiH=!<%821vXO#B;&-1)XRaSx<=z~`4PyII>(d{FIozj}+cYB4 zc{ik48jkPumnps&fTYGMSEz8Rl%ogBOXNZJ(}-gOm`6URhu*eZjeUfL5~ZRVWs*QpW^9OkVi+WGA&x;!&_Oq{vq9vD@gc`_P1=lcHG;&W{Iq zeFu_I0SP=23WL zXX{&?$hWIC&|##VXAl4=1_V0r_LnaTS)LC1#8vb7NA_$J8 zZQP+`FqFu94Ko2(`kS~oNLf__fp-By01j`McpIGsAh!?x{8)JY=Qrz*xmduGd3ydD z&esee3IN-Lf+seL*ov=9=wGqIQ9*+v9oo*ir%1{vWw}QQ)KsS>R{zIj#JcNT(Tofa zMS3;VeLk$*0dTX%`N)_(qpdd8TBl@XY`oNpU77ts_FMS?BYx==%MJM|j7i)V<&(lf zd5z+MXTmzopeVWs#7NBA0TskWAP)IKW<+NTlNLS0;=gEe_nVfYzn?Xn4!3?qJin^I zYKc|X>k$vWc}DtY-UQlOuTW1dv^}>^?ObD;`)VENkve-!@49?YVDrM-{-}>ar^&P8Zlk#4KerDTUPgk0 z?fJUBPiaS86FCO(3{rdqH6@eV_G7Fq6FRdak!USkZei+|;!jJB{}B=40a;@;$pv@I zZzkJ%L#PcHdJt~S6=`+n`q$VJDSQn8?Q>JGP{cm0ofBmZ{5TgP?`(nQESw69m;=(%GVmklPS7BLq^6ONP z*=Zd-lrUTy^R8DeaLPR3N@vX+NLFW4DboS{+y4HYYPd1sdA0NNdkH(4@sy2=i&k>1 zr$i5Sl^Zc*?GELPQxEZPuv8UHY8Gd|>TDhVy7a8P6Kv8j3F>iae14y14$;*KWD4jZ z&a-l=iHjrm(K_V{G(W19&&k~(v1cF)+2;D*rmX;P*Ncgh>_H<<7m88!u%8R-ZWIe!#4=dyG2_rk+zMEy4S-H6|UxovbhIAc+ zbpwK-R)8uDDuz=i7S`H5&{suu7NLp(=>*`m7;xA?8zS|pNK>>rTPL!b7FrAh|9#z? z3dw}<4PYJ$Sqs1pLZCYil^`?I(~NnV9)M*4vJR=8Uk=CA!1V-LJOHiN2eXCP;&cAE z!}uH^jrgx80~`qGjx?Yr-F`A(tj)m~VGbo-&?5pVN6Q|(;SwhV@~n_F z{QL+x=$KG^fg*>7v~ST43+k1Vf`We3znLO@@IoLI_@-2)%Zl&<27laR3q$Vr2lRv% zGoOJr2YwSqIUp90DF7^VSXuv2LWRGBQ>WmiuF$U#G#QBHBaQ9Gx99tr57#IEES{H0 zo3ZXe2??r(eMkY}kK}4>xgA!b-kY}1$MCHz9BN!&H5l!1inl2;TUd8{iW6d?!zs+- zS=8vPRJ!chd?eJ_?qzat2}=V?T+lsYx07wL&dr}-kXk6Kp|v#_))X3x7|{BNJ5>7p z*+&+X53VDdgfhClw=!5KR&)ET)n~`$RHi_Ka@J$wmhTH>l!(!DN91F7r$%@j_oLZw7JAnY-0r= z0G3WlsLHz?D68`g&iSeVzBMt_I zmfS=}C)s5|JP4^~z^kPo);ZHvAN;sWpNQ_qLR3%ba>_n;wKIQ3fHemYWv}T zE=|Z=1Rb<>*0`t4u(crExS*UYTw{l@0=W18bE6p9022*ObM-*4=fbv!L}_5zhxSU? ziv)mYhT{YDY>Lcs5_zKK296Cz5pFdzPALPc)9}5Q?<4K^N&vAFN*2-rU@FSwS*d!{W{C>@PT z*(1mKVI}^rahkt~ zS{B!4DDpof=ZD+*UoGCai{Ym|tf$4{z=MA8hIpHNACaocakC3>G0qOb8ci+5%Lz-a)>qGR9jY;gNBO(7vU0

    j8>QzMeS-BA5Zw0)sJ&QBxkF z{qM(tS6c)Q<+li%Y)e5D2?i9_!%9JIyxpZ)!P~y&?yF2SJhwPS{Ih<%x{Gh+jjx3M z&WYW!vf<0SWy$dDK^c-NYsT=aTc-yz|04Lzp2}MPc%6I5MNIlb&e^Fh<<*2a?~snY zA)!I&VA<|%%OkP!+qaHRB1Z=82{VYEHAc|!S4PSXZ21-)e;q8d(7cDmCbTmXT$Q1u zzrc>r3O8$I3rs=bf8G8-no(UyXY=VxyipgW{7+`x%TzVl?BVD6e_Z9R!;*$X8t-|yTf|2j@5Vsl02$u2t)ZNsBuUDz z8(4xz%nCaLh2EL@M?77`y%n%qb0}HRH++MjmD%!!UOizb zEn1@N;Uo5kTfeA1-H9;S>Wy!4ni$W@H&JBRE&D1MYpHY_RmHN?IXwv-?(pt>)sx9s z7QL?OG}}o>NMieyZ2Inj4-b#M3b$IkZ$@owQTues@`ajK$C)(~Hx*Qy}%X@FEnKnK6?GAN3rhgT-D1{G;CK?JM`by+4j&}7_h^4b;!PSq0LtZEd0-alTuef0>+|kK+cwv7gHX-{-q0pMRri9h1p;!7zXoK3kfSsWY5e`4pc(K? zI3$&QBYY&~BqmoNYJPN-3$#AA7K`{0(F>!Af_u`Cb>CVY#H_pRErAQ?LvWU9R*O7O z`SB^D6~J`hEZ}Fvf~X3VLjpxBD}veFW{{x*pisM;Wm6USV0UlxvP0=6X~`s)#(b-8 zg&t&>M!7jbFbc?!uIp{m;*g^RY#s1odj)KJfXgfrdAs=Taz%lZtAo5`<-nH|w`?p` znN^vUw5dvsIa?7&u5}6`L19mN074U^_oT;{&yg~v0kbPX$VImnocZ?E3uqhAJ1m7k z)C!X8{&!5|vlzMkpY!=Oxj*ayD=VC@*`uv>OS*pJ4`IBi~!W*o^Dmj7(+KB}^Yh>*&FM9R9WYVW4vPsKrPqTg`<}=5f#o$@4#l zRDFoi?Kh`CM#8=Q+rI0^>(|Hcgyik+F40BRQiLngP=Z|T#}MI@U((%?4n1rL_rLAf z@7Qv=9~0K#@z&D0K0p6p9sb>$hR<%48sF_e;aybQ<~=cmXwzU>wL>a$p8W%sIFTnS zf^-nOsk}xuEs)#40a~&0zI8R$`(X*Qme1|NVHo)_B$30eh(=f4dl`TKkDZ_OPwsfR z*dkhHr&u4sqBcN~wkt$4Vd-3VhpWrQ!ZO{c!JOSi`ZDJ4VF%jvJR~5!l6js0;+yT} zSI1PB$Qz3|Y;=obNI%w8Cdp`GEUwuZ-nkF%lnf3bs7@cKy={mQPfLhQ*XFiQkdm!; zcaUkdG3+A4#prMR`}Z$uil;<(_2rLh0Re%S^-mC}@Dh~ul))9m{brzN=(84t_SUv3 zzc_8_A^hqu`+}gK0#gY?+FMq)p%X_n*~u@kjMpSy;g-@F?8F44H^Jq5TgUGZzedkf2k=z+xri-QXK5~ zpqxZ{vr5OQU}o_>*=2%}0TdIkK5>%ouecjJ%?dKk{g=twpI&*fq4f9Q`x6(c`PzIX zdxmEABJFP;5WorvUJ=V;7w4_l_mKT<{M!4iRh4BfH@_kF9x0X8w8)&*wL^QP}Pymdiz}X#2``r+2?;KnNtk7pW$f1^H9Yu?qM4Wn*ao2bzEW} zpPnoy1_sXwGzQf3Yx`H_xBkKK5*wu9>Yza!O=V}uh#ZH69%_Z>rapuiLBcWA6y|i)?Ic3b9O7dNeUPy zqPBwlPCn(?O0!^i3~2E_EjM}(brYRX3}JCK%2)^}3gm1w7!gc)A!7>kxB&VE@^him z>=G%FL%Iuq*Pvd@wXA(X90qz?2Ahhkbir)=KI<{%wx2~18sdv9k3fGb9--z*e$i}9F{u4bKB@L5MCgT&A@_|gj* zoCelw0H;CM1&a@$E-)y<0hzzP2VEsJ8R@WSpuPoq_(Q&`hPy(qzXrvD z|3$*x)INZZ#w21MBW_1zqEib0?~3PqFKlJL_v%}=l1Rhib~viYH6kfK|k zx4Hj)b9mJqRtB=a^=D`7k+4d_gZ96^CVa$!&*4ULE&64U4C%Vo0Y2RalTokWFU}i< z=jBzmhTgqt9bXKtoLJr4C#c_$`;bRVWWh*BUtaGE2DQ+OM} z>*tf!@h9k5hulZ7$biJnpe=$Ju3{$#^lk$SVEYaQGim4e9Eq?A-gpa818`jg3b!~I zw_)ArzAk9F>sz-ic2Hk1=&|nm#{VfjKLu78qjGB6MTJJ}pLVIpPLf|U{&4;b-{ZTu z)znhc`84t#ZNbk!NhLcOU!V2yJY?p4nWmh?h=TU$jXbId;<@Dd%ExbuD=m-G-ZXx; zc`nq~kvE*gzCL)|H~*y4?efg)fA<#jTY;wTRSMHWTMa}lOsxSfQq$Us0CNpQnmoft zZu=lhkO#p6;_5fTc-~?8IbCbU|bny|`1 z-o$6RmyLNfg>NyLo#~B^#^KEh&=6Fo*usW{Ord~RBY6JSjkOa#iU$>#ho>7KPYMK1 zl?UAuyLWG!@iSj%W;@o+Ct2LJ&8MpD6i%)v3YP1%h6`9v?WqMGiQl^GmuX)7z$(3$ zTb)sgCC!_KEpI^h28;c-!Ji6+@nv842rF|^Loj0oRG-Rz;QcD=vOE5HDowx|mwV7! zn>4%W%fvN%59fQ!Rh<;YOC^#!MUVQ73#xG>>YGAa=$^S<- zZ}IzUuaxKvq54|anot!Q?C)8Rw<)wFUTVJbC0Xm>y}MH!vKyb@F~|4m<0ZX|Bx}n2 zT&3ND=)rf^{Jw&;k^-eGC(Z+c8j8lSOYQqdH=3MO2VTuOhG+_YcM_;U#xC5vxGm1^90YUhRE znRBswG##K;BX+)3XFlR?m1FNDa}F*w^l!J0^~&TTh7C zE`{lYsc&{`deF){wsqYpZ~l{e=JKdl^0wfOl-sw-Pf>$!QCkz&(b#I^IkZz)8#;lW4OVJ#XL(nZ3+L- zZqDq-;rCO@R|k3gyhW*hQ$RjlPTp0OS5IuTRA*2eDmcGWThoa-^>)jMiF?JS|4Wn> zn)ce=5=xR@YHl(?*`EBITq=CrS+-9ZGv765hZ7n)r9G`Fnj(2_H1=@a$mqc`_}*L+mzPyS@{PI#BLJAzq}V`q)@b{>t~(@NK!l(>h? zZ0n3lS zphgw{(T~PN0aeu{1EvR8GzfP5dE5RxR0*#ZEn~YNs-TAU=7ajnB9W%q1s9{!`|asA zX_eAfQ8Cv~!Z90rrqIez7lUJ1&+g#L+tV~S52ketOmiJKKW?603!m+loG2&Y| zx=C~Iev{Gro-W1I2PGD1V{Bk2@T{7niD!fL29BL>U)7V#`RhQiD~L%+Av?Op#|dG1 zLWb9*R|iDGA?U12l9D=3R?GolBQiTb?PcC{WE3A7yQoDty{;1V1y}mFRgW~)`+k@7 zd@Y{2r>B_Del}^=8X(WZMgCIlZ@TZlf3qHou-N!62nK{Qu;}x@HGLWIUxH(HZY~Qx zGMWjIFXa*VIX;sP`($1VPF={woUD9Y@u*UnsR;s%0bqt7ydJ}pIqpsOlws^?u8AE( zoRv*mY8s6Ph<2Z~_{6TZ3j!bHB)a{(-@8*{!!34%F5}>5G6%~MY-YfvK>Vkfoa)Z| zUM>!`WoB*F&F{v*Ex~NThyz0>`OEuLw z_MDvTBUw@O>{ran-7jR5hr*LydOk?zQ6#^EmreMPdG+jLYAQ>9LR9t~Hx6vaa^w?N)Z$?-YTF-S zr(0BSCBjE1!H$f;qXhuYA z8oOM@JiT*s@0!VCrKo;Vuh4Tx1n&H(t8cx(nA9%okFRDYD4a`{Hee*~3dRf5Y9-h- zwkB=Bv4h<0A+Z@Uoh0(yJP4dihVPx9{Qiy4&fW|B1zu$F!_|KAk+-HU+STlMHh_DA zsu1QCxPKt#0-$s#7ei)ut*sdt85QeSy1ToBAYN$m?RntS&SztQApSu^Q z9v}gl%BX%=p$|I((siR+#tdSjNnXKR4d_(E4I@uY)&1Fg#GIPyT+9J0{D^EnpOC=l zQeWz$V&%^R&Z0E%z=3!C{*W7O0l%Qq0ecXQc-Pl<^Nm^hhEsWXV-ue2Em+;>S-%eI$QhB<(G_ zE{83NI{JOqzy?7_-E*AsgY8g)e@7=^rxvS=@e2B^Q5nU~?ia$H#Df zBiv4bE5S-4kC2_6eb{FnqVw|dZsVYVQvfNSx^w3aOcliUNnqlE5N`cZD0RaG4~A4oK8@T z!CJO7JAWlw-FgM9VmLqoU(e_MHb?tjoYX#f)gb%-Xgcets`9ssi==>n2uO*5f|PVi z3y6R;2ugP>#CJ5aPqn zg3uJP691~N-|jd>=u)BE<752^ux4oU5K{!(szf_Jlh9cxKmjhcy>d9VW{f@7~!(X28kkizk|Tl#FNZ`mx|3dA*}%Z!cdufe*$?7MLjAI7%czJr853H?>|#ygP~ z(zdJF7w?2lS-1HW>A_%R7i_p9s7&mSWBdzQZKf_k)%NGeM(?c;s?9ES$)B?wkUnb1 zYl!qohn<^!7^J~|vEtYpaOxHlrPkl&#AUv-_JZ=59LokLpgG*6V)ifGA${heEM!aq zeA@#smgjpDFP(EwT}--jXei1j8umzQD%W{6qQZ60MhzFNkO*~DH*05C&Hy-ex>?c( zX^L<^KvUKyVw!^Pb~ZaUH#gTI-sN<0CurcC`}N+(5cC9YHN~}BS4l}1!FmcD`5oX? zbH2XhgR8<2V(%coorkJ~b;)_%9nN5=n%CCo*X+lCw*Uo_F7pR)8n(7VE4MGH^~eiQ zwEFUM{~#!iP=SM8sD790<^%SE)i)hEcyz522dzM$3HUP-$;2O-t~3UMIaR6Stk6_|BE7Q5)0`ut(j4MC|Y6uWIuth;$2u%7A?s{O`RZJj$ zwcdg1VS*Go&As*D{6tLmeqXqh>9QmpYw^)VqMBNqQkIPaiWaHrm>V#LmGyLlUnO1+t1_N zcyJz%xfworRCn~L;uWNaEnYqaB1o(I!@lBB-(QXebQD;rN{dL^S!vvW1;@E$HW_nuUqzo%58 z>Sr+er;s30z)xTL?$uKAoAzOzz6pC3wBmcldV>shd|^z{)Pxyavdd9VUe2*yO;cD5 z)iDt>J>x}D3;pxkkS-4k3`)zzYNise^yW}-8Se8Av(uweOGWkM#S;(YRq~@U#YGuR z;OM%4h`+>TqSVuROM8`&Yp3M>H!MnRiPWLa>_W=o)KRsiNw14xRD(`7^hZdjxBhq- z{=3Ki=#f@2gZwN05Yg%wc-_ms4GtG~)X^3W&bg|g4scll)&xRQXUr>q<$-ajVES#WwxMo`BoF~qPB5$^{ z5ZPzz4)a~PV(tvzOo!f`R@1vFOJZ8_LD2d({@t8%{mKJxeNBb?BG!UF# zt*v}(VrkZ~+5K&_QQhzHq4@!7m*vI#m7IFw-#5vu|LCr`(5QUhr63zcHAGR=U*hL4 z=t%t9lDu7>!?AJEa4GToeeG?lcGun6w32&M4W20ok+od*LTV-$QCD(SUkYDRJ#x2? z+1h%xepIbIThyhbrb?U8IbdD}lUoEOsrIUOVzS2RD@<+oT^mkZ0b_25AZodtD%2F- z_qOB)hX2%*Ae@;B(l&EV_*kE@R4lmQ_(~k{gF+9GHE@FBB4iYe|I1{mz1;tUD5c<0 zAauU^c=~MbIq-j>&w+B_^7z9|`N8!ecvDNj6;OA9z5xLR7%NR-XQn`Ah-M!)52eEd zu$X}BaR}_T0TupStUIDA^x-d1bf# zISzJb34Yuq(o&NrXZR`!Y;l^Oq`bPtGD&~g+n~`C_5|U35r}(H&j-qRMzSW;eD^Lp zKSI}%lmEJEKOm0DuJL1-vAdVc^tJHg9_}?UbS0w!q@i~b-zVe4het?gQ%Z`O?oXp=qEvIwnu(6 z?BSH@x7jno*$kB>sp1Qxs4RQ3XTFq#rg)5B2qAER&c^7DlG&U0-%U+**|#*T zY;3%0k($8U4D~Jy0zsqjFxFh~!dGvxMGa~LFwSRyETPZhsIBfw&;<9Sj-l)=Fn&k| z)}lVk@aIpR-o`1o+e|fP>CYQXj2&P&K-94b3~7W9*~aG1r?0}-v2(0Xf)8sASc$Ez zfA#hD7AW4w>M-VL%g-fR{h?O&eO8whq4P$^-7cx9Xb0yg&;<&Z0g(Ygf;lR1YiUh; zTv);F1=a5okH-R!y1M54JcJ3>ehg~=`liF!?$q5OM@1i;!icI13>5rH%qbq{^h(m& z?pvx5O4jOmRp{Amk|GF6Dn+%m-L0Qvehja-$z@;|}lqhr79nAqLd!QT<%OxkWh>3+S8FBw^j1)$~&3(Fyl*`BnuC5wB zU%croqLF+ThLIv5bv+Ig%azN*qxX_}CDo26Mu7H1VO`Mwn7^0G?^d*E3#!6vfC97}o8_6^N7v1s zsl(=b`5)XrBL=WvzrLI-b3b3p#<7N6IGu|!odp&E1%N#ob`(O_rv@wQ-3(iBR&>(` zy6ty91*|dltdcb1Cuw3`teLrDj$zi)hu;s( z^Y?%Ph6ADSs+a)42`l-!BtXLWcy#`4O@eIf<3SHkQo}6#I5%a;f50V@fA2(FjjO%w z43Qdr>$KwLcm{EL0-6Lo>7mt)~ z_g}i6K6ilYmZkpmzfCt>)!QD&qkTdbo89i4i!2!49B5X;>OKJ1wZBhw;Z7hSxg;8( zUAVGsmNFuD`>M+-rH7e#++y6oZTMLN(c`uUET?_((wXF|`v2pXNS>Mrd1x`F{EV`V1iI}~!GW{$X7&yo+kNi!2lF4a9LDYIp^jc@;G>T03=vTv zvMe4s&1!j<+1svu8`-KUdYqmdtZZQ9gaX<@4H;KGPM)wTJf$tSU{0rYx`3 z)jNa=9SmZ@Dwddtpdw^L8@h9XV7BdD)o-nr9zEYizZhdt{>L?ceO-Uy!AoA5))cT`iqEeEXE_Ze-|-`0_*%rKj*?N_O>tR5?e*T)gU!oFfp{ zFAf5P4Uc`ov)3V@O21QSiO;E6BOK{)N>7Sn0j9Sq5`b# z5Ioc-s^ib%li&Bai(fAK_R4w(2`v@hKfe}hi%=<2Qki=l1oURw`QD*d9M;|#rO(N! zj?TtgGi4h&&?8YvX*oWRJf00BF~1W>T$%Xu4n>CEWWc>JVvVa65mONn^|JdLjxTPu zAI2YQ{NuG+@Drn(a>@}&Xz&)PnDKfoY&7_qx7BZy_*-URP|~9eajhOvD-T(>n)nZ! zoLB|vRZ+xBWi|4@w!aEkO#bNa&kFuP@Q`gN>GcEmyB5A>>v(SUpJ^i=CGE}Jyn1rB z@`=r8s^L`zJ7qAtv9!({x>e#MHj1}0fn2hfSDH#6joO)(>HdCZVffePiu_QDDoBb_ z7+oqXN)TOURJOQ_r5<&f=k5iXB8%utJ$~Ft>m@EPh74p@0iXImku67QH$F-(?%Lwl zSFI#=6}X|!j&>(ZU8N7t`Gz|_tQc2&GBe9Wyzt8=Fu`{|p)Ge-81XkW(Yn`6!pyG&2M|D|;#bF=H*-(`| z$G_`lhKHTboMp*pN2t9z^Q)Z}Ghw?9U64xB>*=F!#k%of0|bxeZZV^W&@VNzVtq}z z(Rg8CLmYQkI?cZ=uV3SAR%5ZMjMFM(WnIa6x1UbdQO>B$-P_95_tm3!1-{m6)EQEf zUobDG$#)n-Ly?UhTdUtrH{;3DzF4k*bk*C$RItNs9p`#9(f4HhP9k+gHT)iaO6*== z3?q_b$MbQ?T011iA9_BNqA{~PXe@suP4n|hIg3+R-Y0d8JXXe{zhR*fcru3Mq_LI+ zL*)y67aGlmE>B%M@S+aeoWg<$88WGgMcO1=yFZyU$tbt1+9lJoEVN1`T|~O?y!GPP zs&EP~vgy1r|7AdvkCJ;)^F-VG2}!#MdvqnOTI^lSQ(X=AZ#I3Do2D;Ta`4wJ@ts9^ z8k%ap)kHkJjz|q-ID4J57|GhV_*=CgfYpHE2GcP_FW2W#MKN;ET507rRw-5xLFZdD zeyMSnyCm5dAqg^>ltjQn#ra7@%6wmpGAJnU9#MgcX+?q93m37L(f+STv+>y2zKkke zf@#|ayY1*Y{yMLSNnDY{=qf}z3OdKR{^^iUnwr?V-NbxJs9GNtSp8gid6tV&;7PjX zx|QoUaC5#8J*mw5t7loOm>ajjGQL$>l;Ck@?+pxQKp&8p+6NwT{x>@!p4+O+YY3ZC zbX*F^R0ZAiY)Kyl;D35y+^8|Z^mpU<^l;F%_MrDUz<3e50~lQb7O1Yyy~%o&z>jnG zI86BFKzLW<8{@5=uyF8;mkfnT63 z!^?d79Imu!fAd_~Fn=Y~E>)?uJj$eSCT6+&lE?!jt*J9Fvx@y#|{n`&9 zK{Rn+0xajO2U!}48uMZvUW`37S?u=@`Dn+tITW6fpE#}I$cu=TtEUdXFWzI4m&BZ( z3!8g|-v7D7mtKi23X?BuoP(1^JKbf8XyWS5PZ>$=ZYUcrymK{_Y$>JBcF~DP~H^Sbl8L+3^uCq)zX1XD4^_+}|;q zyz{dB1tM}+P%S~Yo}ZrtLfj9b1ZHcu5jbn0ma^)LP+3@P*w;LS*(Tt15YW&c&x}Om zR!^!8OM-f+;$r;7!_~+<4_A>Md0w)C_dvf0G8rVLpYcX@W1bIaip##Of~E|ct|4}_@}w@00Wu>!J*ub*~7yq02-$Xr;cnO z0M~qb4;g!by#&*KxJ{sR^%AvmEv^h)%ZG=Kr88N>H>FW1$W95aa+97?}9Xg!Qibwg27Cbdi^xX6p^WV{n8uB<};n8OrT@&ENol)iV z)BGe3495GXxc7wgNrGs&SleejZgOcOYJJAqUDYpK&JXDk@=d_~ zI!P{rJSth(vlk%SccDGJnb*0*T8UuAegUZ!7NbnE2AL`l`VQo{rL%(-1m?{IWRoAj z@_so8p_FGQH`g;9e0&JwG_+Q9!Qd%bK={f*Vl|71F$84^3<{u}l*%4NM5Ds=`2a{h zDS*I`lam9^545rHWka2a@Fo|!EinqXpGN`8oKLrBpd`g@|IV4)^jSx8TpUDnq(G|y z8nDRxD+GNG=K5gnxy|7!rB3>n8p1Q>MMca#dDMTVrzv1r1|Zz!@~X0KxD0H6LhQByO?LNhI^Fk? zjiewQP@_(4@t4sFQydGac~|{sN(@{WttxmfB;;sja4?EfYBepPxHyz%nRsRKB}R0E zVxYPz5xzPrtDd{lTYUcnSN8VUl%$<-6WZ&sxDu{Cel2xpRk$y|uaMzRa4`DYWF?&w zepvLI<*7$CPQZ&d%bQLMU9L*fK=+1_7pS`5=6@qOHJq&CmIr+h-1EzDZ^9eTRv;oC z(|pGRc^>c-dJkKf=9JU3rIx~qg*0_0{w4Yixk8Wx!}SD8x#w~iHd#3ExP!|QRJeM8 zfrG0i+wm}I$1MP!lf2IFo>LW@0j6?nY|Lh<>7To>PX5G%SQ;YF#mQ;p^`sBwEc{)$ zqxI9%*#8iRy>YIi0#*Rvva+gjx$`!u((IlzPT@--F_8Y9u?|FOUj+j^y0SjxjC zv@$**Rt`JlGMi9I>P|+6z&1IJ3%dXsesrZCU^;Or^9`N7-}E_K6%vEKv4$htIKrH!>vrEiAKhdYxVk&|146bwcn8yg#l<)lZ0JRH-ol7XC& zB6WK+b3(0&EpFh8r45_gxVd#hYXpJ}5qb$2@xVeWGV(qwqrkHVcd-pTjG-`q6B00Q z&7qNqIYU?7L)WqELUktnG()WZi}%4YnGqX(P^EyBPOIvZI!vEZ6(pl&sfJ=naTh#o4@5(F1#oF%=^zr0A-B+cwU=XKep z3lP~nqPxJOJjznI!czbIP_qj16MK8V z+KiEWTzBeSyemduQY^9rc9?-g)uphR2veP6>n;5?wpiKt@~O(;I|8UB_6+${bB#_9 z;^Ez(StLk426m=zx@Z@ZJzm>bGP%eES9?U_Df{SdKIW*sXfRCD6dK!3G>9m08?)JyIr zA{&zOxVOoLX#Dl84OaM_43d{m%#DJY;!1yJ5($v)$WpCY6j5f82>)oz1Rb62vtPEI zi(JpmnfUHM_VVf6J)oxjQpRW=Wy|cI|9L?@i;@V9Hd2c4UaJ_H`^#BQwgK9A55C!8 z7lnjT4{Sx?|G-d@roq!E2$!ZYVl6&W4PmH1leehGicxEF-Q@TYV0P{&^}S1doMz)p zfAJ!N&c(n#e9mXT-ZnPXX{W!aRfD)WBRy2tHiN{ASd-~X(P{4ftpd9=qVTB47q!WF zYw9SGvtLmq2L`m8KOd}$dU!v%6>N23ukCEWe^A4^8(YZw?FTBl_H<-rI3O0S>6>fSu2d33*f$$RUDvt>E+ zrt0jvg13@(tx)K-8!LnJQ5!UgqNl1yc0PWh?jl>YJ+(TE{Ivd$ZGJfje~CQ3QbqT4 zE4=uzSBi8x{K+u=x8F-o68Xgggm|pCv-1wPXdzJzUVLO@aKnNA4MRqcOO94Rsbi(nq{PT@tcvL&U83c9^C~kil!v;GL|a&= zPTS5g9;78uC&PD|vqnKYO2FXbn4~ zWc4fvKZCpc6MYjA zMD^58h0%d%0&9p&#vaSgH#;Jap}4|b_SWJceS8l$7S`KvRs-(dk#&dn4TtzVI+bRV zFTPR!+YmUCOo9{vg?!Z@eXaK#aUse1GOx%ts^dG2UptdVNTcG|hJ44P8U%TnvB`>p z^u3Nx+7-E5lvB)cvhkWiD_vKAKV`x~W6rwK`iE7tm*P^%-`J)5Oo!v9oQaKoeuGV{ z853)}5QR`uU*8M&Lgx}ElhIs;bmn)Ymzw0r4=8U(Sqq50UXku+2#_k0tzC#JUL@bFd;H63xiIJC?-t7>CYN zNY;146x zrlF7?8RO2sJ2DEsXq~fVi$mTm;H~f?tva|32Mx(t*v{lp%7lN_pagS-R0Mt zJzi_u;kWy?17+h@h$^#3dS!`7{LIUCZ(_DKkjw&PIC9R_JW{{!0F`RDpt+GD)q*2#a`;YCcukF}niiv+7mkT{v4RTpc) z{2d6Xh}1{))X~eM;W{@$2G^bg?7o#M{?dncSZ_0`6L$oxyYVC*tIzag2(Jq4T=vf2oTnleo!zN_W>ma8D;!6wI;IKcgjD@bt&B3 z_WViVCS|*sp$VR^iC=q?eYi+Mb-dgVo&P>mf3h&^L$a_}u2*ZRen*Y$1d8eF>+8Vy zK3*wD?b=)DT37VC@o71Pwg)X;ouzO%Qso)r-n#s&X-|MRYhpv#ZsOaf+F4dW)I z1?pQ|TO6bOi!;a(0%dz&7h+klwd$e8adN+zY{)5KzN*G}Me=K@W#_&n>G)Iv>`m== z=K$0NM?a_yh&U~U4SaAP6Jnx5%iC);lixK8>v!mhaPlDe(avX1EUgi;f2%Gu9=DD z^kxTXLmu0hn^|bJk`($K)8Y6}rCxWHwz*y~=C}br&a{C=?Y}?O$s|AC1@V$4EXIuXkGJ$xf-`IUws&0NTgzqGu#NW z`#uz{Zl7d@Vnr~rE32!$V2HMs*VwseW1nm}T-$aR%^-zFQk8*wdllc{xme|;%q07m z9}-IeHQPL`v;mRtUp8enaq+kGOan_cEe|IPjOmlo?I4Xk;igP^5G3{>zP>jsQFCRo?sgJy=^V zsxKQ^1f~y8`&M2$ULMu92C-CYbJ*&!U3&);QvWidCwXude&AK4{t7*NnkIQ#n z$#ZkLg3B@Pzjlwz4_dC{2uh_5`IR}PjK2mYt*1Z89;L&Scp|CT8q1zx`}4#3a3Txj zxVN;l@tSP(NvWY%x|NFm27zm+bO zfBm&pGks<8{J~N@MW$5LxPUD33BB2d<|{lkcZJG>4181GXMaZn0*~rYFmk3OG(=uG z_fBl4;CXpOqtP7@bm0dwu?1hWO^XYP#~yFzg%61tl8y%jeOF*fBs1-_)MS5%)qvL&jo`--%Y7{MF77Udw}P9`88w5qCgrM0&(FLAJm_ z<@hME?X|PCN*DQ$QX9oq$+6bbXeHup%~q*FZ4HO#In;019A@$drMoECMz%io9#zr$ zvvsK7dwfsYT!hPra8F5GboEmoE4gZz%xv)9{+{#QtIGF8>Bo31qqKi+wpc2-KaBT; zUys$KZp7aw6vIj%pSZvyClc8oe`q;XWDrqAwBC&zyw}bh7&-Eirg3z&N-ShZ?8K7# zjMc?os$hBiJ(3V_PJ4@xt});zeom~QG?gAbMe1tl_~3$*dJzVRlz1BaQe+ivZ4%~r z(MEavaUs*a1N%F?H*G{LWR~$Q9PGyiD{lv92o}PAwNx^@u=Einu{lkmX zC2Z3h#@_+0ZAjNTXirLh&!7nXbUFUBQtr2`oWm*IYOHK$tCjorWQ0%>srbp|x+pu@ zP}S5Fi)wPM^rrAnPF)|=06??fzyBHl_EioW;3az#8eT76GnJ*zR8(5p0W3_!v=xZz zN;#`7bYKd@KuE?TA^3a6AJ`xWi4sub6^RBC_F!duhR}^dA<|)3ER~~0pVYB;9A-lnV`{fFKj0~t)z%3gWYx+M4==Xk8h1}u9iw@WsgN6b2#X&(t5b%~U zxCZ+6ZV3OaN_71F)JP;vVHU*vzHyl>C8{8J5vZ&z`Z7`^$yq z46Y$`yzr#?kFgWiU%r%bxrmTffU+C%!~K!XAW9NBojbb6SP=sZ;fd|Rh(XhFuNafw z55X6!&Vl}9^XeqHye{`UKxP3+BW^-3(-f>7Oo;v6K+92kbA17J$L&eyxaUsV;4Ma| zH4wXR7#jgj6lSy^Y&TkAPRK_g=+d2?GW~+Sm9g;hVf<^+9HrE^ees-c4g-+Is>Kzh z8XiQFVg_dlkc3OzQ)V&-Sr@Z}%_FK8#bfwmnn`r)18a%4<7;Uc^wC{WjF9JmloaW% zBJWMk&Zn$@z5gjrLL#S1Oe#K>1hW-8R5D%!EfM?cN0)uy^lhRSUjluUmDUI}=rP0~ zVS(E#Tg@mLBx_=-k-s?MhCdWV6U9T# z@WIZsk5f{~n7lhCyt!LjBO%}`#_VIM()pl^Nvl$dKvF85^_!dt$W$^yT)ru>r6K)< zN8JNv?V)aOCF~c1y@X158C;vjT5S;KknL+akwVv{gy*foZ!lDT%is;j^1cfbhhZ|j zr-;NX4PcCqy}yzpi3fU+#UJ{-hq)w2tZg~HioVhCV$`QXcIycAL3?8n1aL* zG!if;Uk^p=F&_Lu*_JiE=BR-IwVknpQS{MKHi&L`?|FmgXmc}f;*$<@j00{O!J2)r zOPy$y<}!FjU|?J%4>Y%KR?u|=M-=Y5%1ZHkHJDucD|H4Q)6Lv1wH70Q^4EsKzW$_c zrwA@7@P+UZc6(mHfc|&jLxO7rXIKI}4tY*B+8Pj7WiR&CzlF`_Uyri2|Y% zkDU{buOHku-t~TT{`fJ_p?@V;9aXduSXY6rOfvb~o143RH)p~tUn=`VDLkUdobzF!b{fzKr+;U4VM;EKzR zGV-AbX&>(H#ZoKE?Kl0qW)Do^0@2dHqRcUf4+UKd!mq-g&ehn|)I@SiTKZMZlw)Hk zUK9NrB*gXx8XpLM#b~xhiG`RGI6M*Sku-%{oTs2?bZAqZ2c!tpppVf`V6&pjYTc!O zOaeI#NwB3=VK|au%)2xita+OcKv!~Xl^hlL>n4*pz1`hzR400BbAJZ@0eA`ORrs() zm@rm(kFt-PPg!18CV__{=Y>eg1&c9%r7Dpvl%&$4Livg<)Hw6tQDrU0{+N`c+M=Rl5=%huxKW5KohwKDO$ z%QNGT@YDOqtm!=M1hXnB`aVCQD?Ah=cnrWu>x+Oz&D1jV zgJ8sf^95`_2ml0dPN1TP&K+sy=K7>ZjwYX$SfXF*Vd?gHn~zc#lGci7{wHJ~Sn>em zN=`x%V@tBXFb15EaCm?K3KVW8T}hrj9t}HP6%IQ!U@3ym0-iw-CUP0-KndX=6#=HS;i{|4shKOS>s{QNzx1+@ z76mq`UO4yOeKfC_K*%+P&(nqV!RG?cU~fw6_k}x?RmiiAM*x}R^HX_;>!v;&@H=ll zOH~QB)Ah^iiB?WRg`vNWI^=4>9r%*yLEi>T%~XMpLj$%B+JnS?3X}f(L{Ca2$!N&Q z4WD@i?LmiyEEn2HAHLQaW6z&Hhl~}8>ZSavh`A4+&=-Z%?!7H`s;=s5{4gf!Z$-$z z67M15(_xg7e!cS#EwNjAqk?OmPP?L;hG@~SZC~tcHRx}ubJ@nAXv+xk4l~{KeJ!!gI^d9Z zp1yxGzeMgH#m*Y=MRH!Lo#(uDS$@2)$Wfj$Qw>a%B7_oDim88I5&LzB#M|Ddjusa$ z-=-^B8b0eeHBl~`uA;d;Bt1F;|H@S?`|%I)e*Z&3iM59vwW1GV4P)ViT!k3 zRXS8Jhr*40=?8T0jPL(=LwS2n7nvSaRGOcc$wn)VR?5tX9V?ADwY%)#juiJ#`*bhg zjPDbrgMS}NCw*_4fcbBQeQ~G<-RQgLq2KS?rTeyCG zCZ+c3%ur<@dlOW;7CTfdJ|({%Z`egkA+@Yqq|O*BLBVT0^@jFutY60=^+y5hNQ1u0rjcv@3>E>*^TLbj?gW}As*NAHVv7^Nx_s>mRgqh5jTWh-rX zE{VnvnMys;`zfl3d894BqH(cLD&_Xat6Cpn6{Y)q$8Wm0SeQdk$ql?`rjoYK>#Y?E zdN@vac!u_*2E^_}|B!J(`x0xn-;-=I9yj{i;Eq(5JR9Y~7`FVpWADK@fApojHtvtf z&!l{lKi?-kvV3^Q8wI1(s)k(gR?F}oMWbSrUr|aC>;`)1U(QnFl*^)E%~#2ZBZWGi zYNdl3!RswTr$2}*Lv`mdRsoj6_(-|`LNrn*({W-*+T?1N%-fmQmHTZJj!fB1EquvO zLD3~DMfqgr)6q!Ur33fs{`(afCD@>vW&gwNG)A^yy52zPx-Lh1USEEUy>b0(*u3Ao ztn)#zZ!?v$awHRr&VmoF5P~&1a~i6%vIC>P|0GTCJa&J}!|D~nZXsvQtm0jiG%0P3 z`vo_g#_)Vgf0Cicz^MrNPb0_J$R@se9cyOoW9q?vx7SM5gr4*AK1t|N%2$1rJ<#3L z!-rZ*H?YS*fC-ASeR%Cf(0_O)1&@O<8S=xSxUD}(+SwJpS-Aln93%-=*)Fk<8ZG%hs$&Kx?bi??UC1+GiiB(!gziE*5)JJcLjYXR9{_`M>t*~J1BAAQNfkVVrMVlgcN z6@?-JU(MY9e(~O_D&-f41Z$Xz)^>y3VxfTR1#=8oc7B2Ua3Q)~bD~xf%<11b!N>}Y zDs-_3dDZM}*u}{sR=%+;m4Sq5CnqN`NPx`iEhS`;@mJJddGzH)`U1NEnq}FVDfZif zFUq-j%!o(6Nz*IkAkfw>b$Y&c9G!P}sWvt&mPujT$1tWTSMeF`a`107Yie$)b|Ew= z9a|GDin*$wWTb&Apf*tt`XA(3zz8b`xxqmA}TqOW#u;WgG90Q1mpuSB7LyUdD zS}(hj_vCu*(3^dMw8Ew)0T86YY**8J+144F9f`r|lWKQ@Fges9M%@P}*XO9G^F3C1akQ(s4B+rfcNjKQWCi^av*aq{jKiTKzzcz4u%l@!<*iz~Buc}X@ zSYV8sPL%4Ym8dMOkK%mUqnrt8dUT=UIJIjBm zLbqWdVg%JBl;+>*^uc<3GVS_RUifP0JO%l3Sm!F*&j!R>mQEq!iiXbzpq>K@Kr;+T zprt?r>YZ$Bfr}ZVISfQ%z;$Dat1d4$?t4VAYX{p?NlD35Xv7SF)S9x#<9WaX*Lg;i zW}Qnk;^={&Ir6DIqCOVGfN6NR5{?KTOsLfS+DFYC_#YwyOOgd$5mZIU9&t=Hh*;ot z`I}Bj@_5gpkr}z-iQdEXea`>Y_aEwxh~QhfgelfM9DFm7ArG;X(J>5WBuiQ0;rBr6 z287-5gkf_oc(=E-F?C4JM;4nio=6#|ev9#Pe0AFX$q-%uoPxNEWCS1gSX9-ke)Kx9 zttLxn!WbYiIr**Yi$JeDSW)io&NYj(zRCnt9F*iR@dpeD7y`Ep8^bzZ@n%oGkL+8? zKTqPzej=cY*7;wUt03rutoYhWpL5?VSH~KTOBX+6)UP|couNB^_=g}OVx)!qPn7Gv zAQcLj6w4poLd|na;7{pvDo!R=XNkkL3xN(6+9{n%|12SrAIuouUT#__mjKg-N9WYk z)Ca#F*)w?S96UVjy}i9ylq9UXpA#&(kw_v3+uMqRQ?E%sewc5@0AS`G#2W4_J>nu$zjPWRS| z-)zgVv|r(yWcY6N;lqUMZwQ6lw74NsPVc9T`J?g6%-wy8!G{D(QQ>Iz{AdHnm2g;o zTnObs?BgI>{1N1X^tWZQ7p?9fr+DYD8K*+Cvb}b67 zGf?kMn?Rf(YebWhw1uLX$c84fiB~Cfm#}=zPdwk z){6OWC@|7+U8X&%*qE?UeF>oAXV5i5aAHF$Wd6W~1M|*Z_Y~-gI+8c0rzzl|1rt3h z8{6--wY5fKBPXW^Gbd;1!sm}YuE9=J#Gjs%{$*izwf`|z*|$GN&||`&vsC09KEamU zgHPc594qEBGK5u93=qi>dmt!7fc*s?FbITw*AV$BtE%_Kix=>ACo15(Noa?$Jw8z# zM#S%mlU8_ZET~@^WNw5ayePXf7$sF?f626@k=^IzDa0T&thnWsuF@_rGty;9ujGN* zCqI{ciKNQjH+V~o`UlyBVf;v!fq?M;YXRy|6taBIaQI`hZ|CR{%muRQDYxr}^|ajE z$_c`{p)b4lGUanorAp-MzGbspl)sRwd|xMcs33I(N>%fQ-x)G5dvuptoU|S*-{qTH zAcyFU)LX{(kA-U35j1_z{Qc+Gipy?fWmh5x?UgbJdJWKhqm={9SB?=N;y+M#4m4);vdKTy@&_VX$d`u6>l6jZUlyAjvryF6b1TrE-7?72ao_irMUf2?uE^o~}KSnx1L8gYDHHyX+?U@{e95T7W9 zqnT5?)<0kf85((AX|BkjWR!7)F`RBeU`YIoTR+TWt zCk7XPd`U?ple&-VIxkvvNfkoa3~nQHjS0~s`O`dOEqj@c)RX9SV&K4L|ENnOCGM6E zbCY2&>V?eRdfzN&^H`>0-8h*H)jjHw*1Ji>#!inj7Q7Yd2K!zMuaEYJOA-A2eERj* z*R0!`sal7M8JtJ&JiGf(3uGHdNd1Q=)5rY^RH+|cP4?p@EAf0LB(zE&P>8$bkndM~ ztia&jq_TEO8qY$z?K*JGc>aN8gd}0?wB`N@yS7w0ioFw2jMQY0`-Ic|*6ZhyYcd&u zfB3hB7U~r{K3~0L4^ZdQw%g&j$>7Y?-$o5`4Lj3k=a_Fgz&g7rSNG5V!2f7o?7hVN zb(BEt+E?sSG9N>qU;{B9gXIIdd%quuu)ldS+=(qq#CR*X<+Od!4yo@zKdk%6+Aq6p zTnyi@Yg`LSe@;X&`U`0aMmo9Ww*2{cpy3`);>9d6$60(8dwJP)foP}Gnx|QWW9+^> z=lYEVeK7U;RdO-+eSKY7<7I}K%$qZMioutTcR}WjAca6IIK+{tmAt|`gnwSBXt+w0 z&cwt3SyhQ0P)W^TkI<5x;?X61*(|J(uZGxO-^>YLq6fE9{T#-G!fnHB`OKQYARnys-z&|+Dc1IV#O3P(z~jiaUgSQ;)P-fkuSiHWInydtdW ztcHUS0!QExJ5r!!0Eqz50>BCd*ffZL0SoSeGXY{z ziis|m8sw?O^r85Y_d;D>R6RBeh&edm*KylJ4G2I-Jm{UKodd+u0&PB@o-XLXld;nI zfHsDOrGMuLL{Z#=N8|=I~?IQKk zg*!$EBTuoB;ahdg_>prOyQ0iQ0Ad}4MjedI7Cdo1OPworn$@Kseo^`6c||ex9v2D| z>EALKqTC5Zd#j*uN05&bDn7smgDKu*%?aPi3fH%o!Xj`ZK)3;jp5fmiI&k{$dx98p z{-grGU^n5+;aHWVZsQUF2(xl>whToTU%4Kd`t=FlBqGE%@I8STAM6+D01NW)C>S0m zSE5hRF8tm6@+3&?Yc50<+uD9heNz&(A@%cZUpfIwY6iOuHowyVo8~oDIYI#qp!S61i7`XCC=g)D{W|Q#rkJ^P0B=!=;Eq&TF!{rz{iSR7N##n{ zEr)$*zrvYb3^?jp@zraAX?t8^Uq_(rGXO#$9ZCA^ zo5lf13Ca?AVo3ly8~~#^0-z0T(w_7wKXS)cL6Zj=p5S+9WH#Wo1E~{7*34kp9v#lo{(qn&>;b+hHySid)$BX5hB215&qZB&G!fA8$3`&oYu<& zGZUmfpxV z@}LiFFNmua=*M{8D}5<;ARYqAb;Hd?LtjG047E8Y+!}~GHQ(X9%F!xLvtFcT%GlL) zLM#FCzOZ7LA;KM$-XQVv4|oaiYj(&Dw||?H)zjOpM8Rlr%AY!+TK)@>5Q3l=f4n*x zSu1^)SNH*zsB{1wF6Ntb>uoY>vn|$CW8JyBn6b9E?*PSn<^WwzDI&5BylOCRhra6U zH|{j@FS66%*6;5p{=mQh;h%xp7G}nVV6mx~c1e&-@61kd^TwOCSo%Mjt~(y`i3vy*Jsb$jlzuI}u4%van>~#XcY%HRg zSy>0rWd|Gh+S`^wGDYC0KwA8fP013@4&W&bvkwnnPi!7ZCOp^gK z$UFS|!J@-vaCS;}t>N4DG0eU7es)LSx|04zvD03-CIM8UlqK>I6@8YmLlpqyz0cfHMip17mZ>&!ashC9$0 z49^-FRHH+RCfwsdDT0x!A#NN9+Zl)F+0R6sDEek-mQU=KxCvETmKrB!i$s)!dHNn7 z57$3^eT&ogVYGXV{`K<#RL#p@6?eY^laz#dE0&-txgZqE5!gDFZmE3(iOE=BL$ z`A7tNvRy0h$$O;Y0g@a#0tR50ft~Tu(#}PjU2@T0E7aHn1qoYLZ!ad~DuYe-%jhUf z9fj&F^O>(1@o(Ll+;j#@6Tm&7#RfU5X5JaNK&i1|l-K|ZTD=ZirD41Bf1UT$pFY{{ z3W&pb0~woOI`bU@1QCvFV5>?fQ)}?9*+gD8hN^Ry>{k~G+*6(RgR8nF@87}Z<0N2VDlGCB z3Vjs8R#=>iW~z|;p6$60&a%o{@ziqVx21JPTXy}~$Usd-t@YkABRP%k>DnVHru9_$ zE&WwmdLlHU#*mr3=cB5@j0);2T^JuIWqzy*Sm`pM$1yW~aS{>nwrBL!H1A>I`rzca zBxR1H6`D8JWfrCCnw*0+uNd3e6G0}F=RAzNh;g> zaCWZ9{}V&l$V+2I<`k{0GX^q|8C;sb*_dPn z)zpFc8kJKGZwRBp*Mi7{)c=}DDHi^<@R8{bC!0ue`7}rSkuck5(?prV{;m);#Vr0+ z7D0({lq&98mmg*zwZf$|Eovmg+GbG{UYEI(OKcb&BWj|ga|h-S#{yTJi1_o|Rcc>7 zWhQEBHQDLy+dl zsWJO8w|*G4cC!~TKDw3&AL9r=9q)QQ=W%Bl>zOva*c(*5`xw1JH=0&A?y2`-wmDGO z;#R%9tJde@sDEp-tVSlGdN`@sV6b1dnV|AWH4x?Aro7|Q2T8@SwGZ;9RZsBF7R2V9 zRS=PnS4qy|Lb9y>OniOvY&n(HA$R(0r*$gFwy3i7L5+kqeONsrH9_sNu4q&(5DinF zBK9=-bn)k-ebUb%TvOH+RPm-k;rr3y#SZzX9PauCZk~=>rWd>S-W{wzXgI;T<6FbG z%YkBckB4DxR@STDfARi3v2&>`_KZ)hNlxO|+ypx&N!_^X&B`VFHfSr9WFpNcj%A2|jUFGQ8{ zQ%}qLG*jf3?GMH_>-R-Q%Q7TCaV^;rM`-XQuD9y&{C@4@^X2U9W8@VzUC7(Fu!G_p zpJPO=ZJj0)5osGP8(CVW!}N>{EYh3J2hZilkEQP~0#L{l;FyODH4Y?&5I+DhWSu~G z`5E}W!ZNvKqc8X=#**_S9cpfJh~p5TnFAyhnWK7;+-~;zxnvZ4*3!MbeK0}5T=M0M z&Es@{ox-W5W@fV|w}tTT_I-TCOZ)5drb6cNvHm-0*`ne;CIWnz<8Gd7Kt9o~>x+t~ zXH>@?@f(j`Qcz?fD4a^OC0p5X4Emb2SsL?g* z5u_YFwmBZ%jA8sh9OdDkenBzX%-*3w1$XPOwo&SXg|mUJOWrIm?V9i7+kau_=Hiod zqE~6&qRkMyGPvJ&(@{pACEmoVw);Z7dFZQKYUw`Ft?OmO@v@BD$1QGt>0ed|))j8u z8z8txSSj5;D~pM0JzJ>NKY{ zvJh~IiS@=mj0Ugn`a~fezPzA%+1;!Pk+l`0Y^bH6#L_&Q2bn&Mf@U^0X)ym56wUZN>0|+`VfS1e$~;N5}5OZJ-MOg z`}hG<&uUDX!{(gfM?DLuM}71n!6TnYbk5SnCDE3zJY(&^9Z^~zDO`lG=ALK0G5}#8 z8?>Dd&d-xU5j(aTRFaOv4+QwbRWpBS#%VAC+FwlU?P0c7*!HVyEJEpmdJ1G(7Pu0i zsM?Mt@i|3b&C5=UieVQ@{FKs@E~bLzTbO!rfIvVI3~Hnt=)OLF1~0BTJ~<0RZH#M+ z-CAK)8$`jcttlxzbMo*Q9RGeBR?1cAXcCAT0-X!81eV2M#G&0}~N&B1t9+w{XI;rr^`UKh~=3m;p)#P0jkai%{0 zcq4Lxtrl!?=0(}`KmEJHJ`%LpA5bd&~AH={02$m>O;!GLF%1e1%;9m(Dt6^jER77m_qI4eL(jEuMA#Df#0fiKMO7{k74 zk))eY3KVikd<(+4b8~5MeS!Ldi4`+oE?CMK1p_!zu(Tuo>l_8k+&pzt&3#s4oW?up zSy_zlXpvi&*YZZZidc4M^j__8*D-$+8Xh5&T~z!y-q zuqw*s`}=E#goKd7xePrpH5=ddPGDq z&y;!FnHh*Lwtl&5QCYlqL2{m+nOV4G59hHmAqIS|xcVvQQ?`7N5&~waL(rU^U$rF~ zWTvE4yYw-|v%$*f>Iy#y6Fyk@LI9S4FBO7(0j|?BG<=vo!YwBD1){=wOva@odo{nH z2&2IK3}QoY(Clz|FI&2~rGR!684mV$hYYSZ_=*>chSqB}dbG8)R^S-`))#nL1GE1~9jG zmEkkSqYg(L+rbVr6IOKffRYlLhS}5;Z4KdxL8 zV^w>4;4kqUhi9Pl&7;Jf)}PC?N=d-3t-tz9Q3aY5m<_;!2W~HTA~4?v zgJNZ0gxCM~u?Jw8py}8bfzAPUI4$AcZVt|lkhQ4L{Om-bTO7e!J?{<65FjlzF1-?^ z@BzT?kCd$f2O6?>0by-RKl`-m?CtEJ-D(t)fAnJ(m!XL_EiG-ePyCweem9b(f=~qFCuI ziN}IeNm?-v&d;~2oG9MzdGC3`(^J#jY%}z&ehB%(odp|P4b?60#VZyfwFht@0?0DY zB~?6GBf-LSEX&LQa!g2X*CL$#IwWF;i)@gBnG4Vr_(BkI1d%r{6Emvy&OudpJ{HvO0>qV2;+lsH0c4uq_Qbr@SJ= z#p}nGbTd{n)H=>KGvXxJA&W%6n{ro1K#Dpzf7d&rq0sWXKwWud*y~BF*lz~Q^vR@gK^hVerZ?#Id-$Vpy#^rr% zR!zouBUJSGDpL7y8e)7ot2w$jnyAL``o7z9qm1YoPDRhC^-%?Xru9}MymSIZ)M-E9 z>sZVBauP|DdZioY*r)ynh))tAc$;EdC2{o6UvO}3pJkB4|*5v3=e#gc-TE;i{`w< z7b&?|cQcpdklo8bpFgriJ}dz(mqzq%cY8|o2eJFrLm5q+)c%;AdiWcp|gbK6I$Dw6O&rBMv!&neN>uCVtv>?wO~$o!0w@ zKioRM-j82n%U#UhY>Yb|K+_M4<34FJ8>Z*VaIZo0(N(1CkI>$E9g8v`lNa+$&W>Q$ zfu&)pyPtY9GS%v2V29z5efPsdF(0qr2kRSuyY{<#nvO;p{YZpKA|y5IvP^oXySj|z zoQ8W`x+OBBRP>h6F^#xii`>@LN!y58BhWHn>0ssZ;oItp!bOy#;5y63FnMY}S(VvO z(Tkk#@_+qFOI`1SZDW;kQm&7ho}1Uc5s+Zso7t~v@Op&>T(4$>numMsdD@%jIM+~) z+JEo)B)5sCb~q6pu@yiQ2xpGRx_hOozxBj6mMdLtLL4|NiYFVk&B5mlH$&P;i2flJ z6%`mVVL#H9n$<{W0NK&Fty)#~%XBH1uS|HL9n8p_{^jZ^AhmKP7OS3zYJ;zACo-^s z3!;r$u#Q|_qPgSyx(MmFq8rAgC)E+~%^|f6>HOTjkNp%`H$YeEd zml#w%FVBSZ04ItvSS( z!klnNNvHFeA{;3n(1_$Q%4U^vjba^9 z%qMZmo{!U9zOX#}f%~~Y;q0rGGva zm6LliP;d{3jqVdly?Y@1IK39$<4hWIboEi**vYWZ4@(;E9o>+B7NMHK8c)vdxPCyJ z_!(#3E6q>LXTj3dHEM94*>YOQm^5zWha-iG!<;>6Mcek^w%vb@6F^2zj@%W#8=G(b z!j>dG0v#KGwlMg}Z}VQuE4H}%0+kv?hy7WiFS!n^9}3KL_V!Nho7^vwtB{I)oe`22 zPftxdT$KUSK71q<9O9x5#LdqAA#0U<4?i;^*d8 zDnvjHHjI@67KxcA@Z=RdMq1qN+*zC1`g?i#b-{?8-5^h=!fNF?1k9F9+ko1v20SEl zb1C|P#Mp!DY9lwy2G$SKUjMOfS{y8D(CRozyaHLEF*6>G%X`*|RZtF(zfJHq!Hh>6{_GgU@kdKbn0vvS{L0Ny z{`mbM?4C$&13CP^-Mfl8j&z~cjKTV&ccY_d(pqG6S~Z!dI7~Yviv+_)H(WVi$+j|g zo|>m=x5PA3%^u$CZ`j2b==0rb^Lw@DYBHAGEcVWR#&3Od_%ip! zlSuKGg_mEDghS=?ZNdF>Ns-$zfppCnw{mB2u{5keh2wkxlC+y>E}!{VA{AhU26ZhG z_YQ{ zO}~M^+#Ql){)j~162FYGX%KP@QhYeJp>NL*tOW)9~cDyHLNgDT5I4=*o~KW~WQ zloq%&S?=QgA=8@Z(8B!9t!c&x037m{10i%Ub3{)mbCa3aGfK{l@l9u2Q9)s0U~(Z) zneEN%->{=){rmnsSF{loB_dI$)u747R6&;f&?n~&KRSG%i$b1WUJ(g#@bjXrS(ico z2N`aEJr#7-USDmw@Rq=bTldcCr#I>Qbj%F-vK^RVwf)9A?!l3twE?s=WPjdDK-T~= zrQ)UC8OQ`thlJ2`;7g2^O(gJbAceBgGGdV=m*%Vgf%(uV8u^ZH_(9vc^@d+w_fn- z!rGMy#O#8P%D_PR9-wUH7!WA4^P7LtC&IjutXxK|8^Q_`_4&Pv)j}?SO?t-NC8eco zB4;`F2sg%fh20J-wfcjz{;lQ1{jYQ1CIZZUe%$-s+=gJ_kw`7CVAsDJ#LXGC&7w7O zxhqi9!yt9zv-BqYR;2`?mLENV8_rz`B}`6UY(~l#qe0W%Uppn|bv$O$p3FC$aWOg3 z^iw{%+tU#=l@u9^cT>7g%Eq6)YD}%sOp=H(o>1D1ql?+;*R>RVQnwx%PmPL{=tNS~ z&DF*2EI<97H=%(&u^|H0eO%FMt1VHD-`=g}d>~+df?z2mj`!3T`+M>%M}wvGuY6oT zzw7>rN%a8Qvu>_K&IFbfwj0XCevhyzu)YW3ut+cJGfKCdFW?$?my2lZ75d53FQDz8 zEtV8L9+6pB#bPmaDW-R{T6v28Ku!R0qlotQR<>gU&RZO}{M=f9CQojYE8z)0gcfb8 zO}y8V0o&n?!zKAV(tyraeC-a}!7{F_Q@k-f_jq2aYLpI*VE$H0z5Y_?>F#*dlVFQZ zqgK%UHV?ayv*6;U`7NeUy|+w6Wv$Kr3%g`O0?IjCL8^}aPha&}*=k#n800hg*x$v( zcQfwHlu@9kq0nUsWGKwCp{8{oEUIjC{8pr7TEa1Lti5%p>92M+(Hy5&!jqJY8F8X_ zYq{j<)~v~0?uQ{`6q2ksRx5Y?xr#9gONciN1DUy}sIxE!^GIpyBvL~ho_&-GTB0u( zChhSGrq&Nq{i8)M9Teec9^`oRdKSe3foc(TPDyhl)m;9b3*Yz7=2K&g8*Amc>f9PN zPnYDB7GsUJWQm!dJ{9e&r%r7|!8tOW+q;9gwfEy?tOhqcGdd+rHfAJ@;jBs_j~%N~ z2Z;V?<=HP_;@z{M!K+ug=)x`XY`kQnw%9858C}p%8%>$LI}&M1T_0puxckHqWq{~! zGA-(e6)*QDX8%~vzKFT?X0wd4#1D7PkHc-hn`P{+?yBbX_skgxDF@ZGDFNTC z6I|{V6`H??qhF0luecyh*MMN~7|@kBe`D?6gZ(6cII1$+&skk`+DQA-&iVpDrjRgN zPM+M2l8V`F7TSCfeEzM4t*c(z_rW`sp?P3#2jLb+v(;N z2Ckz|sSKB?;!m9Y(T3M*V&?H5B-`ov781naQB6<{_0mp73!oLC(>8N*bMeh z{u1S;WXR6p#k6mwe9Umt_~VpTdoRvZJuLi>)~DOu5$U3R;cOiGhMj^}DwTgzE}<8?PtYgB+#@mR|G6B{uwUX+uZo>#$Ik9ewA*vn z#K4hd;J$wM_t%g4xrKfJUQnvE8P01PON|O0-tGt2-ya;b?zJkAVuHSG z4u2Q8dnAtp`f?DA0FCa}R`t_D$j<@&f>x7f(^&}aDnvz@%ZI`qS!8jrq44W|`Be`p zBs~3}ml=rqFPE1hQEOvU)H4ve+CYwg$X(M!hl4YUH@`o9{$-Uam;VLKQxNtrGs1|M zuQjcyo0ndo7XzXD>G=ZcKR|j15KP?AI#3KUxdFS1babDNXBN%470F6wcR^+1Oi?7Q zU(PAZJ+U9tX0Y~x#TLYc)YvcwP3?=6t~pW$aCXE~Rj!TQy3l#{D+9a*pm8B1V|F_E z-7>Yk0jST!B$sqPT4Bb^YV#~bOQu9QU>yn&gE}e#1kB<+@LQ8Tc+f=sf>;hL1Hdk^ zL9!n{xooUh)r{X_TqjBx$&)UD+cd~H z?c5!M_Q`1(Zt~=hR*|)J?p$K|zR#mS`sHK~N@=q;=st_J+RGGAetxa*#ZkyN?;>?6 zFUh5kc4-pTb%Zg0#%#vdli9RvW^a=eyDG3&w^qPS)>YEi-Hpd@Um_+Lud(_d{y7gg z(l3|gnG<=}=SXvY>I32pBX0Kxm^_1?b}`zG*(u!7tO zgFLAjMpeLMff@nzT3dG4dtI5>dM@6(hPWXYn5y^5$r-a>aFr=B4#60QkkcgXtRJ;0l-k`H7OF4cA?xkyi$Ul^>iHkN zX@{tY2q0cbsixkOwF*L4QEAC?vhp7mt37hw^jONWi;^$RpO*1Y6Fxl{Lr^+d_X zZ5DFTMX|;sR_dQLuW=F;#j;`Fzv1yL+J@)Zt`}(-Y;lRzfI}}-K{dZ-Y z-`zPTq!CcYp}18*pFnV%x!`;qciU?@3-4C`RyG2B(&azC&P5%D&gM+bv1{H6H^az9 z;PNXoL=mpAnDg<91#zmU=LJcOKI+CjR4}y^sV-t_Lm#|m7NKSPyI%e$9JK}^;X?qcV>+WFMZf>nd@pZ- z!wAB+Sblx|PgPRguf?o+}^-90Y{)6?RMzHt%AAA?XH-G-W`)>4XvKDRLhqZL@C^7YKSH- zLX)_gp$~l@T9>C@>K~>Lj2Z-O#O*yCdUWP<;Q6zTL%7IYUy+v@;3p~+p<#Sv7&S0t z5Xl4Blum`k-Ij=kUyyzSzwHC2mLCpj8*+9-exgNL@Wbalj0cZke}hvH3YLuyZMSZ7 zs$v0cjroUb(hLl$-5BYhJvyq_Xl!}CK>+=k6n+fe%S~4?f_q+KDh)afWqLs1AyaQO8}?w=HSzZL zM)~WdohpqdZZP}+uQAq)+gp-5buZ1cv&WPnnxCKFl1AWAXToDj4}H>?9(5AfWZk!T zR+bW9mM>bD*C5rMCR6!&`83j`a|*!)D5oodw}8rntk0|T=MT$gw~?haGad&j|Bh7P zcz`QNM`I8O4Lr#IHUn;><;~v2_A#q%=71U0GN{BNKx}QFSQlpv@D1n$?3dd{kkywp zS_OLSlY1xHIy$QmM2%dpA*~TOm!kj~uydL01%lK-6Q4VIXkG!ADQ6R?cBEMca_@jE z1^p%sl8fBTzGen*S4319C5JfF%k^&@US4j9H~pPLX1F7T_fY4HjP!s!k=@0niUS?c z;%O!h@VUNv)ipOq3Yl=QwoE0>0tY9tY`WD{+78yA%Z-1R*=OPHr??XSUXWBxg8|9U zWWUhCz64hkEJ25mpRo8uZ%1X=fz)sGNUdlIb{ZZbAw}4zG|TtF+ZzH@!2~MRbKDo%?A;@I8bEh%& z`evz9YsH?I@#4@QJ_lE5z0cC;!v+SOE^@YSsl|z3A~d2*cL*Z}BlCZbGD*nD5E!R~ zk_Sr^1gLPACNLCe7N{CY6c9)&^)Qum-mTQM{que>4Z--_DAj);gI*~~UGp|hj_S5N zPADheTd7CsA0@LpG+K`J@GKuHJOX`qPC6xzLS_$t;8L!T{=vpR7AS*W+J>eC}k>D<;w>IKldQfJo6GUyVqOi?BHam#IR`xHVvsS*mV{=x1 zN^O!aI8U@7!O7e?VWiqokB~;0m`IMMOASXutzehKJcv-N>!uTBh1pLT0kwkV7qg>I zv_VG+Wz<9sZxjN!htyGGnn}y97`Ej|OMAXBO(~ixnzLe`2T7LrbK^%JUu+$trYJEd z%g&JSs9x37G*3~JSx{xGr`A`cdWKa-hjm=897iX+V=Weyz8RRoN_rAIkd)#jjc#Im zKt;Ve>++dqWKgA2uC2xa`6)Kgu?-?)wPYlyIm)gaM&_783f`mb{T+#L(5 zmM_|TP8oz&QV>xUDYI-D>GIx2SB?1BHGECSH}l1EckalF(w1huyyU} za(!O)9rI%DpyrlW$|vqzh^@Z{pCQ?C}o`o@;+^3KJ@ z@dH`{oP}hGW%**tS*tUBZ}e}sH2?86L8NC3U;gB8|9*Ly0WePhH3q$Li7oxf$q7g+ zrW-A7-h&oh>88Uny7tsj$vNMwBXFZTJB z)^Ye;<-xB%|H1Ox?-+N{RZUlwTSh=mx9s&A z>FV(iEnLuGPbQL44Z~*Ujcx@=;vn;}M<(bK;C}+NJ$Da>z?H4n zHRJ6!_DcXDs;OLkA;B}08e1y;3Ggs@nBAP~_!OkS_FbD6*Fky(ML|I8%au>l zW1l1YIljMr@XABy`=394@HdsmV6tQxudcuz2;pM;`?mpQwRCVWoR%!*y8vhvTB1i_ z+kvr_F;nxUspa%L1jphxX~nRrwe`wvC%5`hFk)K`k3cGvyd}2{ zKS<-?)fT9t9REdupg0(?)SqZ8&~ZRi%#!uVeh9c46l~B;HXx>1LV1WIFU)>}KQLOF z6vO$PQYcS)IXv{}sy$_dCykPJ`LFf+?1P`%Rk1_Lj$d~i-SmnlY$x8Jhdew`%%plN zFW}}w&U|CnHCZ!X_V_45dCcUs17!gFkg2I#tC;io2Y-5*i6@9#Eg3=2%8qd?AKfjx zA~?%sjjvn#@%GhJI{u6%zuV=X+asFs0|QQF#TyYxPb5q(LR?#93lX_X)@wrSkrshP znr(Nav}QoW*_V->{d#kP0jQSu+$*2o-ik$l!`G7EcW-Y`w=Y)8I5cekrUde<86W3@ zr>AWL^b4>{pJu5PmoMm7xI)%Ktq8)=ez25|{60wpZW{oyn&;d>ptKrkn;2xefo=D{Rj>gjoZR>Me-FFhC8AHo}! z=V(;t*|bOMH%elCQlI>*~r}DTg4foEw6oZ25Qy>vmj) z8}(Z%rK@JmU5-_CeZ_JOUIaW&Pfyo;ZvxqKa;=@+LG#_^E3K*yU&_?WcJ_7;f9=!l z+T4XKslKZV!#a?MY;J~`V?ctP=qRVU&AYa}M}#l>)+BrK9*B9#2xUT0fC_WZ^!@XO z#}6MO%dE6cC}v$Ch%)J&;qK1C(ZHP>e-tHWROlR!nRMK3$L@s|b(aeY*k$MDpd1_9 zG>BBxp~Vi<3G<9)OUoxG^nah|$&LEV$K2?zLD3jV=V&MJMBj>lP$cQ7EI9 zGb6jIF!3~A@Igx>+X#ik2%E^Pw7@%F>~r#?>DN_E+=1tAZ0Z%WrPoUlS9$Uk6(!5B zk38=9RnN};==s6(jWaVP*%vGBDm?B5doosnQiQDyAqIfL&>zzfh;+JS_WFsHst@uR zsTxK2V<>GHCzQZA58-FG#7_MTuMd&|omsgMTYojrVh4)dKYte;beX5%O$J>o^xCYx z6-Ra*AKiuq6C~3EYM1}~JxKcyAjq#EC;{c!9E)r$AoPVd;XHK*!61C)(Cc1a4bSRR zDEx4CCRXjxhS@tV8T2v`*#Igz-~W&xhy{C}Xo_(9wTR$LXMi+7z~Y568zofv(xG(* zylzVE%f6i^gJVaT%9av0hv=V&znVLO5-G*E)UkqCuN6_ojExnQgVtrw(TgR30{eJoZjBo474 z;Y!5GwE>)m#q_&48?yn^sK`j@FNxT@aP8~pNfR$6Q-H&pe$qt+RTpZAJ}gy7`axm0 z$;pHdpbaGe0wTd31+OT&pDJimfjrdz0qVT4urUATmt%vri2ij|Vj||AOY} z`_a)9(bs$a1t1sj%rMh2H0(R^7N+K$JQ~b`^Ay z$CiW`f9s0c(cin|uL+R!0zWZ>)~L!f7gqQ&Du;qOIMXxe3`DuIOTe-kEPPwXXxzA9& zAmb58ssGGE(f>}P|MJAgD;9~pqxCsVU!HTC0KVEC0{MUh^9XQ(cu-;_^T|HnQKB&2 z1FzqrPSYX?O`obTO}o*gj~pO>O?VH=J>0lb#d_rbL1~YXkyRbfqniVOY6wROf&w*K z0p%DJXpiTyGt`7RU6T~<-+zO`^qO)s;6+xW_;W=wW)X4O!58n$ti|ovI7G!UZ{ww` zkh*ZcY`wFnj<2;(4_&T^E21dO2HtXZKUHjMil70!F&YMhjH1HO7p7o*&N9DrF%G*C z(|`d3G)A78uo~jC9GB#&6&d>D4O)$;Tu1Dn!27{LYBE1Cf+`ym$x#p{!L_7}Jogkn z5jykULeI4cTj)s)?M=I!S0Otlx-*<4XE&^s7aX?1NXmA{ebOj(&E^lC(hq(a#kcZu zHZ)S`R9vAs=nV_szDRH)6!9;A1!tKt@cxNCBj^gaO^XO8k5#QE1;~^dPm(mpP+PM( zWjR59b}Fd*Q-_3_06B3-k_z5RO3%$>?LIC}|MO&w0lhw&R}_UlcVt(Z`KIs#L9 zNyvxM1)=d4e$OnhyT>AziC1@PX6|0;O`kr`cGLAisZegGtXMX?X?FFQ1R?`@QbB=* zIKH?pmV{J^W;)9959#WHYJK7UBB4W9CNsgI(p;o{23 zKhnB)V#u{_gy?L~v9tJY?^SLM zexyeJu>YO02(@qVTz^rWE)d~fxx3L)`3MqOd8rCTSIOMrKm30ko~Zdrp_&VzDi^To zQ_Rv`{+sixdZ-X}@$KY!QETSr{=Zz7no-@&6_@c1%{pQX zHYkXpmDy*Z=Vl_J_S0u|wS43HW+q~JzpdE&g~qqHk2RKrsY^W>vL4+Gvr=+M-+KSv zIk8>Er@ig%uG?G`$MmoFe2u%S!cMk}pKDAHL~mr=q^Y*Mw>Wc^9ZvUyT|4|2`wQG9 z_nY`cnB?^FgJy8I4-NA9EaG<7{BGanYeNKMv$0ES)OMWwLBBD7*0z;j$U;UtF}nGe z_3_w4TJr}6zD|;hIBz2e3i1PeYGnAGXU-^Fv2AlQurcV+ZulB8m;X|AVy5w&mv{e?q;0wDaM8`@{<6dO3mle126YlNbHsQ=s3_y04*$+7 z-CD@zEjs;%>(Cwti*%wZi9SxUF5^ZVUzwMM7_%5j)zyg;`8PE}C43A5Beq&-$6S&Z!ZOb5-3b+g7@*TDC2U?=H*Fi$dv`LYbQ0tfTg#A(lz+=dals zr3%U8%*HzlcNR&0eu&ylnO(mWsHKq^@vILh%;LZAVz`L9NL!8JkD$2INbP8*+8^;i zQDbD*JBT*!*`Ce7BTHQyst3V6X7{Ab#FemPH=QEGhyJD?{i~WnjVrylx0^gmbq+fV}mnP3kK*P zVPxrPU32pSO^GAW_^@t3at{^Ci>fboFkVR?*IE8wyp$jaU=$d=4cfdqReaB%8+>vz zHc4!9ShfI%I#{ZarGUVmhuxmpMmD5@5&`BaXeRRC?oG*VS8NdK0)@xB&%xZlvG!hHor{183nI_8yz2XVe=^cyyX{?_44CP&E*igaNRO}6 z-#HaL`y|c2P51_VVV8S)=C+0tp8rZt^Jn*q1QPrJSHJZ^t@ojV39^Z`hPg_K@AQj} zn+QqfZl>#r$PS0peZHf)$96cr(=>3LAn;~X+t9Ofb?Bb@Cz2PHUtVvIMEC#nu=Wg~ zuD0S`IE}>F*w6_0OC$VN*USAMf#z5NA6JhXZjc*v(yAU>l_I^lTAvKL~;u z9cJagwGYU2=Qqn&Bp~B2M&_iQZ9vW$C(k1`+_#umw-q}7{v|+a?Y+GtJzC|&kQ=`v zq(mU8A&BULgn{lgC%}9Or64Fu`g;Gtzu3Y;h8wAhg!^AIIiN%EY3)1(JbAE9B8lPi zWL6~N{J&Nc_y>?KY--cM0$}im%BLzSx1_MA4MmX;lS$26ATyp*fo0I#!66yBVWe(a zW4;afCsXn$j5EAn zv=Id|)gUE=fBo|1ORvlQzV0#*?h z6TWv{9{1{NzZ`0Zxlg7+M{SkF5*Z``0-W=U3k7;2B_*(^`23(k{Co-aK=3|_UF`56 z)GU5Lm^S!7#f@|$)uPfy*_k2mJJy5v^AmkP7v3d^rF#>1-l>A7TH z9HR#NE7z1_9ZDMNz{uz!0&Sawpq#giWPd~J!dC9O5R{DPZGA2!oU*=yy_si3r%@Zs zps{r9U8?O++aUg`xP8c*L11S*_E{4hv8)z`p!xfbF0mjA3yFWhsj7O5bd@9HF&J=eBF-Y zIH3^eaF5~2V~R)(U0wo9resw1;pPzQwtomFQCJZ3p?wTq!82q26f7DMVvVM4&E^So z17f9#+4}pK5!Y=7C|e-|>}UgdePf)dA$2|)?|xqJE2zmUqf>SSZwZgT%o%M`WlCuz zi|%{26#X}TeEY-4j|#rNzEAW=HV%=DBv@~Eq%>-Pw*rwdv}fEXcr`ofd;J>pkQ}zl z&<`6GU&4XwhomKG`!bowvdK+xa4|dc=gdfRFmVt3R@{zcZ&8fj}O5_4E?JX z@ZEt#jiS#OC{ECr!4BP~8Of$|@0v$T-}OXP{AyDLUfW*GBS4XKp8b{x?_2w|-=fL{ zaZgAza@=aAnH}~&q~;CoOVi}9HVxPTeoz_(7o&evLtLu4Hu4vTMKC=qQFCb05m>0l z-u+;VgcAg=_4NAJjugA?vDN=j*YbEC`e?%E40?H%{2KFz!RA(|)vP@Yu&I{<{1j3YdZ zdZz=F!`g~BWCPx? z{4##Y5FxS7Q7>4}`edCgMj~~0#m3zwo?qO=skHMQd&@vE`%qZ2X zqoVq@Rw{1TBx}o9YtQODWg6>{#Q1&|GOJIB!5(#gWv(&c2ff$!D$}oi4L?Qdjnbs0 zn_Ve~BtLm6yCX1LkCcy8OPMi-2+?%swiYmKZa)>X)h#oZy{pWMZzogbLXE!0R7Bm; z<$6RQa%0`vMv-Ig*IwEIF-FaL1q?5!VYR4`&gvz~`Z?;{_$EW)!{sJ6;Vvqz!RNO%zMy?C=T`rdVk=i`6l~w_PhI_3iMVmM zIz|@DC^z~+mp$pqv+}v1tNN{`hG#X4(+>9=n3irmk*rmHs_@xP=Gu-WtENVs^U=Zr zcl|7G{Yd3mc~tRvq6C}V;GMeZ&uXTr(d(yL{^8~=IJ8GK-nSOt84I#E?yU(>`R^KI zAxeie?Y`BZ2T}S_`sE+o|6s*HIaE8%t7du6szrfDgUS12HCc(LPW$fnCS6SG@Ul4B zY^*FacXq!4G(#P|Egzj|2DKDcoP^D7!iqb_-frFzVG-0nRfrkmr^nxMa+d9e5zfWx zzcb%Twf;b&#pJ@}M~#uiCY%xeONfQNx@F2#4CgnF*J8x9PNWk0mQQ!(!gJ~Z%F@Nk z4We#6y}pNz-d{T&s!|uK+E6v_Qd8W`P?spN+fFin%ktbt$)kc=8llwiWSSsICPMW} zeU?R}sE%)xcZHHEXZXdgD5o9kpS$uTK`ycjr52v8R&ju*=)Fd{pMt&r{^DDP)8$mbs|-2jA;VH58m50 z5tF?7dqGV>RL@y$3*A`yCOUpFsCq|@8%^6SHJ=7?pgmr1@V+w3&)!lMVVK~5GTm$2 zaQ36R|( zJamVIq@;i#-C$56-Hn7ugEXSFfOLtdG)Si)@~tz^_x_u4205|!z1O-D)%sc4e2R5s zXN8rZAzHe(gCT9?K)p%2wK!JsqiC*Htwa`%tZnf|Jz;m}G96MQZIPvJLZR*it@?V_ zx@u>uJidk6FBS`|J&$@BA7aFso(OMV8xb++;lC=GG1tAzCDwW6QhYrd+IxMj!U2y= z7i)1L^9Admf9zmjFu=CSWHum{Md5$Hzcob)W0F9IIsxzf`xQdv(~!|kh%7(nsHiB? zWkZ@Tk@@374TGt_k6cV!Z~+uO`tcDBaJr(f7%ppidwW~hX-1&Z0}Tx=gx4tzdK>~y z=j@Tnj-xePGeg(+<|cj+acYt9U+OVqvMQXWAXi2~j`VQw8m07XY_Nhb09l~`dAOh$ z0VM`#9nxxQv?*evUg|cQsMj6HxxT2XtLgZ-+^4y*w+GY$=>p!eFtRkdvokk93bJg* zz8suH8QjWf07Z?Jmwv^Yfpo716G*H|^WhwU>bqgZDR>Z=R5HVoW%sFWy9Fizm{O4( z5@~eJiDPu^Fz&Adkrdm6A=}47$aV|5h&-d;+Sre{92?4Ycq_>675KIH0u_cFrW<#V zMVbd6Z_@q{f#*{nCr=err%w4W3s15T-5TFa`ZEkz9!%wZ6^8j(9|s2bl=_q$vr@OI zYmB~?z6MYYJgP~T(;@R(Tr)|Ov6uifPL>O*1_r{@EF9)eow6iC3o!J7;{Dc zz2oxpa{y-4eG-2&PVGK71FTZ|M}i~afo&y9vDOr)qB%2NPNA7`gqm*&+%qfdB=Is? z^s*?1Ba}FHRaTFS6!-~0xe1F(u-4VKsW+S1`$#AfXx29RceO{dWMvtaHvD+L$}Yz! z6q};d{yk6Mji7$sM?E)jp4_Q|@>}rvi#+2VQPDnHsseBGd;9Yu(m4BX!gO0l@}DUV zyByf;@YQpdAho~#5z^C>3R#3CRZ~pa>|b4t>8JqzJwM!iSe?HrxXE^6*-BdW z^o`?5)>}2r0UIV9K`AMXVjU|luh^=N79|Kfu(647nqf*SQ4mCq%?k_LPre#k1j|%R zfk5unX|d2H6cd7Nd#q4N&&dO=P5MX6_`OxAB;n+iD$v`qg*gQP-FE-8^G(g*L14ik z=N33gK%fa_t3lxc8@`c=36d`W`WBg83I75^A#5ZW!=!K*02B4W|Li@{s0#UlS!G*O zO$}5a*#Tq=Vm>qB-ik^t8c7oyFRw_oRBoWZUiL|vxBK-NS}a12ellG5pr9Gc%!m8R z$TX3_kU)836Z#XOkP)lTz1e$*0&;e3VDtqjdCb5d2V_b03w)2Mw^gDSbIa^;q;b{Izg0*n04>^m16aS60BHRDWbraFfb@0 z%3L4nxLR3(MgT?jWWDXtj+gpwuCDA2-7XNI2T71fMjTQvbYk^M4}4-wDhDt8Vj+v) zd7)&^`KO4`fXy422Dk1Ou6M;G4uZ!~{txvunk4#fSwewOr$ z)aXW`W@w#6ST19eygO+Otmajb}N%h0`Ot;IhLh&O1BCGPhp;nKTv9^|uLv^#}r z@!c)M7EA4Y>%uJ7&E{UKX~8eUjdKFTX_t@wXb_x>j0FG9ydkOo?*X5JmrNMyykD&r zE35AqCY)aVi#PHEet>%Fz$Xg`G0q|WMg*iFbaY4one->%J91k;(KJY$M9hTNdXKCQeCxv2CYw^;$4B#Xk-i{lyyDf52*P&0)+*3N@c#@5>0- z&PKmz68uc0FP@o}W@&9*$Vlr~Kox0Pp!x)c`ra0u^;R=(N&@Y0E5GjicwJT!2;MtB zJF9r+1uv=>e~Y6rnXQCNSErL3jBZ_7cNM%Ww83Li6wH^C?M;r$R; zFJ%bGzFr{Pmwx{SUe5KRBqxUkd9s<9FeE5j8j~*l8F>bWB{z%=z|ZpY@=7x&T7i5N zmN>MZWTf$Z;ulkpL<{>GJm7zBZ1n%mg6wvVA=fOwM`0u5z>5^olRXn#SUq!z0*e!kg9mF3!bQe!vPlL zeI}cK!_qtZ@#8H7vs^yivudDw??*lE2g);z^6u-aDudGr@wNKjft;kv5K8sP-F@sh z0g$%`e-a=31RXD5-eOb73D>`is_XfB`^A#_S{qnH9b-T-3Jqs~{yx6wHL2`{G*%=` z4E|Rb4*dN5V3e`9v1Fw19lk9uimy>4d}b_cqg;I?xRE6~Y>#Tl zHlLd8e7j`6N>yWEl9JtLE3nDaA9zgD<7k`-+vkbu3rWRYHN`Wi$pJQ#xN(?$ZLwV78TLp zL?8H;CicLvjQ=TnqA`1#eF%;kd*ZE?z4Ng)w&DtDwm{L)h#Lr>2L;L{cll#Yj0m1a zFp2L`id#$xf61T9`HQ%jG)eew>~$#bX+~(21H-fj!@m0W28vghRS^bwMEO_xbf~^u zUqoLiOGW+}ZFFJEbyfMGDT8HF^JSJBTi=kY_*>+ZR}iVCwK2Aj9Gj~sQUC3~Azdf# z0kkv8`$k{TR~O@MbPg1D^g4zzcr!gxb&^syGvfuTGkr~7^}8&y$8iB^yzX3CLyp7V>W z!}Hb=9;K~W1x>!b^E;biMgaoWB>@D4$_f~%a_?|)ot0;`KhbJqKxZXJ3HLTG+5GOu zaW9SJ3Y1$2$*FxUtSZI3jZgPY!)mgZE2Gc^IZ20G))FIXJ#ezw;3+CI9a3$9!`ArT z$=<7cIHFn_OCrkPlTMjR#hd1qrCrPrFY&S8#bMZ9!CZAj@)v2!l+lwjTCv(EYz$go z)1GUy-tTh6D#0*uS36URm@#Bm5_7~ks6nM2I%GnuogZ3V&Ne<@Rjc^amEdTjK}QhR zHD(!4tsHHJ>oCWiLY`!wYLli1$*sN-$+pCh*xh$rwhuo_fU#G9m&IVy6-ZD&~ea|ju zIL)K>&|VGeNl|&xyD#IT^R*b=wfA0BB%)RE8Y4)x3VX+Vao1*KpnB z+>g|=NS1EuYC=mqlXek^jr%lzIIEp`r+%x7i_^L9O-P1aRI4Tb(actsl5qf9;?-qw zH2w7wNq-9#x2{s&lq1FJy{^fh!Cn@J>KFLQR7&N#zPPj~m4=U4)Uso z8g*A94=Pd8rVK7r`Y&zzrkL}M>QbrJZ~(y+i;0Q(MeKvi(1`56g}5(;HV-E}?dVZ6 zhM%abpLOz+-h1c?L$5kj)ql}aAaJm=u}On;s{cAl;3WH!@e^W#4tzia$p#9vjqPnP z*1SeAGiFNINS*WsETvNBjc=0Fq~T1T9h1Pr3*4~)dXu2LjyX3Xeygm5Dh0SC5ExO& z#6J~N4-W3s!B6~p-ql41XDCzRt-oEuHNU_?E0p=E(FGJ69z(BPMM0&51O@@eWsI0%^(!Ec;}B1Y0(=MAfLcKk)+xVe{&(J zVbzckq;r!*%0j6J4V=(ZjGUnIN`Z}aIJ z#mcBu$AsaM4N5i!9d(U%Ym=8^1`>3o;f83!gp8(N2u6G7q`v>G*Dl#SKj+*3edEz< zglN&PTi+^ zidbD2A|7GU*?FrbJTxV*cZuvZC7P&|eJWpt1^W9}$cS~9ar&HhdA{3w+Q)mh$KHD+ zq7h}psmVU4R=dH=&o9G}lTh(2MO`er`{jTTeE%>s+0;HJDnlS zCJ&09_$_uxckB^H_rSP|IyDNTgQ;7452$8*U>T>q+Sp6(aee^TuAQ~NRBj?3XF4YU zobnPHV%b2=L^)w~#P8i?mdYHkA^9>V$DZ7MBti6&3AXER9ozqyNTUe>fS0fuK)Z=h}12S7NeR06l@8gOO^YEDl@So)nROFMhDN76a5WXoh2=xn9+jLBDuh-3XXyApi<$@QjhU(edT5}Ghb*RjnsYgV1- znJ7?931QHx=0c|DKgvkSWZI{e7=@xQEw`+RQ%dw4bN|4_M{WMhcE+So18l~vB$k{% z=bSKl7wfOIiDHw9NTWJ?HgoFmpgV5SRWZg+qf#OLpPLV7;NF3S&{;^1IZ^*r!}xgf zcPQ01nEJq^T)c8lr1|-=ze^oo`%XjbhFp`wSf|n}*ZG$t?h1XwKd)P@2iJeTS#slO zCScc9E|An~tl_Lcdk^wuOooZXQXmbEf`nh7JVocTfH7?HBP{9=JqMCw2oci+4?WPz zz*owhw7wsDa5eD&S&o1l&|!!KY7X=J`LAdmF_L!R?P^>W(DgfkTH z`pIaOE^~DG6NRc=sq5V~$WEY0ilQqBF?nX$YWh**TH{zk@abgsnd`k=)_r1q@omiX zmZcdslbpr%vZKXH0r7kO2= zLG7mc+$OFAHnq!5$L;d?!n=*a3U>=d`JF7Ly0!n%a$Xcr!cK$J6 z*=vXe6if44dv1Qsx62FDZLHL9mEEpOqr{&Y_%%2`K80^MXA&ipimCeKgpa!LZ+<9d zwAPN|KYhMH7sgGeNAx%nH$(MUZY5C=VyDy=zM>A*V>Wb=Q=o%ThVT1FZ)h}7LSit4Od?Czm>DBDLbFmsD_B5SY(q%1?x zpQ2W>Gf!@^zs70*P=)rX1#gy!`8Mak3yied$$iStVyJ_pVh)bPMkpz(nI5%cKf*RX zm zq{xEqqfN>1=cBCwtdS*9}Yt-7D|s z4Czk4zt)3u|E3G|2mFOv=?YHvCw<-Mfz?da#HTVHwai$T1#wbr*i{Zcrn@S;kA=H+ zybDao$4_elG^L(BQcXs5+oVv;p!W6Qp;Fff=a3t$ij<3wlc5vx$P~BwtO6P9aTF)7vhRKLF5j6E!Ra0Jeii7Y^j;rU` za=N*q;j8!COeB+WHLUkGQ2Xj*9~01By`1v=8Loppv4cPp2|{N+(pyYuUALt^5i>24M9;0fOCn~(N4`-#CSzL-%wtDe?Civk6Zd6kA_wldhc^BIE z#kGV|FETd1D65M$Q_zS&(;Cvj9R1i=wDr>bofo=WetmL?j#t8{Xb_|8+LspjKf1FTe)(vMzL z&NCkc|3K)zRpGqoac_&@Kjm9I&QPvKX>)uU^!s9zZdTIY2v=|(?5z9w^A?A@VsQ+|P^8K$+ zBHlFRlR^BL3E8?iOF)60X1?c{R042S%{lbJ5Q{#1e85JwhhJlu`4ED+38H&M#Kn_>5serv)~Vvy02v%uF9V z7n_*Tj0D%N6i%1;0V9~7dt)(-lex-nU)hI=spM1SHHgnBPx;rc#5%oyB+pSoK z77}EQI2C~u2(%7gE@T95&86UG*F~MT83K~3s-rm~Vnqi=)sNMs%4&ECHwlAdI zB9nmUoWV)1So8Mz%K;VQBj={#u8;d)309Bzc~UJNEs#RH;AdiP5I8|SP{+}Z8!`H8 zRq@}uE;?J=@D8@mgTe=1YE$(Un@JVVmA~O(QZB(pAWn&m1WmpZ&dFv_3a=9wBttR; zse7Au6kY%80p_%<_AfQMYwv1QIPPjSNmB4NZ&swAR!@ZabboTnA@-rcx~cYImLU#< zN#zZZ%D7CH^ydxtj}OF3+S}Dy7(Qemv@_aerHp@^iZ59)o6{NIMTkDuF#SrzP0pcM zwn`|FG08!b8jp5pii|8%5 zOxg!G)6rEieu%t(In!vuwYFaMM&m7ktZO|jEv+y&Q$+>Ghxgy8XySWdt6Pr!;|rT@ zD)+;Zrb+0M(JR;I-^77^6Ev3;gwXue1z0a`KR;N{;A;lcx?Ph3LYqCyTW% znF!|aW#yVA$V6=2>yXpbOaLc0tm9M6|4?AFuHlT&Vobm19VWsd;!Sr6Aur^Z_5%@vCASjI5@mwVzNS+%ZICKMx=w?b@5OiwJieh z!`k{f5~-eZ&X~P|OfxghMq3)VUUOLbqHOq87!r`Qok^tzCn-c#BkyPc5w0(vT?>a| zApv5TPhl!T5+HW=>jbh|Wm&pqdNJoAqzH0KTA;IWYs+vnNoi_o+Yqb2vEJRF+~BfF z?-Wq6@OV9SN_w*(CVSW_cBO2M=<~+CVUh4=Dr=2MS?lLV>t~NS-L$?}E}!4JSR|Q{ zyvIMWEb#n7gu_lWzExmc#d}N8pi#(Y-zK!sBf2ZqDbZt5!)0FADI|rl?@QO&W8ut@ zp5MPon!X2RCM57p&j^u`CzNLZZ_Xwz4jD1zKx;L7{J|cOAOA-AcH%KCyx=^O@V$sI z%*+IHC;;2=8Je{S^v#}s$QoU!9py6}$>1pK+ zfr1l|aEJ}xw!lbKc^>f3d+641TK5;h z0*RFGvy|mm*QakPt~~Ma@R(}u#%IQcv7@8IsV11Q9^d6JP{A`b7Kh zH3;e0ld&O*847yfI+@dk$3^#|MWcG%oPgGAOo;+j8#tarc;^kc{XP{9Dc&3}!m+iN z7Wpqu;fs8!_y~F>#TW9o7ax%VP=t^q2$me_kpJ zzp}Hko=!&Y*1lwa6}afmUHdVnXT>$%;ZMtZCpv8P^k>0uFPoqjE7BmVB@3R^`nj#j z?YOehU#r5?xW!7ipBr&b^VNK945OHw+oCEHxke?5zXkZWLGHOgD~eimkUI zQV|I{4**7hSc15Bq?kK%*`d4hG6T$JZw8nk%^F#31bYBH6_F{Jpsnsbk_g%lr@e7~ zP|00bZO2J^pWPf8)RfZ)!9~E00~&*j_=eL0l)}r)@ekI(k+gE;3z;^h1{EcE{VIPr z!6Bwvj7*AnDUZ6)2#RFBrvd!wMdnpU;k184K)X(ajsiIqip4`-5B>c8fdT?O9}qq9 z%OY)lCxbCp@Dai4UMQQ2U>=qohHKcZ^Quu>?JtCCAQLwBB}R=5H6dObK0k;*1m*`g zAb5m|N=XR?&H&JaRQUsa1TPviz;Nv$CkXIo0VUqOcl~dV@=g`dc<=$hTY!Y}{~tdI zH{!=53HbIl_x2#SgIu3)aecGH3j~0B!Pl3HKZo6^K%6h~zvNpxxWoY*&|**i!dFsK zRBJo=PuQfXueWy=1YE5;_2c=j3m1yE@WX)MfZzd==F^+Kp(Tsc`>}FWYo$`6!JXs4 zPPEC`)4i5!*s$)Z%c3!u1kpZ^3!j6{6a`i{AV6wJaK;A0oy?!_l_3Um@{YnC~@jK|%O5 zJtC^v7&j613xjaC375jBM;&`?URatkRvK7I#*MW>+Y-5S)#|(p_|5^v(~O+icTF+4 zT?D#_2`qoAsg>VARSVZ5bzqhMWSLM}8G==$X!M**31g)db@rkawQz*+T&lZv^1V~5 z9JXYe(8JZJuo1l{YSYi9%U{jur1xVNc--qK0(W4V$W-Dfx3_wcu&~>U7Mp zV?G6+1M{J<4Y5YvrR!nczNzh3=b0&YSH&myHoE-sc0V-)7PU?14 zv$`#mNEN<2KyWKC>9#oEYY6{tPiycv(Kz`T#*9fQI^N1*Mp)z1hxH7D)*4uE6hinH zZrIMhn*HeAy`EoNWKgJW;NUH<^42sNas5`BztU$`hIcC{0}N&zv}Be&XNV(;pb`~i(6nFlC)toxrirlY{g!)`P|%Xf?-_a z6DNC`8QQmb9sOVf(}yOFdNg&(4C&PD*^WbML+(lJ+0jqr@=T}5Y!g^zlDisf0&j(3 z3w9_~vJ2iI8PS$Ksc`7DD-$B{7Lq|HBldWApCBDehTqnjorL!V=FL0G%qX%C3P{Tr zVo`aoyh~Zv)JnfNap?0`LBGQS5rtEeZQk6`O5sk!)X_d!%Rln!Z>6^sIn>sD4!l08 z)nDFUoy2(F_V2{Pt7|54H?xMbj+LiMQ-r`VO%30xR%n4po`~UT(WHyqhNvzR3$-!P zSjp3mm)YxNCWYp_8cGYO+14+uofLTI?hg4nVZDhQwE4-5rG#S9c&Ge2V;H?fvytSr zZR9JLI2t8RQ?{TvLd#*HVDaDw<%l)aOLr@4(T;cj;%aG{iZh()lG=-@Sv_dDsV9j!t(U;;mheOAsWcLy{cO zAP{(qZ7_j{b?`w?Nes?3D2r13_6wTLp>l&#fnoD6(d*H5-}P)$=qEz!10XF&D$p@2 z0v@%mZcoB~qVH&=kEBqbgU8Dn7?_N6gjn{+TCHwOaRCZ1c%BT{@Pi?@uCdW>+81&x zo=`vcD~#Ljg&%+iX2Q^FHK$DLPI^NiSJV$*sbRYbk^9JLQ-U+wO+u4BwfX%J#Bt@U zbBq!6m4-|DpJvI@^W?v*(Z0C6NkTRafkEz1pMD;ncnf$hG7O@4WzVAZ6!YlF5VCZw zot!ekh(R#}aaAJ+V|)NH!c+56jYyqm-SLUqU3falGAI6A8_q;>`0al1T^0H313iBx zUt^SI!#^-LS7s8Qz?Tk=+3J%TOf zp7%d5b4#|jfBwaXhj%I>x@f;S$FR5d-P+L+RoKqmK*mr2A`vK4d=Ea)AUdYO(| zCFT!G7Fii3@YOyTb#yhX&So*mWT0=-g}ShiBbw{a@E;d9^_!5tFXsQu@+#&|RQhga zmsGh-vx?gyi|J7*x{v~$uiq>GHGV&%)vf$K2SG)*hMuo~ZV3d$y|hZWmq=wP^x$Kj ze)nRzw*SAZztNJfZo0?O8ul}DqPBMJZ`^S;;^Q2|s_5kj`g32RQ#QB^Vj+b0|1y^$ zh^iJJIr&E~PY_d_U`iI#kngz)&dz^-l#du4gpBMg}jqS7ZC5kVr>WIFklLTLH|FOLaC<*!?K`> zjC$Wa=RW2{6_?1Vjn2v4uc9inNCmCt*GOG>?31 zRuD)G)`l@xe~9opI_RSXlbjdWJmwY`p-YtfUX$lN1V2AN1fLs{QIg-wd`Z>+zEe;L&* z{68%K_MBOY>E5?r&w|gM85=+Rc(kC$uJ63?$jj@*LNGYVlQ7g}sM!HTJqR6$l7Wz% zi3vHO%=>s=Q;rIOcRj1#xt)he%g1qXC0|}#^sgRb5vK9!%ROH7Eci-&&&;4YD0)KA zaG}gN1=^7ILNcCOnyS*hnjv{z|0^;@D3ZWnY>Tx9q%Fd5a6`KgZ#mo2)$TLs#05p~ zqlHH8C-bwj$U+}z4~3IRfgu5kSH~9?Zd;a`xoob8-~sOB*v)XerKu?uQrzH7gmb=R zdECGcW_6_C5Ar2){|@BtBm1X;xq#UmVGJ9Jpy)gD*NSKYi^;nnvqJZ}pB{ta`qWZ{ z;)gmDQHk@LfufrBZA@0jhKy!o#|9JTQv9?-uZNp2gFuIfq_?1U)%SQK;Sb1`t8No) zTlX%zD+GC?>c4sIO7Uv;Eb#D;1ZYQnB>r(sWr6OF?KW<^!jMd=Izc~*+PZeCHA4cg zfNOog@!q!ed55M@rl4&h%KgAP@`j^H+Zop;c>g{U8kGj%Fa)nC$OG+k92Oec>|YC$ zB&+uPH6WQBpAo?JUOn;!!Q~E^A}JYKryL=?2#28b=f_C5!oEbZk;2Z)D8HklHf8_5J3-A`)w87Pc*Df*2m^qx0c>|XSn;x+UzN9rp#U&%S zQ-KW@-^xz0pYqZ*mENkITCE!L4-Q_^`VCwx{Zq-Y)ynO+8t=C$W}&Kp;zpwx_p^H1 z?Blpxh!cr}@P=5EtPwTPxIq?qQen=!&5NQ@rJ;I&>(E|oEJ5r8)HIPNH^5izu{mCR z+lrvlreq;%_kKfx&i`700XKwJtYlSp2ur-t3bac(EYqbk`qyz>+_syTInS+5;9bILTnK`(FYPM6#58ciI?ebb+u_=;TE@Q$a)J zyntM+pwSLYU^O$-S7uOD{3B1XUr-f4aMeb@dMb93S+43*MB_(3BENI*E zV^p&B%gu&H)Wi&?(dpewJiC)$8Gl1IkMqUvpeP3fzu$xL#})U2StcLV;-JVg4aN?% z8Zb@#!49BZ@J^z5?SeWXW4U~pgMA^N|KWz(IWrl_k0Gb1h)dKZ;Z=tGG=ieU5+$7( zB_mQIrHOF_e=Qa32e}1=LTIGc6D6hF7;!uD9keNg3DWPXwwh>JhbE-UbTDL5;!WW`H=FWrOwa8-GQBKAcoPnvhh{2O*n;*cG79phs8z5_8QTl<4&Ok*cO zEBEj6>_v#SvsOPNbeKNKKw)XE%Mb0@kV}hXw5qU7;X=``R4sajUT|>-9g|>c8&7tM z&FbCLRc?*Brm$+RB>K$e6s+nbue-AIYxAVzVPan@|x zs?FysvxiH)L|O|bE&21Y%d^yZRbDc*)EI%bi&*(o6VrFFD4w3&-H>8A{w=={aUp}H z3Q<3^?(%dgSXy>D+e@-37I}k|E22ge{Me|@;$7b8-UOC&QjOFpSy4hqTmIaxqdUsey-tzX+S%ncItgFS=BZCpI@Z|)`SqEx z1>P)2@oX26b97(a;K#@8S47G23lMx5VoOoHX{Ro(&(M2HIES z;#Stb{W>ci)X2^ntS`nq*=mrUd#JR-?Q-=k)%ruR45eYYFWV>6TW?T0F0!R1nVxV? z#YMcwmt{j?_>#W)>uX{8fr%bNHxEK~(zqvdd_?i2nWJ3o?^rM0hwR-K0?J zA))LKBIXH#bo8Ns!Uz^C@GP#uOSW|?%WZ0J6pgBHnq&{nNk=0iTRbjVOX5L5-L^vKqI$Bi{Rb!@WSd_>QPX-}zk^ zJz4n<4zYhc)yGB39TX@cTpVJWGX_b7{yvMTlnRTb58J6xI#>KlEQq_0hw@vBoEsVy zu=2`$eI{MG#Dei%xLumZiYS@oMu~0t&}Bjx&8+R?3SGDZF%m^}Y&B;^WJfBT`+5mU zLu;FpGYaSRBmZ1PfL>Iw(BWiDm?B~UWSlluQ_eqj4VigxZ zke|zRtyQRlbUDRVn{@@;O=}fZyJ%tI;YcA>&bsw&&>;MRCI|>v2v~ZnT?MHWgPK8y z#BeABQGv`__V5VXyPVt>WM*M5n{t|T^pdCoZ$RAK2XTIWSvNNxSuCVF+rk0~^bXtk zf^@Bj%c!o*vcz`lgksJ)4hnxiexzSLB!^Mj$2=1#jrn;BaA^UokL*wctordId@$)E z-Papq3{YLmh4i|^%j4h}f2O+`P;> z0@6c6Q6xq|Hwao9PZ~)-d4>c_&~3xR0yanh%#i8_5s@xP>@~jW(zM_xc^`7V(IK7; zc7~wSx?FAURES?A1!)A#>JSHjtaSzM<$n${c!I$W2zH*?2eXEm8>@C1V7eI?c!{C} zbOZ!@gMkag^s2==`g|qzE$gJnDI8kZ!A1icDssUFeGmMfS666e%^vChg%6}Ze$_*x z5vOVV&~zPaMc=NsI8O0TSxIWCa%m2i{w?&8L_^iPw@=G)#8o);_$GSePF=gCvP6!Z zr)PF{wxQ*p&qQH5Wp^KxB6S?|^XzD7SD&F%Oe+3v>iOT)+s^NH6E#kGudb`lawI)$ ze1mq02{!``Qg~7rjgMDqas6ATBuk#T8=6R?)`ysH5^pqAUr_j!@#NiM+HmB_OHbbA z&da7gIj*;c=c{^cKYPm1VRG_!rO(YgaWDHHH7HVSVt+-@GNhOAf65Z!9=R6nT#CG7 zS3>%vgz@QZm-!wc|K`AVF>>x6F*c)x9%enK)Oe0JC0wNJo~^%jY{JI#c=tnQ{8d7< zy-HuL5!dad#9v%juFuUYWEcpoI0*}vHar6AH9YNe2O@9JZlbgNLy6V6BfK?sCjMJU zxVj?jEgdKTf~k{O=8o<&nNAtG5|Aigp`s2}m*b1la1ScqbUif?edi5$0vg^796X%(tT zEGZbD9O<8ZPU5RZmVOewv@{k1JCd`I6P0AtC;Ah=@Sx7o?HS5^j2aJ`{gst87_NTd zJv7-Nt#N>K4233+CZ31(aWHxaWa0vdj0~a#q74iZ(k=J(EA#^_po|r$n@AlYPF>Nm zueH$ecAe^uhm+_*l{eYBWm`s@jf!8K65$f}oDIH9Oz!$|gtz zfaUP8=WZ@I=OMq00@_H6;eLfI$b$-tt5;xw=QeNahwzM{p}W8oyeH&wXqbm?tz+Cl zkUPR{rugCqQV;bZ_}U3lVxZaPM`66wudB1Aw_2>oo=h;3!twDOc>IH{DGI0ux(*Ew zmjg2j7~p;Y5;NOqqlJebUpiH8mIid=lv)x^46!dYiUe#L#X6xj%!-u_quSQlaTfNr z@G6ASv$w=7{_c#5_#MW)adUs{orSs3;s|McnagfI$b zWUEGAr9Jnw4*l~WC>P&t>E~u*-?5k^-h~p*r5H13pJxib_vf`=hYJ6Ca<6aGNS#M@ z{t3R$P+F3DB=WRo2Mf+ikW>HL=6Ue*#y~rIsW8I8dUxZzdy{aRc%+Z}7^~^h=i+h>vaQWgOnT zH3)SXrU6I8!l0Cvx;oZ{3wW>X2yfNH826v!Y$Mk_J+7gC381Lq{)x$+Tv=fPst4>w z;CBU8X3^4~=W;JDL&6J`b~wr5y6XWu69M3G@P=rw3WGm)UNv2(z_t+ay56aCN!Z(5 zZ1y(5oR6IOy|6jL-~j+(FT?IR>Q;2`U?sbk_+%U57z!!V7Zalrl(`m!g`n$g~Tm6J2B0Xx`NNZzP5u|I2UD|Tf{{rj%$#br+A zIbfHs$6CgK{cKY#q_%CbKX7!eOzBvl^xI->kNs{x~O z%F#hV#%E&wkn{6113@L|Mbp!%aBmZi<1urMAh65S8T2~Dy)CT%GE=&Q*5{4WK9lou z`RLG*1kmmvca|^Ip3vCfe@`zHh%jL=c?xW z6wjuU87m2hb4tDdc{*qV`zkPMy-FQRd&oxSj=zU$6tTTnUr4!!#4I2h@qD8&9@>zB zwlnVx8eY#0)@WTU8FL^b5KbLRcWL)I2!p~kg7ZZP%ud9B!xFiqf!#0)5`?VX%aetw z9=7&^;t>{57$1O)tXw~tvCyrWi5>hg@m3QV?(=VN=KaHEFlOa1?LjpPTVQYN zL-1X~RSlOAvY`%+J@5$M?_%%YrfMYH@ooif@_rn=kKQ%yREP?clxa5??!yVCa&B4> zWRHN86)q{XGe-hjUa}`YyD`A81#BsDXaQw7$*w@erY{XZH<%gFz>M6K^SF(y$hy9_ zm`7NdNp?v~*%{XL3Uir2S! z%LAeN`{xsfLp+^nl;x!mlx7)_>fpu%%WaBYwza*cOz<_^HPe84G$|NO-^lneRV|T4gA{yv{rv+ zjeJls>ONpP63&lk&|7zh@Q}`PjxbU@JsVGV3LD>m_emUTbYm;_58+;b-h+JsI-XCl6O+qoxIFNdI*}Ywo^c>1+(m zS2yML=lH=xPhEfSb8_cx=er7Y=lfep-Ts8~kr4-1dE^smzmVMAuUFcC(mY3o`SH~l z6IBPkhS$IJk=h%gfc4wQEXHf(vCJnjtQTm3YlzEHW6N3aY34&3rFb} zqnfR=wYq9->l@^z-ejc;$?*hIR*&B?-RO2!AEhz$m8s_Nm&X^H4#wEU2HjStl)C-@Utq3`LE$ZJ#$Tw7Ug!Kzh*%`kN8=$Hm zF1EEKj0w-*UkR+%WAQvN!*>(;?1hHG|2Rk6yNZmyimVCBVJR=zwU{Z0;Ja!)-)I?50ORv(|Q-310`z-_dIKaG*qE)i~w z61O5NRGGJ{_9_N{TTAdx*<%J!klUA@_8bx9G`_>JFf z>G*}j$WgVJf8m(TZ^3HYrV>G_&)!MIOguaLA*B%=Z*tQ%k}&j2BH;%6CuW8u9dgn* zavs&M#HQTbHMq)lQJg4bZ|ih&XYdDYt~-nN0|(vEd@(wM>!NU<=gjS9Iu618e^O)} z7XDG1?bk6JW=x4}ev8~Yjb=W+0RdqIQVk||&`X9Lo902A26d{+OmE~F@E|Z9g4e;u zGLo zS{)lo5~RY{)!5s`xx?}J3)SDHyp!UFAmq|Pe-*e^Rf0!w5wAAktQsju7)NnpcDf8 z`>X#F6yJ=lis}V}*bkv69A#99krz;%@icxQTI~K5G3qhroJHUivn+N?!%08x8J@$gAc4`!(DrPZ z$iugx{m06PkQW!f4ZR=#7TQ0fm<`7(E2UeL{c=Jmze)J9Az)F4W zM3#`|?A@or*?8K@PV)m|5`fVwG^srJ)l*L8-^vY%~UzBEfg zm#<@EXA}dg7dMr8z5O!*LjmC|7_YWWV5r2CKk)hX0<9lonLBy#B^#u!kJd~%9xOf^ zJ^y<&3c(7H8U~Gaz;FNW9AtX?J0I~4k>6lwsVxf4+D`Ze) z?q+Fh3z40^|Ne@C;es(t0h0Kqw%Bgoyu`tjga1%AwFSI5ASXMGdRP*WP4?&L?y=v) zx;>@%BBK2FL*XB_R`+hh)VjUB-3A%f(9TIsAHbeWe0q8Yas4YEI=2p>L24ZcOY9D{ z(%DQsw}qu8dtS1y4gwGk0@y_)IO|o5-w;_k0FxP$`0cp9o_ukB{ulfNa$J`HM)xVZ z?PpbFkSEBIA#eftL(R>`fcxXq1Pm`L#fz3@kzW09m`E*1Gi8Nq+1ZH{IE-{}dnd10n%;*R- z+CoopLbPvSyj|hPrlp{vrK?4ra|jC;Ez^7A{MhO+Ogrs-l5!$k@&ZrVB&7$W!?B8=ZeYMFf8H_r?Hd&YQ#kCo1%46+zZwJ| z4BP2qJ|U4T<)VuuVC+JOoLmNiH83688LA-a@O=Lh{-5*Z_&>Wl_`ChA15S0U-`ZV;1mJKnEc;Yj>*vgo9sc z@wdk!&AKJ{S_)JTdh9*0x5M>p*5-p$bV6vWtzH()+i=^>R9OJ|=(v?PL+^Jwqi9H;GpPh1?LVppO-~tDBI^2U0l1ILRyzGGT=9QFGm->G+y>~p9 z?fXA&@4d2jw#<;dvK2yv?3ul?_sq;5S=rpS2xW$3Cs_&EWQDBoJ6`Y4@B4V%f4CpS z>$^D zbKBdi#L?~7$>aJ#l%`v)2Uh{_H&C=ODEkU0z!DdBbTD!8(75~oKKr3HZzs1tyX}$_ zJUdm-bm{)^U8Jt_AZcwAo+@-NFnp!COTVYSQ6Q^ zvOo8X-^0bQB5cLt!d?hjP29fp3w7y;Z>fTU<;Ya0!3t%u3Gy=6fAt~*&r zA$H*Nx;ut0AXUKe7X)}0ShL!7jXZI1mtf!k@aXyci|Kr&Vg&0P5*v`*z>yz<4p3@$ z-61=$^J-rLMkeWM=-uZ!z>(Cco52^xN%{AEhBtFqfD$j>?-^IR;B)Aa7BKJ-dGI=% zNX|b$*nh(Zi_XukVyvk{l!yBONP`n2U+{&xCAK&OIIxm{&Eu481!O0J=P5*U_ClWp zpA+uG@%fP@qAO)fg_y(aX-()^z}+auN78xC_~px&(8sY{(8cv@EPk`*%X^fIY;&IT zVnG3)dUSl;azO-?g8*V`@lYgu{Q;s6nVX}e1fFX8|AGL=JGnxH&b?NNaCisjblID& z#){zph|24Y#05N)>%hCRw)Mk@5m3Q}Luy#SIT56Ez`BL!2pp!Q5UZ6xQlg@RgFU+H z|Bnj*@HyCVrK!2!{{$-)F%AKKGdvf-AP*%82i-L2zHZX)o8CNbZU1Hut54+@prnXt z3#{9QJbHrY|7E8kyiBW1xw*OjmsSq0O29SxGk!BCv&wh#iw{9>-}BCe$0~iXMhbVv z@cDB%JC0%Id)?PO3(v1AuFF?oc@BErnhe>D}pAM4W-}e>}s8utE4jHjxQ}0U=SL1W4PE zUI2&V#eT;@R&K5()IR#vptQf6tjn6Puqy$J*ixvHy&52hxirX5-d_}QaDrD0_FP!R=f^U)9*B

    Z4_+>v2 zEm}x`HHOF#k}gojl7pAW+#Gr74C+T4d)0Y2hj)UDwKvH@45?llre?9EQJ;Ig#S^hd zstR>k>uWumcS7~)g?f0M;wWaH%478k^6St3QVgc$2-)5;rwnQ0r722$a!EEM%g>C) zhfT+khLjQ^hf=6q(5mYgv&^A~j{kw`6dhI9u0MBKc1i29k=1UUkw~6PciZejrF&7Q z@D&QnMAwXLb{%5eZs2GD`LRPt>$A zh|)GUaRuC;7uI0u9X`Ki;~B0UPIEGRpYeQd9j&^v`E6QMKM!ffKqGBLdu!U}?=IpW zjUQZ-^~2H3(b+B>i3m*RpI?6Yqcfvevt7I^_kQe)Q*>ISqN|iL>el70>mtsK06NR| z92sd=3sFlmb~Cz?fF?JZoz|ov+8eBUJubPzSz(=8OSe*_^}#GpzirBg^F|aRjkvwg znh24xWfZ)Q^pJ}_6rgN$J_$LsN^&x)>cnhG6*RrO{EF{*>8Z7*^H-cNd4AvZTdCRl zD9YYEGd~q$jVYWyKthe7ifoM0Nss+Je)3|NK+Z;O@!?<8_z#5DuZIFLO2RSB$K@@l zIi|j+FDKlXyo(+f6FfOgLz&6_>-S7^^2wg883W8Z`StBYG7eT3=ri_~7ed9e*L}|Q z$rg@@i5ZOEA$Rh{h%wh!d6v-SZu*cYHI-1o~u6YFQXeiT@%OVxw8MdDR|SBzS8a#90Z zTqI`m*?R;Bd;UniQ9-NuWK~Q)#7bkc&=T=k64zYf&%4r}MmT0ir4Jh~Mp`xKahB}b zvc>N;?_?bk=j+~n3o$@S!A4I-_pXy)Fs5GDxqe>gbgw^#E4$Y6UgyCtPX0-bv^Ek8 zS}tyNQL7i*?WmHEWmpwAqI8Fv18v^#M_x6F4y(CdE6)!IEfJu`ZIZPfq7z69=LQ~U z+N6=}v?{lhKd~c_YyDX?`j&|g*@0FS$?Ljh`we5{b~Vpb({QIr@FM0){EeCLu=4a5 z+8VC^ru#GZVhuKQJaYs|l5aIUA``i7~&&Uer9RGki>DaJtrg+-H z-0*5cwDWM(ICs+@BoFP21b%L4pChZ?kvX9#oPY1%yztfL&q?#!AGTI+zUr?c;>s%B zYbeSHFce_doLiD%q)wph*66iV03wT9!|Sewty8Q2g0S%>}@ z0}VH|ZG3<bdyjpU6^5?5T$&w=Zx@}Xc3*;VGBb5* zoSNjFD1{<3xjRd(Tb`I{!&ka5$`vi88{V7Qc)!VRd*~j?`fi?>@A-cX4V{|Ri))vs z+&uRl3+eMr?0Fu3#ELZt&8~EFHuld9kRINDPPL>dC?KL7A@cEiNNO?H>8glx@ng2v zHV#FKY9%q^1dHCe`$Hl7K{VC4gAXwIBuW_QCK^f-+FYYQ9S;2>YNE@@yLY9G`DR~F z^{;tTkbIdg`)h{H=_7iY1)6WedXDU`yqd!q;$;7O?8Y^uV?|xQT<@!6?cpEY6O=c? zs5Tk*+B>?$Rh6jcl_D{A?z84TH>XsE1(fQ@-KU2Z^rxS&ovp%sWaJz3&6dw*o&VFW z{n%SA%II+9uzJ_OZWwEvg}RA2}E89Gu0d1mY& zY1(wyKc(W>1NC)X2`h4X@5@-lw+?PTVH)BJMbL`Qjve2l@>5^hZr?4KTbBIa*R-RjbjzFOMXD{`)|E!^Zvyh2g_3K_(xc z>*=N5{2tTU&s+Zy6XTMVmbn-Eziby+h3KzmrBQilJ!gSx*J4wafm7>~2eow@$T zs_}`)(@p!_AsYMh!$AEe|BnL3O)u57S3V6`4LYIrB&@rr_xjyG)ay7BIOX(O6mA9v z)(6HY(poUf>nb(`<|;}Kef!4K)O2hm^q@VDes{NSPDZS7&Ve{i8MvN^CJWF9*j5aU z4H#1&aaT`^RO-&h#Iio&BnktV1AOtPo=h2k@Wfs^-tzV*dxZ|rX{=(353`&kF(%X1 zmq)GYFopwJ9>|r=4e_FDktNoz|JzxZ{%6OZkDtUBdC^hZ*Y2|G+3x80A!ARj>0#3( zBYmd+jJZG#IQso(*0Gr1(EL46zmT6d>ETSYMMEL&ZUBU<5kL4Emvp%RHeB@S`z77a1G?QB~W=^ny)_>^y-a_?*nJVnI^r8Df8K*JkAz!jG# zpo*0EH_32KycBSp(C~qa3q0QDkX60Yf>yt|b<2wD=cA*Bl<)D`a%GR)i5#iiwYhn=kze2VSL*gQ@*to|V2p2h zcK|SCnOh+TatM1;;hFr=OBX-c>LJI#F`^1(`-O2pV_G2hQ=?m)BsN)vH6CXeI zNzcR;58Ub}bl_-p*B){?fsO(M#nhMLjO8CUKN!ldzs1n zw*%J|PdyA=mIj?~3sU0Z79f;|7S(v>K7MfZU2CyEvwUfpRg)L0FI2Ck@w6k4Ujmx| zNSBtV4htf{5{K3%=TG$>sx>N@n3}eG4*3iY(_jpKGj|HDbZI`>gd9-gd$}*F?jCvh zo$jQkHQ;m3ZF#>fR`E#|m86cE;LIJRR#7!&$FJMAoVchl7YczUKjB*|;wE=?5}5s` zHM}m^)Rgj5T2j)=#%3VI_ELNY!^^?p6||+7*U}*NgGCFkD@aZth^%;4uX-AgDQw_d zAn>nx`QXRZ6!y3#_)|85R8Zi9G*1NHY-_PJ)@ula8*mj{8%Ur**zQ~IUP;4>$rW|^ zvuk?$?EYn=i7}Y#LM%avG zscB$8VjTlh0tQfs#_+q5OHrtCP51Qf=?GUG&~Y1ETM_i8&i?`7U`!38kP;X^vIqZR zSL^&o4*T6ELRJa%ULbrUyf9(u5V=Sfls~Ka1IERFfRFJ-HWXr20JsEat8HbkISj+r z0|;1wJVu2gt?m{l#1H_HAg9Ga7SnG5KL@i<@J1Sl@_tE(=O7PA2?E^%6nsl?3gqS)d2wHV4 zis(;Mqf|~i*ervrCy@xT&WkbbK(n7)uJ^MUANsuePGy}%U!6iRE(4ZCEt8yEU+h#p zr!DLvY$S-B<~ThVZ>qm$y1rqhiqHvlCFN;UK+;pm8_7_^#9+onFKvF87%@z18OkDu zp&n|bbGQ3bD5?mjSbo!)LQe8Tuu!O?l=IXeFB5a}pQUpWS1Np;Dl<n6;8MRIhVwAR&B z%+!#WwPF=i3{=l|%zqAteBd+roW^Bn_LB44ftQv^#MrQowjnO=_@ACX^-?tBf8y~= zZ6(fIqHQI_S|Su#v%<9lzPjdyDvkt(jd+?5y>K+_d`(u~R>n3iGuZ-W!z;NSW^tPJv=Mq1!Qv?wo_>@2B=sGwM5P}4x~^FxTs zN-cKeiFah@9gftG$SD`|`&!j{k$jIP#wvO%Up2UJ{b#krGgT4Km5Od{+EJYnA(qML@<@WW?7Y0u=8_Nv845yO1#D{t6lmSzNMTK7G{^u>>*1k3= z-_K}yltc5F>s#<-Y3If+S`rTC&s(^egwg9~srefzov3L898wN(K zpU;XC&_8N~*xsDgTWu_`5XWi-%e|MbTEa4^n!eTNS8C*u(%0FWZ!@gT2#cTy6T37_ z8sC#u6|17~pUrS;si`Xs9Xfd@M;S7r*a+upMQ6_c4bnSe1H^Kc5k5&DMiylrbPyw#3 zp@EsfTHec_>yTdUDc<+v$A84>h_evN9xe>#W6r!W#7OVx@4{E=M+{Bc`}!9z3Yi~vBH8k`FAHNHW+iW{WNr@Fh_;!JdS=P&+zD9vFeQu8AKQgVm zTOcckpFj@;5l}_I&QAs47w_)w3r}&Ax6H33elyRz*Y>rnNre)ju>UeMTE-?Er}7&>%N_mS3zjGGX@y;*rNUl(L_@eEwt=+h1y^U(3_renFji&-B;dJsC5xdX@6Q z_xuus6g+$d?q2Ioev3>U>k9k9K?Mh$flBXmN|*NKrrF)dBHf5;A2&TIZ=5XZT2VlG z%gy`7F=D=cY~u7V@}ayziDNV~amp;7ROWo)xcMDLI-LG{cbLQUM{I&8HoT70R`t_; zSe3f=R_BQlu-QH*=jF0$tGPNDI(i#@Gx8D)ib%<0ja3h0dO)H5z&-a3o2?GWnZkp`G0$+7=Sr<~iu}NYW7R+ZbR=UnRA_-6uFQe*AN{{azq(zDG(u5U&ts z)?jVqdPcYpH*8pxu*)1GvF&&q%miw3>M~M>&}sWZXS^p~T@`)Sj5tS57we za^P@MK=ZHk!2)!BXG^ysK9Xhg-(pZ)Oih==B?hHj;A=c_NaUq0?4y-auCs7Fr`h2EeSJvjL`H> z+JWCw8kT%GATY3|eXjOi0v`=Q_X9E>nDS`=II`&cq*`zLv|W)FbLM!<6D9iYLW}0j z;9G5G;%G3*saa?RvwWqa8Ur5Yh&3gQJ|@5mysK4tC|1~IZelJX)jco6Xj)xXeep#^ z3civD{+aR}7(_#zKYts&N~n4s77>Cw$@65&!#JlSBvs{?;qqNt!MG;YOj|cU3d`$V zMcaYHT_@UMj6o)f*ok`w#C0#JT>RtD(CMBM9R)~s5B8F}%T?9$7$ev6abyhm0t)-# zHu}J0``}ebM1T`+ED2ZSc8w1!wm6kpvtzP<(X7&r>Br0_u&CR{$DmvT$I1D9e z?4nG-`NaFj+a;DB)ZWAE?g1y02xCJ)eh^8);43u0mq9fcVVH4C$0;Zxq6DPzhzflM z2|(Du5d$p*xbfg!V@a4kY6G<#YpN=0HY*7>G&Qj9fS3VeEZ7fin(PbX!Q325MaZXw z(Ffq*KDXCrh-l@De!d{NA}zE3C2abf?vNv_K|r_={O9ov_U*>fKbqR-AHN`+3K2{< zAWL*z0s%t58W2bZgi8wa!SEMqcsYgcBn^(rYI7TfMmPYk6c9*I0FeH3;&`QndD6$I zL75-Qs8X%>vU%s5VXh4RFihJ}Uv7msQ_do3Oc?l84;LPS$O5qaoielp%C$`x1HGI6z*Yd8S6PGE=Z%wg2m&k!AN>6ny7L(^>D&J~JZwJ5w8g94 zo{Lgvuzmk#%biSm96Yh(9{PREe~?j+&mRAs0qc(hMI2SV(3_2`EpCv>*f(bdd3Rw7X3Kx-JvOxyN(E+fIDI* z`~}o-P|EAL&&z%EhtsUZ=@=X-KYdfjPYgl?N}QVBzH6&|$FrO8?@{?wO5wgI-ZF9R zOX?PE?jL!)eYSg&UetIP;Qa|(phV+1q5+y`%ho{bC_-3MUd=PRRE5W2!9Ot22rWzh z9aG3XHOG);bP@I{D6E?UuYA}*5LN?afj*EI1Z)}5WKhj2DRjBJE-=iM?Z=($#6zo= zb|zbudR>5(8d(?J5`s2&wtsLynxF)M^n%=~|9=DkfMc)-U{M+v8LdL_N%J$_pqt|Y z8kP5xc89ABw+8tCuKNZ4lKnfyz<+=e0xf?eUY*fy zMyHYtXaF4l?YNii!q^;ikDI2qyTPN;3_+ivmH_)0DntXmw>N1g48XDQ9vBOkz1fx4 zzjbnUc4n0UW{Ka%#-pThKuiIFwYmG%j31Q5Ie$Cm9P<~tB6}qBdYw9*UySee1*>$K zsv6zNM<4p_%E*PMpU`cY*w8|Y&$z9OB=C7?QoH-%&(sSQ8o{2J_SZU;G}t^l%lWT3 zpUHD_*y{? z7{4rqpVP0(-in>isJc}WP#hQFXHZU)roIkMOef-)4bvL=j^iY^X-TAr$DOJgqfuFJ zE~nzA%w_d?yu0tKgF|Oz5_?TAnog{IHAg6l#tG9Eqp+T(DvDC5)j3lk4_Zd#;>X_Q z+`~vtnm=hJqgi)(D*3JENJx$pmSYcSc2)5M;^T88zp$XDaaN3^nMe&SLts|tI(LZ5 zb5ue)Vf_n-zvX{ju8PR56aDm;>9`(G_`V&k>!;~7Et<)|xZ~-Dr51}*5=AcF99f35 z#pyGIQKFKAH{xJ75@JQo^{2+HCqC-u2wI$+1WLv49~TMB9ZN3<-T&&2I}Ze~>Hf`X zrwd6b=3l(PWF2us>$%kWJoQg$M&6eyYzghRx>ng5Ch|A-a0!S0dSpKu-*Xb&H}V%=6f5D#)5$^d~YX zQ~GiAl!v>0&=?{u&KqludNW%B+WEc(D_~MyYc0LfiN?J=SRN8|D!+6){BI|%G;t6o z+$C$YI306+!-}rn5xZ=*1%NYkt~A5M==HgnirUet>nGL=PrU2$QLH1lnFP(VCl$0h zBWka34x9H1d$gTGh;DL|v+BqO$GB355*Li0R#sK+X-w}Xb7hA*E&M+&K!FRr^I?2> zSSAjR2PTuXV5wkP+MuMhY2|Rfi>%;NrzZ=B{zZN@$Gj((Ji|qN5A6aherrw62-_hk zM+>;LjDOE|r;Zv^^g&(99HY+_yG>%zc*RxyYt)6f`NoCqMTuh+m-cMZQ~;0sYSVH& z4-Y9Lf8Ij&PSI86;a?OxwX=nm2HThNxUz2_MX0b=G4e@xn(Hprq;rlEL{bwzv!Nx{ zr}@4dUh`kRXRx{B9=V21W%%F7Zeo%Ade;D&g{Ko)7@q@hixami+&cMc%0`{SlCM+w z$d+k?vQ|`(`YT)I=I~;1Zj*zakQ6aK+nVy=Udlz9_-v{iQsDaFc9heg{&?f)y0&EU z>ieP8#=+Qwn=;Q9$u}lQsK@~V?n%LAzw>yTbhPK_>2M?e77ZRzD}Lp=>uw}{>9;k$ z{{{7)Cpe<@)vtN?mFI0 z|7t8bE?PhBDpsOj-SF|FrZ6?j>lo4`z`x#tj0j|kK2WQ`76*qj`hTDOZ3bWOy$@0; z{VTd#i1FzcP@IXlsxJ|{~O_o#Zfm;Z}_pgIeMB}0M2QzB9Yl6-X(IciD;*YY&x4oOX(%`h=m zfsGW}$CH0`g#WSm-_P{iN3-RLwJon`ebM|7otEKOH_^W$T2Uj1PAv1)S(0xb=1o6nK44yWqZ2L zwZ3QqHQn7+&dy{m7x{{YB&UI)PQHW3FAGW{k7Dy#okYb&9bo+8Vyd$qj#|)NOD0Ew1PAxY$hbJ{>r#e% zp0yJBCQi9(FwNvj2RjC?^kzmj^M#$D$;S7tD=6yf!;l)B3j@}a(G8+rc8b({noz(7 zT%XQ>sVp#`IMN3|xkl)-nTP010P9>8BL+trs5~K47LLsfYXK?VJ(j?w&F$3k=Cl~C zHsdl~>dnQM2P?k!z@zY!AtJs%d^#U*1;dDZ*9NeqG zOcv4+l0@2%lS)JnG$p>nCYCl~%ueo}{J% zd1m7dg)2`kjLZcE-gQrH?v9vb70<;swlO?Zbo|vuHmCDO_pPktYgS^-l*IDb1x_2a zDdUgs>De@*lmk+~USnNoM8pnZ|4My$xyQ6vi8ok-ldwMZ&;4K9slObY5d*)b(`0i%WUX3eq)V(fZ}{{SOu`gM*VG9T5bz zp1;*tImlkcKaThCaaHM>VWCI>m-oAVAEoQQKL_$MHxx_=k)^WCrGU)kr1F}(@0WGD zsBk9Be&&mSP%w;ViAq;tMF^0fJJMB?53BJW=9lYl0Mp4RsMA3MHF4OGe@9AY`)bMT zchMjSMi1*vnP2UpNx2}n!#Ks^-WB=I4j?aR-f(twu0ErUmQ=bmx58#54Xb4H`6 zX6)>At8IUF21Xa$oRouADdbopn4iyLg$-g(yF?$t(7Yk^>yF4Jny>*_(kGzcn335* zi8klxjVAmRc?iZRz{7>wPeqZW+FUOe2K0xB;t)ogXNxZ{AU7bML>EX@Aov08FpSoL zP#6H;`PUJAb^u*GBJRx=mT&Mm;Vm4To;g`r;8z8V;;KFSMU#EF5!Q)tu4b_$`J?($eA#bt^uz40udjzl7MNni7X*mG+~C$`*&iy}-!gd2_VwD;_4bhk{M|*z zkGZ=_bvWTZfh98w4u5;!%+*Bq<8$gAcaqMYN$-%A!eDqW4R{dw=h6k6YinyGn%c>r z#f6UoarCpZS#z0xJHD%8nIqM>ew|TLXOCXt$J%LM6=NZq@a4>VWVz6S{P2{~$mL1( z#hb-W{V!j=%Wa<$1)AbiZvc)gaQ{9+B?Wh6qpV1$vL4dYmhWix^yOyMtnB442ETv9 z!@~o)Y(2nRgP9*x@X#ZGKvI-0eQd#|DfZxMAO~39u!@}j3z2&^i&AFtmFV$%d~Bnz z47JkNBDg4VDo#ZYDDglfTQapxlr%VwKGf`2*vTd?(=^AE_h|EnA9aEf+&k!wotHWh z3_idK(^ddx0>>F>WkQi{dYv*3uAm8l?ySvQ)6e{|rsm}CDZrsYJwOw_NTlxubpz_c zmIyeikR%O)1YM~ghn2q^xe(}bO-sj)X19;k&Be4b(PzAXIti3YDkMkX=Rr)m(*lCA zD_?{Np@!83W2nP|+v8vn(JmOwKobU{IdGf-jM9v(5pYMr8LdnyUf%$BcZ=T^kwnl{ zA|O#fy|%qO5aDPxuE0XK*S$cH_lAbBffo%Z7i7F)Vq${45GEFop8;zVOk3VP8$}8O z52K1>>n20vnY+LcDxB`A6xXM!DVSuqQgnh>< z6%Q!sR>y2N#M5i!(;Y`FtRu9?1^?FA|3PX275rhCz=9kf{snB*+3E4^L3x_c`hWZ= z6+z^3a-6uDbrjZ;@_i>2{7Rwgq%PG6+ylNVJY&drFVf;aJ^Jt$QV+(~Qd?r7y%$S7 z#=!cga4DtE##Rwtbjj9F@B0}$ZlcMW2AxJq&d&an`FKJuL`dREeRw>Te~)6V{vTrM zn%DXB zZATpn6#gxDQBu&#)-p@S>Bh2dtxWpDp=+NdhyK%Xh2_7)m#0AR4`yXlpS{rzK5$GH zdCz9Utje7_N6=D^lJM+;_rxDp-Q3cBJ#*dP#z>m_u&>*yx3T^xjjpUcKy4DwiO@z? z5am6OtMijr_j*3&G2}4fKKdajy0XRCb&(iUQ=5Rrqulr4LWw@xcKF}aMDg8{oXloH zv<3YtC6O=l-v(R1Rp~4YwldGQBw1g~W<=MmH1PY7=-W;qTN0&_Tf2Yido|ij|=0ku&hNzo@JB~$KBgfnD$a) z^9@8Y>JeMLasBX%Kf@1ttntd-HXChC2ORWHP-^yur-3vL2$~A_IFJ4 z0speWH)+(@hB!$22YEulqFkwdDPkO{7(B$(?{39z~rqeOp8x#{h?xA)0DnUi$O-*w-IeKrL4CnURMyg_I$k0L#kMsBE%}c@i?v9(9El1o=YKVYqK!% z%P-1-$Uc?0f07|Jy3^RA$VIkHCHFnWu!}lGO!k$X=&ZYFe;b-IjE-0QPFre{$FbQG z=i`g9zGpD;c;`C2#XbFMdM|=jC>{@^yRkmdy1L}Qe*p_APIYzRNpe@5dYL6$*|tVL z8O``jS;}2tsaHQM*grW_lDKjw+vTQZp z*~j%%otiNTE{oH&OD3VdM7z$!x_q~cTTB<-Mw*;WA6EQ|i2L{XhWxN_;Go4x^_1V}nT}H0UP({}e@CRV6wjvz{8U9w zRqN;?RRykiW|ECE@3KBkei_K1-GxFFi%CyBury}d=p5%>Qy_M%p|k-34v(cS)ss3Y z?eSTT;CZ2S?dsG>p`8!rKMA*6H8#_2@Bd|#yeE}wwKpMmu(Witx zGNex-$6Vf&pT2JMxU$ON@_9;_uCx4y=Si9>T|@)Oq_ClB`k4d0hDpB}6)t&3@Q&2X6k(Hc$_M71|LNeqVXD_YO|Pp?ox z=(WBm2sTv%Z7TWYWT+7FS-5nNJG+0D*W|PSN}+n_cR(vQU45UFl%Rtk?<2+KJBqK# z4i@yv$~q8dVpk#Q^>g;%Z1Z;OrPG3FLp4D3Q401&vDU9+27y?=nL(Ntk^G1o2vX2J z3D6R_Ibt^qMRHx*%<4PkL?5V2Od0fA1Tgon599Kfws)Ufg@RGOyKmfexD=03J%3mC z*RPOH%iQ4)5da_Aa(O||15^a=5>gXtJ?Mi223J-DYImvF3vHUl{(cv!@uqo<6@k0B zlRP$`ydy_Lj5&k8Ba8bvY+d|)OAh-h6oI(e2__*=%40f`-XhxvARyCsh^a3uP@Pa! z5+hgm5s)+cTTHe3kuXJnfB7bX-Pxs>So42meY%OWCuFe~*uTCf$EfPV8J=$PJK=%O#hqh_o zVS2r-K^+3x0tAu0&6tfO7UrY)kWppVx&X0XoT0H|Fu%7QNQhMo8_s-sz8roAQ_;82 z5iUQ#aAToQ0%bT3L%<>O>ln!{P+|7R4gc%OlQ9DZ2OQLwmoKW`0c=hR)Vn;;8i0ch zz)IlNdUHs43-N5DanpBzR}V!eBD@0eYhWPGO7ft6@g69O49_y&2d%chq0?gK-SfsI zf`TR@nW7N%Fae!~-+l=CT6XV=e4cXL0?v@6*%M>Uu7} zN=vwlO@uzG6JF9>Vqc>A(b8no+p%>VGiEE3ufaY8;}tPqlx% zeB^O6LAbDU~! zZk4kV1mR~;h3!dB@(xx}avYR%zq)Scf|Y|!8J>4NA9yTtOUu4a3QCsMu{;UrFrLjN z7uWG68MXerzg#<0mw9+HCj{0tP;EgVH%j6vr3D*#Q}G3NjnqFs5B{-qVMnfXFcX0Q zJsrFkEBqLkm;#cL@meZFb+xs%7QwejLPDARqN35QOP!%0$NdoW5smY%I2~ba_4fe) zWCjM=4~N(pEL~lRpdtjh&=igmUDMa&QIEZYdu?R@@lnK;z2(UAfe_(;gTeozk>!d0 zq=Xf$Q3_Yig3>oQSO%U0EJRJDbV|9c_C0SJuz#WNgv2foB185ABYn~;IK=b<5%maM z;gRIAz;l5LhUp?2Vz81CkG9Qt06KF}ySaILQ)FRL#684f8d-wiEGpG571l7wHIS`u zeqKj|-36Sf;?`DCq^(9|4m9ujDd<+QPo6A-E%7fv8#ZWD${j>>bV=jKT03D|W%?3JPri%`~01atZ@0b;Sq&dTDF< z2L$|+rw}kwdMz6P%B*aSfzR$=?^pib^S+{;ef3Avx8ZItR)FOUA^M-~x>2%+gTLF` zuow+My2Z;eT@#oDVyfR@6gyjw1cIyF05HSFBd7|E*E&LqXXR!pz^0Y+{D{OaArS`v z9qaRgnP<`#l@-5@h`MRb7@t#b#j6JAp7x2C(r=znRdoQU#`gf zin(oSn=+#mNU5nV4@Cp%3%`$YV0F(9J+#gRix!A4i3^a1^f*@_xkI!Wn5RzjbI)0~ z^i+SlP5#Zhj2hOv!Vj=7Uh-hZR>_)gJ~HKVv`6op@=$o!cJClRt>^^9X>e_X^pnGl zQ5wLxk3)tY3_|F|kl|&mTeXKAl)va=Dau5Unckk*sb0Mv4u;C0Cp) zbJ*2n=A;1l6QI2!pL(sT`Q6_agYXTKQ&n1(So7)FP1SsjkK&6S$=t7_%!m{n>2j6hOzP8e_ z-v@$;CtN4g2avJ^^DugloI&?XB)<&)C!w3ZKIex_a9cqu5BWB+uU`|xkp(|*m*9VA z+JPJ{R!$_hzsYtSdMn~sMU8?rUwW7>)VH)mxr)VWaYO){vf>KzIpCZ?-zuAaL^;Tx zv-rW66mBQs?@pGk-`m?g-Q7qCJ>^ay(qX2It?aejUe&nIrb zG9?Tbi`4jZ&H;}yp~-#cbPVTF;8wcOY%JKZRkT~oX-MV^|X6de~;Be zNXfZdyOGg?utN0Akf;`q*UXZcD0xZ?3q6pRd1muZp67&oh_JX|vJpff^EQ}ZBO9qJ z4%_PuFZ3gM)u0rT6^2zmrLD!Lbe}13BGPx8t4T9lI{epfIa%z`eMcn%a$kJPV)8eq z+-gI37~zIN|4mj+;A-8$`w_6FA&Zp~l#-m7qWPo;<5Z`c6nh^_tXEIRcSM^cdP0Pt z()8It!kSDeVMVgHIfwU`Z_eW4%C5-Ha}=Sry8czN0z!p?mzKzsd^lzTlt`rqXZj%# z=;P?Pf005D@Kh8r2w(C=X^}p6J^w{`=k7cHPXYflpKfEFuc301SHI?~;XvE_diJfi zB4l5tL{DoeI&3|q%(QTmw5aI5^t~9ta+YerSwat|7g6hv<&l5B*OleqylE6?5fs=eu{5UZ;)I)Te=L{D!%$4E2E3mo7#T5_<9U;)sQ6pQ-ESO zXOT4xwymU6WmEebc_DM=*|LxWMGf?c_R{>( zi}tE()Mt-gZD541#D(UfX51QB79Ww8T{;O$Qw!NkrqAzEJ|P*5cXO?LNu!Rz+5C-j zria3WY>W)4tT;PeT+2)_iPMZ~rgJnR!u9TZBBI*rEWXIwg#W6I-rIPG$~XQ(0qgoX5sjflw_2GMuf!|j ziB5(sq0y)R{+jy*Fn)eJT5nDBnyGs#$o6H?Nj|zpQV@}t#r#}Q^s@buTsuE$Psyg} z2*$8i!C^w%zp~el#%DV1>sd0>{?7R+y+E?=H2#S4(q1;3MzAq!qn6rWC|mDLCnsp| zJbq5rLUnexn`s7*9w)7EJUk`wu87JQw(y3Fxb~o@s3uR=MpV_Xd8c@tcv-`_Rrroe z^4=FDvT(i2z)Rk{C~fBj_;eMQ1#{$l9kMb@8>C%bL$#zi9-gRKzgL6bSH5sQ>WY#6 zr`L7mCHj7zTWP#^Z3ltrc({I?9y?x3sqL)v_rqzT7(p8 zl28xWmK;&GN@5hcg`c^YX%K7h@O}i1>YoP-co_^f1hw66YQ#2f_QcM2a2Fn0zqKUW zeJd%DlX=6}B5~J(ggf)`A&|YnG%EYPHgnH=EHk@wqVjU`rVZY^-FO~!*Qe}4DZXYu z6j(7%Hj1;dX$F4(pcKp|bC|}_pZN~t4BP=KHugb&386S$!33SQi2nY&FkQB4l5#ak zR9h!IZ6f-vkK=RUh###yXxA$Fu}FCoKRfME+`*rk6z?rcOx3ezsD((DeqRQtLl%CS z(bY;z&^n8~!op<<#Ugo*#pHUTxVklNtv&Y6^}H<7xRY?(lY&V!zM;X5HP!dqE{U@k z9wEteO}}j(XR|6hzX)KKKKO&(sf955ar8OFUmJf%U4ee##>2c z3&TW{UrY=QgFN`h+#-NO-#gc@US)T9U!?uXMFBDpFzvZVolC#Jh>6rtv;Q^d$@}hS z$%bYA;C}*HDJbiyKiC?)Bm2yu)xg8Yr$TRrQh&}6-2m**Ws9_ArI&0E$z-nP#z8{# z6bi_&-F5?$kFf~Pur^~pu&+OYtRMaXej%Y3^i-=ya9(#s0gJ6jmuuBl=IQ~Mibm*E zmdNQ5BgjwCOc8=vP0aOmAi~GO(O97P`cG!pr{3N$?NUUhMU2v0sA&6u%GS`(fIQaL z6O0g616>{5X6|cP%sGM)%R-rCQ*bMlzw7E6H^WU!F(Aul zCyI?o@H2FAp$8j4MBY(GW~Q5KAz37pIRXL#1Y>lNv;mxrUl+%=@4a?2Vn?Beft(^x zM3E!ir&VGliQJ76zF8FnwFUiRSCS78GJPT-TW0=O_?H-8DSy-S+S`-(OVqi!b0oi^ ziW=6jYrUID<0ac%Pfnf{-|_h_bFv_sD7AvfeE5brdgBkp&)7xH9ufVUb%*~hJYcqV zqHL)$W-9l=1tl_%MJ1D|PaaD(lpYCNMRBr6K=RGIc`ScA*4}&6I?E;QVUdv!b-&!z zh)*;#t7j;6$A$*MRljn1x*F2T#Jcy#2%@6X-_9P}jvr1h)+G;>2uMjq(un>XkiA6$ z8AI=DEG4BV0Z|E18O6Xj`rlR8wFIn-!yZfqXj*&YNmo=TSy+nC4~q#Aa&KB%`epEc zS{W_~4ArlW1d8q*hM;p|P^oFx%`~*N*_%HsIT|!&e@*yOoDM4La2oUPKN2nWK{W4k zvPDcg_^?t}(bQB1OlRG;zupCWC`01AP+a1g}hK+uYV;qo$!vcWDMma^~; z?ajvR?T3rzT~bmxz5mAr5F>yXs?jwREs3X?P@x{KC?H8=y`6J}*bZ2JV59_J=a@Bq z9q__O`CxocLCt<54ZtS^D+eJZLFi&sRcE}wlm?fS=sdUUg67}e(hV;R0l+Ba=xOlj zQ$!Jo@B@HaYX!#TkO%$=#4pHAvpwV~A#aBmLu>3N*ju<$xL9Lbpa{1T%tjhcA?ihY zVQ*pC#4>pe8W6^!N9Dy5%y;r0VM4bT^16maW5iZ1>4y-HHq@j;R^YWk4#Z@enJ^-h z@bK_0PjSRu0KW?GqC*KMOrIv;PfAEIFMlx@mbXRUExI>$?tOCrrJ#N_IgCeH{0GsO z)wM|~Vz=l^(*~SBC&tvol1Lfs{r+t?dTHiA``dBAmr5wqQ(kOgru7L2nS940!P-nv zR`H7zZ}Gsfb$4i|L{dt=Wq2}3EI*uKJ!CdXatsrv$`z>6se~eyGK#Hq{hp@DJyI&^uKAx7g`KD9|8A^+Z>sI(2M0 z`wx&k^n^fAvfKtr>6>%Q1X=>WH>Rou|OXl#-$svcoN*4+N|E z8hu=Z2<{NfF@Vt!(Put|iTtH&V`Bq$Flcv|F~Kne{)7ByAg=YnzjHhIDFvg#EWaN= zehB|b(^2zyLn%1)(#f>Ey)bAQ`U9IgQ1Z{t&YtIGv^N_{V`qUv$+{w-ysQjZ5O`{N zA=7ZZ=i85i9Rh+ZEm4cKu)wE67Py{;YX#T8ZDH(0NlD2sVW493`m!GQy)cBzjm`#z zQkVfHv?R#gNFOT4#igVk!q@;BWRcv5AD=6W=M5mT)0r}dw-=dTy?f!}LRb)V$q8~P ze561)C?KGE;G_Q;KR0GJJDg9xZTB!5&l2p~9n)QOQi_4<4t(CWf(SZ-e!ov{iK!n z7Zk*!uO2c|;P{Yg_24wB#T6+TGvd!(XIaatQ1`A9g+vRfY;PClM0k>Esi+3y@b8}^ z6WdG=q9c=|wqr?VkrckFHQyW><5cD4C)JRdQTwl26UBF{vkV=xX@ec@A9D+1ZuWnD zWUGnzJFEYpj?rN~9&Q{W$QtYs#wBJ~!$NuW04YLQ^w>y&AL~g#K@qo>hCO;#DTa7* zjo~`pJ>7*OE}0Jw(>XUQqUf$}H@za=j(!( zs+J70L={8D-43pfrQii-484gq%R9|TxH+n4!)OfcL6k9u-q$}9O})=d`2W@!5Vf6< zJ$bck_ADySjet#3MG5I?w{7aKjk?)J&L>tgO#KJZ7&ks;?LB^<*_x~f0e`J1{ zt$-PTrJ=yaWXCkL<3Smo(&$OckCH^iNQE~=x%x^o)WDv0(B@6EY{Z?mRK28j`ENo^ z$ZMSSY30_m@O!sDR zT8Q{1>-#jdUpgvci5M+z+f6v`gal7{tWzGmDjMNWt!%L=>uFB#A)6q2HZYZ0#cIQ4 zgIa-AQT$@&Tx8R#A>>=3Vp&hQ&a>yH`KDLu(2=}9 zd3(xyKVQczVa@$odQ?1hR;r{ew85O3Azjy&=)LpVb+2g0vOyIF9{M4%@%;oXnUr`r zEP_ex5Xr}=LugNe6lDbo@e&x$0!R_yfY*FxIlyJsCfLWJ5I6}c(%lhnPR@oH8^o9T|7##|oXHu>`Lop%ls zeA|p0Ec595aQ*Y7=4;O9Jcfa=v!W#v;nuBt_$X5{Hgvdn28&(TR^RJb{}7TIO#I0} zZu6@Ru}WN}wh?5pt>t@6lKN)5u!J>phS33|PgV)<6Ph&3U%_Xo>>=6v-q*Y5i!oj! zcRg<(|3SVz4-s1 za~yk1_Fhpo**k=kkxH(;B81Fj94jN6LSc_UsI`Q49~Kyt+ekvUHcV9f8X;UoXXt(!lY=rg|tq*g0>$0b?; z^QT=dGy2ZEt5nzH<9~TPJdL=a-pq3N70p*bC?+8v?c3Zmbw+0{Qu2HAU6}71D`#gk zFxb!_DkC%24*5gn_4m|Dr9+BV01y2qKv%ecrw~vXTyY`FuOawu*KOu87Gk$n`|kA6 z1m+M@`bWvR+yRzC)(_t|ppIyE`@rM-UDJf^~y zQ5~U$!-YtEA+0f*|K8>^1?d%Sr!*dx#W{H75{Mdt!~nYb(lvj9qYM)T6P!x z~%UpYWSxpTQ0vZr-1L@Jx(dOCl28hrdYf3|d zgH-`ugV^gCppu@+3a0B?Tg_hFJ~Y49{i(4LR2mm!V#wwoHW>T;d$hgYq-wcw*lL|t ze#&+i4xt33J~7b>^eixa-vbM;W@(ZKVXHOr+O?LNCp)aWdwa9J8I(8ImS$$Cz(7G1 zanat^#f7|-xp{Y25^V2okdEf;x&hfJoUeO+Z!bInA<68FB|FTA@S|U^GSL925%5~T zjF~x9-Ug<7JTn%IHZ7%J$z-eikFEOiKes1e<8JK0wB9l)Bh1?5R3#?bA7Am4=if^o z139H@3mqB~bImps6Gbvihio5~)EG#7L}y8ixP`+m1W*2Ua7m@E8&c;=R;2^qN zCh98{u~Kee+OQ*B8q+to+Hh?s+D?6yW#typX@V9i@)`$`2?C@oi45M9?Q1T+6@O zu7UlD;OoI}QfU17Z)e;hXe$52Am=|v7CYU2ZNHL7FjDPrC}ZKv0pU?7%o@&8p?iB* zadq^|8yisW9lt`D)ES0M+S{khHY}R?`|BfQ6xsmL$#A}}K)D`A7$H$Y+ioRM9FW@C zV=FGBpg^X@nLp@=TOKq^{zA%KV%I{I`Uw<_;R1Q?a>#S4JghZ^N-td9In=5luvG8`#A-rA!^5>`toygik}@)pP@!%r z907_nIJS`7?*DHbH=P4L1xFVOA=@S}>$5Ozq z43y2a+Pa#WNGPFz-Z%;E)s+=+cjCeT9bst#wRB=Ck3D-*>wmyOKpiq!IA3t}vxo>- z*kfC+h2O>XTm737TAdgiv~k{@pZ}(>;R9MeECQlR@JW)>(VS7Yyz4R zt|>Q&U%d9@3p`SQRDlx$9x2xT{wzSe+c(Y3%pl-=0x$v6n}E%Q2VTe0j*P6VDm0vd zeF>P-^2SEjHF*{a=0jtR)YW+T+}vDP_b^l_TuU`DNjTyR;+=6tbZ!rejKsG;4Ji*C zz~vodvKYJm3zy7tX``{HAEDH4 zK~G`9xbW-oe=#3cENnP&))}! z-DoTKLKC`=T22-&uYB}U8!Zewm*2~<9x~j1B%0)E>hMfRpeY^Gl8=hGzi%6ItwiUK zS$UFx6#Iqw{Vw73_ck`Z=rxReuQeHBpZ82l{Ce}ra`RHah5WlBj)6B+8PE6WoxXTw zgwDu*W&J~6n6K`bM|Y8^6`yCujaa~pNO<j7lThnkCrX2q$y7SGTy8ZDEvAoO>pV-HU75EzFi&r791y(21$^b4iUlWa#k_v-fG!;pPY5ilf>-TvYgHf(rD($`s?3>_g>(MXigKz zW>z3p>lH7QJ*k1mjR)ynSqzk&;9y%XiL8J z$sC)^4puf;4WGxut6@?+m5xmRah5}jEvaJB{dedzfmg2~?7d zD*uoze_ZM6{E;8VJ$%baTlL|#oc+`HpLCTaFYL0-1^vpVoQ%r(uAP0^>+4y!Fd})p zi8A`-pBciuUVMCu4_jH=I-in%jAdB}e^1&HwUd1BtcEbZJ|429>c^_p%Q-=Y(wQ(6 zFW@wK$U>{8BBK^c!AewNWl)jg9>Fp2$K0Oncj&hma)&lCb}hP;mOPF$%9Kk4cZqpP zg^lj#eY&Hi$3B`Zo-=>?_urzfB;mIfGZcdElP29OSR&f z`>pPZ?t@bGeyP0v^+HvX0`{ESYln%6@|TVa1G5HHVzH)J*C*%Pp~{El1oVzUWv=u! z%CVHMT<&JFcOhOO(aA2k-AC-f`{?*edHz$Oo`8hUy;^rB+0gM^{gejaM4%zu%z&L%%4f6^CdoJ zeM>2SEe9%c>7C7uLDws%qn^IKtP&5r%!Vm1a7?nfce|IY7BgJx!#nKk8(O?Wj}c+i zV;&QDmWwsv^q`d6;HoE`;Fb<_+DD!(`g+CeaA@5(TRJgzP;M+*Vz4MMBq}PXZ^XCI zKcsP}!sQy+Xx$V?J=yw+=*}X)t(dmv8LW1PhA4t@8&5GUgB|F24r^kR8Ny~bDU6QHwXhN>K`ZK`m-4hw-y1L%zF7J?kC5ZG=y_2`db5EfK_A^tO?5k?t zIUltIvdhfgD?>dNZq)%hD-OB@yuVOyM@C-01!e<3zaPMsG%YR`L@Bmgi-Ee~_n@9~ zYkz+NCk8a%_ASb-J8GO+4jo=E1RZ2po-I9r1S0+y-``0y5k;7KD&!|s!ypZfRgihe z$rO8e<>qyPJ}SoeP1;QlsL@JV@WSx`AXWfnlqHBCVD-UiaS8{e%AI;;L8w$;|Fn*B zEgKXe&}RcGwsK>#Ep?Plt_{rip>u9L$;2Qt0_H)j-H{h^)nHEmVFIZ7w?_VxCJO{1 zB~IIPzTS9>kbd+f+*t6Lr(CG7!n3FQe_>^01myzko4#Ohfk!H+=0SJX-q8`6e&zGz zI^s}=hpAQNE4%dc6Utgs<=OL!XZD8I<3j)8}?^v()6A-$Jl|3evdC%1=QFGOkcvfEd+xlT~f>oT6aJa+e zXH}tQA6`)OJKsr2WhKLKqv)-)!e*P0SjAx5ieUZRD4kh`i1rAX;>=+8DuY@>**m%c zZ$o{><3QPwJa`*qkiRz%h-`9m4`$iV#Y)XqH`sy@CwaFfF36p#L9U)nb#q)-kuloEP8Mo$O9K}2$8u|gV>HG#ibs7$M0rEgI z8`d-!zF{k;gb`iy`*-^U$gu>GAS^LB@z8|J!VD=X=|P3^u>>qL5D}YeblJ+%5&;8O z!8M+0Q8hA)ly?U2OuhYprwKQi{H5h-&7LzSbkpjI0oS+|$r#`T-1mIFy`KT^2Q=jc zH$qxw@cCTbgV=X6%dT6HW&Xwkn5&x7=Mbr8#&37sju$~lWh;=ovF?Nt9p&Q4Hv7o4 z^l^@R*_EC9hRnTxAp$e>r(FJBm5-;_Rx?j21mgtWe4g!bKN!}59ZTr3hwU%1OCUvVpyaFX zRx?5z$>4_1i%LQ+1<+%|4L^7v0(b$^sd!Jh*r+IC*uQY%D|h!T=6v4gt-ou<%~G^< z;*LIm@{6fjPzOCyvHo(x$jhSyI{btp3|HwZP6F*8tbl?L6mq4Heh8j_2<#_P4 z3>G#9o-(;keQBDS%48gZ_>=9!FSY-m>IpFe838q(D>QIfc5i_JEElR9U`$pc0(gV5 zXoOk%5q3ub$YL=2FqCo3>|dKt&7+)lnXcv$*}HF>3im$T%K|_Ww3IJgq@-m%=FW2S z_$lUbZH!6DGcdwHjvWllOaecEQG;72?6*)=`HDE8hadGo=0i8^Iu3?(IHPbpMYN5jqp*MkjQ46uw4 zsOXMnuZ{({?2i$l$N2;jMFO(E>ivqMs~=V?w5Pg26LJF|-Cw^D6O+DF#F4a|J?CB) zM`6UgA`{epIk=_9UN0L%UtwW6@_?jN?27MoQi*1hymH2n6OEhLZxfbuqU)9!1RvcA z@HysCF|}@zPO3_zS@nZ08Em9}ewSzNX_d zOL%Evg;4kV6>0BB+drfkxhA0TTXH8ZFS{U7muG@r`9OPvw;?kBy6I+8f3SCju!AiT zYWl`1!!W+00x59;``$8>nvR>J&^$F&Yh8p$@g<=}?jF9}O4*VKk56WerTHlcLY7eb z1ilMNH?*!-Y#AzrVLb1Yu`yxM0?6w@8*caqzyAa_F9#&CYIVi=KczCX>O`OlitMcn z4~0e_yDo+H%kh^AD8#t9d6q{lXP3Xsu{OLsqHwcAJ&zpAXDu@$X4AGA5NM<6t zIU}A!_Mf4$&22}=89eUS{p*&mR3{rGRb+;%J=rgdj1zWP)E{$hKcPc6cKq!#RMWEX z{b7nSyehkpbcAyHB6ikIRa1b}n82tX^=|XxV}G#X<7?`&@$3J7a6`@JLDgEq^dIlI z<;)QU6%@gTd{wg_a|s`ERc+t;v9`s1_``z$W6e*ZjZaCtpKdqEAmd#WjQ`tv8H{pm}oKX~+4 zE}w2(Y7|txE9sOGIUDlyct=xvE}N|`455&dNtnjgDDxmv{aVLfo7fY9_<=1!u5v1h zfAL$}hjelAueEq(`S>(NugXScrl3dx9|-P^;#6lLY*h2M4Kzp?2n zIfIFAX^16Z)3)I+x0UDRnNEblBjVPu!6wQxN!N<&S`t;RqZ|+!5|}KpFdKtPb!PMW za2@<*bw!y+3|5~BKQIQb+Uv&^?JfE>5cD}=qhyTD1D>599P$36oMd2R1vLmZf;}Lt z_?|FKpl^i~hF;&HjjlH~3kas~qubnWm1CGoOUrE8{du)gj@8J?Yf}`Dg&qW5CJiB@ zu$#EL{@!Z3?fm8u;y%KFLV%?sE{ya03$nQTEnK0r4|#QzEe0wsMx2|I1bY|bQ#^xT z+S2dK7n1+W3ObVoXDW^}S3XQuZfa)_iUIt_wt|s0i~5x=XIM^?sydfdcTXQDErk`# zwmyw@&q15)Yp#F4BS`Zr(Qa#uo|a?9h2K9tWDn_PLRA_C24vQsuvXk1c=Q>v6=H!A z5Xu>gfPQ5Sti)CFzE#Vhb1Z)|wLN@LD_h%d{Dh3MCT)-g8wcp&#Z;@WwnD*oqw=G) z2u?o9fNlf~$X}h`3CI7rfrb_&hB>!urPZx+z~S>X8)SX1uEsGa`_n<}>AFxNJ;MJ7 zBRkpPanm6S=G^CgBZWD4ByUk=0O5WaZp! z%k^h_qHOUX+^5GhKj2^Kv9Pq6BZo2~g}xT>(In{dK$5kXgoI6G3{FJ@xEqY1fR=-E zpv8-o$57k$(|sc+m^Rxx{@GE*g+WCxgq20EXRy*n^M*a4E%!ye7$i}jZ0Q(d=%?=3 z%cJhI>!(4zczE$r)#djYQcM|quP$9I>nA3-k1qO2^l+Az$tpXHF0-U`t~Ghdc>E{9 zLzhbYYe^aj$utI{^EpPEVJXY5m5EN()Q=>Ao?Vr57+M_*+#%@E#A|Q088RW4iD_}a zXp_NAJX>k5QF~YQ@?fZuIPs`^VrL%2_PCqMXciea|D6&BIUA$^LQNIy6=0#abNicZ zBs{x0g9x{#CLRnviW0tJl%=|%A;`e2EUO&K2nzIif&L)BXQnK5I%}CrgYiiYN$S1G-~D>Hf?T- z_V)Gy&I(&L=*T(p)vHWeaWp2Jamq)z%Hkhx;OblOu)*L$X!#%pxFejk;3bB62sAJW z(rW~LyZ`>Zg^HZs*V{b|61vi^4SRG@+DU-`EEKjwg8t#b!BD_>0poU%j0V>Ossf;Y z84#s#C8`wXFJHP{l=8>{-?=RPKTwuo86Z_%6`UpjbOJmLBNB-4{rvoJCIwK#1D63I zz1&g54wB$x$-?cB%7>kLR8i_MusI;EexubyB-)Bc!K?`U-{2t_H~u%X`D|oby>OCb z0-~b@qM)HC2ne+pBfk9ESu0TJSi;r_-wcQapIJqR^i{KPV@QJ^*;+_N#%|y2wncN* z!$=EVCVj}&GanioLAUq~aq!K9f(?EeyqJ~hR*M(@4O1M(@Adi9jtbN_I=@C)#fv=y z-BJqyut4O?kek9qOOihQ55`~&?yv(E9;2LSffp?VQhM6VC0Lh3JRYsVqHxFtGbth# ze*XUvQS0khtM{R^IbE)P*$;Tk1jAPfzDBX}h&q4nle3*sL%qLqe3*{G(oY0Px zb3Oma8IBOB*dVH+`)@R8rQUx0NEtVWb7$a=GVSnkFHTg~1Yff)H#axXUEex7h~U!3 z-R{864(uVgSR#ABERPA^tb-0to?k zsDs14pg8z_;Bi4TjCcWA)gbT_x2y(LsXo7L8YR3)Id~Ax&dw0}i#`T_l4!yLp>6f6q>WQ2Oe!MOxeK4eY+^Q%G>43XooNzJuTDt`lY z+QX|FH{L+rM2aIgpLDx@&p4?)Z6tmK*j>+2b2&_)(V0-uvD~KQv(4V**=HM z#sU5Y!YW{sD+f{I*RM+81Y&;H5283c-E~hnxKXGH(zU>=ZZ4!+{03_bL{FK`wX!Bg#SgNrS+6 zBmX5$Ws~Exs2kJq?v3_g`j6ko5EK1s3wg4sK$0Z4=}VXqhu15&yiEAGmqm2ZSgHft zPdvmek*HHu_h6*u!wGdU+XJ<6%3!{9cGEl0kK$g|8+}SmB6VBAcsPy`XD4!YBlh?Y zoROEkEHQ8MD=YpJO1dH^-ihF&HP#h3iRtI9uwJnx{ZX0Ih`oiqM)JeGC&~8Y#3sS`sOjSkaT5l0KVuMJ7+nXDC(XFk1!C*BoIJtuhM zlH4ju_8is^IU^lK8Any*!+k7=?2b72wC!$-sDA#NgeNI0b{fe(gIU@7fUS?Ky3xsz zGq!+6v#>hTGHLN$-$VrgB3R;Ur<;XaK6tO)vG7{C6m|w5mbr3`t^*gLI1#g)h za<^~Aemk9ZtgkvZ#Jtj;ljW$ElA{VM9T0PnzwN~c(aN?YMdt?ILl+kiw7z#LmKdMg zzeMM~pzQtNZnR(0jreZ4kc3!3dZ4YO@6;d9WLW+?J^P`oikGjTSI*}9Q_Gj+UAcwm z#XuSiCeOMri!myF7HHi{OR+@L%^8h)ld9#O?;cp@ z8pNE61+l(a%V<&R7 zcfeqBVB>PCM!e4tdJo>~|Jogkmh>lVim=t%K{v*4p3}?x-QTnq{OyfVe}Jcy7IRC= zFzsbG@7y1rh(*~&xo__|>xxD7<9~I|_g*&MyuT1KZEUZ)=lK2={?F~>U8hTrJ7&a6 z8I_89!xPo_@D}Wqd{hI@t3|n`654v%gB=hI{}kl|{zIJA-<-Em(&`}C?yrz`6T30A zVN;iObIHH&ePit=)AY|b=Xc(iby^zC-0vJOI!JRVUUXhLFP&@~K0I?Jug~+!L?snH z&~CRvibez|qeQ$VG6Is<2M*~+rIFSrTWwnD+{+#@V!7}7ANh1I+P7*h;w1@8H~#vz z>#M?1`}|18<9&LomH_S8Ej8teN~D(Cy=He_noba=e@c7v_u8}yS?pa%w;CxwIwERS zyP&v2WdERDOj$Y9SRn>lWxtphW6uH^w|vp5B6_piFP;$TS&rXC0TF}w@MveG9AaquMSimJb*{+25+ z@7LC!oEA2!^VToV-mi2OQ_qGjemiwJd*FTcIO^6FUKWh3^X|2tIJq{li^HAMiXgw5?zr8PJx}&ua3aAp41;cE>pQ;Dx zEIkuP0Afw7SDU}?11KGnb_Ng_PR4P!K0Lu*v+n8s5FZ~>15&&>YA44P_0_64^*B*cq=7jXe z1ZFM;d$elaz5IfM7wpGQMoF|YA99bm>=9QHo@a706yz|Fc7SV{`Mioh6*f5u$EMQMKV}oHz}!{~>D6 zkNnalJII29>9WRWLkVX-hDWn#n;U4Yaov5b^V&Z-8# zlk)M=e|JxRMUunBtD}Y6IVg~RRWI|mXAm>5a9NMM@uPd?7A0@FWL~K?C*Q1bcuUTK zBy>b@ipsc&Hn(VPii-c#kfBBS$k16de4AY)Fsv2)amez@{DOfrne_bcwmk^IYxC-$ zYCk{ycuslOT=@5HO<1NaNzh3P`|pXp)y*#y;7w;Td9ieUx+b9zuuZGD!Uk9=WcSRJ ztd8QwukYiGY)ZZuX;-Pl9=n0$zYt`EJey@dLq0vOcW@dJZFMNb4y&Www-!T56`~G3 zOxwm}_47q8mSpaw{H#E!)7--Dg#BY?r~MP(`RD!$Ot4@TwTzjCoG|M5!%VoEiJ6&A zD$bjK=kX?3oYqoDic=|W!$SIP4YmisXJ@N)NL6}H!VY~9opcjKoG|0b$g&Q)xz+a-$03bFV567nJ zXU{d*I-pPm2KaIy=>RAPDWVFIm5P@XB7U9|$uJZABl|BzK8t=eDKY|`j&5KFACbS~ zq{NKGFtBb6`Xp7{Rgj`4Rkx2p`9f?IoKFld*>uoT+>SLc*Yf4$|0|Nu$D&kl|^H|6@@bRGsS_+sSuvX)8ry<6x^y-)W zt;40PT=S1M5Ivn)=snl(wIU~#T@IU-RQVu~l(@}FPcAMLRyXkS!O;hs5RToGe)Llm zPlKNpmluJH_XV|1m>MVC9Nc>G0MEf`J|T}A>75A*FKC!SxB_JWRX>h+)^9(p^U;#v z0)8RUw+TYckf?K92PVS7P&jq=NoFUWS+TL;Z-_Qf14D?iUyp@>0@(!9dn%l6t>C9X&2+)Kp-N=6R%>(_|4;Npm=ZfH zYtF}y8$Kp~lAIGUw{?~j!vWZbMGE%1oE%OC-%TvXk8^Mx;Rs>aq}q=+8sk4Uo-u*a z?xT4FBtgIjkO4s#Xr%y$+1xlk+W;LB%(QaZYdwEy&ogE6~}`e~re@gg`%WL6v0Z&AT^hGGD@S>ITQ{8# ziP__idv@GHE)mHT&{;WdrJ}6gcvRF4HeBGZA+QxH@V09s_?&Ux+grKIu2awaVfFix zH?LV5eQ^(eb+I~Uh=Fq~>DOSCPeFYQ5C40_K)F^k)Noq24wT3i5Vi!T4Y4sG2 zq)^9nEVdEhl<`Re#iCF3QZ1KCt$bZy-&_>`PY9+TqZRL@!iazCYDbJmyQpf>pL>T! zTmB0d;#!)*Q337^Dj!uO&AjIB|M2HI<`v{%8&a!wZ7EYB^o+yrO(c=Y2`miIO|o0I z3{5Q9Wlr&^kHu%*o!fhmt%vCyc4#!1wdTO!}m zpH8?q{Jk#HmHN&4`_$VTt4@@j;|l2~brze#EH5G_#ny*h@rvyR#|< znN_r$@T;I);zghv zl8_z4{I}3ySyzhcwjE(;Vi;`Vuuta*ksyd=+Z8y>^@x;8=vn z`Gpk`@ZU_3RB|BXSa-i)F=ycA%mD%Oy&^@ak0`2VY4yfA>J>vC5m8vEwv?O zl;UlK8H%jj-7WpgP zKqY?_a&uwscWGf57tK8=D92+mh%7fWw8JlSG8@TL5^Iai(RrstHT26snuP&7U)wcd z!EBkH68w7HhHEfzu0CW}4?${r{`P)4W0&*va^Qo%u7`!C7Edj!T_(>QH)Df>B&2?% zX-(g^$x*)h9y-)*$bHhD=p8;7x$0n=a~My~k9S))EiOa) z*17t9RA>GR=O6Q)5=^Ey)&2bal=RMubWz0lk(YgFZJkTMeIDtArs#OngL8)db%*Mq zm!}z2;+9S+S<~p6gW{8=(OO#kiHpRc543bY43JD~ELq|C!5-i$Cu<=rm$B++#Qc>u zt#1b{r^dyGzkMpEdn?Y;_5-`(3e~M%3b)E5YMS`kzW`efnn#X%IYF5wY=5W(8 z$cNAaMD4q~{G}F+1Z|j}lAB-rYGX=z#CtEFvp;p6;O=zKe6B>DUgatD>rTUlgyLXD z5=#=-O`Yr8ym7t5gzTowWmed8?B<5}3?+dxLy{Hgl&9r?saz5B2@-Dt{HE*w1$2Jz zu3_hzlIAXco%B)2;AIcPkdaquBDL!mYQ~KVeYp|2hJ4-rcq+ORd=Kouuq=x`$2_5z z40yosqKF88rjX;5Hfa{!9ER!U-@VOg%4j{0-ekeQbTwGb3Yq(eVnv+|#iY-}8Xi2V z#(zZA!xFY}y!i|-jGMhPj9_4wfO|K>?BH^E>kCIyvq|jvj(o*(wc4APOukhfky(Me z)F%cQ&4zG2cK^5&U5d}{@sdLHLpvp{N(mwp(>KRb zrW*DbjCVAyZx|ohU>J&B7Sa0ufdO6b(J31Lj%0t_B5jl# z*2^qV7+3|EGge^;HU)&)Y&IUfwy&0I6P_qxFyoGJ z%F7FBG!&u?*5ZlkVyV~p64e*h$a;2Y>?ec-OGK==QVIOSId;K9724U%bL+jG|3O98 z>|t&@Lv=m>A}MbAgGe2qPo8DAKQ4kK!z|?%OHt5gw}Lm_Ku)>+bK?#xq$1--snax= zQ-;nWrraU}KgOS)Dk=nSGlb6ek6EE$2;rwIl=Z%4GkP9`2yFV7J2w?gkM5UOF#E4! zbM@yfcPh z*o7lDBdOC?cj~r4IB0E*F1L2ygyRfBb_-+t27&F#&@nS%ha$-IX1D;-@rz*vfU9(AX=yWny>xXO z(Q(UY%Jx#rEEPQp>Rz3UrFo=Sg@Y$jc+VF!#^0(61p5 zBsO2pj#kN16ktMyvd9o%2yj>aeNL*_p6cs;x5%7Bn=tol_y?{!Gw1p}l6nm!2Uz*R z6aZZ;&7fks&zEe@RajV?V*y^G^VDe zV9&Sc(k|F@aM{0W zqg8BvC^&H@y&zprJl&Q;IvNDYFNsIEgRExkU zIBa-+)?*Xn<5uUTDQdX`@P`(+zyFWB0}bkNY;s*?zIIV#{+aEA2ZRuG7OsYbuLQTT zfsT?O6ba|njaxJ?HgG<_UmJn+7J-MnkhUhq6bm1(_4I1?eUANq|BM3@jirduB$%e> zJg#5BEvL?f9QC@-YSb{$sVhf!W04sdAe&c^8-Bvcb%Y#=3Ng`NN)bk4-x#sEo zvvq&*9Ur})gQ)BP8QxFNKU%*!;X57GWAVMHLe}xt`56!D08OOJkSJ)ZgA_yUKGY)T zy3M5?iHO_g#A^w$LHZDd(R7+>a)|dBS(|_2Kw5i+;Qx-spAvq;=k%IYeXdbPluwt+ z=$w@J9U4{Zs85C*&l7ULwB|G}l9h_-keMDaX!fHK`>Ob!l|(pjLBU|{%zCZH7v0}W zsYrUt+WM=~pRTjt@l_yuVD>%p!(hs!tK>qm!a}#{gQ=oiVwxypj70~Z5F~IRdx!|} zd0AR0=$YJ7DeUES@MN49IkjSumUuJQqpm-b<)^Ipow%^Kiw=PSdWMk6(!M+y`L){1 zPC20h*5}H>!7wSU~ZC<#)BT zC<79T8?AP#oL)U#oYo6GD%($9ZWZ|+mvaveJ+e}<_Pl9zH!;F6eVvc!qo;XTi7Ic8 z4+H-3I##5L*6!vX4`%8CSNR&3(5~HmnX+!BXY=0qt)lPvUj%{r?`1to*? zmPQkFJWbW({Ld1uH>y~@(QY4dOgbU4KPX@fYpzqXeLOdc3Tw@~&Rui>XO!Lf2<^w8 z7XJGF2dz>phXv0^%Z}^Dyq(_21yZtEkUV8R<>8AXa-%4EYon!RLRnSSqlI;UXQuPD zwZ@g}$&HtWZNBF^mg0CFgxRbp2IX7- zWKTmKRXGY%Y2-A!y9yb{BA4CxX{*x0y^J+Ph9NRf66@FUPP6-FV;t@0#>j;<|MQQz zU%qNLzOoH%_e|DLJrKyCjrBOgQ=M8iIj>!hL@l9}IGdk43~)3YpM8J4x#KhbOK|U= zTH0ZpN_?YfxH?T*hMwil2urD%h05iHx8_dP$HR>O_7yzkRFpOVZ}$56#f!D|x8%Ql zAGm$SCJ%bZ7=otO&iRpf>%1)+#D8F)(|>gHH6BzEXZLG*&7&!KRq80}NO3(7U-BN6 zN_WSRmA?v_C}nZ&F^x8@y~Oeo3;HkB*SQ?ddj3n3X*%Sbg*0wz#0!W774agQ;L|25 zE3Fy1C{Ze+0HM)89q7C{Ec0If!_WOIwP`o&`Drhei#JkSUo0PBwX$+#tc72Jh+$T%<(x994Q`$1DYatqD#UzUeoMD2>H7f9Z_P(q;=_r^c8_zkF?B6dwN1Tb zo$&DUe6-2wN~|2PbKqFCsZz|CF&jK$6U{{F%X z_a88IK@S<++<(4g#Vdd^El|`h?;Sy4DEO@j9Ns{a^5)U%M;kC%gHaV8Y5@Ne9M6JC z8tMA=kPk8v@%xx@b)TTmfrkcWDc1Kk<~wP_s%1|xs`IC+SjsZV6Llwo0t3BmquMt$8`-B?wZ)!SI`unpX z96oT~Z2?wh615s)`Y2D5s3G)^be4kXinJTN<&}XK51Yx}%%cs{6_PH z$qPk1eH`XNt%A~OZemfZK^W?%=_{qYR&#$$k)HRwpL+QQz0hblH*1GKTW?RXid=B( zi#sPHCDQ#$axE`6TDBAgT|UhH=d;1V^3UDVHyZdPm2fR0`U`G}iNevf+8y0IAd-Qv zBh*=nQ~+Omg%|`Ev?Llh%lzgh;=zNZXI0J^lZH6W24s-ki@B(Zp>$`EyYveoc&{LwyVAAWgYP9aHL&^&ZE?Rbr35R`yBV= z#reB|9KwY#{TVJk82LP<`Ej%rFhU!8{>MsY8O*VXJ@!CDfCI?2Vi0=3aSg9+_zv(SMbZ$P^@Fy$n@LkuPu>6tzHVq>{C#l1 z0Fsk#S~W5wjAjHy#I-p~1sK*|E+iXrW%cDwZ{*%Bo`sW!MT<|Ait`~chbAHlJl7zh zNJ~uY^$|{eE*1q#L1rHBX6(o@s})qq%d=Zoe!|1nN$8XdjvO97(XD^OBiqiq8AgQz zR2?MMAT@W=wJ{dfT-X{5rf=(rxjlrl7G~9jN>F*E-u^ghqy6#!C+)yo3`d>dzCq@@ zFV2|0`FS32m=l&F-7GT<%Ze=zis4~ObxKl`8!QE?CZ)wI^3#x$iKKw-Xr@jWIEu;o6q*%Jxi+q} zPTMjVN&)3ImVaAU0RWm~6k~>#QUXH*NVP`k$LWw+TEz_gGbONR0M#%)ejgmX(8Dta z-v(?0>;bz5WIf~#-j|tmH5YDT`9858pFu@Q;;Lr`l>Wvz0?>?WQ3p2_I45x4V3@Gs zhJsVtgSQ#DBFLtL+$N$HD!}ONCey(J3`+tWJBcySc_kPvL&4=SjY%RTJ+*MCqdZIC zj6OMG0lNY~38Dj3YY@m}r~@KFFdB(7 zNMzjN2BH8Gp?*C|MSjU0h&<*|Id;jX1=9jpKH!bO^`W^>Nzk3d7Y3nJ^Xmv4em`pd zl-!EJ+Ru*(x-*d`=*#}c>z}tWHvD0E2p|8Jm$J6%KmFibPiY6nb_mq9-JFAEtR^T3 zu4SAd4J;;ii(6HGXy!IK$G5i+JO?e3)n@&iO!wV7;50xMr{I5(aBrSU<;MtD{O(Yb z4TBCSs$lcN?OZs91Qxy-;5@qP@0wEaC1X&qHkZh-Kf4mihzy(TJf+ol|b-e zsL|>ufRU=Kpmx zc_GT9=r5keg_Ft>U8Qr*osr%c7J1UGV`tnc^G*XHrYEnnM*NCm&2Ic5{;40Xe>oEQ9fikFiib*LB#OxRs6~)mo4^&uZKi_E$(?yerB4z15V5*&Umdw*Ox@2;i;w85JLWFqjTI+(jy6ea%E8ai3^CjSGu$?IbR{aJ)M2kCEc7T=wBL%7Q6J2kfnJ1Y|H8-T=1UoC@!z-A-q|=;Rbw0e*G zGF(I3-#QUfU?dEiJ5q^>yQW^)c`O=_2JA7NE~A)>{Yp1gXwqUZwuXq1`MbOlsj~LlseBKrJjaa#Vuqt!#J=^@x-_O)BT#h= z(l?${C#zToqr~dMdAuBhJB;2@ZOU>Uch#J}I%divKj-6MOhJC*@6psGqD2=dp{~7q z*QFkga?@m*vB#9Dg;DYS;mYQ{p5MPMLGw*tQ;$ti`jC54Jg@eiEtY^sD=v~vM{KI? zjk+Z(=2THk1Un(UxbMPI7_vgxhIpbz(&DBP&v76zwcw^P`C4Sf)$%Vd{~y=ADFf~F z^}F(UkADnnyBJg?4^ZGUf3+odJ4n~frb+CpTHw8i_dO4p?0Db4heT_dt6BTMJ4~w{ zDR*2++US!$@T_LOYP=)pdUQcEP&3V2M3>*dQM8Ok{Er03j0#tZ8X+oNoj>pIoKYkd zP0r)&pz$AFyVMCeTNf@%ItS3Dz4Yga=hRia&msPoU6=u1nPhC%!0hs>TX9HxFTrb) zeY2U;);gZ)Ynv9;SB-_#)m`SSAB`LD%Dz1O*6uJ+q00aDb-;sThp*hs@-K2%Y}UM~ zuK3h%gzPzwa7=m9*!FS8uv{6J^H@pz;yBNej}F5FNty8}rEV63Q-tV0)brq&ZGjT^ zuS$A-NaQ!cF2V4%Yj3x%D*xoQ^M7LabMbJahFX*0t>EY5n@2vE9y?i4aZrWOr;gF} zHSKyJncOz-4t!6#7Y{>>8sWiWa1#y7Bf>MvBTGp38oL=~%n6s?rCKTd1N`6S9f<&Xvpl){SlO zUehByRe%G88#GWygm6JfUgA&;i1umnM2<4Qx9MHoSS1Qk+s^S5t@OIx2@eAT5d@24 znxP@Hvb&Jj1kjwVO$pS-Lz!X(olo=8?-)c==9A}YGDGI5@;WduZ&qGB`09$5QtQz0cKnBK@_)EvDtOO?p5$< zYg{O@er=1{PZ}5R=J(U9wh%3tUAOk!mOH7UQ3OYV?3Im$-_PauU+sNUceEt}>nkkG zm8*W_DY4~#UANu-eBX^Ja?bHj%foMdf0r+472SX{ zJw{hLR<9)9LNReAn;8s1+)oGQ>)~L2{cr`u!>j|Q))2b{2-->Nm#n-J6hd@bW4k9x zM%;h=W)C<$n(G_ilK61-juxNPSqtf>HVm>n{$uyU`JOG^Pnk(*u@2p1CcU!78xu~+ zs-`!24!>+pB#<%YIpRkp$97j}9*hQtWsrUv0V)a_#eD<_I+Ov)9ry}GZtuTTI2BH9 zdi}aR?q)ZOYK)2d_{tlNe3ph{fRz8U?EtxW@^9pn4WDtFC*u`}B^>D}LlLl6kX2IZ z15Te%#{jx;7~U2DU{DbOPV5EcRG5uM0j>OPA|BdDg_Elb(2|bSNP|;PvbfIdB4#z? zhcC>W0b;hGW6s@$?}n{}Ypw4cQ5h1oCnTlBoA8gCG=0^;IK973p)gTv(eQu-47Y4v zRsa;?6%jv+{yMN1XkTjzV*|kwps%w4YB{dgWCPEVKQ27taik^6rfr9&Qn;I>F84c~ zLUaxB2pVrgmU^H0I*#=O{w;$b%1F|veh!yNn9JI|nKdiE179DX-evU)BY>^$EAXs1^(Chgzjs;+fE-(N_!UFd!h|P1XX`y98mn zu$lm5N5<#FTHph{c%aDWeyii#B2pUc=QrqZ9ajMytcKr>Up`G>5}&^Z`v#m&3~>G+ zBM0YrX7k3*P8#!FSiBIw6P)v5r}Jb;k13{nxY^6`-o*TL~=^{P-jW9K_YsZZLLD)X<02mL56&m?A%4m6d?k%?X@DLtJu=w}sOe<#dV+;nV<_?jrNOWaXWU^ia@fM*7#O zsdg~oK&mutq+k01RGu>t&^>61Adv{D=}j=*6UGk^y+F<$uom!@5Dg5G5#Z?oL%rLZ zkNn7>)xUC}slh_E6bw8t=fPiiKade?C(8zjL$)wvb+i#o(lFeBi33h#$Y=uH7ShRg z)=Ta^S2Y~C*7FCcV4a5#VVgqS_5q*%lDlkoZ)8SfAQ0|Qm>3Uhk_Go@SaiW`3_p<^ z3X_UF+D?x*md-03kh^|sjsbPversaz@nmq%!NFx|X=(S&9u;JVXqi+5O$Lu?R)${Fh?n9(sG9gIZw7%>`?R zo%4S%5CRoKsNez532;3Suhb6GQOE%Ac<_ecw)*z1moOA`Shq{0e7p{qP)6CC;LB!2fK`wKp?3_wRgrPD@xZ2*G2b(Q*L6q8rDl=q2 zBtznita{#mkNW+nHY0wLU`a*tx(@0U#nif07?1<`{)R%Ee}lhWI%qV=_y4o;^T967 zs#&A%Wqr9EQOc?YbwHeT+#Zi!9@N^Uj=sc?EA%ld3>Z^GUChIlyp&_xf?)+v0o%Q7@2DQvd(dSw`4@vclO-HmurHGOv z#y0d{3{kl;R-9@O0^!cjC`UIX-VS|X-|CSJg7^Dx%IP2c#<>s&)J##of)F|(yMbxPP;o! z-7MWsr|ZdZ(Ya=w?5#`p6Y-8Hfu&u$+Wm!;0bd&vsdIIyf?E9Hjuv!=OxOg3fu**# zOS+LJq7Yw&vRDZ#6eH0x*7sCaPyEFdZgczlXrvJ3IkEHadAjSdT>Lg6cj^0|dMv2U zhVoe4V8H5N#6J$#!zywb{fFluVp+U0wvIvRVffsFJ?_e(YO(A%;n zJGIU-bRjkoE2yQVn|JRGiuP99A4wk9`&<=PQ4_o<^OD$&n@g3qUiZa*HLYyi&(WO* zoe1OlYrYh(JTYGr`7ekapw<2gsdaDlh-yA?)7ZakLljPdP>H~LdocaLinsT$Zz}U7{9Yd|3y_dYb+T*h)I4WIXd_uX(e$fu#P0! zKB+Ac%jYO}%pR`DR-|4ns7WL$_07Ub+MtZ;=a80}+5N<65$daV;yTXqd~?exxuK(M zR@3<=%IblsL9Y1^K6*~^29Y5ab*XlF znyX|?U(J2*ay%YKev!57pS;W{@hwrvfv@Ep$t5_(|9XvsC2vRtk@2uj+}^uoRbs!L zwu2drTYgn7O~1HwWaXS=8>}o=cnvWcTPupK$nsd4{6^}8N8)>i!!SX)7!-a9u|jVB zGO7L5?7eqEo(yMA88tPVU>iy$FVF3F(YhEL#`<*V(bB7Xf_gvng+76KYoxl)J1&{i z*85W8d)B9d^ps$X1k)P%uFvXEAE#kH#B$a{U82?7DVA9t$;_N`d6an;Xa|P7Dk@yz zcp6#?zMDj;dS^UWocqJ0xXo~)A>oGTR8gaGb&2Fq9rAwgt%m*x3#Z=UF{Cp{N zsoC1kIG-&Q1Pj_c7*s6}4t)zr)nfQUnuRFZED?lS?#|++dx-PH{_*rg+=1ec+iUa8cnl(Qs2IBn_qxaDgNFQ#LI@6XW9- z>C+TH=44NwK|iz301P4lY=d8L(khreLM4Q87pi$XJS+$~InW@HZLn&{q9h?1#wz1x zZDYgH8XT(}7^VL_Q}F+50irZF1Ls5%Hi-4z3)QM73BNv5zK7a7;8ur+6t6juLhvYo zwkLRoBGmYBEjbx4_!RKa(gY7b=*}?ZUV(K)MQhs7vU^Z#JY=+}8sWswh= zQx&JbRX$`uP{Icgm09JCXA6xgi zT)gPZ3y*EyY`^da4c#y8z~|!RVCHgFQ}f*aLL<%1Re{$A_6}+$baiW$9B)`zJ-AUu zFKG}zq~Vv-mn(|9Y71$o0DNGuf@1PTnv;1NCd>{Hp==+YnWo$gfJmal`qvb}y zDva6RC*L_fvt>^$D+!x7 z{R`u22XuMkI?;?CKyJysKth5J48pZ_$Dpv6B&g&N^U@Bpc*|C4!Ni~&x7QVJ+>Y5z z*}8nfhN2^u66DX;mB5Oji5$Q2lAFu@s1H7>|1;k~4AT&4HGir$%<(W)N**mjR~&d- z;XFI41FZ<@_%%Jfe3-?cmxGWVRZF>iH74i12OA-NxoPfL6!uhkX`O)Ug7&*OYwlCz zO_!jxOv{XH9qQk`W7^*E3YJgaSoLXAz?9e%|AE^K5klmib{V7@5iBlqdxU&mLK-TF zOa4tL9iI)yz=?}ddHo#JIHak^0@{`{6%j_#(%Ux+#;kqH3A0YDSS$8pOBA4VJ71l~ zgfuz;tbpAyDxhOzC)C}2{Ae`%8#xd0z@3odMH^{TVO0UoiS@ck_XiI`A*e}W+Zb*Y zpx}Y4h>+I`DQbja2Ub>{09!34VNcLOkSP&*S0LC|r0WPiseq%|IYQ?m;l4^BP6!I3 zQGVnyNM#HJ>0dWDgLG{Gubje=^WueO%k4W)%`Ghn69KU-=(Ipm1IYmJ6$Xi^x1n5w zH1CFrf*AFI@q7@@5F|6fr;3?o3Wylelchf>Y z%_Vp9+m1<+bkUKpYenU{_4Ql)ns=}!+A)(mV;w1WV)7sb#c=k_Vy*-kEn>hCUE5BM z$WMAY&wQ2Dgdy8kY6bPpmEGGaPinM2pYb^+1>G@Khv=4X8T;6s|HJtj!>JwXDs*Px3=#M zB7NTXYk6s;DG}pZ7Q$WgeAjNPpjs34X|0FvU~;bG6o>_v)b&t;P2t(P#D5nTZq%>} zMGN)l8ZxJr(2(5aN6Nk%aMx=rou24BialtW)1@xU_6 zveH*l)d;TWcKbXMz5-l@VPxLpEx^B_4k~4o(s_MaFlChfy}F&&U5G}97rPSUv{8A^ zcBC1~?{$duQ}CChA5n6N-I--M5Kj5{{Up-f{$f9sY1tL!i;I=>p$(~l-Lr@Td~7QY z`_wcbQ(`8=hx6R>qy&|qD3!Dog{{Uz@x2-xfA!0}6e4wH-c!c|^zRd+H;F#(3i>9j zT<{tTxzsHxubb>8M`ux^#7DUgBM%rzy%<7TU0CZ6l~&nE90o6MDK~$eBFde*eV>)* z!o(FZt5CPRj>*Rk#p(J%P=f61myrVoyNcHz6m z9pfv83b&hyaOFht#VWp@8lYOj@|-e~M$gnnAGHqU_?y=Kfgm(o$Lor%McD zt*Da@-d}fQD{?~H?VV{e^S9%w!K}&rH4$&DYJ5}huQ7!=%F-GYM@sVSQ`J`muTz)L zvcF8C5zV-E)?YqPMy?KvIaJq}b^n@CpwlK>-WGmqb<^V=r>!i)(b3Yy^@Hv9e-w`+ z6oi*0Za07F+1*w2yFycbkNL|xZ<6h8^*3hTE^Zsvs}AhP9C+NwqX-o-$MGc=mK*V1 z1v|N#v7ND*Y9gax-s+Y9x(oyxfgx9>Jm zEI%W>gAmKUSvuFPmw#UY+{%O2aPmqNzbun@k{dSmI)V%JZ&dSVls-e2ZX}+H7cUTh zQAH3(RLPs{&IS&)Yn3)kWrd>%4Iys}oe?|oca<3~K5RTzqm)j9Z!>lHvpodSDnP8i zF}n}BJT`aku$CFo5%deczqQ25%mtin-B|k99Ny8M&}1Q9TDQ8js{L^ib%F*t4D93o zry(8r@dx@!Vb6~W;`=lW@hQ-21^Fcv5MB4+0bS*4rw1DdhV!SL7FTLZNI0;> zOa34dM%<0iHZb12v{d()PCmg(~2wyia#kgsksqioFy|zY3p9kNZy>sV$J% z$2ZPMA>cnr?ko1lc?~}+yvzx0ZUB(aW}b`lpPrrVyB@T4w%M;P!l$XrVbPZZq}K#T z9cYsa#Q<&X?@U}D`=9$a*2|Ab1r5|)!Nk~dJ%kkLm2?G~J^N$i!BON(Q(UdpHU~}T z+z``m`sgK4B0Gp*#v6^IWJTy{4?ElfPVmIVVJF6pZ0FRQ|o%w_%by zSF(#Y*6)y_<*VwO^e9!@#V@o@{HaOP+PYPh1=BbCX;gK0G_qD`s%5vZGAwxyKjM}< z7&JJqsBPuOX$!qR-MSnu(|Iz;0=o+FO@%iz_q{ljIv{og_VNHYp&JV-vBh^Hf9@T@ zdR$HP#gDzvZA0=F*U2|M?2v*fhyczG%KCa|4&{pPJO=#mo$$UOp}q^I2*7rS$06C1 z2_x*5E;4>Dvm1M`{>Fplu!tUJC_ZE4xiP&y!vhr=xvbS!&YB7 zUAQ?f3T&^+Iw5eFK~M51Cu)0}PVso>2AtaBHrIvI!+$uhCH{zibE?CKVe(O+{^(fE{cz1-oI-%m=(e`^8f^((p$EiU2U9|J1>2b@pf`sqR8ioz; zg4h}qI#kAxBHIHA=t5KUfB*^D79<3^4yaDB(rzjwjxft4f%F8h8n~b{JfA^NuQfKB zWDf~8_szGUPw`1R2sjBXv;lJ=%n`LEvI)e{iwv=#8MV1vN>P?BY`e5`SsD2}# zfYf~}43Ty2B9$rtQIvA~j}$ik0o)lcL|07Jw1tc7ok-ek+?MJ z#df}zRKw6J=ZD8vBDqIOphAf=>86qv4c3ZN%K1T%v48}^0>ZCtU-670`BSPz(slk@ z)+T=1ugJ*A$h?;E-jSIr9YRAv{Sp+EKmd;LMve8}4(C#TsNPU6GZDFsa3#W)ev=!D zH)Q30b4k1QRb^%V+yEXaRr@=P|s)ElDv*5`ZwVqSH=n zoOY|hm6`j|hVT*l>y=Ebl>^&t5}A_KX)(F{wyn9@C23>CW2u)KVCBY=jmkq>0`7&8!y4NT-+}WDIk!iUcJZd`*g(iE+{qvl2TXPyUI`%Z zA=KIV*tN$qnB45awbi8OO_f7`k7a_lWx(v+_wS!V(8gX64Vc+ zcDJ054xrbX(+NuAOU}&96o(=2ui6{{WzhII+=J5wUOIe`o!D-ePvCllrR zz%`w9v1(!^*F?k?%)L!bO@uLw(B(*2CLHh0{ZLL`k_8z&)0rs3h!FE1h}IxVj#O|0 zr<4o|TejV=YJIwf9V%$YGF|42zARZIBLumd9jxBs6h>e;M-cD11jBKPFEl}S53>q~(r2S#Li$qM+?^LVU0b~4?}?peVaIK}>#c); z9OXA}uji+Wx1AofCAR$=YU_sS4i*QGdXiQf1Fof9=6`V$s#Uc3rZTBXiGPc={l3{S zS9q!r6DG-HyG%P+A*F^13DxQ~6rwgm7a4fmSMX?98o*Tjw%4Fk@B<|8LuR@OhU2$P{Z#p} z_F{Q1xHM`^_0(IZwGVL)f7%Ly>AH;>YT_|r&&$r5Iou!YeB~o97X+@8O z|5}bZ!U6Zz2E&ttoaGd}lXj=ftNoHuQi6o?BfHaXT?SGXHH`{;2E>S?aIIK(3RhkLubl=m0&H-4DBBKf!AmmgYOst}CPwxn=k)}=@x zcS^tEuxy1?p}l8{if+K$Hi*P7*1Yc&ChiXVyz|b5Z}(aSmsE&+h1**@-g6X5!BXoz z_#zeJ@W(`DENVl$&U`n#D|l>e!;u-$e=M*=1=xv$k+=^9*Hm|QP2ITK{?~{$7)yTuYZ>q?@ucURTK2u?D4trxZ`E-h|moy zeY83{0(YUG=|v$i4v$t9WJdO((=KXdc?^r)BNetQH2X3BvDA@%-kQt7%;b0c+M&ce zwdk~KePB7eW#n=m`yq#q|H0!wi~Nid+@GpF*X9R%j;1H+#(2YOZNic&CY+Yt-&mbq z%pEeBZ0b?ripY5AJ?wUVrq_jph-x_9_?)w}oD=7r_WaIYbBo99e?5eEWAF|>4f;FG zy;0fozfAHluagi-SS~Kj?8=Y1M$E6t+s`?6JGQb5YIR9-hKDd0FlU>qyF`6-EA6jO zIM$M?A`dU zo=HCH!M%sUjE&TH?RyzDpPQzY#5z}4cR%7bi6SpQxy)oDWxy+O~97Sic$_*_K~ll#U0SfBUwojcwp7&7l{&fJqpN-?!J zq?~H5CZ9~7n)Zw6dVVEN&eCG~U4no8Z)H@wwjF8gWJyS1%&l}eu0!-k+}<>YRF!(6L7*e zTL8{FP})FlA0$?&=jqRzT!jcYs1*Y?->FdfB0L=7J|DWIWsF?iJNoI>2#gmjuK^su zik>Mx;Ema}kE_)1lr&ZmPS^SA;}0Q2?K?Yh$dO0zGfO}H>UX>(`Q%6Za9|yUDYTJ7 zCn*r@1)5fnG=u@Pr+v|@!kzKGBQcoFp6jvh+?9pRwU1ANYkd?jn6CA9->*dxJZHdf zf^wgr#C>cJJ6d>}v-zKA&C7~Ad4-_*dsLK8BSfOXOVih<=_JjXTV3OL@8jE&7xj_Q zZe$C2krB4Yt5-eWiO=8)ObJ<#;P=8ZJ=#3Rl$<{=n0XKQc+H?1Jci=0A2IYL!{7s9 z7m(%`=4R^>)u&ndxg4YKbn60|7`&0uPqqxM$;w7`K4DzcNz&+DEqEA&AANo4Es_m6 z#YhyGt+rJfx2?n4ph33Xg{T^!Pmze}CL^snyRCviX`Ol-nkwHWInQ z)yjS^&B zEP;!nMt*zPi1%&uL>CJqmJ< zr1gY;t~dEl-|~lO6-B#WX?yv-u`(87aA5ZXHs+4KKu~7KY4AeMA^`|fP5|EwiyGi& zVcgjy)Fu;#8bEG@Si?zB1yF4X(^C*ymmxTH`e4dhg2=#tive+i6e`9%ai1J@YwHbO z`#-CTFzJXE`n9%3bsY49xC|vwK&o)&F3}D?v2wLhl&n}=1@s+obJ_gESEMCze@O`L zGiI+IjDGgE)Zj_b;3dR4y_cCINXQ6vz+kLJU=u2alN(3>YM&FwU&|tTCAjdn(*4zlqLsK6l@pMSN;%_`cCernoBY zO@TUb`RR6HbBZ?;E1PowOoxTlVlX9!I*)St901*jzV1(co)muZ3S~$r`ll*B280%1 zX#`^%+v%$TSQ#)RiXVa)P5ELc$=3c0lM4ayWm>yuto^+6DP$O zXwz&e?4C;l6LXkHsRH?$>Vq(8e3X-NQ5uN#32pB%@DlQNj}N`!WP_|56`=?a{p8QC z=Np$-hi|zV^30zN@lQ9jxD8Gq5OIOrtaoiqr2b}#7bpZ3@-lUb+#wniekUZS-u{a_ z`k$&@fyOJ%5PG~qRvUq>Uy>8}+-+FaZ7qg7+IslSH!7qC?obfJBL{aPf{h%um4xaR z5T-yy89{_j;NS`Axda-Yd6=)LTYjUN7^=i!f`V1kd#chy*mXg9JOlVt;f#R}mRH{0 z)cY<##K43Cj-flo(9Bn2C`4LF!9BG>_s$YcOY8=TO9YwAv`fY2obq@cpy|kg#~zV7%HeYTS{Wsg|3E%uI+}i zECweMckUqDHXnM4=HJ_NQ=Fn$vvmnpaB^-N?7`W6w!a&2`)2pvtn!Ebfz#c#zU|vMFH48*F#_D@M;G5y1@Crsni^tuIH7ku_k#&)bxWV#wcC#d3wd*dNboZ27a5 z+w^)@Ja>34x}8Q^kT=L%{!m5v5M#Ehr<2EAlPh9Pg2U1fNvKPxCqK(0wI6hPDx^lu zA$eUdBw*K409S=5LeUe2GoTaK6GvjrsBcEvP4!7#$R1j=Q_*=ZE5H}-{(fpM1mjoN zkaUJ^g(X9x#j^h$AOH0Ep%-*X9oWTiacnj8(?r@{7Zr$ay zIpDKd3wuAc6NBBaW=awuqVqUY;Y*`vp{_Z4rY7c(M(0ISa!*lJ@%%)~NJriS`6H9O zXcEzHl}^K$wo~=UV4|S0y55$n%_Frrmv_TH#NgCvP1qt^bkr(t_xkW+vh4)+>)zbk zp%wZ2OUwLs;*4mWd}FZFO!?P6^|s4Zch~CEgU<>`QF-qc^!0HVE$HZ5YLtpQ%urn5 zVJ6i(|8e&mDa$S=>WR&@m!o(Ma$Vs%R52A-S~!{?l^0evhsj7Rsx+T&P&cqXX8QkH z02E!p%d_@(cSIhqIu7gRa~5|k1%E-NR2lC^*pb=}xy>vIHin;cX}zV0J->OO#?!;_ zb`Nu3?`~>a?zj5^R{uziU-Z7WnkMV6b*R@?3({c51v{D8ItX$Thv@6nGI0^5kmR9= z%5Rml@?n>`5$z$od}(QTuUwTY6z44;FzetDNQ5SljT6&=lMO}O`i%G8E3!SoOK;i5 z_*{i|*jYHQpX7YIg~CyiA-V%t=cd!@5Ut46V;QZnXZP$)cG;?^LysJlzfPtKB6K__ zTgBeL+pMYXkXe~~>hve#cO|coEsOao37;Puiy2j*mDNe>uDRKY#O&j5LuVHYtFGR^%p#Tc3-1)q(Ck*X1;=gI(rR#EWm3C)>&|^?t&J%w6M6Yb zjzh^W;nk}fUNaOuwnTd%_KUxFAxQ!Xy*PZ{UNRCJm{toRQdr-?d4u$-(Ka`S#;LT4rw)Nr#*4dtpeHb2Rqpv{mNUTYd&M_ zb>fD2!z+&p&iwPCIaVe!Byv?DQpuaWzp%E3o|Uf}<=ioF^LbsnYU52U$iV*PoiFw3 z1)1clV(lJ}outh6_m{43uC3fa6)0vn{uncDimWU0rq3){VBou*o|yX`)tpOX6^RZY zIftW>Rk=cy{J2-gk%}LM)>mXXV4^xKH5LZodG2L8MJP6WNsBszg2-4ZZ^{-ZsFI1# zxsrVmhTK4M0+LM9D>41*0ERHLvfQt~e;%+~U8uPN%on(a2#t@B2mx(gsV`QCTzYG& zCYIIfKk-Sx!z5ngxw5`NT;>-4utJV;)xAsR?iNI!ozrWzmbLTXVKzCjm5M8rV~A9| z@Bx#IK*VThA|kJ(|I)FM1;O=Lt)y4eH4)Jd`M1mOV$DnX9Avf> z_6rdH{_;uVY1vAhquZE$e9*TGpDCh{FWZ}^Yt_!t|!->Zba#K~NvXrB^0<+bAV)B(P*b1@P6RI^+*KN8k` zo{D3i>qQOdMyCyl7}Tv(B9Gd?Ue;q04$q4b204r`M4XsYDX#r(MEfD7q#7;bL7@KZ zSq{<6Yb846^v?!HZ;MIBo$tkB*J5Wbxdqt_&~#x6peqa_ME2)FeGm#`m$oolWrIWQ@6MF-v_})>HbX;Gj+U^plYCvCn_wM5mv)^^`8e!A9 z;TREgHw!V-d9fl;3=a$pggnm4&bBeGC4^V5tzk=JvzkRM-r*sWgP8!K;AQbrK(tGy z&Pr@HGS`zvs9QDb$V0VMOYgB zzf4U~Gh;`^({;qNoWT$Zmv)b>2O?JnEYV-TenozM1zU@Ctz}5XA;i}I>0uNHs|y6o zlhJU@52T(4ImmGP(q~S7ZYZDokLip0eH{@Tl-yG3rWs0jj{Yo-Ij1Bp9s(+Ei{?kk zrdhDw`qRaEf`L6BNbo!SP#BL8qwWtn^!nwFJyBVN?N?2l2hyX%TSCz+@f9g?_hj!w+H@{|sKJ;!4)SZjU!@ zw8lPv{+wy*9#fJFRNxXU^1!<{BoGudD(DWmHVaY7QZM+E`{JFqPAY%cx6faKH8eG| z$Lqejh9T;0n0lFJUq*BLQf0~?VBQSwnWhdk}^pFahA`}zpd9ztxImlu6i z>!ENMhZ{)DfjEbXy5rjsji|Vsf)lOWTp+%oj{>ANXSka|KvG@j-@*Z(gthKMh`t~K%e4hdr*B0P@RMQofyoWBT4Br}SU4~$P>UxiyWSB-2KqN(>?=x2 zf5WCF3S^JK^h?Yq<34A{A=e-J>R{r5>J5VJ zCI+abOJvr!4UcKCT5Vo>%#$lW9jJo_#|FcwKgy~>6{O1^AFTt}#? zIw)Qb78#JW=Nj;+ic5WeM$^7F<+Ey8UHIo-<+3Xy*yI&V&Q|W5@RIi>MsztT7>=y; zIMpS6lQO0Y*=N5cwJA~SYRpU09Teje2_h-{W@$ zPfu8P>i#lk9B$KATUorFqCTe7BwJ$`8Er^nfBL-`wusf1sL!KI*wm2koesjhVl~y_ zOvdNg<$o|-r&#@1_o~9h-@h{~gGK+p8+S>{T$paIy4<8H#4bk!l7v2St`Y72xBKLD zid%@hosNgFsH>(T!A0|!{E85RKx!_p#l?iMnI5Hgp*(NMyU4oU@k@z3jrWkc@ko)_^YvD# zbq6tpj`@Lm#iCq-PV}ePt6x;w3i<=TzbVPgJsYOyw|CCu8@YS``n_dsR_v>qjXo-C z`rjjprsaZEFPjRcn^WJ+V<;7jjOE3l34~aCnoOXUbW6YemzL~TGx=btJ3en-V1}g_ z$Wl#l*(5RAE7_aXyKE8c(o~LP;i4Z-{#$MQ!S>d>4YJc-YQUUu+c#6{>oqogO7#{ zJ9=1OfG@1C@JCGsv!)1g;O9tlX2QuEab z556+HxA6%GJM3f_g&rQVLpk52W3S$U1#W~)MfQ1to6+*A?t;NOF4rzaL3p}l(k$T+=Gk33c_ z@jLTLRb84DCl7Y#I5)mpxcXhE4au-OZ@Z@{$?53(rtwoPUZP7)fLnDU0e$h^O~f18 z@c-OKTeELPkW->>=#LMt)EN(BR;Ru3HB|iLcWJr#+S32@=p*hhzhK;Ao#5*^SpS@V zQ}18d8WZNp2o|M6sU?#q``m9mF?;Z)%dg>2>LU}Jjy(Q_$caaK!G1YGpFUnM-Bh|3 zNyP^27DLs~cJq$!L6DH%*2awhvb%u8N5)&WzJRbE=QeF4%B{Iljzkwp1E$ z?0Kw5Fk6^D3HzZlbmX zhec^nHQ#%yb?XjrLDUK3I~`=4*4}@`B@2*5G2uwGPZRP@BuR2lpR}DhmeifcHJ2WB zg))b7_}Ns(+`dR^Ru)rVX6p|BmvHNqd>F#(cae=u)e=O z>T>C_-_2*2FWn_3o{~IPd@%wH9P1~ubHEXk&!K9HNCK-=7jC|9QAErUOR4;95AV2! zMkx2aZlbj7qv+%qZ=ikFl%~8Q&A4(vRi) zBM*Zkp@E&#x+y3c!P3{+)#zF?tJzYDa>y7QFrEN^JDI+)yVg!FvdW(Qm)5}gQ4zoMlsCkd_KMJtJVddl=LzNC8 z=p_rH+u=l-5sPn*c=YelxrZCydO(~Cvk*vJ$TrzO{-=z=_NUkj0Xkh{IdX5GOl?lm z9e2FK^PXb%KC9@t&CB8bPA-8tZbyReXeJt0C-WTtfp0YUbT7D%kdF61nXtUuT;QIi zMUxLTK}VIUbZ{1|Yy`106d#Zx2sO-8U%sf7e|j8pN06SOC`f~ef_7>|Pkl`t@SV7{ z2t_riT6-j9LqZ7;qBt2A_$jCvEl2FZQAgJ<^vfdSq(!fhU=GFb+O60gRc^2Vg+azMeD0UlKdY0UscM{T4 z2KWeqbr*B!W}@PgefZl#gz6_mv2!RqYHurZ6;vxM51;(}dH?7~NGr%>6fA-g6{+zV23NbT;sy4repBrkI!!UP2k z4oYu>M5mKmM*GZ>va#reSqSR^bQ#$_6QOBcne@AVTg6C zWws;tob?J0=ComYU%G)aZo3-a@cBu;^?-BiBAE!ja$%{wLo0C*BP! zZwS_0@E2UDY7TvIvQq-)Tf*41xX2@F)f%V9(~&0#@QTccstF!M-1_<7UTPojXpxjT3+q)-_Rv18II zO_Pp|)lnkSAUJO~Zv--9UR`PhGo|N#4}o=8hit|@{~ymE2L0%;@4|H&O;&y}undBn z$PuYu?`+(TCg5;Gw>6ONkn2v6uz>JiA?P0yNcoo6qLlt|ug-9x2~j&>n}m3FFv@gp zD+H{X&w(ng9Uvn>-FNY)OG+oia17^;e?KIYbtftwqG5T~yVrIa2zqi#{`VH)|e-o80=UP$s7T!Ue?U4>veK zN_Mg+c0vS7A~@WTLrHvJh1({o`Uz3{;2;Hl|B?2BC={JR4+_Dw4oxhGnw4LZzueVLMeyOlNi+Rf( zh1VU!?0rigKAUX!+~zy{`1?wCvr3Q$J9B^j9UkNIcX?Bv!WylH5C5v_K3d8x+}E0n z8d(tWT04I;hG?Z!ab3+1DV>ynr?#0b!Qc{zsU5su(=!b7IlClm84n^1Ne5^5L{~O_(4ZxH+)z;#*LTi+W^k;*KGz{o@9+kmHp!T@)K zRNC|3_3rxSHPx`N9Ct11%iFkFl{`l1qR*)NwOUds47 z39c&((F|_S-<$jCkzvZIBmBrvB?hD87rAbz<7D&So}rGQjf#z*nTpP=80NC4u7YD| znT8+Zm$vp-R|9X%imGk%IhGmCB#=a!UN=QZ+|zUv920-e7@ukIKB~=EB1frxCrH{vG?u_#WHV>gA-h$))EE& ze0d>2yL(}T_nC((t9gozF^vJ!AMrM9WYMZ56YKTd31{mc1GE{LGSzjT)TfAhOB6&b zExX6-D48xK&JXNzWMpzKj&)rzy1-JP&Y3BCZD}T!a`OiJnhPhCnO<6Rxiq#)M5K*7 zPrIXni%QC2PIO+2w7fyACcj$j6y*G0;;v;Ob{B2)*_nIzzpBDb1KnkDCFz7hL#G$d z<_l|Mb>wlrUdScJ|Hg)d);6Bo*1x?YojG`>v4utN`mTP}U(61I`x2MRvmEw3!|A>| zG`|ZN{q(gKcBIsb9z?3C*gagO+W63J5Z;c&kkN~h0K*~R5!Ozb?M2P zhLF&FxG(}q3j8RL9%ol~{H|cKS|*$&xx+q3I#-w|ywNq`5%3S&Rd%12n3e+XC`Au# z_$>F6cxkg&Z>u*<&T&WJw6=XGjn%y?c|YsahP-#}$A@q6*>^@|4t0set7ZxqFy34v zp|D#)^t=sSL*}IP7pL@-$JA`PUr6te8!mpyi@1cEGVqq-(*HaD^Dd3h^A09Mt=(%l4JE%E-uEE@b8o7Bb?)gt%DT zsiC|}w3tgPb5l4SDdh;XR)nQjs{E+Fym!-A6O&$>Gv0%#oe5{Iwr+ST(mzO>vdR(A z>{78XG!cJ!l~Ik1Y4oPjW_jBeWegRb*AhDlAk-Gm*#5D>{5Q~V&|m|Y0(2gIGr3A{ zxI<3ANC(0IC&`%n1ysCzsRJgaaAtvM87dhPpcItg7Pf+g`MYM6Mu3^gRW2gC!ikkU z?`vlf?XS~Gl<_bX5XxAA5ELhEBglmR4^8hKPxb%*|DR)zV@3AfBH3BV3L%77A!P5F z5<YxHhu{7A{`|hLOMkpxm)EOT=RD8zc-|kk`|WnU0i_aX zMyn5BHraq(SY^U{+8%a4fYbov0dOk#d8x6MD9#e~@(KTUrhk{^Fd35+8u$diUXAy{ z+>KB(uAdHHkNGzA2ECMg*IWt4%UZ8xX#L&Z%|2(ockiC*r+nQ=tJJJ}P|E`XFB?45erkV*yZBI0SE=fj1qD%3YRk zZ${jC|6hu)O0WB0l9*fI;Q&Qom-|QofK#v%*+wkghl6o}5+ZJ>MtFM%Tfj`;<-2?R zc70OdPSkx1q^D{*7s|4sEr~xq8ub&D?r~Z6QY7g_E&s`@Ioi zwC(9_Y)W`?j}QR)@a28Z_s%EE{cl?u^p? zxiBe|5sJ&3H_QGwZ<8>+skZM{ux>kjXAjytoTPsC)b-P&XeCekWRG(7#V;NoX$KF+ zUrXB2cx}?#)wRzZ8CjGnSbx`B`0rfQyG*r>jSMH8-{E4jt>EzFzwpsPQPrGR4nZy| zz0zuEONg+LHN`qPru`?+5rh6upIGv`dcv@Nqna0GcrvaBbL#7@D=(wOq%{}@(kL%j zIw+eEM0#IxdYgOARpr2UJ6}@Af%yIj0XHYH!%cR2rX{ibfk4%%EmT)gtR!cf)LP50 z%=Ev@<6l^$RSel&_@6TlV$ErA+c|r}uzD3*y^;f}oE9FGFI!~EKP-0OY7Ys!#_ekN zk4y$<$>-hV&PNxOo!%3VV!(am;u#uQ@8v5ov0oWth{dOjZ@p(tc931ObJIET+Om)& zdR6*?ygrN9J<7SJkuXk`IB(^UOLR#ZN1mNM8QHV#j8W^?i95sP(Zo^pl55I^Z2!*- zz_DaR=rk%b)H>ny_oC2BOL%Z)c0HMaBi4qPAc3JS+`UOcL4H+f+ubqia&cdbpfDk& zV!&X1^>d7UtFYQBht;Jhw!-a?FPrZ;U2QF}y+(SIl}izg+h=-5%=t@fw?JovNSeV0 z&fWDw{JhVydhN2=-p6@pBLRAq;vtSu+jUXx^wFR^vZ83kNSZ%TPJnUnFfIdDw=lFYGUk;r~7Oo&r=89`OC_?#A62VyM`&2x?z){jO1L{_iFjp3np(qUAxJLuQIvmdz?JCPdg zdb`;QWm;O#!sL*=x&Qo)=xFYe@~?6C{e9@x)*>7vgC58{(@O2LUY(S0YkOeidx#RG zs4A@-RL($@AsK(gXS++`0t|7*LjTyQzKWlVy9yLUXcmXx$#eWo~D&xj>y79ZgL4g;Y-6*5z z|CQeU_^-U|9Og+-P9XC3G5y1F&Tmj?+mjo)wSyiMEaX_bme8z`z@&4Q&KVCBx) zkjJhF28wc`HGg5?C;aKlotO`|J8ZimehhwzTHNXTCZoDRD{6Z?0hWo7i$P*Th8<@$WnPgCt$hKC)Wb&R6bBW!U*=GoA*!6ih@%$1id%{$yLv3o#G4Kk`B zrF!w&Z>+>-v-6W6$fcb_jfbvI7QFruGwiP($v^GP{dDxra>s-7-D!M&OCr|!G>QEHE+ z>J)G4rCR)*hvjZ zIDG-~1`Qn#t5aD81-o|tPh$&DUfiT+`;NZ^mQ(_8V)7uJJPT<_^rZpt9|u0YNGoENm(-J{<&86sDtS z!sS8DfO0OSbx>XsyyDe|HLf%9sfvr^yb}Cj*~~sYL?ioJIw|w(&)|p0wYY#oL@91~ex%LYQnpaV7eubErWTHaqyIMP#)l;<3kg5> z#G{0S1bT(P$Sc7LTaO8d!Oku#g#6%1 z?IsItD)^l12c{urs|t{RpXOA-mKi+v;Ereq5wzO_GLuMI3s`#*p%1YWK#7gtS5{oy zx6_&e1XgCB9}>gt2M|R_3V^zesB{Kf``tUpp*aINidRFV7>j z00@9%ZgCM085>JLw?w=o%l+BsUr8UW26vju{|`HkIJagG5KqZNSuz10aA)*igKG*ic!a}#02|<9itmsj zSp+%ghg9Tf4*9zc4M9?OJ>#+3$Ip{STxv$edato}J893MbBMn^l6kHNQL>jLGe zOwM}TRnZU<6d8W8P=9K;2xbc&PG(G_P@jLT`DyPk>fM5JI%dZZfRTHX_<+q-{Jxow*3?~%ucpe8~Pc|FN-v5MB=gzcb$#y zSBo0eu#30EF3NKK?Dw$rYZdv0(^-)eFLH8*cf{HGsYtSd5KsBl<&Pp_4&z3VE6}m0 z+F!Y^Y&CwH)8_4*`+CjDwmd!$4M>Q+Nq=(kRg2_(G?m{Dgc4S0>(eZW819s$Xx4F{ zRJuPZvD4FOykUr>ME4!P{P$LeX~U{O`>PoCl2`$0{pbc$D|jM`IwHSWP`kzqCpFN7 zd)`djPcSj^V?_Hjr=3<*acE`grE201tq}ew<&*sIOW}_B*qx8X%#`#RiXtDQH$^t= zXZ7`17llR=)*W#E#ZPNcTJ+G9_qK%I*_U%U`j8RMJ$Au`xpLifBnv}dMj#gARo=); z>UZHEE3GPTLG392U0kA4QPZ%2_{ng+5n4lw+bMXh$-$UfR)ZhI+3x9`7~FJ10Wz)h zq><>r|0emlqRj|j zv5NMN*H4thMpta!{h9~|eA|g#?T~T776;Q{5eqFI{Oh%1wV}A#s zm=XrmI0#w?uCGm7%XoJj7oE$vxA74SnnyNj1z%sO#bs<+otl1W*x#buNTsMP_ww0s zgooDFikRjd_Zt?y_4$VRi>s%H&i+FA!!2D`g=%$e&KW~=GO7%^N~Arqt8&u|?Di#! z!#L2mX|{tw1XFbX4H}&M&UtFy81i5?Lvi@A<==N6O*YLxRK%QZmGm7f-@i&H(`gE= z4wce=X-@R^+Ag0;x3ZdSO9-7Gku8y~UrM^Bk}uVG3jI>jC;<_ZiG3*dH9Ce?Vxc#d znOs%BS@cV#QQCT$GS<}DIpJ}kFRv^=v2N+uUbNdw+C4SkJCI9emr|gh`aS;8rD)*5 ztY?>96(y#$?vc3nr1iJOnn|)}VMOk&|z73n-?-WYY| zGDjwj(fz4LXhMeKH4a9yoOtTA>v!9Q({~5?kkQ*j%j~Go z;4A(_xjppSQo{2%7}bB7$Ihzby^oq*uvoK*{a{o?yM0Z=KS~3-3mq4|(h|z~g)&=4 zlHYga{~7#b@OUnn{{9M#&OqKp;iU?bzc|0A~Gb^KOy>$;?hWm?F*wCk%(_vr1Tpx98+B_ zTRgsQ#f}O>67WCz;V}2Z{s5jh&vdHomu*_wsO9p?ckkj*CTw6o#zkOh$hn5%WjKC% z%@+l567U=x;YoNteR|uGK8IUDr)@37h3Vrh3E5?lA5))2ayf7P5bh8RWUC3xz7x*D z^LTV$m-M@R*D%yPu0AZOwx0}XzKs*mq>H0hHu4eAABLd`Y zZ|9@!Vg0olJhpNyf?+6Gsn`8LyHZV*Q_-f;sh+!%`(v`*_z_*@Z(@^Tl>XuNH8c;N zUr-rSJhQD(W9QvBpLKwa9HX5vN zzKGy(hmtaJkYj?XGOolf^etsvrNyyA_(VOK`ZJ%~S#h+VWUyMcCln*c)M{Ce>S`@{0$||~8Jx3>uKw!ecx>#U(6K@dRmu7Bl}ksEWCs!fKzCcl8qOXetNQc5y62(b zjfH1<-ghU&BL|sxSpLDz-fmeS$fv{ix7dy3ZYYL}LC0fclvkyLMEKX)!<_O*C_J1h zO?t#`JpTpFJbl__CKC2xbt3Ar3WUNkO$ysw9cFj z=8PKqhni!zZu5a^LWIW4t!ux)?nu#265x_kl7^}fbbErmtdpqOS z{^OCmd)!oC0ZG1Ue=cRH+qL1{lkA(bW~1e2i{Zv2Che1*y-{hsD>8Txp)uIjqU z-9D-H{oG&h03){*%!tPQ;wbfMx_SvMg=XH=}jaM$~mkG>PvF zh?~wC=ITX;eSB|tiBfs{NVA|>$bHW*^CEktOptP9iYGWa5yxf4DB@)VVGo$WT_{$~ z8MnuZACLR%)cmXahXPCxdh;B(FOcXbWIP|rB4-H?A0KJTAMuN#L^vQI!aIxxF%)*X z1M`NnFhH5Uf#VVQVoN@*=;D3J-@=Q}qrpQb=|k&^l~i+KkkIr3UeRj>^46BV6ipuZ z?f$@sL*Np$rjzuxx;i=@z*$2$Zy6boc=N1WGdF<%;^u@YjcC!l?_pBlfGO#AzcgQr5D;s8pK$B>L$hUA-T| zk(Y^Zgg*&7)7(jD#NI#qlWLsuTT1Hm&z}cE(HpQA@5{bUF?YZmGh!6IzcYM9Awv?6s>_Ol)=H9u+3->-4|uC=|sK_J+78>3(#eeew<&?j!%-I;UCKC*o`y@4?9 zM*p+>R*9k=O*of03!ilKJ)n~(NG#a2d_^Hc5Op_mwzUP+CP67iuf<0U1$Rd*OV$vU>fi_ep zMq0m_lx(ehnMsYp%7{xbm^f-a*g@Hjbe{65>D?|*?B^Uj=ZuQB+wWwgvPw8OKkG_A zYFq9Y@Am!8k6YMu>;CXV{C?eunk6FzBihT>8Fz5H#2ZDQ%Q(HnV(6EKx08s4;~no# zR=(r~*8ECw9b%fmR4NGQWMX({3_JZamjf&r z;8HZk;|=+$qo_BoHP!f#?3@}^F>@-!@87Jjs7WY6yW z39(NWh2un5zAe{oJ|V}tdp8mB`}SxdBh<6YHTwJMQb_`&A6g7G2=s9h!>TAkHI>4G zHt51@uW-{|@0POL9Q>y~R4mz9@Y5sZ`AOo^F`LMeR!fm8yG$-dFpJ@m%Y91h2xCdz zVwfJ5?2%v+Hdi5k`$K5f5Y@0z(yet0`L+aZRV#sYGCY!8@7U*`j$WM3-Ep&Gd8zyN z(W|0`&r-eo_m4j=G*pJ~*z7TtTgJ)xI_t}RY(5sf4f8yOncgHxum1t`sq=d(*u+SkpmB=L<^lI_MlirWW24~q&FluIN06z zYBHHuk^k`H;zBeY`*2nQg#ej{wh5#F7`rmZh`OhjqxJrVwMh^pah!d1H?pd=V-V3q zalgO47P9A?q+pN1{`^w2R{Q-pX)5zA5aS@yA^XF?xcmAf0syE(Fy<7hv(j{;ud8@bH5!OnTMEvzWR93L!bX_E+H0|+1x0fOPlk*m ztZ`fwjnv;I3*NomL04M4M}NR3-`0{GFyf>rOp$RGgIWxNo0DJCiPhRO2W z39)%Uabr(!m|Edjh}#GmwxuuItR!Ag+-54e_+of0)y^Z|R-HZHPJEx5_sI%Q%lB0n z_gOtl^z&y|Yv|W`rD_%5NjKX1{Ae)sJKhanzWU)`Md{h84Es4clrs%yvfm9)hhGx>R*J5ev6 z?jO8LGYgx|b`d*YYbWDAhxq^w11R4p9GGICb9YomtOGorgz)4-HKjah-Lg2nGE;)vmIEZlIX-h81 zfQK&s1sVr{%OC~>k41nJh%()-o&u}|MD{F2f=TOZAN(RgG#YqF7h0>o9bUBnhvL(% z%}w%0?|5I_ggxlDW``kh^CugU2+$Z&uEI#^wn3GI$1>!j>;#ea53nwx;5Smi^B7jb zQBepEGQ@ zh$WYyZble}Nrn{zei{&+kuEh;VL|~O5Cfj)4?Dpyl)!O|6%gT&0&=T4f6CSKp` z#UBee{lIhui-1^qPosE?$fC2r6)S75#t~R^Y8DI)Y)661&dA895$ua&S4GEqq5p7h z4%@^7d3_be*qE4k075houRdhFfBO6GZ6VrHkQl3H1LX(^w74(yd|ATz#lIKQS(M=x zdGBDl_+B-n+^}9Lu>&}2Fv5;5byyla(!!y3$W5Kry;`V z^fU}=2!2Ze4Cw!d?TTwk{9hjktRSFl5xE&#kV_2i7MNs#ZZJAJnuhNV+AiGdjqu|V zN(x1xY6iJLhd?~Onvw@c3c$qeqyfVXAvQq0#q6qHs@sHv3lv@`)|%Q?eS)aZXb4o9 zfE65aWRS!AM?O5;dPiDZ9JdjbfncbC=6vTJUmTW(%C1&VGM7BiZ_Tz-k_NWD5&^ z(;5#nGS@Ee0$d!7ozhRwEm_ zv}I{uA85?*+r*n|ElocG2M`I?fe9F)6eA%$z)*lOWC4&FaL_r?D{#-mm}9s`F(5e(97+S_}J^}fBG9k3E%(-8rxE<^{c z{QWcbqN~_IZE+BJtOgZ~IgKFiZOve=(#-YMS)9O&+`)0St zHSC_dwjzKri(d!;7T2l?EwtkFibTWLZ!w~wSpI$2{e6xKwLk30SD%-{7r&fdg>FW9?SIii@#pp#wh~P%v z?2+Ky(3IFyvJfK^5l{1FUAyO6D#*AUikoz?&Dbm(#)+(1l(Lw*I8x? zD{b>~buF9k?U$z2VxHpG^-6{?|kc(c#CMu49wT zmx+IwKL|&?e_Su+cH-TXk-!?h`xNi>vsm(zrAe##thM0)(ft&(h0ep`g#^)w?X>nV z&n|8w!gP;>{VxW-p|-gm<)Tev%|8d2yZstwuoqMAUDwsBYMCO58?Q>jS4?jYFM%J5 zZ@Lz*$TR&Jib~_msU)U*drj*2MOJd@nNTziH&(KAv*v>}CG(HO^mf&U*GQB9Yh03a z5TeAU42Xr=hdcOD8SU7~JTT5kx<|qMZfxW=&fL^d?i=2uNmRXS5!+>+5ZkZ~gAqES zzs^4df5^I}>HG00yf@>~Rlj&3n>aGw=Xr8p`%LnuqGV7ZiH3_&sN7UkY~67A_*h{U z{pf+}NOWHdgAYEPh7_LBQm6=rotUoXk4U9xr3&MazZCtq=VUc4uzQ!@;WDUktlq*m zY2^Nu%N(Y>9(%#tjT)_GqJskh zn;6WgiI|hz?-RBDP^IZB+w!NI+=&#nEfMEV2RI>Lg^y3KdwQRH^7b;(Ev#F58w9bZ zB-`_U@4uyz@v(n+%T>QCbo@`g{SvJxZ{hvN59lKLEZkbEcXSAJM%CESWaWeS$}PJ= z+HEa=|4Iwrmw}R91|qbJ%Li*~FY1#gz@v(Z$&*O=R?xlddDMkZ6UDI3whmz{eCN2w zn0O&lA>kB{(=e?Xe_Qf)KK1eO>E_WTv`#GU!zuYtWx;GsnwZ(f?HlXMBPy-LIt>v# z&&*L7S>FfU@b$h+NwK=2`6Ov5-tlL=YEE~{^P*IK$UP@;C}Lekk~CvV{heq1Gb^Qw z?g;Ah3`$8?iT#qlyS~3V!d{cz3#Z zq6;EYaXb+MWS-kt+tNtHDZlLdF`&4MAX%Jxe z!*n_#UmyARTlCWg(^Cwt{x!M&!utziugMgajeRL%MF;mbYl~dN<>%in*BhPE_7}4K zT{^)z3XW)YxG+RoQr!?@SMFx?`kMIc@*^9zw7$w+5_P_9*@(x^vVv@uv7~jQ;xF~{ z@>K99g)YBHxm_AVNv)qJ#9hW2rW~(~bIr$r3ysf))}hM5iLrLDLFcm%hP4snIpM6_ zq|h87cw8b~V)s-{u019Cw6g2d;gMHz;Ak!S)rF479ND=qBYK=$w-?T*&Q@wT!o!SO{@aEcxMmTX6n>LXx~Ln>0Q`iYR}OEwHYX&_%lkl6N73JT0i-4n zfrvQLY@sy4%Go)J4y#9-?Uypa87HHVwxl&pufAjyRzrE-pVHe^?%>M%4Z(1_uq7_S47hb z$W*~=Ffun^DnkQVP67@Ca%X4}#h~V%O_(}z`2WZJDicC{f7;p>Ad@XDEWn#@hQ`VI zgRfhnOp}nNgd7gNjmDo%oK6U*gX9LaasU*7ybNewmkU-{#R+Ih@Bt@<f*@%2*gV>tmVr6P5=7JDJ5g&*(0t?O2L4YmTqg7)N@Rc+qXP4cgR8O- zI8N`q)vw01}+d zb?T2`N9Zjk3ufGQxg*<zzLkv)9v~IYPiN0#pjs&Ngzgt#L2GsW-ep9{?TNg@ zPh%A4?&@m!&37)13IbKDZWx;<2+R25#(1*xgy>4z-mj-Kx`Po z9uIA8@h$1a<}%ujz`UBpbldN6n*(mi?HG4|-0NpMap`Z9mh_WWYAIOdQIvb#>_k4% zul1(k9EP#s8WnH+%lCS-Krhpf0_7vmQJWihEPuMgQ_Q)23oldzLr3+Vl;M!-+`5ha zNh)pI*kbyYK5niuMq74Io7A#TCWxDC!ye(RbB9f#JR*lG$!V~0JWH>G+ z6+{*)JAHf|KXsFd@M(7HOXoq)aEI2+qV=Rv>>a9jZM_v9UFAzbdK%Q4@r^c@O4ijE zr|*oes5XjjNXy*H;QjS)N76&lSJ)$;t!9Dwab~ky<~XUM;l7J@Rg(7Lru^NPt`WS1 zUt+VG_K%DhB)W;1GK7e9G+Gp2PkW^35a_3S+*NjF;=Ss`*QKlKHg~v?Z7K3oq9?ND z686BkWhPU=B~9P)eWS=OeLP<7BE7cVFa5-<5l_W%^w!@>rcQZ0rcOMU5h`k-zOp)^ zs?K&#xhjj(=qvh0is?tYE+?B`KOlyG*(-7FYtcIESVQJyCXJlNLyK{uVc3N z-$&=jM~k8aSrv041c}CKVkCDN(4Cy43OLUk^By3dcNre5^#FqmVMn25%y@;T=|qW3 z!nm{DC^bon<1PA8WlN=zmw%ZaxpDDr)~RD&ah{o}$@X=mvQVrr_E|@IiV{S!=lzaX zhz&f=IkGmg(Fi;bGS%QCy7#mtX2GTBB96W@_0nK{hyhQjjT-9r)js@5hUM`6)xvt! ze;2NKbQFjCT-bTBWbz<-ijuqJv!c=5^Abg)o5y`3NyI3QPI`!XAVDVZ;@ z7FiMtVH?#1?7YSb>=}>WY~i(W7<+zvp9b5;SD!?~iB1l}!op}YNS92`GDXM2g(aZZQ@c4OiN#mOWqcN@=qVBMcGXiz zsK?6h4JMMcsw&&!*F1^$<990+SXE`K2cILm?+RP2PF{rZkeS(Kez-0h03Q^^c64FE zao@h({PK6`KOu8w^_<^EW+yapcVa#K>0i%CtTBooA5m(cQf3S$!-__Krmo*R-6C<& zD6e@IHz)tYd7dkwFV{3Hj89xzZn}M;-$~kKEIw

    F}GQ&o}wlKAizMB6fLpG}~ve z>b(>-auz=y`BEivE-2@zH{c*y=TMEC|5b>j_V(cq0c@k&50PJz;_l8@E-)q@#9iW7 z68fX4HzsZ7Jone)V&II*n-?m|N9Q@LO(e)O)_hFE)LoHH?= zaxSmr04^h1FGv|S*~-?MKK#!mcq`N{D2O?5M6vn}NaJ~|IBOKo382Z?SR5Y8$0#yO{6cU!fJ3rL?7$yG&&04dcOd0}`J8Q;GME5m-tv zh{@%cSx_Z2h_F*|-~p<=JUPB4jegPeO(neK9@k#G7b>fGDDU_1=(tn!IKzJnxrBaz%=1INgNIxFUymq=w zB(M7Gp-O8lyBbd7qdGHiaDt@6zb}9Fiz#r1De)lL)DA$X4`*+)h$#O+IQU~ZB*!40 z-FOfHnGhtuAxK||Xh#vM@CXN)2sA+E2ak;SlnY#aP-bSG&f z)*6rCVbCQ-d2Mqbwv|sTJ`q4niHLT*7KPY@q1r%5FbT9*C}p7E{uyo#v8HJ|nCuu* ziu~c)LtHug7M2T#lbEB%46^c|mcf+PeX~G+{vR>sR~JFR74S!@jU`W6T6#j#m|^+_ zjJ99|fJ1^Mq(dMibl9mI7!0dv_Gw5cL0b0v(1{=Wq8H%(45Lc5m7e6Xeezlr|9 zwm&On$F(j_D0;(RqdZ}DdjV{~b}}aLs%4Hay#`ayr!f_n4JW9SON6hac4LNCp`iI6 z{8wODM7t^zffx$vG(qtNgL%k-fn%_|{?`MUz{ggx2Aa9%pP*@r8MI9Vy-a%L3l`SD zaBe}$>5$+&f>tiR^M6dLw&UQeD+Q{B!}FdFfcOVkKmPU!_3y+s(cck<2c0&FK~F|f z>^v`UzUmd@@7Sp0KF3Qb7>EOFB78?6(1Q+#2sy}+Fphz$2xGr(xK^H)k8-K&o{yhFcwGIJ$q>cUeh0PA~R2w{@o#-ofs!zvP@9?&iz=n`+du^z7%60&065Z5n>nhjWZ$# zIyAuK-~(}cJt5lKUVAYH1o+T1sm8ttcNWaKVtJ1A;nUf6<;I9I3Gjvwa5}K>nO3t- zf$J*V4(>|W<%2U8fW91G0%p~LFRaI_$6KnI7-%r=it`yA&hQ6@&=#bN2Ikb+#*L|J z*neDz4#%RShRQpus9!Kl{D2u)I0U}u0Azq;2{N_fQXW*NYxCyvxj8sCLL;rnvG~z3 zu^i?yR{h0TDzonTKr~<75V5g91xKRTqAU)mbD?;g401X7675NkJOpmUUbfN~apScU z#5pNg=d6Uj4E+6@?x@yZ(p4=!23Dl zMw?_!dx==XF5`U`*(r-bI;qAD%X~aeo_PU^gv2H3AP;__BK#_T*FTG5pTEtOaTf`Z z30u!aw{%ge|2KkbA=YcJ|NZw!aTNuFJZpqj^cC$5@`sc4bK8ZYKUCx}JSjGURfM#9 z1RRPxTF*pvG+Z0yu?3f-Uc_TNSER33aMQAhqey!B5|6ZMj_IX2tV@_>T3ph#>I_UA zsh9Lft(mN8MThH?A9bzOOv;Q{i4nVz;9W>gGMdw;*QlXHB~9GES=AgEnH%1S(=4pU z)Fw(wOI?p2dqmlc?aU_<(PvZmZfAoiCDuJJsZv#Nv>)Bkk{;p zi-#JSkZ-D!Utn%IF7Ez7>DvuW<5MM+N3Zz-Oa%~CcQRD z!M+|aS=!z;k~74ptf}>z2a`k3X!0t4iYntwEv;17rpcta%{_nTf@rKGDRap3L`fR0 z-cn~;X3wQ4@4q22(lK0VXmQr7sK^uH%P#yE#%2GYH_YGHemQ*V>YBoW+va+ippCcQ znXCZyi(#9k@=0-JL&5)ID+-8_O=AV{+Nb z(vnuI+p8#+W^h9ac0SLZWGl4w^)XCdX5Yqxhlc0I8-YD{`hF2Z3QwLv=|``qL6S7ONc#&J53Es`p# z*|IAKmC&hwy?Vom&mhOM!i;n%JpIG$aL2D}i@QAHbT^2ML~55#5<`S}B$Mo$V@YD@ z>6UR!y_MpHyKu({4Zi=}E>uf5LDW6#CpjPqS^k8aM8n?CHa?HZNA{Km`&m zIX7`@ahw|0}60`a}a z+W|SVTR*o;V(h4iRK(+?DCldR9C{J{=018gcH(oJD@&4JfJ!rm@1oy;15wW4T?Y=; zez$*n9Jhnx81el1Z3dczsXm+onO; z*>Dm{234E#3Snt=wBwA6?@-TCE~*;nvYl^>VM4ftEfEydzmzz3 zhStp-+dthKbz4@kRr(d5g2)oAXabZ9JKI$}b~LFe#~ev=7->BRtsKsZUKSB#4`Ja9 zoA!`?4fko0w3cSw&+De#@NgqW-7?{SXjE#nD4V1A9$@XJcEU_1Ce0#?#0H;TObO+a zSwxko8gWJZzPm_Gl+Ld08M&Li`640C+zG@&z_#ok958&r<4&Iia*v0H2Z{p^{uuM8 zr;p?hro9eV^5V8f@3{lco_#P7?(GY?)BF@}46qaoLVMty<%^`Dw*PcrS!fO;1+tLM zejU;z205Z03#ea)DlMbbPPKSg_=9u=E62n7>>>l4APDvnFnyNdE4GFxxzP=ra&Q=u zlid?e1xQr-w>2LtH?~#mY{qHx*te2nD5k9mY~2j0j<~5$0zb&_9+`%;2{UF zm8czi?8>DT6kv)WfL(kR>in{>uoVb+Al5X#aaPpJ;Uhs zn!g$T1rkbud6puS{msd<+hiIz0zu>C`s2-4yo$8$^3No(U3zkNc}P)*Zhe*H`w@5q z0RIz_mzkACVDbB<3r(q2BH2f1^!V|^4mAuFO%Wly`^6v>YY3EFy>EQ-j0~XXv3+S!V6xclB|75r%EC(dppJIGc*Y8qvW+j*pe*OCa zMttwOOo!@`vD2S)4UPBD_wHLiehdM~HQYV*F6U}7m<6ej2C%lQ8O#rKzD%VmSevBoPLgo(J6KRZ*ZEQQeCcW)Q*JA|-UHl`DV zmh}NA-kSNZreLcJM$|&6N&Za%I@Wj}XW{DAhRQNhyBft`!c|8<6e0*YndFdo9a8P_TQGry`uDboU;A`OB3u z-I^B8%eVM(dr2S2R+=Y1lv2Lu%|b?$o0AmESAiZi;*}gf7KvsPJ&9Ppw@=+)=< zE8qn#a}=GYz*R;!enmSmu5E@q`{@z6;^8LD0Pmg5n$dr{$G>EE%)ZY_F8}q+yd?Kv zoU{;+#e$LLjh*^BPX#A;0omu=jx-{oC+D@!<(t9z0SSYoU6C)`hYZv%w!T+-^8x<~ zFBQMCpsmO|lgVR!f-l?`^HbE43(Qht*Ttv3Gl|}>^-!!*EDLxO)vQWAn#Zd9>_v;E zyM%l(M z7jwW?Pd8=7*PqRUH)LJ%ob*x@P2962TnEt&I$|~M0!x*w)e+93K`tCB(o2sYd)|Ao zIbKqy^L3y+vKE8k6#w)PjcWigmNs!H|^w?_6c|lb>{|%=j zo8g}~W`fiU$o0}QmRF&adN=O2>@<&Um(S3I?ltSrc+-Jbjy^X1kWMBWTN)RP5GyOF z&l1ddNT>Rtr{)Iz_UmWl3`zoySZgePA~CgzF$odN#C8v(ro$%nt!!QtUA& zvu}I-G)1x6H}QGoTeRP3|0syJ6UT{h&aw7ty2A3>(dGTH_e`niwD(W{g6tPIWg~8> zRCnvVoL@I^u`tPwGG;9vPM7?xpLL_eiATd!pDt@mg3dpWrm?D*f# z?Cvj=B~CamP^R9rU?@-Wyu&i(qjP%u(RHq$XAh#*mJh|A+bK40v+llU-!x6WdO~E$ z?8IJV;XVO=(BuROAg=m{YaS(E1E_oOv`uEbn%MTFA~&D&nm=FGewp@U@jxKaHM=F;KmwxF1wR_LoAE-49FAaY@94;Lp2#o&mA{ z=LJ9wZgH%qN8%1dUKJVm$FyU2^`bz<%WDtoNWLr6hJ6WL#z)C|k1X}^WF7_Ksj8{q zQ*lyptnc0Ku;Eb0d)-N79}!TbKJ#% zbKlKdIK_Bz2h%arON_S0i48`1PL1YnY{{FSvLvwI-|n`23ecxGjA(5OU^vO6cUfj- zVlCVK^7*bN2kgI$dUEtXa$+v_>AaG@hX0vGoIq+=nQ>jK728$#BIvC*r{zDkE4sc3 z*gF?A9UmsQm5#=na3yg}uDllDW;DsseidaQ<)o=Ww81sR%8omrJ&LznIaTQ++WzHW zcVx|XvTJGEG0SrkZ{XT_UB_MPFDqMHTjfJw1yj;|1~iZV;};|82XN&h(Z=a%X4dP0 z(O{GU8y?iSmWKR+r5bX|K0Z|d6$K1Xkf1CDCZcjK7PcpO6E4u*BI-pHCf98vhCFM* z_y-dSG|hnhPIwNiJ5T_`GT-{n5Gnw{4dv}kz<~#wK<~$oODif`wQWIxsNb@NhZNvO z;JL?&(n7TRbPpP(%8tuYTy=7;tDA8fIn)9?mzXScWjjp^!21_@hO zYC;e~g+3f+4Q*6)NBY0aEq}r*U;kb>+q-{$5p*wTteTjCkp`L|lk}NMynuK=|Ha(M z$fEsPX*7y}9(uLlS=D3_3*bbgpc4c%P(u(d;>(xHg~Lto$_iJ3d7=o*MW{h~nhPC{ zZf>!eN3H&k{QO7+c#z2mkkePuHt|r$v=&6aQB_^N^KZA`>re!R=qXYhnp~HEvH<*~ zn>GkaSxKNP60W7^&d(cmxLnJ=l_s|BpVw&Ec=6IagXrO^?dtX&TSgmj!)^;&92>pD zn72QMoXtF*y+I%TOh<_*2r(@Jj6FVNlJZ(ev&F}cAIY)#U`|t97lWym`FX;m7Qh)H z-wU4_fsqsFJ}@9VGi zBX>->Z*5O7N;-PRtN&UAf;tK@K9)xXUY%fKf6E6S`|MHQV?~aTJpN|gr^f~e_!Z`n z8vi3P7$@07i8&ts>bf{x_m~0(74VQXLySEUBXR~&B`^S?l zQ59z5(iN(xf}{(OEblR_gxd}>@;~=CrViV#)(0UIC44>L<__OFp;Q);n?m?QoM2uh z!AH>J;HE=zH7IP*b3ATy7_lK{jCka}94)=-iM>;Nhw27Zc_)1ERIR&20Er`RTZGYLUI`w_^#7H#emOrofiFUcKJ=lnz#oPAzziBKWS!uLEn?G!O9O%? zlC%cfVU5=^IoyN5$wi}P&(97#&(8uJianu67hzDs%owzRWQ^9fkc;hg|ESnKfE1aW zk!}L8N1Bgeryu78c9?Td}670sN=yLyjhwYr|`su3f z&eyE~3iuhI^7HfQFF4RBvO%eD_WwuIbwE@7$L))YYhNSTdzS1ZD=RBmErhI)Y%)Tw zP4>vh-YFz2viBZQS=mLhN7;El_y4|cr_`yZXpS4}0+XY{AmQ5XgJkwVpS)#wo7W(`-{axbzUFDby`FK=311V-G zDtGoE9G<_8de1}nFU7f&1$B89=LaOZCl^Iu+(8{uuH2WFXO$e%!{O%WcE0SjFznhE z?=>3KkT@FBoR7AWc-&UT(wR+iiLv}Zy!FyDW~gfBUVrJp4zcuAQ@KRd+uA?4xcb9d z`Tp{*X{NXN;|tx^Wc@ItKM-w}LH)Y@+YU6NBK^m?B)Rgfx>zu|j^%Gja3otQ@}GCn zb68838r%`TbLn|oOr89=WZ=-FOVSFSB7=|H`gf{++a)(#agH$F&MgokWb1hKQ|d#) zDdSS-YmB%`)b(nV%?{TNZ zuG~YA9=h34R-2K9yO<&SBd(QK9E&_Zi^j{XG`$t;E8d-+>S(l*K4*FI*pzj##$jKQ zJSQ3Th=`c}B&a}6kDhVY-&S6Sd!nJjccd#bbyJzMqDDK;xKilaS?cO`P~>E*TJo>2 zhSK#x{29^Y@tfqgD!noOk2eFK{bnKDzpf*=azT%HU-Cx|zlGBasm_)<*G=ga9G-A( z2ETm2HOpONi^KdN^1>vtH}|Iy$Y%pY?4@TBZpcT`6O(+9+8tq&QTVJ$pd?OHDVQH6?aIo)7V;!(KtDeT<>$ zn@(nXG(G>`!_;P7n%0CS9ActiHBTO7)m^6Ny28JfzS9!fTI1czvG>c#SemK}>q8*l zRTRW-zE3~M|D)2)O^8cxKtlLe@YBYh20N!eI%ge3bieaQHg5+$AF}#Pq}q!S>B#U^ZYC{F()!m^doG+#cSLybEpsDk}X%T@%sv-v8TU9{!l zIy_Io`enK-k5_mG5( zBU6?-exD%HS}`7pzpYzyQ)cs&xF_2;>QBJ3-S;$^J1N$GR{P;#3<_R=SE|Wy~tJSJTtQw|jX%LLbE?^1mlKl(GFsbc{l# z&QAy)ycfzg>NR&=6PfirxCUC9_SND5y_SiT(BPj$MxR`86l$UfFS9QFExl4A^D9ra zgGSA|Rk9BaJ>vPx=;VWJpi>UdQp{F8nSz{*knR68R6WZx-C|S`Ja! zQ^T`o6V?~wQ?nViTNmK$u#^bR70emCp)efKYo2Da@*pWVU2il-JUZs}uPP2ti|cnU z-Lni3$d?p*^394m=pBb1Vv4Y#1nI&+$sw-&kdFC%j*PKE!k5@IGK;8)N{9J7$l zFFUi3mLtajVwqYm)RV@ya2KVtyS?%V7wZH{y^mfX=B~++5_~$#ltNz$O`%+?oZE97 zCu0@Tkr+t-5nlP{eQ<50<*J4DCtj1h5!i{p8Gj0`-zx8?L2f1ToSAJMPe+*1@fos) zK76OodfK#tExekjtmnt8%-wl|IX6qI^j{~qs)mcC41{Kk^{5Z*-nEGAusbv(H!o6A z(H~yI1jL~Hcdp3e1z3HSQ8>x79keb!uXLthv#oy3lZ}g$WfRI5Y?C{3YZW)o>7}+5 zEfOd2k-7qj3RtL=ocei4pgynm=l#!7U z6UywczR&vS`QDf5F`2ESm8@=1Kph?cM3r2>G@}adal{0OXRyp&BRTAdr4C^S!@xF( zjO4Pc`~cT7m5C?!FM#o4=f%M%Bf)Fv#aK&Nd)_zxWdLY}9fN^dK1IQP)m_!>!PvT9 zd&hwxO-!cY*XO>gS8X8ngV4wP`(dGhfTqUQJ|gQ_uaoT z6bfiI6fVqlefHAkIzVn0z&5|84ghn<@%*o2Rw~OiR?Bl#{!NLOeUp#>Wv{gf2d&V* zb~)ZGyl$+z9|=4h)Wx_;e>SrZ+8nkN)zJ`1TfnA8!Wauc4rHM)0;^`$))XsSNei9|2mzD&_!p11`btL%>xb*|7wFZYN}&A_3tWJ_W0>vThJa z-T-nCAVbZ<0P?__0ELr71|zhhHjH5lVCzR;2=!kLsfR~O)7<`p{FbiAsmKZz9_Z$k z0d%q5|LC6!VnlP^Wpo34AthyHSS}GZ3NSvMlu}p47Pw&LXn<+}NXxKff0%`q8M^e_ z>^jB(`yNQL!W2p0-Z)^mNH}&uEJQe7d;iSR7Vdf*{VIqqO5~FCvmMmo^LH z{^d?~ZzdgDq~s}C5Pp0sG<>YlQJd<}8|Q`lcL~nM1`_w;zgt+WJ%ONw=J3OM1P*t+ zyyy@~@cV$YYu=4c!|cwt*ZHC|VmBit>i*4}EEy%IoELdK3rEJj6uP)6osN$(^NaX# zT_IDs-YE^4kop{+p{5m3GI%x-&VlVz&gX{wJmGdAB6DSWhp2@;-p1@Jj$X<&dT%Eh8QYh8py1 z$dA65R=-OXYeaD>%5$%XVhBzi+>E<^k-poN=9036GYZNIcOx6IlhdCRG_8K6RVXxkjWpQ<0HN1T1oe& zAc%@Tnw6wN59R!QqU-mvY?ZXN&L!nH9DH9@-yDbK%C)_T={YKM3*#d`N_kT6tK7#D z!;weW7vvbTzRdc#nbE3(&Mo@_`X;gNn-X&WKcPe2gT_Tuh}!64x#A5G?@V-TCgE^` z(YMSM#_nQTEA3J;`rqmgHxpJ&HHg$g>>Z`jp z=&@Iyf7Mg*^uugs0>>y}f*qrV4l#j>R}Do` z&B_Uj52NC@g93X;xdZD=$LV~>XfIkW9@$|`wC`}4e~Lx^Bez*eV`KEu$k25`=?acw z(Ffl>F5#))r{s8iEMM^IiEH2Aj6S(fn@(_1;?TT@My5f04}ChsFmCa(D%`DEp> z?H~K@EA5GV=H{5at7<>FuYIZJoWCk2TO`%}OTsXTwd6uH$<0Nn-vzc6& zUBetG(ZVP-Y7=@5w)N0o2kW73#p9|U$8Ua|Rs!o{(bFamDQ34%ki%zOB@KUBwrKh| zxMf0k_U2+tLG4EOA5r1t4_`%n%?Lc?^!@aH`r7}9x;EP~_ir#pen3%s$>-FUbuvaWb};YpF8_-w%uJy9t?o?!NmR3GCX{S$%~>K~>8mxp|9W(bv0xUZ}$ zTRa2ZTr;JRCRc)-|_u< z75Swo*86I1pO~$9PjX*>^;$idv48elcBgl@#8Itp3=td87>vM8_`0@K>tfF!)YuSt z)_(PS{Q=rTZc?G1Odcnb21CY3WZ%VZ)xR`$f(rJUsas`_>no2{AlVNN)lpN{Q@ka1 zr;jiAC5Y{7(U&6M(W;=$n5i!Jm~r;xT$WL83ysG`8zW@ZC>3pShRNrCUPSS6rkxwS z!_ykdI;^_EedIfd=LeE!@Y6yGp_0XISY`@m+WqtP`N*0;&u6qYyR})*%3GDdg4a(cd9Z zZ^#rE`Pmy@5QHYx;-?`dN-Bdg!JPTGAh^Ny;J~r2-xZ{d0H~IrRiI}UdW`K)Vlxdr z6<&TVP8Zg<3>*jOsm6Zde&^fI_%DeNOq)itNVV)auqHylBTTPgxJk<9)c&%pwA6V* z{-UX>DF}Mvlu@0-@$fn1oNp5q1(R z$>E|PC#ORi@X?@eQo;)%s2XOcoUb4;4x8+D`9YbfpC9Wr$Jq|x;b0IsVk1sGz?f#sSM^)#RgM&xAH zYrYgTPH^;qoUo(~z#}GFPit%5Ry3r!^M)G;Li*rn!7Z?Cbb)Oa&K&FfUVC)TfSqwd z5jWg^M7z!d;N5^E`rhD`kfqKhaxqdhM>?D+vLy`31R2T$!m6hC&DrwM7??3Cro_In zltu{K*g<_g=-SMh$9^UbuTV$&g8XeQexFg8-S+*XX7U0WtXCRJ0Z?VbuaHMbwe69G*ByGfOwmqZS;nmbuhh5%*^~8X&khohNMJ5_X8TO$2z*v=;K;}Av-cSkH2 zEEj1L9gqMBahE@S1Woh#OB5uMI&l+p0O5)K!Nzu&V|~F^B>B7F41syyO$o76fDmtx zBmy@JQa~Wsu`Ud3N$1uU@9`WMI_xUogYEFt3FRot4^w@7E%}7oC^IC}L*CMbeqf`e zT%)03xov_ZZAU5CrjMgq!tZp+bBJ9jyqqAdHGJWsz6EcS_G=05034pSLW2j{X@VL8 zp^#c}RTq{!UXyoS-{@o9vJ@D|V>Ksr{7M+3 zKW04i$ETRc4IBQQKl{tl;@NKI@v77#`Y*{1_w|j((+SI^x-VY$EB4Y4l{u3YqHmy; z`$1*4$6+e3(s06Tnk4#9K|(Ff!*=CGu0C~%id31cJmB9Hrg9R;f4j|1)L=gv#RyJRu}niE{0wm1S*ZVkoE-$b!9{x_u zn3k)+dB^p6>&o9$T9IDHx<-Z>NhTvF3$wjA;l8aQQGqQEithK!ZaQX zWeb|GvKUpQ?>QN!ZL>2lXdv`1+mL9zyjDCtn6Ib!gd+1xSXF?fQ|yuQXdthTnoz*S zn_3e_!{rI;!D=d`4X-+o3mAvcS109CpS2~E*YOrZ1|-s75ZR|vU0oA2j#YaZmer zr&VSthnlI+L0|OQb5ylvTzc0mU&$uuYt|oIl%vl0U+P|3C5j%EUq5fC`*E48-EA?o zOeR6-<3#j0DKWxk%vys2Z57F4iBwVPt95gx-y^Byqj?EZpzgl*3*VcYUoNMb&GlVC zcJaQfb$Lb*(ZBa5F=Ap`x}`nzvZtpX-e4ul3`ujVWnYs#`8`CY4Ow`s&{1q|nmxUp zGvjvRMb=I?O&H|#Nkp2W+I77n`zHxCJ}THqP`)}zwcvN&#mv;Ji}z8~RAPiVl~$WY zgHw@3+^0Q(tVgkNgc&VGlHor@!s+9PTO4pjvAI-{Su+VJ&i4HL!#>Y4Hd!1YbS!=4 zEJu*?$FB-}T*Nm`%|+#_F6Mrqu(_b6VSA^SQy z#FwR?O7fteqUpHp!tPUU<-?u)y}xN^_Q!^E2ReK|bc>_S^Cf~eHki{hly!6mj8jn7 zx8!?;vSV11Ot`Ba>tD0*CW07#4l?C70Y4AQg}eMH<{Y9ZUxaF`Bz0y6FCIqXDZipp zZ%V}H$>vklL?|IRbqUj!7j@Z|U?8)SVlO8U$?vGA7ph?4xWG3%3~hREw0{8;_G^w;tg7FO21qrDDU)zuqY z$8OAed>RLmU&(MPzWY$3{WIra-MOM;Tz~8h$}$Y@r%?I(p!{!5ai|*;8-1SDYq{M< zB7`kmgPOD(=SRcTn9@B(MZFW^_Sos7%P`}_s;GbVCwpOBA-D~c(P60=(kt(JliztO zqM(QwA_`-1JTkO+bFMkmBjX3aMdy9mIKAPLW-HF%ME?eokO9-^pBq0+ETcY<{>uLB zm-c8LRv3jXyDPq{2m{kVLW*s`GEHwI+6Qm zKzvIU`VB$o4Kq0~#bWD*Vd{z%^T7xVJSM$nLa+3&{#gKifU2D#RmKXH=iUGfY@mo@ ze}AihDn<;Z>PGiv-@39R!Kfg2{EKtw07kQQPuR4F35|*+t z5w0M)7o?TlE82szPLsB#>6Y<<%{2Z@PKP!y_eRm4d3Gm-fN4Qfn&x$RrZl28zAuW? zd$dl4)z0||c_PtaxaPCyflp==hP5VDcx+=IBu49c$cSukE_NN!vr|#UyYEh&D9B&H zwcVDsIb8{;`Cc;p+9mx{$6xkFIvv_dV{V7=EqsB8v=gao-)=O%#+ZGeel~F^UWa_! z<9zGW?-Ew-uTs7(gBC`^tITny|MZ!0P<&64UtB=MI1;|mtWL_1x-?~2j5 zChMJ5&BS5y=I7hHJXK}iLKZ^e|D>{C)cez8ugfL0Sm3xKDMm8t!CPuRuhkLl_erJj znSj-65j*iwOs9YatzZ6dw&){*ZOfMR$Ej=)Bzcu7X`g~Lc?j*52*obP-d-Crp*-I^ zXK5u7lGvGh;YM0|H(mH9MwFHFl{z2d-CCBRJpC0@;xuW($W_|H=yxf<75UARL`l6n z%xU~k>4**iJZFBYJaR5sF@y2&Wu=YbDOP(5TSB&yQmxeT!4L&)6s}HeePCPCgx~1y zfy!EyX;$Y0!r5IU(hAGYxR3bc}~pqiF&jB4O7$|Xz#O>*<9kU;uho3C`$I| zA1!926wBo4!WXx4U8bcX*ygcMF{Jpo1>qr1tij6V7AzS)l@Xxvb6}eIi%aJNo+RsyVUU|Nh~yl*+VqbxFKV>dw^% zEsac4QjzmcpLkyZ2RTLb&ip?Mnc8zyeZ4)3qUR^3cvS{+enbV0=-NN;P|8898^soL z&dfGi?QwSpZX50=o3Vs%3~`UY^Csz%5fvcsx}^M*PJUUl^v{Pq!uCpxx$ZpFs|_yG zAN%6WU6y}Gn%IYE`#Yl(I~DjI&r=tXlb>2oIxzWU*1DV1y+nX5$BwU$ElnZz&%zN^ z&P;7b9MUw2I$t%>XcimG802cPE8VxNyx6Ow3)6T(Pq3Oy26&Go3weOohrFXgjuBk>%5)+6pcR>#nnEOW!K6!C2dBM55BhL7+^Jg%LGv3K8JP{a z5qP6mFT526F6rS9fF|%}Y>1MH*Ut-B;Rz5Y?+lygx?#zKR0PRE;6%RKzEZF}*qT$N zxd}GKb~pf#2@C7g!g4U+?gpD`>|zCVO^~-WVrb##m(|JwLzjUv#rcQ( z#T*cPgN7R0N(w3tcRpw|gSC&HR7vofIqMw_=QpG9Y8c|IKLraNw%(T~VL>PO2gdK; z(aH`i=&$#h7HL5;KUBkF2`?zoSODu{ zh~CS|28_NcoGU?}_R}bs0#%41gb~HC(6f<@s#9GfWeP@Kd8I+h$1YEZ4&*<8H8+Q> z_|(`bjM27idZR)%$BnA?&*5RpA0)!Wa{<2rP#e}>2~r~LmLE&-jjwUL36Yh&&dTZr zat1U~*ibegbFjkt|NM$CnuqNSv1P)T&xXA6U>PLC=9B$d8+QiXjg^OMaGM%7=gQZY zS(gU%Pys2kZz8|DK@M4y_(Pq#b7Tler1t;9t6WZn^LUCQQBj3 z9=dSt`hg0Aj+44a-Ul-tM@M=Zo9EaE6}ZmQ(ks}JY=X9&0?kc09f-wC$;jvg42LcB zfJ+Jqg7Cb9PazwWlK+V%;YNz6?E=k)y|NP%`nkhRFQ6_3_6*oB6j0)0YsO(bowD-* zG+sbBK_?qF)DO&tUINabiNnG-&z;VT*f>0FVH$L30Gp=p5OyuVkimn^H2TTpy^=;a z9312#V%?(H;WIq7ppnQj1*AuR55m^k>{4ky9l)CvQJZ4$Wre+t@YDa{gUIR3+!^z% z*9voFRFv7{$HA#698)i^RHbw(C#kf--HASX-r*llx%i8A>s)KuE9hCPI5fbF#TD^@r5nnsP|!bhB( z(GZ)EkTF7wUQ)k^Uh;1V{xOe_4$M7F32;hDsJgFX*m{S@C^M10vN5cd1C7@=&~9#; zdh&pipdwt7@<&5;M8GI@Y@d&$T_zq6_owWLdu8i8hivfT>b@>Wmuuw8!< zrk0rTkRLCFB+e&vent98#V{@AaTiWd1ww-iRm^@b{YhWosIylW0ykg|qachF4qM~3 z;&fIZ_`6WPW*aX4G{T6Tdda+Vu_7$Bo60mm*?^Qf!%pC@%IF=rbvo&T^Pn?E&kSSF zkDu7)aeM6~ZxTE6$XYSq3K7#_huMe?WPA@)g=)7~aT)WePu#Keh5^d?}!FPMkT=IS{aFmiuroE4w16>=bs6@Pg z8MMFCmA8r-W@Xe`6EgbQfp>nl)!ZD5(KoqD zX49`iTSQ5_zFdCArLj{}S|i1cm`{y8+wNa*&OD?V);^1u@0MU82>THbfYMQM=a1f@ zUt}1n974!D&WQaQ& zYFEIHs!=;&vErLgG=6DupPJ1m|6eCwbJfwe@S0Q>jZYhf(pKZXVTH#d#jmZn)t=F< zRxsHicXIa1)JYx`(=}MDeI@&@c`m)7Qju9Z9Mu~5MeY|l!vp$^m(SYqnLi0wUH=3r*}Jgew{!2`O}L-f5zVg#=gR85`S#v0tlxT9^WTr4iPk4~ zRn~|R9A866WocZfEdEf@(pn2&lO`J$(|ySzYY4ke39VtNZ67vj#KpqPwJu(i$?pYo z^!S&yv;AMax>xdkYaR@DkQ(*?-^%J%?F(O={{DW+C+YJGf%jy5%EJSF$(XH7ZH_oQ z5~al%Ym7d+XW}0UyH5lz8+$g}7hM?k%crqAAny_4)#X$3OeK$IOtY!h9@z^0rAkHR z&#y{3d|nW{txTXuh}q3f%y`{Ge_sF9RAWxqg3thg!y(O@m?^GlJ{s^_{5FY_JfBU@ z!edz@{aVa-BNpEq9mRI$_N6$J8|JnH-Rr;btGbUR`B-wsi`YXlgcM${kVg`YHFwlm zH=%RtWJ{A#VjdA3!F8&WRmybflJ7q9Y8Da}Roc zUTu(H_;HBp?j~#JdV_0y#mDopjC~ZvKyYTFq4d`=xJ_0@4s7L?W&?%sO$5h?#8@50 zHiRsW{0IIYw;v8M?R-=}7dvW?fKi&!4VrH|6j#bzeE=ZBH}{C4t9~_nfr2W#d`v73 zhn*^t?}_uCID~_OxW*qHiZRpLlW}BAUj&QY{rmS{tTj*`uGi0<31SCmP^gZy$%i@K z^hRdCppuqx-^t3%4&DUZ(pl0TBwY5CfXH_{fJ6vO}STUPUeoJD$KUCS{>u2yoJG0Bna{GRL%U zF!ObTgq=L?7Mt)}SKI_jPI?4+mWEeME@W|hJ>C4@fHVT4d++XPrCo-l9BYfi#BZH2 z6^>spFM64a0#!B^H-c#akm}Bg-@g^Cd>rg=0MfB>uH*%t8&g-Yw9krgl?Fd{F@*K5 zX$!pjhXiHD^&y}pgCoYGVXS}|$e84hByxNIB?DuZacqXv$dEa1&{?qsDUb-#|}_miVdkLC!#O%OcbcUHhXSkF)(ygoc!iox-bsN{`uhQ}^&jhBZ99l~BE z!5(Xzz2!w!xv2)Y2LjXfU4N{n`dqNw8RgQ_TKsT(lqio`HCa}9Zt^oeil{P#bIBDg zJf!L3ZlK!4MVOMfoo{R!-)7bz96gfq`%wqAm3?wCDkT<|k4`w%*{F`Kf(}D%{WK+P z|A1yh@GL|B?ss<@>4&}Sbb&Xiv=kp=93FL#i^+GFzHC*dV4-)Jt2>Y>M#r-l$4M44 zm!vVyiZ*F!;E5J$qmifpQrsKzvAt~6mT|q7Xe9kw(1!(Ae_W}I;T$CA2F6&=( zi0r-+-tN{P>0f`Oe*KmD3Po4NWeRCGm{@oN2iUCtbEy1DAYzCL!2+1qoHtFY6f>s#O zkY2MbI~>p@LlA@ig24Y`%Yml%ZX>CWPH32j4VVITHWqK40Gf?Q&hUeHp(v7c+O5v zevPtNPVuV}-5<)E%Z_i3b>2EQsrm-#QpDMRTy|vDrJ0K2*q2qz=TLShRbn5GjDAfO z$&q(Q{@cEm zr|CqOFUhExrDoW9>K@n1GgX}9?s&&Pv!`zU#4^?$h1y{U_M9-}AIriJ-j?E}$UQnF9 zplB=)HF^K^Soe5#D|b3iPU7G6#vf7(uL=0pR+@7-{2l7+(5=BAYCnRBynV-2MfP#kN9<4!09a>&jxZSRcVnA~E8Y`X)`2>qCeo!O2(P2)q%sXVKX?!bZZY}TD z@#7maCRyXX(ldfmvL}t>H;bk}WJw(BvKsRBzp=S0-yy+wZ(m^Sj#%wp>yhj3`-Fz0 zE=K5X{x^MbziN2J^4}dR)tHr6N%Xt)3|rt2{Ies|=-O>j^sgPuowDx@;%C&dWhlkguJ$>GX-@n7TT@lNH3BXX{Ds-v(DlQ&>l`=V>D>FN{ zA#prCeW3pc@0eNscMHaFy~nuS@-h{%VrY*gX65~(F4tk>&h-JBf6eEAnjs`2+Px@7 z>w$lpo^3I^FTN07&rg}Av$;n%H=naynQ6@%y!YMD@xr9<{HxC#CYe6u4-d4rcOJ%+ zH%A8A@nHnwo@lzi|I?yZ-5FK zyjZ|ZK!ZS#Sr|6Es|$uHKu^FZ4yZb88o8YW^fN+;fCx-%fU~mG?~qvXVu4qITt^It z(wkm{hH{T6Sd3Z`vO5W4Awmnnj;tQ`{g+w~od=*FQhN7Q@q>QQiWk%fll)cQwa6sW#m9%~}g?x!a+2Ux4=dkBjKg zKbL4D!gBdq15}>9saAnwsxw+H_d>G4iUh)#B`GfVLYF#_5sf>-jA%O;vMV1lVUV$r zyDA6mTB1sJRz$TfaCo@8*V?K3p<)%J z?!Eh}^X}{RMZcYkHsTD2tJ;1q!EkDo>e@={z?iR7gM8cf(}l@uv-9GkAMVuP{$Yrva*_WXJ z2OTyVe`G5yxD=RAfm>KB9OTSmgM%Tw;NeGyh0l4a0~%FeL4y#iZ?`l&fLMgQ4hVhKhZ0xqtv;g)umV z$0vL{8L%~wryx=a-%dczztVHzlO5i3Iy-(w@OuUX_rOd6yah37Cph@9bsNJg^eLX8 zorh#H_Z>j8Ao))l0 zZ59GsgV1mvv7F$7T0VM{X|o>p&GC|jdFr}*JrSB- zq~UpHC@94=-(i7t(_Y4wDWv=ZM+mt1RI?B7dLBp_!Rmochz4CB8w#t0+&aK=-k>}? zIoN`vJer73-Vi;q0F1(yVOquJ!g$=8j(&C}D>uA7$_&!4_#XVXilRxCO7)8_hG2S8 z{JEXy!?S5u4O}d(&9l5ajK#JF>wlW08l+a^1QResZ3+gg7sh?F@?o%YI@FB(?eQBf{QKI+*#lSHM+fR{ZoAA7HZ?;_*yDpH;gpWR2T zm@OzEF%HK~KQ^@7?lR4&!eyKSWQwCIBfnl7;;NAqd5-EAw(AWy1#am*<-5X0)MJx7 zX@KW!SAjYi@T)0i*|my-M5wT63bLeb6%D2t2@__jwTg%SRf0lPB} z1wS0yRhA#N#BUj>HmV|c7#Bx}O)I1V*Df{_*s$_cahDiqPuS8-To;&sbk@(`a8?uQ zc)oiMRoio_jZM*8e&-*zXKti+jp||EJ(#ZXEokfuIru79X6%LUasNVe^hfsU0Gg1} zTf~ne!`k+>*=dk6DPRC-q@cfGfByMLOJ%ObgL*wMHZI#n>M}Xc7@kploS}|dL9pJI zlvjwD=so(uL-tFJm$cE)_A+BUj%a}V+cwM>8ck+&N;i3ItSG(sB;9XgLbtc9b$u<& z8gW7Dzd95=_PIk1jg0TQ?g;W`S8iM^iw^KEmTeU-sXL*z?zF&Ni=mTG)vB6fzH`(( z7JR6Yas0wu>YR)09Yyw%b3luW@Df67j6csU2;Y|fxMiQ80Ea^Mb6>vnwfXI&wgA$b zibb{8uW^P%cMmC_bzbP&$RGT!^n}aS2qk?@aaU=DbSHv{QD7=0N@6;%%DAF2{(?X) z+e_gXnR6G7m2ynQdO;`s&NBx;tsefE>CN*Wsl9S|o8ufuLUIX+NBl=TBgJ_E@$|V_ zGAdGp)!uK_=AOT?%hSuXn-cy_R6p3gdc8z7mP$vJgo_t>pYXH0p~FD+l!ZpWjFf_p|Evvva9%0(9N=z~o zt0#XG6GC`n$s#wYdtDLdaT%tp=_ZX1G5=*UJ>Ykv2Yflh&^F&K+z{VR#CLGMs^r^C6@i`Re0U&T3sVBIn~hoJTvu{cV^JHmn(9JD@NgaJNqX` zWAxh9kMWB<^j>J6+=Y|(efy(4tGi2UObFP$pFdy5gc~AnOt)?R6&ad3LE%~C1?(<) z|Jv8omu??F+UOYb+esKOUp%AC;%zV2eDx-D61+XGqO;$xQ{{>kba z_AlaH2eN+m-uU^ay_Zl^tqxXrf`mAQ2qre=$y+DIY@3b;uXTIw9WWf61}$}lNPnN4 zT<`@!dd8faJs==9DpLd(fVMmLo(EgEIa_QgnN1Dd%Hv5(v^Ia4OJp;(^E>laq&2KQ zR=I+s<2so$D^v)Lr%?b>*~!O_67W7d{o47a;ZDk3 zDToK4YPo_t6!q5P(=~rnAnT|^m4_T%;_rA4i;ro5bR1Sex)7zvM-Y0NaSlE?U-U|5D7kJ*&cpQ;V#3YUHnf|VYqEj%UAcz<5|Qx5tpb`G&rQaq6d z_wPf4DJxrY|A$lC($t*DK21AE1$4H_dolfMb)Wivwb#|v#jUI5?NcEL66;Qqlaob& z>4Y#1D@do1>T2aCNN(_K7=|7ScPVfdz%P{X7k=Al?>0(XO)ch1ZJlzw z@*rMKL8M$?S3>U`p+&;TzmMN(3Cqck8xj@sN@ZPF)2zK;y@w37=0<+VzIfs;yDasw-dj}L z9y>Szg#z})#ksOM@NDCVHEt4o&mnD5QdAH@>3$Ho=3Y@46-;YqN`F6JnC&VtPBD>q zlFNjxStPfmotNH6)5_7hw~}8~%072F_tl$BB75l_uCjpf-Vrxs>*jCh8JepHVF#S+sTDIfBDe6 zJ^YKrdHK!p6=7$|StP;Crxotw{IF1T$I@e|%Xt{fJlD182Os2?nq+-`*Qpo1Rc73x zs1kcn7+k7Ig6DukiWvzQ;7i>46?2Dy60b^``0niiJ%`mLLv@FphSux6y7wQ}O%ay_ zRk2@BU=v}d$&c01G0pxM_9vQgHeSj3Ig2Gt=(2dE0VT((!polM)jUNLXp1N-TcM@N z>zJVFzV17L@AmWX*np-gwTxWJk3|^Fy;=fb>UJ^Nr8sTH4Q1xE9tK=_QM!1thgTKRI0L1Zrv|wp&j;%Imx$O@^z| zU&h~(U5^OEUk&q|LTBypliXTO*pH##%TuFw*Bw@B;u99p?KwB(ID!hV z6LPC|N2)uoKdgA7IHQE`>U{Q^{CSc1WXNiEtxcXC#c5+h)3w`kLDc3M!9D}iaH}|i zo3ct#=GY0ZPB>J}mdPOvT~X2`n`l5h?CHV zzv2TvBXz2U^aB(p3s<^}FP2hjU(}XaN@q&AGT5kBG(`WY#rMh8j2AsghcTCk2rb{L zEQV$#{`xMI=QorETX%3?A%qLupf(UqAmWD*sk|WK3}n~(=4M6Z$FWuUFv)x(e^J<< z!*9sw5+kPM)B$jkl!7%>fuv`8IC6k0Zzw(_tz+f8nk?>0P#!ZJ4-KmLukU1Ys4x&ILDT z8zVq%f+fw&aw}H$yxb=U6)-T=f?*%vf(lM4(0m1Q(!R##DuFBrbm8WN+c1d&@p0<) zWmtbe*9J@iL>2)X0tA82jp03PlOQA;@x7$N;NVK2_b97ZKp`e*REvSG%xqrb_g}XT zAOb!G#{q;tpmu`!DR!cXFoiCq=|F4<6T5rj)wnB5oy=7s15VT$pYi>QX_;c3AM}m>c?p8vY%xd7d7MBwGm63AY=8 z*1Ud31*~8VC8eeR*|{J+0>twma>ph!vBDH(AX>%lA=Xb;Z3qEdd#}h>>uPILOlxc< z(nbt<>Dor0ym%o;DHt<_i#TvLzmb-n&O}T|MEBGC{GTtPFh;lMD-c8T?_t~sh=2+5 zreOLD{E~n+{PACs6S$m^;@(^@@>m2S8$R|%5}&+l zKE4d9y(F^Sw}UHtz{mig(KnIEaZz`8BhVrF47w9RfA;6kGc5Xm;IMExa7+S)0*q^S zw&d`hesU}mWL5xZ%>8U5j7Uy-i;{E$#0ZcE0BKWb|NKpRd8uTKS_jR9jW~1yVcT1+ z<|A@ZA01}euzE^hwE$-k{L(cER|uDXA|4HOS^RN|*^uG>?H&v*f9Mo+e6MO~7?85J zvLb++20|&*nLpL=%D7-vw&-}XEVoW)GZp-4FW-`7z1`M>;K|KN4_n*_Kt#>pw1FVJ>AI2A#61}^I2Oat<9l5@Vutp<_bMopjiQ}^97mz#-ZazUdk($Dfh~D24W||H-&x|oDIHu8_DU4RJPTj z5f`J;v>I4lbeb*uv#TKy(jhF#yjYokG_m1sF8N$0{a~^7Y+SH&PQYVQJk#Xp^3DG1 zkO}t(96?VUeWncar$%HuFnFqQf^5v1EDaUCaO;@zgJC6;iIJve(mKMg`M4V^tSUiJ za8A(HUr{B_P<{+h5Dm>yO9n6diiGksI-OUsX2xb?Vqs8rwA2v|*E9W^q~zl`l+O^=QnG2l2J z5!!n3@L}F>3np2kyAm_e%NCuP+Y);AzL+-UaC&abPRYbQvwFZYhbyYlmYj?^Y*VIzJh5c!FnDyv+VNG`7h#s(l*i&0sGpw zXk$L!+rm`92YU`-)N=ktAj0D~`c4paC$%arF=l)zAC=s?zxnk(Z^J^`iPJRfqY0^a z`k+9L1(~=XW~2Na(f71`_HBvk#`@l}c(AGnRQIlH;dmn{agUA)SK0LbJe~6tkGt)H6wJmW zH!Zv~CCq2uk0ia3xf5c*UmP$fnMm`DlP5QrwO&`mm#>CTD5+VHi|t41J%Lx}d+Chg zM{GS@;RIP8{0&>=u~&n4w8wU32%{6?1{EF|FaD+*mhA6Hp=ZX8orryM!8&)NN=IBm zQ||kzszB`bH1_K@*BISqr6YfGH+8}VDFLBYa1Kf<#W>m@jN zL+2&~GqgvTuRfJLbM|lWrd7BW{&2L)%!s`-CvQuLy_>RyUvRF1UkMe4mm7y+g{wok zkEw^5loq!{5?S+oYpUYNo!irrO_EDIQA%TASUXYqrj91RY@y^u)nOQWK6wl0LYQ$> z*drEFp`a#*)%cOS> zI4#@0-eFf4@a)R3S1qQd-gYv?nghw@E^C+%9`L?1`Ush>YYel`qg9BHhNNg1@q`6w zh<`rC?}44s@;U)`5}^9v71pKg9qDsNhH&k1gtpZsJ9Ofe^OCNoW9&O5^l(yXfYeejH1bYLI@~w7S3tJ84h@U<7O@6Su2l zcS?EN8Rh->v(tPF3QHT9oQa^t^?omgZ=>cA>+ z9;mC2SuqR@49v>g3hzK};W~lJiCPrh0=YL&Uje4C2<9C`Gu(s0S)TJyMLJ?~x-a6! zl{Hl2_AN(P-N9zlA`rVGtKRHVImua1)&N|}=(UhMVJiw;XW;5aV?<|NVV(+UMnD|D z4oci%RP5m~%1zyeVbvc%s@I_+8jzJ}U?>cwkba;+D9hnI%#2D~$xnIQ^6b3*8N?u< zK@+{PYlVizc+T0D76paNX~BWMK7o_Hksn-JV}?SDlzz!6cj_e8TcLLnxd2fO`qw*9 z-GjD2OQq%L#K27qZqKb_1qYg2LSWr~@BwG`xB_mvkn1-E{~kc3>H_}B_#fsnfcnDU z8HO-Z=Yl~9AP@8E-~N<7GlRx?gLQOB&+41&M$o#RdK3s9FbEPgsLRO`h_7o&fS`m< z9{$&22-Df?+S!X=vriDbUHAgRul?PZhYzHZt<4wTNnk4<$Ged#@DnDkK0gUFIl%!Z zdWNF9KPXXPfbc(T^YIP-Pd6NYJfKFC@v2U1YAj$W6+NQ*#voubYBF!p1u|q`(zo6d!{|peaWTS<`94eZ@#~L_R%%q~QX(SZ zuoV2SLZC|atSToi9~8?p&G1zYM`}m&)SD?iC%~tDQ9I*Ji0(bg(Lwh;stEcNjKG=o zv}RJ<_{zZWzyrg2k(d!HB>mXhKYR{osb=&j!Y33X;qSf6@@j;T0;`l2NfxfcLv8gl zuX;+s8?}od

    TWBx@NA4LPLIY|j>AVw#h;T~uP@k8#oOGKwhBa&$`TdSqqX`Q_^M z9TxtWP_DPwq$QS?a?u!11jc*EYc=!n5W#~IymirX$YQAiz+g3*9;loRL$%%2hTHa! zEmk9{VzZhY$`NY{V6ab|zp9zp3wVr${`;En8E%W+IS zo7&T&cvQSzI2;z0f~)nu-3)e@cm>=eZV#BQ?3@m1P=nkCvw?T*UE) z;QfSqnRM8DU+ZGnc=TDUR)h$7S$$($3?~~Gp6^~D1sjQH2PXY!h@P$a7@SS{T7Th@ z;tMe<2(0hIDe0AoH7Y>1_7~kGY9d!AG~LOL4EV!WxYx=M?zOl4j|w(v!8`6b%s4sI zjeOj6x2DSlZn5tkTP66Do?=TM*iO0%5)Wrqb< z%t3GOZOwo`ezSt7!(LY3w$8A^qJdv^Wa2p$k>&hp>$!r2i_~x;!<6FU(aQl1{&(^Q z>s_vPwTMepOq z=b6`Q1p_JZLhzaymH6>cxJ=L;%SbI&Nj6@@!h~xUXo^bpykL~evIHG{Y-dWFDu{sR z<=Yoix9)z=z24<2ba3+fms!DOR>xt;w@bS(N0Vi;`3)JwKQQ>0RL=~sOr)_AF6`L| z_#X05lH4XRqb@IXV#T`AMCQ-bR__`)z?_kiRqg9%sB&nX)L&XVAU))(r@)A1!=Q_q zRuY&Mqw_Ib--yfHw*Hm5KWX0xiedI~>qUd4m;_#YpE~DtrUZ)Abl$led>`kAli2ib zz4O<=;|B4#?>c)4Us}*xt-L?^D_UmeFAzI&M0>dt za7Hr85lGa#p+rvO^SFJW^@zuk#PanFFq5TTn_&HLCg4dPmG5Cq9 z9t)%78050=CX(KuqCM$;_|eSeDdvX{o_ljM5=Y09c({mnJlQWs`*Y&5>o3}r+>i1O z7DZfU#ZSI696mN5p9__eeXqGMZZ&=WMV_V2S83BiF1n{vpD|4rFaeA&eh7*57rqfj z?!NTBU!C0=LT+GL^<47@dE@1}RKY6Fn?9Mw<9~k9E4J9T5U8ZUA_N%y5hR#+o1zn^ ztc~dh$^+-&|KAG`KTdxTD;eL&Kbz%$&VKECil^2Z=vRRIfpD3PFk`43Sh}EukY5*W zQU-T8gO?UT_` zpko@{KE^fw#7lss%2WaaQ5PB&RynDB!*mdpFel^%E_Zxo4ml81}Xu(kqam&|7hW2pMV^+d<#$N z2dCI)B#2~;r*C~_h)Zup++kI2Fyc*d8r9%J2jb94$gn^scLVcpA!MV-t~z*JlV zB8q&C;qtB>c+Wvrf)JeVH_&Z})YjMq|H9#^HoOUrc_Fevu=JpsdX8fR>cCglNxsbPWgeV0$*r$RqfOr z&4s)~upCCAzW$)ROYZz_(@g?7DlH?k;t%CjQSixt)?;<(qG*AMJEuM`9ksj$K~-R* zV4r;HMyvtisF||{ zgve+xSnyfLKx^er0;RI$;w|-jq`=GZqsTw;`t(sZT|sVbwlpcwNpWNr5mWz2khshftQNO4UBOG|mI^F9)YK3`Rps8kR>lHSgZor;j)}L}+0yutf%A)!3Vw=lg z_5$rG1b!MokHAa7nFIQyRW$&3k`b{d(4@zKU^f|>t&bR=okyUBNUb~`E8VflaFrXDp)yT z8w!e@V9(mYfNZQweXqp=e8edsE6iISk{FYI$^J44sJ)&$o8H=vu}#O(V(jV1t*(!K ztKARV^hoz^Vpq6R@1~MdYFeR~P%X8lf($5Zo&!WfmYg+dyH}x^!e@Mtp91ZS=JXbB z_le&Xn_cRpI-Hv6T+okZ8I;&#GvYTu3X(B?!ZQ@03Gp;i5s>5@CfW;?Hz4-2`zy1P z`t>fUzS3%xQbyaTo4@%vW;$;CoXCu3pBwl0$ zI%Z~E_Z=ILvD}w7;v6|_9dPp&rWRXAXh} zcC0Vw`wa723>TFC$KT$z@0>quNX=Y#%An>C#-D#P@M>{k;b73v%;%V7gNch=DknQM zI8;!AE*}3oF7a^qy&x>gm)H3#<~rD%{|UXu;$374>ZaF!%X=nXdgImUOJ{Pr}C!ceUx(f3&JNSiIq* zdXG!CPx`t8VYaMhc;#-MaNZLxAqI0!q3E;2aQVd{l$y| z<|7%g5~AvfvhfRhtk1Qc(kFZAPFGYro$We>U*<35-8fwt{I7sA?lrrlJ8hVO(?j;Fdu6=oqST4voyMn;sp9T};ShT$L+ z3Wp@PN$h4woLn0Q*0t6_#C4V@l$c7CyU&^~_r63-^=VPuDl&Q#HcCmMD8Lu7v}o}6 zi|+YHHr;Ol9=fFC2USVOSshB3<>t;vh+LRaxA2hCX4o)Aj<&J7XpQd-Fvb}AuAjFI z7@C|)kxn3bH3G0B@f4o^xc0>8i&68iI?ZGDrkNv>ZND!O9mKItqsTd*C5yX7qA%*a z-D%*d74C&C22~-%vijc_Ri?xw3A5daXl7ON4cqp+r82+yvO+~6oMQX&3k4|^_y<)F!xBd`!bHi)Jcz4Man3O6~Z}YAm2ykJC z9x+v$v5~2_5c+YF$Y@wbQIfLKc4se>R?|VZ6ue2qAYFkBd z(?#QJophMePUoHi8wFL`4BM7Z5R;q$VTVnBdU=m?fT&0+pNp9DY^>UjPN+!LN!OG6 zKFOJn)z`d|gYYKOBc7IG&mIhI9666}GU8RA{l$3o0%6yxs`LV36Tf5qdNqKxb*O0X zVy$nhx<)*h3c+@EnQ%ZhAa6OnV)FWVAut{Q5D76jAdbRTqY@I&qTPJ%PN)(Y#bG6>+4Y&; z$R}To?_TMSc?;n<(q9*iJGo;U&J83sC`5#t+r$iBFH62`=jR4J|g(R;|zxu0g$B z#0zr^giGO2?M}N60MHxFiT^WZ(g89M*uTLle@d(Fcu{Y98~zDqfBq&iM1(aR#ZF3K zB(!KRTiV;(|CYkELCnc$4qR=GTW-EurIxb=t6GD`Uw{38?*SGgbYC{yP``eaK0nR+ zCl0Uc1UwA58^Tna%tSRO0-0CzviF9`DFK3v`M9)prUh=Vs0OAWzIUAJp~en1hA0Jq zBDnkl*-FSJo)p82Sz|*RQ392hL}T8-DFNpi{E;HpcNfLV^)s0W3eT#pvc_LUC0gSKy$2vALS z$uh*s`!7XvJSzW`Gj8O}U)<=gSYmr7XddhaN%Z4b1V@h1uh(O`7-`qW!f$3huO z^t17EDO)*<#$MJY%gkP8ma5c`0~Sx_aV)T1 zv{+f#dP~3WQyd$O5!yx++&U3WLTAc>nQai*M*ZWO2QTQNa<@{0NdNwhoK+l z>g|8vst3u5b_+#EA-PACKeFV{88p2j73hra;Ii&z-!(M)oLc7Kwd6i!UdMhSF?yG! zeLJTmWaCAU@nos2&(1*s#w!&6mp(@!!W$-hn!lN^%QvNk#Bld>i{;Mig-?OUa|F?vA7Uj zTk32U^CKalSzJjmb0?vS7x^pp$xo1s*<~;OP^(5qliea!&g5##*QHg^AhMH)6si;hrt6uK{KF3Z~m+In9B=U!-n{VS3|ouf~Yq zVVd-Uf%luJrQ#9WM^jeA1MynhI-I00mJc*?)4w}EzGMnnmhD$^b;zgCBcJ?UPj9uV z?lu4Yb}!$Lp>6uP=C608{0G}+MiCbuub8YLxaLm@YTCie*BDy%^_V;wwx#JdVzbyAH-f2efIw9%UZ*cLSBM%dY8;+Uq?;)23m?@MB+R#bE) zvXh5#-?w91%7y*#a6Np5uZ4&GweGvP0f>|3h>5(C|3_Zff%Uud)i0~}cHJa2;g%Hc za8u7_X0TYaKq*MbP%^%&kz>i+_P;@4hB`!HOGl^dQ(qfEWTvHfy_xwd<@$Memk}fW zcAlcE5`o<5V0Rw!M~8uaAL z*d)bfFgHH6ca456GDPjL&|lkUGKzAH=3ih};f4_P@{V6}<^yKC6gU5CXDWHPomRKj z|KKkj;2eGi4I@MTwg(Q^H=(E04Y#pJXhxLltPi-V%uOLYElrjHE;cprIm!$(P zH@IJFpGc6L&47@y`u#u(=t2S-r1?=%_~4d8`-$Jqp8w~n@eDZj1l9wZi4OHTLbos~ zd>g?mgZB0ml!Bw|%f%5))sl;6e7wAsz5bIx6oV2nyO;eOcQ@EC97kHll>odG3Dpywy#`Ox)ukb(>?8M&p0 z21nHal?lw^;4sThM1#ZvArB^`XaU(npqfFsj!%BiHaljacV-9Ea^zkl=^A%aCkKWF zx(#SG(+6Gj=k@R6ID$F}P+b7ZCu`C>7VE-Ks(J9inRCGHYXXn%+sp2Sz+f(mrWt*k2PAc8MKV{rum+x~-9D6;_VzQ`RdVH$%-*2g9~+xoOurj%4%v z%^pv4bOw76`O&`f!#-qjn=>Z8|To1OmXAGt^U&!=qdd~c=(>4G^A)kH>m zof4^_q*H>e$+uWfJ+zbu!1OhSa51z&84zH!nlD}<|6uDA1|#4M%YklZQG+XY{xd-( zWvTta3q0EqQm(Y_l9!b$pZ_k=lfD*0d8nJW=xOR>YkuuxtMG-wjm;RIj9PpmtJL>& z%7SU8j8#w(5`>b;qYCK`t+s!1bZs~S-&w7nr{kgeZH)jSryw5b73P$*UUCB(RNB|H zL2TBMUM+SSF@?ZNR=YGp>JY~4_{BHcU)sq@|RVmJiOy>H&AkMAlnRy~?bE(!>i?MlGJ`paKxS{l4rD!u^2$HoiTW)+8 zG8J6rve}aVfUMTld5pbGLs(qN*rJxfLhFWDuly32z?T%7f`t#G=3OrA8 zO)OJrc=T1zC|nk@3}*!{91OESf)bX}ws>BTjJZ4({q`Chyt|)-$MuVDp0r}V#I`kl zZAbWESeK~FbJIT3fWMxnzlv-TBPB^9e1wM7Jry;d=gV=(uUv4TPn(rETw<8JZ@TSw z={l0E_h=;dYKg>zV^>dtMbU~;o4YoZjde3=#qKqaN<7`?E5;p_D5ZF3>R~BkTdKp2 z-}Kx!`clNE&Gzd)Oox96ZEve{sK;&*yoaCqj1iY$!>h7go5K0q919Zp^503ZZ9!p9 zx_Go@)a#hPNz>N`NVlZA|}$`E37s{MGN77hx-ZR;AULZrZroyx$ed zGM}2}2omuhp6DCV&P~%Tx|6v}dg_{-Cv3(Ygf~1!%`jkgq(C$FalmY)MU44ZGmxyd zXQx_ck`>C>nBqcK2`yb^-q$em8oz1o?w0xz-8Q;HwEfE`^2+hpkOUzLm(=ja(g74) zd=900`~{w|Xo-kC;g`EHP*G8Zg;-ck3&jzEx}Xd zsMg&TG62^{qB_~Qtj)qw(G?w5RcfacT>H8n6p8TP3tol$iCN6DxbIx76?pyc9}6srR#+5QQ&i`9-he^u7sKP)FWS9R@%|It$L%DdLJ z1I(v>!>*U}-fJ&aWx|4hx=H^_k2hsPUQ_*;#NXt{o*#^f*TCoyrS|h+?0*}J;b|z=EXxA!K(izpe;Gp3_&@&8oYgl5T zyGyVT5qgp`GW1=S^0wW9TRw8cjkQ2a;XwxPiWe!^&biNES;Nuv6 zi|tp>f2+v0z<|&QVAXez%NEhPeue(hU~=1$vMm^JXv|==5%0BNPmurc(|iy;BUCll zN6B&Pp{oHwd_X;#07w!VF~zJezP{;S+sjxg(wx)I%3k&w^7($^I=p@ z;DLr0#2qKGGlD2y?vQDr^v`?X)JIIiUPnY!6dh{^kpyhiV5gY_z^A+@D+hRQc?Q6Y z+nWEetc>LaGfHBr?*Pm-aQp;-ehLZ*_>FmQuzj|Ido%n9=u$jm<2!+Jpf=TKf*}|d z4AmlLMBnz4%H|%;{-vDp-nfaz!TMhP11iWz=sAWT5pC#!?*x-42o$m>&BRUsct4*k zyMPOVh+jmcy;AAorJNIB+S@>tKseRaL8~u15di81tWT(sxcG6})ZzGy2J8vVKR-N# zI_{n`e1y_*9)ATW6i`5eL5e+{pu1m>=8U3ePfhhRJXVfSGzI|FA~@U;;H?7p)*?VO z;pNaX9m9Du!|oqZ$LS_OTspzTfet9Z-vAyaI+n%{5K7QoRk49g-Kr_i&Mmx>maKY$>e^d+BbciMbmO?Nv z)N+6Q=La+d6Y7O7m$WZK%WUDK=l5`N!OSP;HU1om?r+?1{-5z*aUVTjgB2S_L)ej; z!gT`Ti~<<=0sH_b1)K@bE=HfRHARA-sy%Kd&%+ztB#nkjz;~&GNTBbmwMQF#ir|1k zd%3|F4liKdvAgzcQ-EfERPAuR=iuWe)voIe-4bYx?czgAZwY9aU z-?zZySER@NpK}Zdv>6@O&9!r_eKI>r@&I)^yJG>pkY?0Sg#}maW2ob4hH)R#u+NDw zQYU_WI{yD&fC@Wb-*Y4Wg{s4Y_|VWQ^{jN=iiRPvrY$?73l^24@-a!=D^*!W)oveK zJ6VvwnTWCy1ZJ5nXi$Q^V(j@CFK8$$qs?mKW%7FE_=|dR(rNh9Fh)?joE|(x6G5bN zJZGfajE~LdsK*7^Z5dz<)FdZp&Pm3M&qGFS#YSdirgagLzQo?DUOXqIS^njR9(la^B?#{%W(}Gge_a*`TcQgYbfyzo67Wo}+^oBMY zoTKgYPXkB@dJ!I-3j{jU>bOaGJw(il$!=Hs4*RlY^P=6kXs$bAV@}2m*@TV+JyS|1 z>j-|gcogoFImjN&CcY3R(*FPl&-Q`UjgKlg`VYv)8@FBRP=T1;pW=rHMGkF-E4IjW z344w@Zf$o4-zW{f+CRtFfht`bncIFz(Jht~s6ROlP`hyT5*uP4q)G>aH(>D|FQ-!ag5t4nf?tM5XJ z{3Sa7@Q?8Fa_67L`M|#s^2;vSU#&m%h!vjVZIH7|-w12F!FNG0bG92X{>#LIG3_;N zqji&LW8vaO+X?F}sp6cHNWzU09p}=7rU`#JIllNlR$@D`7^~ zYKZsI2<0cnsgtHNs8h$qlkdrJy=EY&VG>Ztlwne1;<52*OKOQ9Bl-U1f|u^jT;T4X zNIPXKUTK-Zs?%~;(RhiSbn&6z!rt~Wd~aLB1_yO?3>BU}!QaOoz+u9{+QN<%U7=UN z$9h*ALmp09w^+VBbh0ccK`SC?OVhQP-gkU8a>9%Y3tKNQN6E4!^2QSy7hC$@h)Xkf zerCDmzz$|}j;frSxlr#wDw%en#JzCFk=A9unnJ01rNO2Je{2hhrIv49n#v4q z-gnDB+p-qXA=Kz*vHXbg)u_N=HX9hAUQ%8Tp5?pzUs_+!Nvso3Qt!p>De zeUqv7uMNcT7h^^eh_e0gRF??pt*kh9TVB4bD<7Au4S3Pui8jDr@bBZ#HnjsfS-q{teNz3$rZdJZgS_6M zHStU$uHyoarabR5;j}a(z>5}f#ac{!J6ng-qH;)X)t@cIS4y{H)#q!&1Cxn8A0B-8w*^C)r2E@GcG!L->cYLMH<%0? z11*j09MjAxA|RJ`W#9mKlVU0SmEYapMX;peM~ahA!EPjwSRgj; zAWhE5O}nYQ3GR@gW_ac}Pl1uy?*bYd1R?8OSBYk2k?8RY?%jZL0g!ZFu5rHyqn64X)@^ER<3Y*EJY0Ne%Kj7*K%Z>ewvX73+95--8L=vl-uknJ$p6v zM!d~)%F7JjI~6yL)wv)?Cuq}wBT$cEARtpc=3t5Gp8I&(eHm(YMz@c#TCwjPE+SdP8LxB>&HEV`?}bwD~IKc5YLW;6&DU|j)0 zKp=IQ0$RWGTOB`WKtNX+$*M;@!A5S}h2Yoj5=7V%5x%^W}Fl3s4Vc zCCDj&P#Glw_;sGeAKGw8BE<6kvMD#fY7q2CNQ}*+ZAt0rO5lHkJNRBoz-bCvC?h+C zaYTvyHqh40dMSm1tyfxfCr$alwQw)Jf1+kjt?eh9QykG|O`g0-Rk5Wux6hv9@- zbA#w$L}}hn z>tMTrbtsGi=rHV}To77w)N11JE@cTLg|m@ zJX!J0yhOZUMv{fW!5}LAS2kbrl8yoG;QXOxrBQwU{n>>KTpKh^9>55DT-G6B4FOPq zbDPQzO0xSW3B?JD)@o+ zg>BS-P_Yxk;qQ78iIGEzfiA*SjN%8QuZ;x)eACkM6Z2~q0|6y?C$OeUt;3&OHw1}o`;*w z*9M%`ievwV0W9IN0~S&i{QQ5}aFrQPAAO!34PuK5>j=$D)Rps2-fEIK4imN)2v6g- z%404F88=IMGN*LjrO=Jc%d8@YT zr0KD>)Iez7fp3F@!btrr&E?kKdFIaQ^o@)7%xXqS@r6YLuzzQl`(;cv`!0BxMpUw* zvZQ&7f8~u>G0&{>+FhV8FEpKjNEQ~Ad8B@Z|e1pO(~H2*3#3C>D&;81%P zpH1yo)(lA~S@37L$WgF=ELN4wB1z~X3k)`6lelDOXWZJ1b;ws!PGLIu%_@NRW{R^So-btVtl{Wk>|{9RRxSlb4QkL~kfC(RG&MX3sSm_Pm0HMq0X zcB0skbn28aRIl}QZ%^s@P1#qB7FEmNDw3^nKS`ufiY)F482-67cDwf-i|$X+P*&>q zG{f<2Qj`Hj0T>GEUYUW_2*J@CnGw-h^Zu{*gwD5o46xV_swj1odo7i}EuTwS6;L`q zIsLGEo4!1o1XF~-tjRg2e?j|S$*X^h#}q3om)9wi9Tg%msznZzsUo?t=hR%UpW%|4 zss!1K1dftG)+Bgjg!JR%4KrUJ7dh`wjXXCjzevv_BYrcH-Ool2^{SB(6-{1|>E?EAL-VO3?FM6d1>bgqUTq78$w?-I3D)Pw z636k$X@beZto?V6xJDQf7nL*x69jHh=Lp*u!ln%=;J zn_}XC0waKq5?5uQ?#T=H=SIGsmtC*EA9~$ba4Fqj%FI`C%H`ydIb7ZWpty!+47n=H=vgm&|V zJSn@%mxTG$Hqz@Zl4|~?dj8_XBf(~B85}PfmaF6>uy|f2xY})!N1piN_`sYB10|3@ z6|PsS%l_w1u~B=#KEnl7?zPiZ9%=tWynvI4fRn^+c2d8HcJ}4+!@;^cpA;Xe1SB&S zcscIz?Xy(;#%2E%j`nKKo?2x@$F=IOlf|H9dqk3FfQ=y)BR$ zJqh}aQZdDA1cn(xQvTK9fCH_ll9oF|M&hoBguQF)oyO)hN$cod#=#5vm-SWD?)6e< z|96?=$j%zUDsH>k58kDYZlZzorU*=G6kWr+&U)56%4x}0)}#1@*VJC$eKwpm7_uTi z%*N&Tj)rYwm)2U0)xl}UR798`fg7Xj`S9V`W8h_(x_Q zWTaL6bvdt#$l_}xj{U@~|K(eBP0gKjx@%3!+pmn21zvd^2CcoOkugYOg zhM-7Xo<~Kk`S)hMRsQ;*qq`e-^no4jd9mrJLG`l%LJS&af0m9$`{TO>mu2d*v4jCu zX=gvU{7Lw@V%RJsl3i(J-We_pFcp3bYw8n%kZN8-rzda zu-{1HjeduRJ|r4nqt@Tb(HL&rb01rC1BnKvAsW23?LxZ*%_$HQsW-h~F`E3E4P0VJ zBoI=S&jwKu5CF~43Iqmhq57@uZ3XoxtEw)+Ozd&yWS;d!y+TDrMI?2Xr697O@hnFM zgSzVnoCCNAkOgq`p(>IeLyw8TlMtqbVG&I2fVpkfIy|!EPQncO2s>Yx5zsFk3LxI? zMd)t2xVTU)9D%&4BKW*uaS4BpmOKIX3-k%j{8WsW=Vql3(0>TZ=oz@WYS?~a1sUWe zBBhwWDUC6&%`oDPYbVSyp{`Cy8i&Y9e9S9Mgv2cgNKU<4s`3C#2m|=&7?{#FufXI2 z4=GqBpz{GvBs@GEG3T1{c{7PHUuFsON*9r>J!_T%p|h|*!jxf_P&coV%rpVna+bisC!f98_MG_VooV1CBO$SHlmR01;2;Vv z7?8>Y`1zZ*07{J2k1+N3&&259eG3CI9RxMuQmT9W`!8>*bV^Uo&!<6h&cZ~frs)hJ zoo+aI!nF4H)VV$$z-C{t7rMWi^P&5}Y_;t~9brzZ^2_7h*;!*O^kcy#3R-B(v7c4- z=Eg>dE&-SuJK*z;Q_n}k(3;#ZQ;3jAAep?=Ee7_>C)d|&eakM8%nd%~6DY~`X3Gb8e!meQ@oofhS^J17nsx&l*%D}-dtJY=2wY#24jYiZBq zEr$=7@&|Y<6;8s#qEoxRq~`EkzRc&XDQ_Y;EF&?BekB5!9< zAWsD)WN@x_pMA?bs6ofmDm&p|f{e8q$IKLKdVpS8kcj7~JW;$^c|~pB!Mgl*{d1T7 z3}m3BZqXOsrh|70`&2f}@3! zO|Coqg2=>+BNC)$NN?`_ao1)nR9f-4SLoCpnU{}6_R=Zl^J#J{#VFQ@)}44$7) zt`W1oNroAe(jHb{h`4HRUk248CfqFA9}rv3s@R5zmu2RrX4qKWFO=GJ1&p?6@pVEm zI3M8~n+5++4iq}dt%!}?P_?^i_JlWIWM50+<+$ghMf9%^mJP?W;TAW06`r`?H*ie- z`yr`C_{_e{&0f19BlPTRQkPph$LD-P))A-17vgnbu>3Yqzz`SrgQmUXbUp zKJTGM6}kDAS*H0=ju;0#Azt~a;A`(!F;K0gKKVQ@FwHZ~4=QyXqJtLI6*4f39w|=< z1wVc*+cg{iqwM+(n+E==TNRp4@%@iWsEjBdF>I$s&G60byWk8RhKB1}XGv;`-+Otl z&*><3q|4}WmJI(8pN|UJQ?8AeY5C}m{S%}748~mkMg=?;Gy8Blq1u9bU=X!tsPE6fMncL9fo)Pw*xJ&LRWPx4I_<) zQ8?4*yHxQk&usH+>g^3Lk7&==~8((C9LvDCX%%C*;b~ zx$4Km=U~3pOv|05Sp5i%h7)Sw(BZKX5Wf{YQE&F+8b!%R`}vS5jdAZE@(m8DHC}Z? zfuqSxh8$UD7*w2xg!YO;^ARY5@8v3F#;;_#WYx)eSK zJwhPMb1aUIj^g@gFDxfla4j+TT}g0!qJDj zIc#-a3pI%hWia{}e1`QS9+Q}C7|o!< zI3-9IJ34319TJZY*o;%Nvnt$43sU!dAnV4y9%DI5DD3< z$lmMwxO)FSzi$1};JD5;&h!4fKkkD^p>7$|*z>7r)vzvWbiVDUk6ev*TCjA4o{v<6 zJ{?!?VN1MWCo5f2oe1dL=|lsVL&L(xMezLMqfg!<-G7SSiq6;Y8#Q+W^vpL=97O zbLa@FVEVba$z6f>NKb(salW~`r^Ir(NLVvj$k_!kNvCz2*NTyR`ET3~2|Yy;kznXs zH}d~$rb-)$D88+iKoKG`d=An?M&pDRn}jfgTs}!~pvw;HS&~sQ#(Iy@5+8^)$29uh z(54oy6iyb2V3b|dF%oRfH5o6$OmrZ;9RumEME!8nI5#j-^o=c6wg51OXS6Gw@G0*!zAx4uk7O2)K~pFEFQ;57u3T z;3@^E# z`^aCz#V_tHpC2XzVL;k&am~27(4o`_kE{BshPD(PPzcj`f-b}xKJ&(!GpHfYp zF4fhX6Z;OP_2pZnrw0Dl|9D~^HnLw8+DCV*1a;eS4?WYkZti$PPNtWU#~C|_`hADD zh{~nK4A+`Ex9i_bDm=sB^=z#$z0pd(nT_N`kJ< zq-StO<(os`iAZt99?dad6JEdpU-K77N-9eJeuGRv(aFA_kQ@nkyBV(rtdA9nn!~B4r1MT5g4I5=OUMVx9=#X`p`#T zgyVH$=pSE~OWNj3p-69?JVc*n6Z!`ShLR0cr`FYFDa>9RzcM*pG*VDfxuCXO{uR1$ zH)>abtd*48U#KYOEpDm{PV;`-<-@NPGS5!?^lH>Tj43PPwu_s;dDwDrGbO_ZQn}iSf2L##716hxF%L1 z1LpM?REP5|=4Ix^3r!NDcUDJDxheVB+3gn=I3`Gzue`)~&x8BQ`$~M)J_Y@px6sO$ zAFhR}m$l#Vpc8*Iv^m+hrsu3jU~q66w@t3r-*)c4Hsh*EhheIixqd!GTP6I)%Qg%SCs+7}t;${8O_s9^g))$~5H_&DdyrrR&=K_kQ{A2mRRC9)-hN zB^fuL<|qr_dc%cFy2e7Oq335#8<8xu=6;7ULQcV*H!z+iQPVCL$BvDvQ;#syk%IPU zpoV}xaG73#jpDu|c0M+4Uhjq7G!gf9Cl=iwDXqDoxKHLXyeH)U;l@Q1-8bglp*&zZ zcTJindXQzc?iDXO>>@CqB16XPGiwz$=PxuP$?xZ(USf4JR#4mMdp_nH-><^?MIASl zE}O^%x2Uh@zR_?rJ5pu~nBgl!q1-8Svkr7RSTIa}SWo znK7#r^1SnZT7Z3hv8Dbij2YKzn`>Ws9gLP$jZ1tm8Fld^veg>?JkCP1@ zSGZVo6i*hV(tI)0OV+)Ic5BTN2x<9otn2-?*cRgYj;yPn3JMj!9S>hSzQ$qwoo~!F zz})KBMn!2@Ozk^CvkP*p6n8Cw!_PNGmtMtG zdFt#}H?=-IhCllDME@v8nTasfxq+<;@BsiCZ^%;8w=~^C62YM-2Q*AD@IVr?VYp@L z?oI*N0OAN*km(naHUxwe!7chyebKBgL>*G31p_{0ZG|-%e84>*pYlbuU=y^sv%9YoT^5Ec+L@~^0StMg{BAU}{cKuLjI z3`9jUUk_s1e< zyTjUshBDCYO-Tt79zyszIF~MgNL_`;0y%>~twB&lK2EnGU;{`#RgA{4!oS(d8$KIe+B!N2`xLZ*GKRS=2>c=%F8*$ubM|M6 z#Q>87Uj_EH`Tg|?j#u~Y-u+A$>slWLc@&Upo2_2R)FOn`B}Xk-O;*#RdO(4WfG1Sh zI$%zO?OPAEi`MRfWL7|nFCnTF=uOaqHC-AP2w;T!AE|(BsfWvkQx+8y12CvUldUW) zDjJerd})w|>4O47u~Q-_Q-z1Xw0_%%7Faq7A|xI@fD?31kO%@}LQ2xYV!T6VXmdu? zT`;gkxGmuE8odsHkl_aNBm$li-lV0q!#|almimAGEDeze5SE4sVoFqt{cDv1g#O%F z9^ea)NA-Dau<3+r28u}L=#2FA4)`;g0v>z%e5oqkkVF!M-Mf|R z%9NyF+V-6EC}(!o1kP>gE?+E`!RsE2f38hnqJ4mS1$p1j;Sn4JUr$aCm3GOPN0UTk zB)Ax$h;?rZ~7KPCtd)>TG{O^vL(0@|z7Xqr;y|F!#0 ziKX3Dy<`lC+KO3VXJL;HAC3~- zAV^Bax$yrCp^8=s7yBZFa8=;WMC5@;(i+_UbI`gCD3wD(c|8;4cID-5^A>)7Vld2X zI{sdQe10LCRY2%qvqi#g*E3WKD49-}&YrTwo2ueyVxTu2p9cn`Ou6G6^IX_!Ee@QC zhF*^m2QCssX__17Gh<@nZ(_<(?sCUq<7l&-QP?f5C3h$-d2nML$#bWsP2Mfl!0>cT zq`=eSJ*bb?=?NC-)j*e4o^I)7YWZ`ws)h0a7?lsYPUb0LaSP+{dC&_UOjQCpvv-_U zCOua?gZgV;ClYjYDbv){>=Hi>zWZ^ zf8*L-)zrJ}S*Jnuak1$U{h7)HBDF{1a&l6oqgA9lD~IdRlvx(bx6caWA!2U(TUmkMIvT2OQ*Vl?90tZUv}S|QK$qZyd;zUnhhm05pu&7~dJ;g=^VEO|o-YP#Yf z`-|7gC>~qo@54%

    Ir^n zcV4uixiIFEE_>{3FWDs^jX{O^F?KLe)I(~H6j$!ui(a!CbjKH3);os6ep`+6Tn}9T z>t06v)%(*O?c~b+stfNxx8K9t=%>$9>iyw6y`s;mJxNP3< zQ~aqU!Xk#eA(HXPmO)3_rGY3@@Be6hvp221sA+%cbna_m?&*fBbVWXrz+c(e;pQ{y z{C<;^g641gem_o9@>p5pluV8C+6Nk}A=Jtq>t~Ly)sF9|4aAGuM_;FVi52^Z6;FxH z-QbTSBBtYinNPMIf|`0C-QI36^7M)n{S4lTdJ2DELc=G2A{w+plG;>{Ou^M4?((jB#V|FD!}+Y#HF)5d%Q0BI$ELq<0U-qo%g#~fh`U0`BmaI zHzjS_$tIu5tc2QYs{ThovC=-HhWGFxyGyWZ> zCD=T3PN?YmPjx4-hgE)y;`gtU;ruMOOyBzn6X^;*E+KX26F+nYw%#nQb+ScZ3^oN4 z(EA4jFesc+RtjGkv3=np{F6KMDXm)O{1e7>Llonjzv|Ngu>$ku7mbPpFOQQ?^v4o> ziDwiIAG*aS26l5#zSw46oliKN7dtmQ0}vS*9X*%f_Nz6<@6_y1=atJ>CqSWF?B`B=B?G_hh~V(Xx)_OO$u=5>_29~=n_@ksFU2go zDg6lQ2!rC{h+z(kLr3JlaeA}^5_EHRi6_5C4t!wIX3S8@ZEmKGlEDNqHh_0{VI(;L z$t$m!_Pq&Q7C|I~D|?GS{aZH4DqV}Ed_%BxK9L(u$TO5j$D;Tl$_d;C$9sS5E@8zo z*odJBeCZ=3(O4rO;QsrU7q#}kM5@3<5{PC99DNf&gEdJB=~kfn5)qLC(K)y}0H?!A zIzBl8eIIf?rlzK_C_XedXJPnp`bTQFhksMGjjF4=kJvQ;tiYtR6UkkI5&I0(2q4Xd zU@SO11>F*yejtgSXHn78TAlm?s1L8ZYzErr}y^;=p(H5WgH z(&6_K-)jJ-km5zKdO~hH7&-@dJrMza_9F<^ottBT0i}$L3^&Ny0evy1^&vU?Ai75) zZ}s%dHZP4s_Yc5_-WHGx!VD1hFFlG^uUz373^%tcc=t|w&dtm$h}jaV5RcrTSQG#< zfKW$w>p*4zhwwt+iCK3|TcpFIxScQZ87<$vBhuT~X97P3HYq^RK_D11nM4^I8~abV zJ30~}a0(6zG=88mO-f3FcY;(Jf}Nv+y1%zK9nAt;1Mbb2E#{oIH}*{8=b6M{LfI2S zqDIbb{2-r9jOda?%kv#s#x%L0K=e!Ty|@nUJyp|QhNUiW zH6;B(Qd;+nE?%HodbpY+pTHicxBBqo@V(|EWjNWn->hd4DV<_O{O+?2hp}n&jMHlh zs=|`^X4Y}V9ORuP)f!w?`2 z-W1~_?WeYA!W!K>1cZcUP*@6xe9!X%Pcr?@OO7uyV$8V;X>6VWnr`keDUT$oTg9BB*w-QLheSh1Faks!a} zWXyZ4f+}ZvuXGtNsczwO((vNw-+Rgy_Xrn5$MOBOw8~j6nS!bv?^5^Z4`qaBaNxv# zR?^I)+OCzgxF^PmD|s8Ok{Y-fRP3tV6^oVmh-iaMgL2N^Th(jbo#(*iIfhv!E{Rzq zl`$nIZWRB6p1q?ExusUOYOm1}76+C?Q76s81tlBC`pGLr9O^%$$td4_<^IjE=1Poo zr1#b4za3P#8>U8@cD$nqWGFjjzxFrL@trRwa%97@w#t6-^@v%GdsB!zpoRU zENda9Ui@UA<7JsW=?M+?iUFl!t9lauMWT9nNZAN5|5XuoIY=DKL~BScwDZdUce4(sCY^tG+szKbgf!?X;V_V1s4 z@r_(~#ZQKw?t1du6)k!LQ)u#gU)KLT}9+w&w6dvS?LTr$1BR;3=MH8kMGS9jx+u^h26;jgCN= zfKx3gHPZg|b*fqao#4pSZn>qQz;3zc!S+LC8u?0oj*Ha{e`pge1oM0yP6G@E%HkaZ zvLuCGhbCrr$0ZS%n~e)faEOUsL?3kdbSs7xPH(!HO}3;!fkkK z%gRWEM(I!xC*iZ%TQYQ;4LLhATK2jqE*gvdWOZUgYc!Q9LxX+C#qB13 zN*p|SOKIb4GvH>)TMR`^H#+uPPdslKq*wEOlHGW110}RJ{c={%A{|Ua$K8vWLKd2C zY}8nMcY4h1?<%tKo3cRroFq1LtxTePoJ`#pKa)BkkWT!~+Qd%O+3}Lw%Pyw*_R2tm z5BHklmlPFlW))TK6>y(x=v`O1W)nO`lu`W{Yvs*=p%$<7PQ{mW+R(2*HLRC?JDVb> zTs>4Cn)#jT&uKNDD47aG#i-0R(iW$GS8IO0D%Nl=)U*{feXjra%m(e2#Wc85Zu`jp ztfymiTYl$+>oxBQ(?N8qc2-_jRo6gI@!S?iQ&Q@vPLjUG>6=v6{lnt{cArnry9Ur( z?UdpiQ)s8Q!#Pd4gD;_tiH$pVL=ul*)w@@LCjW7v-$A9H-s zc@1Q3+~QZLQ$`hS?SHm|JdHt*7pw2SZDc9R($NGiyR?aBD%MKZ~nGX zV{mGn#M%b!j97#3W!n$-BPysVY$miEF`e)2PK+~Vf9k(Gw;LT}Q#MbjNX0@XRI%IN z&`2so8F{VV;55p3$jPR;!`K!au4eu+LE_ofc z-V|$H`Xp0vRq75#5kVLGc%4UQ;^z9#y5-bQ(F~-dF`DGMY;t04PmJ7ekaMa?J!PwqY8zMt0FYIudVp*bMxJ83$V+iZ7b z*<)f1Tw=aItA}s2e(v$59fbc%o{pa|c#=mvMqZRff4(=qu#v0o;FdqT!k40YR?d2X z^e^Qlg2GH1@-Kxl1PDV+zR=w{R&M0L^`GP8Cgb%$n*rdxs_*u%RuNgn^*LElR{#qFH3E`2kmd6dHfwdtBjuH0z^B0+ z*0Zsnj=II4OU^Tv!Ui|i@;aWfag!PwcZwZood9G3hzT%a>P{V4-bw>!;NdKxUpR1c zpj5gXzv}Wv!uXl77@#MhEI~0&`5gxb2iQz-3;@6GU-|%-B?|M(mie_2G z>Q#)J%VdI8gdPiK-!+UxiVr}-J`bU<95!sh#;8jHPvKQ41Z9^G_V&uWlhj|1TjIvb z(4o*=YJ;Nx^l{8g+bgH=7J%2aO#KSvo&YNyKI(KcObjbFF`uy%^Ly*;EPc?bzQD(T z01RN9A$fN1_v78YJqZW|m5&b!R_e2?K$;8^)j`4rBTc|22#y|Qju(NX*|ao7%@%;K zSpaT37*snNr3t_BNtug}=N#KYPBD{X1 z=@sHxh5mAmM@Dua(6g){c=t^=SDWMQ)UygdsGI5l!db0ktgiVA0RbJsLpW3js)g`j zoah(z2GtnxAFfH3iY&rp7qb&C&jCHVvVRpgPFo%%;)YAkD465Xlv_|x z5Yk7{K2X<62-oG~@uFwSKssAKUc`rXR0KXSV=WAW-bF#mT!;&i{A-lcBZ#hJvKvxT1 z6BG;Dw{B({=FF3_uCf;IMua&@1yg>=<+9B+0Ivw}4ulkN_7Foeq&#bV;8Fag=g|0> zz#H_EBC08AX^N4pNDnzk0T8UIJ}xUO3t6^s;b1ocCj_*JkctAIY~q~B$oRkF53zgn z*Xd_9qyj3a-*_c>mLT(kp#-

    X3(S*!+^U2BF4Ffe!ZP$cko0X9y?>2V1trY-H zaGgI2ie7ydpr%_u^I$XrOF)34?oRLT0%*?!wN$3GOz*AQ_@qn!B5!)Vx!KXhDi}v;w$$*hrbWmbn^!*3!Sy9-Q!M?t2j@n zifPuk)9?RB{XMTm?;Tn3j(#B5v%bnx*e5{w6KlbchRMvU`@m>t8uC2rV>G)jMmfO` zsgh8^O+7X-krk4lsG60y+5~xfT>{b3H%kpE35tLy1|gr#A^h4pG4X}A-SAP!AHlcn z2ARbnI-jB!6A*mglJWZ4o(lFx{xjqKV$F@iPRTLn{Nnt|PmKd6GyzykZRo2UI;w$Vmh?rXA8g zSHAt9;1s;a*qCd`Ld@m^MIY{6aInLsqH5q4-?Kh`bND-V>Tl~0v7rH2H!(b1a?Bd9 z?Q=iUq-U9s5Se^}_#%Lxa2172k`V5YTnxP~(8&oFWd6~5i)3W0So7D<(2bqtl7j96 zg+SUH?0?h{a>SFI*uZ_R3;5JY$An1$%bCjX#t*6%ECKNZO0XGs5b^A;E0G{LuI ziZUgWZwlx?^bhGYm~3xR&?DR8?snqzK0w)XdKHfmqgh5B!*8z}$j61RWU5#u%fxH6 z0@d*KcKp)+(*i8Knqc!yAX$C7GikKoS`+ZISd%@sB!cCn-{&cm={j=u@%lD^$Afh=zD|MZX`c}6DP4ex&7)i$Y z)nmkt38P&!)sGz&nU*~<*BWNmyU~)rvY@t1dXeN&n&vkTNmow;B zyX$)JXj?>Mrm_&ve2>lr-NmF}2+i#pwg?+UL_KkXiN3Y^r=$kUwebqddn%)Eip6-4 z$`NgEv?*hWsr>h99&OLx3%w*8G>r%xwsp48d3xJpTI}~qMdi-SY<-GVTl1+Pxsa*L z^p17AtV|yCJ5@7yK8TXDNrqqzAA^4iLN$bYP zt9W9HlDw>P#4}!HH$w~V%L0sT?{B|vq z9UI1o)!q~*h5H==`K8v~0W~~j(?W@w4?h11;GD8&ZE5-A;p_z;(@N2LUKy+O@5gk_ z3(tg7zv6ey?y=nt##MJ<<@=%+RqQ*_gvwxL^2`QuoinlVQsre<^z7pYNpZ`I#IeOT z?M>gUuOv=C%j6xvO*@n$6%xa9VPhT1!|2YurdZ|eUULe+|HndesifYl4M+O*z>9-~ zZvHlJmNi>r6ZV{2q^*Z<+>WFcx^I>}ojX`P9|^j3InMc_o#~2Sa^>D*?!5bgcoI4! zR$PVj>z8r(w8@nN)t#hq3s$u0pU8@isfr15FP75?g<8rQ`JelJQf`S_d^x<>nO`Nr z+$c5sSx%^M=5Q&Z$Po3wy6Fl26MPjs?H!AEY7<#y`&km{%Q$#71Rt{H&X=0~(OkHg z*lX90+b)NWS8gIdX0r$jem3{nbTkf2W2S5DTG*e{Ya6UwjKt|TqkC(rpr`Oy^?reW zp>>)WA?gl`l`cn4Lb2JEt}on!Hla4e@ll;$BOB^Mf}o3xd-Z4|_pPmgwu~Snx=2`2 zhC^6XGMW4RAZ!}RBIhXjbjWuObNVJGJqxElDvI3niwQxh@pNRUWO849_w&`Oc7vGY-#j-**$-vZ;q{wFU0yq1X?E?r#TdB#PsU#2A0cDnOqE+=ZB#@z?3Ecl zO6TP87KpG3EO=Y{@WFPlZ~IK@=`-fSTgIz?n8GckxVjqr+}=DSSFzK!moZ|Emor^4 zfIZq`Q1!L6jQjj{VXSAD+-+ittp4R|nb+UoVip=G8k(o2AR?*17P&tPF}1HW zRhNWEyroBrdh_EBi_2zfhaY#-3OT{?LL>JhQq}zDu^jRFL;>Ze$9moS?zZ_X8b=ou ze~w-)%1dfl74SaQjqAH36Z7+@$HpJV7v5hZx2}5Jkyl(tOo=FoBorDX`#0DAJ1sn* z8GGTu5r?Q;HZR%l3(dCKeUGCs7phY4UR;ix3vEO{&L=!v%9*aF9Uk zMIB79V5mB>_Fy9IujgFTDrp3u1DL)MR9QfZ8z`NQwq{nm>=1e(qY}ayl*QRO%m>q@ zMemK?fWvqGOcBM;N^ui1iz`esH30X44VdrAe9&km_&H#$hHh$26JAM1)+H#Q0jU&> zu(8|;%+i3iP}YtIr!O|)1qARA)06k(0r|MJt~>V~g5TViTf~2BdLK13`_?ncmhtiz z1wo>+V=C4f10)!D6zKUEmbJ=_@N)nA?#kE%)TgixMUANN1=L8`dU}#UCNWSI4i3@u zR&kU4Z*wTU+Uaid(@NW0!}(QMKe$7UU+?a4VAgvMDL zF!nH1^3-ptZQS>4JUToCk1mIu^|$yMm_N@6ybhi-f7Sx&9seuYGkfd9)AT;{;0*w{ zG=uOCp6{D}*uPkS0%zb?vCdlX+CYdNkcrq@K``MUYC!LWg?EsEgZ{);p$0}CgJEpT z1uX6mA`OB>N7nw8Js9bKq1KlRhuS-KnAk&Q_mwMG(6i91fpu5|##UuS6JQ%lA}dgf zRn5&|uKl#c_}F?G09F0O55PMNbZD^&|NPRkd&#-?1fIdYW)FA?jXsK>Ld2w{RveE10pSDSgUn6i!!$Huyfqqe7Ave#hdCi2T#53LN@-BE1z@4$YKet_ zuSq}LOmLMHjjv;0cld;ZXrkZXD}QW;dkYpMfRMn|K6Sz=9CH;X(jVNm`e`##5?0a8=jq= z-G*#wO{XPEpvMOWZa%$lOHnMp>DNHV!jclDeJGc*l)s-f_BH4PwG|2MU8-K$&PYlq4Rp=`(!<*JK}2wV zc>jVH`)8;h0WFu{JP>~1=fDPf4_%xNEntI*U`qtsVKC@-c6HHv>9q{NV+f2nwm}he z7O>ChrwD*V`Gs_ZN9HOrUio2Ae(W3L_gFCns1Crijg9EZ%ZsLnn8d?|-M|hA(Nb`} zRxtnj`y2NvAoPVN5~l8zhkfeld+1$D~-_qD+pMGcf8XN8o*-c=zVf<4IBw$Dg z)9X8r!!gBkX)I;rHeWXylS`@&Rh3kdZ!_FV%^)!m$^5sh`bdu|g0Xds^5IMF!H0@5 zOWy}8hw~q*m{H-9N>gsi%|-2!usGvqvgfh0m3+`aaDB_eLlE&?Whlm|U@b7lrzdqg-X&ZK*|+8t3z6@7 zf+=KQMs5#WZ#zrIHI|kAL8<95T*6luoT=6wp~lM9LVBToMzMT}jJ$P)M5;*pCYfWi z1X&Q`<&ce{8Wo#Cw9ziU>^pHWeklWdgWjm(Oha}9Ty$*uQtG}<)!nY?M^a{lXar^?U!3iE$cjJMYdX4JetM=H87 zS0PjE^bR16R_koKfE>%(5wbr=(;!(K#5}VzYli=sPRA#*iXT^xGun z`788?n!Lhj9Di*#Is(*Z3VufXmDJA(!)Z1otho`Ym?9`PsrwjN;n8UuK_O*N_$&th zTDHtieZ}*e=F=TGQ<*fWspX?uv_B4l(>)yVGyeF|3@-$T`1EIp+mO z)@^hlUxlDXR*GGprdm}xkwW zQ_(g_skyCUw|DJRGyV_Jy7AwVj+6vzUW8dgGoJ6&!b8(a^4Pxk;ptjxs%tXIiDZyF z0g8*MR2O-6A_q+7B zmn6>B&;9E@gcBZ(dwC5jzqc#6EABsoKy6hpYkmHK! z;oX^SJ;GxRd1L2pqW3QL19g36w&vTNj8`=|xuqm!mcR7R?5FN1Ua2rlC47L-;DQK2 z{giZ|v21aB9!ufvcZWezL4gaP3TtVs=Y5QNv4hnIn}(P%w^w>(VvFU!T}}*dQdmnd zwj9MCF7a%a@F}}}`TJSN$KA=Mpjal4Ekdzn&vyGPDnQ^i!X8JFz<@Wasp^ck0kevv zoAM*t>>A0Jt#UV0bPKn-JTW8N>MtDcDiZDbHu0dwgORD40=+3(6GA!WE^9L!hBiFz z7a|^$*U4wPa=^_>WJA{*O4E|JO7dnzWa4_=!cFZ$5mR-K|Inq=&L59P*2LMOG2B34 zWA??Sk3KsN1f1C)e2={@T(^z;HQLOroz~;td~)yfk=_T8QN`(K;|2FD`5@3&vc_T> zV;IM20(Wn{HsDcoO9C+>HUYTmQuO$9P!>|)KosCo5MWE*HZGM!E+q;tf9@73E#6#a zYXmv?Tp_xymA0ezN#9adTCDPQVzxRtY^kpF4@YneOHlY&jpk5b4{?G`F)`o)mZJE( z>l_5mAkc0@UQ&y4JeEzt^v#EE%`y5Avxi-y0c$k<9k@ULCvwCOf*5e0wyowlzv?_N9Ja8gLnc_v^3 zU4dZp#)b>Fxyy8P5MWfesOntc?3FH8do9K^_AU7U9R`?WTke0;OCRwYH%Qs=M7IL+ zW3e2e4>k{3i$cf=VDz3gYy`C(^-xd<)tI z&%O%ILEN$ilomn|4hyz+R1lkB1MmYH{ayfi0Azz1;T5=MCE@nVmQ|hix38^K@o*Il zb4ur>a8(yw$e0vx0OQXYF1#t*Qq|Ct{PR?OZ?aYhF(xik@q9?)YKM_hcf5k2V3^@%^8U zI;i!%SU`*k@ufq1(66)uRwD1!TL=*0cFvp*07bQu-wx*uMcv(jm@MA4b52QExPZ8X z2uc9Qu)me#meWfab!HC@NBQyl@CWNUI&qzKzADa5jy;UX(ZKsLduj`@J?BaasLu;h zK`PedmX|+h?Chj@#ZAQw*_TOHeFh9&eLX&;D*9Y3bKbb5rm02@E(4;wGfSq&*#Z z@C`{rhDOm<|3Zyg+JdnJ-epdN$$8zG{Yc{ z7H5_ls%0DGUr%z7-fg4{R&YF=*6;SDagZUdwfrbx?8r{FbogrY!nR~b?Lp2-yUfdC zOPa}ZtLC4~#%&L;>~$wAMkiXK!c}Y>Q_Qv>w({9*a#&xQt6+_HR;b4$4G(za%}hlJ zkv;%k(IajQNub0MX~WW9^!KHH)x$*DBdag%-y19fuUgYz9@sMBZ}DZ3?QA}IYx$sI zWxI3zf?%MN|EQ>9W%PFwyGE$$Wj-{aDZjv}-1($J2yMot1v(7D3?VA7+o^_8Iy#C% zbCvU**n2zfrs#oVnW*hlT^jGLL5A~F{R#Obcq(LjrYDOL6;5V-$(wGDULWV) zF~9J;vS8=o_>9dfoHwq;dbquF3OAQ=lYZJo3Z3nd`4=5uWPp!SS0qB_Qaqtzi_;}` z)<@*y1ru%Rur6QG&)P!fBQZq!%E$RccJz~ntRW{hv?4AlLNdB`H0iejZQ`W*ES7zF zNP0H>_S2k#=~7j9wL}<-YS1gun#Hm6EKFR7EGaCM$IeNF0%JbCc(_Nfn)8K|;ntBSY`YH?*~a`nq+7*p-|;}GR2gz+~#V@YT| zlJgH0>)@~Qm;M-cZQ&0$T3naEjI6js^qw>GZOXeMII}p@5@|V)op~f(-EMbQ{N#9+ zw0NC^El8!10V&E}^iZw)H*HK0m*TqS%;Qwjq!r@1s6S7d(k$0pXUqhQ5hf6=OM{$=MZ(Qbi*2BHxya>v*rKb3ZdKWU5N%G4E%Vy*<=?kw< z|H{yEI-Psl_hn~S`!;^${&0hWOl~l0`GY2r`qC5kOODeubB#oWOPGqx+bLf856Z71 z``+=es<#_Y?QqH!ld!o=N7zR@grv=Jzlh9QGSq0!;~V`!bBHlF7D;2u`B{Ufelzt} z!vX(7I@2o0Noa6z`vqq0JGsuYqyrjVF`T;?(ZE6qGSiH*&L{WGqls`iq}Gi78% zi}wDDJkxc_Em8DrmpB)nory{Am(ytJ%-*XH8g7)o^RNwYVG5E(%3N0@MTpa&a9F0A zC^;7?%=XiIwEG3`Z10agGk9}%WE1Tj=7M`PW7;)nM7>E%!Gkauwzck~R_sQmud#8J zeFc1p7LfNwzE&lkHs`JjawAzMhsO=~Odi1$6Sce)J90qCl!xzcMTumM!O$tkA?EJ{ zHHK+x-=3=$@_0*)_(0LE#7fRe$ckTNSN84QNwwR=08O<4Mp9Ld*C3Zpg+E`l?2>g@ zb5iI`RIPn5=Fr1ZEGtR3;c2#z-~#YYUC~k8Lmvh$=&KTYr}9K!OuKWtDUx0_BaK&5 zAeiZ6&tr(>UND%7WmqmGxNGf&q_e>L_YBj@E|gWtrgR&V9N7|X^Z3wf(VQfU;+_0A zgITZU7Shko9mi6`ZMcuSy@;ayQHxCS&mC^vjfu#h|g2{jh94rXufBpoD53=#YV-Z)iLk4g(Hk&FVg+^}mxqwJHW&#8FF)%to&Pgg~)jW&VgxBBq2d0Q&x?+q(aGhhRlPRJ47=1b{A#N`T2b z-Tqit7YF1Xju2}(;5$eN0p3iL7ptj+KLEgi+-)$(fGGneibW>;P()V*;<0}R>p&#g z7~Fn84yIEL7`Fr7!ZtXAEg2ugXzv>j8Ni;q}h^l8v2sWqC9*U`{sn=e?hS~%+Ax8}}OR0$u3c$hv z%%026`P{yVS(I2Uw%@V=OX zO5Bh_zE3D3OfSb@N?d$3v*oL4X=_rP8UY7`zVPMOelMEXEp-->4U0z<;U$s{ykst6 z^zID+U2lyRC?Y}93gX|#7&9cU!Suw$tZ)Eead@nN-C!icid=s*hp_-}2@t9N0=BD2XjSl@8m+1os*9W@j*!J!^PTCtd zgc(hQiSG($uwB!D^WIrD#3&p`Dk#Fk38m2xg$>to-JbVqe$XFjpeV87o*f{JwF+3e zgdLlsR%gyP{};|4+fINH4BbgUB$n&x>o267ucnxU-Kv{}JBMhIY}z3O@cfZ)~_Vsz_;Lp5wI^v7ogG; zo=V7U?^6dF8nlvFRf?k{WFwuS+D+sOV#gRj#R}O?*aYx5@0)sy#73d@^YCz1L`a;0 z6qs3f%Ar?NQNz`@wg57@IS$U>H2=GXAV64x=wmTMe}3$(ITnmV0(sw!Bqs(9ywLLR zuKs%ilGqP5Fq(+qBfsdx8hPHE%x_u+2T7VUYQ&Y)vVxuP=*NJZNF|S%my3 zg09z^wgW9nHQRJ_)E#|kTuGB$N#=K=Euke|_mXG9-JqkjX@??1j7ZT?6b%N4lam#P z#~)Ln=iGO$G*_bhQG~ip%gwf}^pk0xq62M2g7DP8A2GCy6!-|X-2%aHbM$RJywBg` z%6s`bbk&V^6$WwapRcB>skFp=8-3}?b`NcG(O4V1HrhBicuE<2ee>m;)npvZ8125D zlAR#~2J>`kawV$uHnHK?T9NyjBt#A;sKcTwIJDIZ75#ZQsnR|hy*Z=wMWQ#AQTV(i zE(*5pl^dkWygW=1**I+cqm3A<7^a~`jeh&y7#flS>csow$w)RzXNN9UNI~D;N=}H& z^}1-aAxg;SW!^DQ$vv~8(t7+cgmKv&))_}O%UE3pZMWZ)JkFZjEVcGU?hMFhsZSfV zCq4Rb9GY!>M{V({xe&xRU8iI)Uva`6IB3GXTBt;1j68~-4^V#&S-GS+)V1;Lv-j6M z8<+JmuLX!QD!7Pk3p=={zwoy9!rY?qRDrEv8iPr*F>5gvLLDnz`+r)1`wMM2;?)x6 z)0Z!Y5?`$8H)CF#Q8!vyU!I{%wyRAlcYW#2Br>k~CKS(BCT8-F^hU`?VR5+>!lSY6 z*s$%`i3u|`eoDn+@=}821ruf7!cdV|!oCZFp&$IS3g_?5S04uPH&5lsR(Ar@U0%jz zWZCoza--`~r~5S#_4%O+{ToH3cDQpqd!T}h8zx#+o5Y>MNa2c~95Iskw|?I(?h@~( zblYY2jv}OrqoS|j65H^|1m5a@6mIJj1ry&vJXU;-ejIIAT-Q-z!yxtL9^v=AQ9D_6^9pC!}u$5U;b{E80_`%hokO|6cz8lW|aVvtc{4~b&J zrJWY9yIr=Jefr&lobAO*Tg+czMm-Pek$4TWSFU_WZ$)#l7&BG9`)kG5`*D+Jd!HsQ z(Sup)3Im6yV$09u)o-_S_+^}Oe6n_UEMH1?{YrP|ma3)3V9?02j{;O*vusuWSl?tG zip;)TYU?O6Bbu!F_K5?%s4uD9LirsLj9^InG4CZDn`J|NEgrU_O>sj_XBQ9lH&&2z zEj93w_0g&3*THkImxwm$#|R5HR^A^*pHmoqRyX@ByWDKxPBdQXeDausa zFsltJR?zDyrM+W>b1kD$gi7MdtyzxtPX2cG$t3r%?fWFBFLt6|HPJjpe(xq*qY@I$ zw*FaEf66c=)DTnSwV~a`T*K2NWN|(E>w`pn-s>kXa7(J$JWBBmiLbKOh><;XE6Dq( zKBzYz#2A(vT4ArME5kQ<{%FanA^k$?hMu}3q<1)Nj(4pQYCgsPcJAdKM%q4A+RBD_ zh_=V02ztdb%9B`DSs@fzzbC%9%e#N#QGUPN=HWw9*=djJ>57tjIA(u`dnIMe2vYN7 z3J_dn#QwXz(*5~w3a#$XpYO_G^^eUnie;pD$na&CcfucU^1l?a(q3r$LY(jK!|=tB zHpkq&?(9(IM_5^OCy~%9F6u|D+oO3uvCm{4=AlhA7{{?|4h8o~y*TjH8uT+1vfj-f zy{)bZsv%6`#PFlz%E?&?SRI<%cN>PjJV$f$pk5=0I7gYamxMd0p(=LVyJAN9Jqe!5 z1Wy1C#>vBZN%zUuh~~B+gF83kg+4cM->A5%=tlUX-wAU`UyxRcD-Tgkc&THg+zm|# zqiK43k%jHg9?st*jRKtS6bX?ahpa|pQ4%-vn;hISaC84$E_)yK!9$JU9U+^X^JdY= z>g@J5-hddQhOD)#7O;23Uo_0TQ>@lR0 z_)1V`tK#RGF8YM73TzRg@!~l*VQ!7>zLkn%ECaC7e4Nl62izYkiVhD}Y#7FZrAO*B zBk~KNIxs<0?F~ybR^BX>d=?GrI$;d1kYa`|7cTGBcNX;#AdrO7thYQ&>bxd>Q4nO{jfIiDg%v4~RR}W0>9n?P za3A3*wd^Vt;@b9IA&dQdldT;wyH-|!4ZDP98LUqSuq)`?7O)QAU!f-+Pa{EZ`tapU zWGe#l4qKx;=z!3Tgeg6y6l(MU?t@L(T@I)vDCNlL@$y&gjYR}!LXZ!5NPvBXZHyGZ zJ%lP%LS0=VKy^pS;?!_4#~<5~c!+*`k^bG=;F3D{eK&Z+jztA_Bd|HaI%h853#J5o zh8DZ(*a~@tpqGHM7G%8PD-{OnC78|wJ^9mFmvUIu z4LdalyEX`EgXM=jv|NDm0^o0`4MTT=`&=M}wLr!#Y9$7BJf{QLQ{#BUjE6?5-~Ii# zU5IMP^xA{EusGoqlLpkVnl+UzYw>XCfTJioEMO_qxexe~LU3rQMd@m4`=$smeR?fF zA)=I3X#WGKA|qQdN=gD8v!<-pGJ2m<_oanpNC|LZ&JVrZq0KBdRd_ABCQVy=bY=;I^g_0^824|K#FCOR)J=1fF1!a^gnM45_loagg|PxPXgA z83jpAxS+m-p5&EEB@g4*cf6nvCUs!gT>_gm?)WDNjv;-=6>L)gdciI42zwW;b{^}= zkItSi45}9v7C_+w%8R%#5Z|c>zXT5gz*Nu+@C19nCjq3lKVQ^f zs|6!i6$PHz34Jmo#u`*WdI9nK{>^Eh$r$eGeAb!MR#g~6sFQdwc+Qox6&bHPu125qhZqiyqA>yPi3D;*BaKSmM7PY zr83LjB=C|SJ!-VlfKvhz_VhG(F&bOu4mWn@IBCXuxeA718CJ~?uk`-jj9XaF+!Mpo zN^KYUu~l&s1=T~0PM2j+`%bpLK;J&~VCwD=y7WO@)wERIw2OVv+{tpa zI!3M$qg)t6;Uu*Cv{8MLf%vt?L-Kh07w)%2zWy1M6zz~YQ?iMfX!W>!Xc1=PKOw-( zzH!-{_Kz&&8F#4<7N4}#53Lg4%o=hgnaZy@(>|jX36HiJMoV>kAf+U^MInSs8LshT zU98I+b;84LMfq2(g-j_?;Axs&W>Tyo2^&U9bq{YMz)e{)T7v8|#n0N%!wwB4#dF z=^dGrR^N;98(OhwJDBTkr1;IutibUpuD9hA56zu1H94;~3Di-n$K^C$M`a%+f6zm-`!)Gmz~M(JRD^F`kGL)Bc&w~x9vlw zwA#2f$DezxT?&UoJ8eU*4}xwOSt+B0FgiM_+RS$!r82YfD<;iev-^Zv(h7Flx_Y{F zx%u&C?0Vdn*kM~lY3x(AiOhSv;p%5pA0^H&$seZq9v?N=kTO-@q|-tPR8UYcFr58D zn44dNH`uGC^4D$gdiQp73!x$Ic1EOn^M)b1f8i=a!i!7$-GD0LC(V_!X? z$iHtI$}iRbfkazh`JZs##?lq8>q8`_-Et{ie6gN15$kKcSL)>HMy`#hg$(TJS99p6 ztgZ%>b)r%%%W$KD(u(a>zO)Tf5+tls7}^%O4NepZyB*~I^qW@JHXaI?>k@5Nx#99I z-0NX2-jF$^x%w`nq>O3QKVmwEz1{01&$mwE{z90c`$_)Km*)p^jyLxjS3_+BG7f7K zt39fpRSyrcdArK;f2zF3`N9vc$IwKO74JtPaX8s@CH$NyqLA{0Ff?hQ_ zi%nR@DWCbSr+M8;9si(&_%_e6g;dD(k_yZn%HPC-)s}L`O`JVh_f7lS&pKXc`e>qG z;Vq{p-{jn=V-Mmuty}4(82*w-)S`pAe&U3dA^WpFFuHtszu=9-{H}cVQP|O=nQ=MGAcI7*%wg-mTyR&% z_17xIMecdOP~B^sPR1!4=EL!$s`+GrMoKGIX0}IvF_jB&K$iL-H~mPkJLcW5#AJt4 zs|UJ9`4kj!NTFE;wo4@nsv_5gM2*|1^(|Vy?Q=d)BKY&mvh(Nkkv9ylYwa-h6_}LN z^6x_X_Iu0%{Ce{jPFt3CoU$K8D+T9&^_K@5Io@?}X#BAL-SW&+uWE8&JheSQOEw)b zAZWVVMr*HPVl$3|R%&4osu(^Oa;M);!C#C*$Im&A=(Ki z`LFA4W-imgXR?*O1+Ql>hs-SQxY5xwlI2M!#u{P*Z!=Ui(3bKM2?Pl$^nohI;ciA! z?#%HdgQSq=Od_t|Vdinw63fdLuPeo&=*!p!bUxM&QQ+u-C`J9l;?%Jt6yx6X>sF&y zI{7Zah9ogBH^8PwHMzWI1b+AZ9=L@#Rr8ZdL1Wmf)24;kD)i z{xi)km)%|z@5%nwmjI-6WwuY~&)SZjU5J+#4%!JL7JxjD_|!U1iGUpolA0qT0+Mc9 zv%_vk-paBkkl}94T|nCT*g;q5gm;}WX*SNE%>HE{OEtMGo$k2 z3Xr!zw0i@g3c<=`qX`(xq0W#lsetJJpGefn8O-BQZx4mO0Fz*u&Lf!hFS^Lb^s2P9 zv_M1fc<`-x`P%cIz546jMom+XQ*D5&>>xzFv-&$+1H@xyCMVgf9A*KzE%5M0a;i|r ze;MHS;R!m!KUnj-Q`8#d&aA4J?d#dzJVn3}j+pPxdUaA4=*;IOM?!hJu1wm|j<>4!A6oHj-6@{{G6zg1yq* zaWi*t+FswyNfVsC_agS`F8b2XpY&Ddex;qKgpaFXu}kOp+&MkVVRQqO#=ae03PsYu$V-nqfOuD2yjln9HYPSqKLc1qa4;@68|Muera z*#K*?gYD#Lsg0$A0s#Ps>z!diKpi5WWhxtj#W7aa*88W1KQ7jMaju3rZIP<10$u}T zs$}m^#t2`Eo0UMIyHb{#=;j-NFiAI$$E05$?xch@j_v=w4V5&JaI7%zf&axT%gDfh zfDMCjiOk#2egJzu#PUSm9t&oNBJO^v^v`6OEZmSlw>F|`$&^e%L!dYW;ZIE11K18_ zO!w~H!)F>C$KK7*r@~+$rJbz6g{c}!0?8F^0P(_wc^k5?3IL)pOrpE%ZqJ`Tm#utZ z1t#|exz6vnRi~*4dDA%3%TZE!~2TLZ@AIi1lbN9U`I* z^q!Bpo&OA{1aWo8E1fuzxJ2Qr`5q#>!|{!@G9QS`;P0pVW2P_XBQ=7`4|@QunlKD2 z2k$CC^C_qr{H=loHB0`<@teHB$x{tWbz-R!6-srkXlb&Xl&y%nAbTELr$fyqK|zsK z>T14nOzP$D(=s&p??j6II>ySvL;}vT>nK2L zk`i;6^t)8ix7Wi9-_tRFs@ymBN)vMWz1qiyX^3^jnhuj5bI~rez3>UTw*Kb2n)jj< zcchQQM`a#Kyn!W6P{xJejCUJMw<4+57-$)qJ$ME$LL-i#-}f*lPsYvV$Iysl)4F#?653ylK2+A@SwTZ*7C?-ONN|s5OA+^MF z)==$|hU8wYef-Ks{HR9VfX9_@m1=TF?^i0?Aop4KkrWP|Jp+^ z4rmgb#py4LMQ7vJsl%X%fpgJgpWXjp8&WUII~!#pogv zE@OKlC(Zb}qV^+SFU%ji2#uvzX#&K%G)~uVs0YryOGUxdm{?m))Q% zQ{bLn=(s@py|5=?zII01l)b9RDz>vZ$wF9#7pL+GiSzo@OF9%+*Y&R6wczr@BidaC zkO~!*pCfVp?RE;qDpKpiJOrBJ4riw0teCJGTT7Nj+fKjXeYGpij(I<<_FJTP8T&VV z1uf!qpBsO!DJhyBcv|V_B&U9%PiSh6kta$hc$Tyj_fYnYJfAUEoC1|>qK!fSro|T* zc9<7yxMxnzZ2<}f*#k|(v3JVuueV<--6+KSODDS*ixR&4; z^1Z(zc2<>VNQW&ZM2W{pyYh+piCBdm>YG8a)g0RBvAfGI3weewJq1)Z<)qH>Sn@ z#hop6;hIdS8!q)Y+&mTXt1Wj6)hiPo+_^Uu7nIsL%fW0fnNpBAZ7)uo42W$*o6I4z zA91#=cPX39DJMYZm->~C{(d2k8#OpI@u*``zntSc^tg~QUnE_Up5(oRDcMkGn&K*^ zuZfTRSL`^?#V-txUen$|u*wlL(+^VlG#$M0Dfb<39#1qK5TTn+DZRMxHqeDWe(S07 z4^ylf65AbqWEEfY&Z38X;&uS0ce3U;6|z9f$=UER?*2))(W2$X#F?7K%t)$y%I;G~ z5c#jl84&vC<|tmeh*}a26U&+;O`vyLTaved9!&=WR^?O^fxsbn^E znkX!M(>S{LynL!impUJXLwv0I=0I!MpgC$gEaps0$3zGl6_p}g;=OUR+WTo~o@S$b z<45&4BLs~{T>9CfJP+Q|BsF~N`BtEw%}Nm@$ge}UR)}Mk)8+ESz%;|b$rr^6QOvro zU)h2ZtsaDAm>|{TQ5|`NyiS%K;nSH_Qul7JJ0dmoe?Sd#Sg6BCe0vetEZ^BxkNiQv zx4-Ux$O1WYhia3NfdRrafW!p)31Eg)6L9?k#D&u)BT7f&0lZ}c@G7$qfC{Qj^&ZDF zNScQyvd-gZvAA&Y*zO2|EbOTiHNd|{EVe59!4?QRzK7E14Ix>E;^=j?l;(+@gE11>Swon2YtOUuDw; z;r)9$>$O*296x8QIbOuyIxy$!1*T&dJ;;qObV>^qRA~}qJ1?VL_po-O%uAtUkQD}P zJhMGrW)=0nTiU#?t$|A~A<8fuFsrsr|_zqb%Ve zq?*eadhAYtsmuxG=Q}QB&i(>03S7Azz|{i|2MU1yygNXubMWyc6pfwyi1C1$rcu+M zu&rmPbpO4yDYrj#9_Ed6yIK)w>DQO%T~AhFZmH&ApP9q8g5;BbN8(R|+H+J3_Mm)Bl_>!?n1>RSsuv6<#5FC<+AxRN&z&5qk2yZ%*PQRnY2NG!PtN4 z^$_$L(L>}HZxb;h-~YOTo; zNn?ixTTnv`ssb?4ld;pkmgw2y1M3&&a;mC#-;9NDgXatAQ@}N$PevQa{PuPXsRzb2 z&@b5A+lOUJkj?m{tz}1$7(gOucxv*95Q)T}7WV1wLrPzf;RKTrM z6`@&n<7`W;)0j`EyyyHeZl$w1nU|q-O{?PwD3x3jrtvnZaf0Z7y(;#9j4lu5EBIXK zlVB7HV?g1Ph*)0@aU_M(aSs}Sb2RxV9-5;iHHFU9BJH%&xu6xQf)DBq7XOf2wu zTren(Z?8!!y+2H3(f53c%3&~}ZgZ0>lR_sClt@;uu!Q$Mey%m~nsm3XgoUOw3tv~+ zcwm3u*XzSVaSNbJ4k?pUqD60u`yj=l>oy&$EB}kXA0P{=}~b zE84hMAthUSb%4%VL8&lwyRYUFjcB_k+x*+J$)QgN8CHL7HBdDSwftDrp3RC}mDg^3 zKy#w}(yB~|?)cb&jM2m|9d;L^!wS8tN3^sqySM0X@I>BxV9*eEBlH=TP1tKG(`CHX z0h`)$&{2B&+V|^p&kn^u+qxl4c^H=~CJyf`WewY^oeDUfFu0Bk-%xh=cFOe|O8IHG z(q%s7#^0RAN^kcOHx6xW(^)WA3UH zv6Dwe;VU&9oroE7T(lNPo|IE859E6|jx}Q<=Lz9UIW0=&bQX?Y&yZ0FbJCipuc`_% z=ZSI2XmNTIE1rIcm&CGExJ&bSmvKL~G9+r(d4J8Bsqa3Kn2dSl98`ZmhY-O>Vctm) zN`@Cr3D`gL)my!5QKZ81-QgeYzk&@|FIVkAgk^5V`hD6##)akwOku?EnvhvzCUy1k z0Io6J+f2>tceshrpijC59U4g)}HgN&{q|u7Y*wSqL*Z02$~@1^Cx&I*A-)) zWy#Yd2o9zoVU6sQko^8|`ew!uj=u-TlvfZaP?1+8NA)wVk2K8ELWQ zOMQng!X)}>@BekXIg5!()@E`tqmSjzz2Rz>0DJ+J8XsL(9%Cur zkBo>Qfr!Ta3wB_(i722#R*4D7-AgHt!O_k3bgkc-E5W$f1Myw-3Y7DsF|7ID4X6+=s*2zMEixg zZm~nOd1Jtvo{;jIg&VMe$!%k7@7%ia3&qNY zOHHlY=xE(&`oTiezr#b@LfV>ApjAw-Ka`i7sN_j$ADD!VMyQC-%O$_c~; z*Di3F>a|kI9ybX$AuK^PiVnYw2x1Cv?EIGjzuR>$aWvBCPu!ldL$!U(wQrK|lU4+N zlf9>*P&Y=_dB?NM2xb~QwvciN4dsWuTKDypHmIWoS$Z7MWWY^M{BDZ}4LTSq|Kv}v z^=S4yw?n^2C@71if42Ac=cxGbkEUc7V4~?)=gFiFJQ5}n3O9SPE9s^H!oWIuEwkVtHAk3?kLxtEa#43lA=#(e+@K>*=FM;gibQ3@crk^1#*Uf)Wvw{-9+80Twxa22jMkHrqW)z`r7X#HO8*hyo#( zb6VjmH#ACUGn?!*c2|Vg^u z8bm<9vx17htAWL4!7#8u2&BWA;?L)lOCGdW8Pg_ugg9kVXPC8shcoaEKZ(z<2GI&7p2%^wM7Q}yngoQ;N z>^A;LnYwjmI2sTJ4)euQUUPAY;hch!&@wZK`2lkiTuE(M;+gU;Fz!d3s{jrj)(gZV zKG#AYe{2R;^)%8H6!O8m3K584ynoO$1G-EY6V(k33@XV5ap2gXqo)^0{|qyy13*fE z{BZE{QsyI-&_}qqxSD|@r`RAD`c(|csi}1hQ7J6+0L}!@Na0JC)PA0V%4aZwz`KIQ z0JAX|jLCYqnws{;-87`I-0N!v%GD zO`E4fS`4dB!18|ZfC-RFfXl#Hf0JgsukQi`dP2z1qk(zwX24l{TmCs%8S)2#fClgt zOcww>gJ4iOa8oM6LY#7p?9hPk0{BSavE()w&>B+0@8M%cmIJ^D2LXlf&dIMjo&!zO zbPNm*|1)s>&*#$i?b#)=oDbG0FyZ9z94DtpXhM{`4!AdbOrc!xhcsNO&Y3mxQio-d zsPm_~vmvENFuD@7v!*46a{jX^dVV{QbI(r1nAMDW8dA~Dh6Tg(EI{EOtS3+^0*#Dk z3F89;c!q!%d=o&%At*(eWchaL;1tv|-XHm+X&bb9T1rO7rxtwJuzJZ0b$dL5k(~9E z-{N^)cnd_JB!lBC{R{pOW{di_848|1MSb{kOkiHf# zK4W8HLBOHO>^Ql)9gtg&hP9IoWTi2DyNr|drQ{G&NDaWz;=4saEs_g{Z&Imid^iUzzKykqeE zE-RN|=`XwoX5lmlOMpw)^qcPD#2kV=7g7S?`cObX5rla*Yy~!K33pHR6a*bcjM4=p z9xw%day)oGUU82{M&}F~$%>#cHQlBAI^nCF{pGm9jWU!&TY*`|E9)o{ z1%+rV+N+R|&S=RICsm5|`q|>kV~+TaZjc~wgfm5^9Sj&=rFJe(e)y~C8$*#%e}y%M z0o#u%P|IPhfhmj}W{{iFFbc9J>1|+pi~Ne?(T;0aHDYH1C@pY@nm1&~{b0 zyEun=K>sS&uig+W1Dp1efW#Ejg#c47VW#7brz|cX`+h^9(6j5g>l2$>lIO~UHQ&Ivyt3r0Il(B4GjepeX&^89Xw!6XBe5>ZLos}?I`Sxsh4ruI6Nh7m zjPd87N{;qAH*Tem^P1MCaCQx?1e#0N)ZgoHOYV5kkp_~?W|h~pUWuG3HcYEvvax*^ znum@R4y`2=*KY*dlHxQPaJvk7m-~EeS;f9zDXP63Vjl7OmB7)0Fs8eY%v=%om7^22@b(O zW~425+etq#qk0;u)%Wj3wkTW84Q$6hLe!*6dM2&#b^y~T%R~?=crD(GPT2WPuMHtzdW6ZSC{}4B1k_t6X;`Mzj(jn6e5%IKFyrXv&CCD8s_9n(V~6*H z?mq}N`9`-#B=<^7DJHw3jK;RlP|6%~q<*YrzxLeQz(C&GQT25-Y6+_G&PdM3zIBEf zOWE5ggAzsiB?>cXEaJ+zq`P*y0(rNvR>#*A1KMA=cP74KCTVe^jJ@%CsMsyuuYIA9 zX=9}$Jt&$dZ&4`7XBwmWF9J~1__a)}y+aoQ`zl|)jNZ^aubgnTPMNTt;c(BL4Btrsss${}Y-Yb^FdKO$U7l$gZy3 z=FU!>Dlg*#cUI|%1f0LlN(2+4FlhyE9Mgy-`e9vYy`B*lQQ9-BU;R>I4YtL*MN%;l zP2b*6zRu(;q8nF+pvs7e0<|9;y&j6a9^WSJ1mp_p&G1uO1>TEIT-FIu{dLCZKqzEu z*vI~r*@RDjiOsN)u?DB-v-%loWQL0-d-+iT-bQZ38OJ~pLfr_7 z%nyHyl)~UPzbC)U{_JvPNbIBLC;i~*RvRN!$Xk_k7&a~f;Y2|}!2#QaY#JB^WMvT& zA~0^l#sdGU?*lBAtr5(XJLBEU+3WU>nDl@GQBn(`a$3gF7Xd;%7|5Ez(40{gZ}LFh z(CX5F=Rv6y7x-eyX>w!-inmvqN&UO>&ju!FC)K$<=jxAA;{SQJfp@!P8?4y8cY0`X zBY@m8^ZE)5;B>JCU&F!RtL5z59dfp00LJpJPCw>rS0JK%liYE0&tQMiTG;GKij$ok z0yZ1a>hUGQoPY+5aHc1(<9`k#DAOZ?wSpWu1Wm-3voyXal0^6tTl{`HN}Yz)U%uci z7)kC@0fkq>iC_MctqKqMMYLmMkLgRmj0Dk@Wcv?{JP>TI7PL(+v{8My%hF2*4dd{6W{oSlVCBNeAt$tfZ{W)EhFvAj1XTn$jfF)=LGbCta zDe})o4a$Ixyu>Ik+T<=WAFMVo_Q8&BBi#1*7yxQrqJuK~HU7z-$-$%AyRWwZPlo=I zrnL|J-*sVPb$~e(8H4__$UfxPZKiK*>#T$bjJj~ys=G%#x8J@GN~NQtBVd~r zjnVjd_V?+Y?EJURk1Mz2y%6qQ+^NaR>sLFzO{rYS* zUb^6&VucR%CUIxM)d;$_Ymgv>71+*zTO7c2tso=@vBKT3%B`t%a)j*rM)h_jEZ38y zK~V>GmtkyitNrg^X}Iwr-{gJxKsV&ai9IuCbnW$(R*kYnG#5s@#`vEn z_?1BFFqQfNtpTfsgNKJ)L=F>Xs!7+dqOx+Q$5SC8ArK4@fRHBZP+_ViF9zUv0bg&L zgp*E}KRPnf1ZFb`0D}4a!n1E=vKa0y$XQO$mn(v%j*=&>l79dsLzTG`A!kwEtZSL*uO?3Kf^r!mhA?a|#W%ichwzbK7PMUk8O&k&eDtOvq zEiO08JDvni945`JNt;DAD(v*`T3XNk_pM-m^~6k>;IWvog@TzF8O*wY`;G4WF9WZH_Z%Gxv?hylT2BD!Vw_m`lIc*N8-6GM8V~$>c9);H!h5 z*Cl>A$sqL-^}EB|_i;YTy=8^7s$w5;R8NwxT3xNDo$>++WsV(WqIh>QM@coOW~aQVGk0i8#iplnF?w7pkV#JJUTFwP%y*&0sp``VkDf)E=)Wt97(6oEhOpVylC57}X!EBCf1pj3ur#YN z)Q7gDR`{s3-T3~}p8;K&m2scE)peDS#u-w5_sXduI+7&PoWq#SZM*U?(!3;LU$ob( zbHzF5`i;u^n~zSgeJ_l>OkihD=q*6d3l8jmOnd*rDyGr@NyVekeLLA4zGT!8IzaZY z)YGj3sUlvT?-5}rOj7UIHliy38g`h$9kI|l@m{X=C;E5!0iVyLSB|oSVRO*X=*vtV zX`2tx10^ym0SU4QDSHrrj*tJ`!mN@GZ?c9|Mz75rD)x^k@_dsfsPYO^@o5VZ3|hy< zsXiqNov>)s-1)BAw3gS9kWj(t9$aj9Q~k`}VmfhC&Xeidf=osZo>PdiZN`d;rj|gg z8E=?}PA38xi**D9&<#q$nrQw-+YQzqlCV+Dm|lZABh_)zj)%4G^V5i@tNL8zfpobk2x z4~;`z9`!rIPn7;K{iqVea#K{zE!?_Z*QrPA?*Qv}>x^iOYt=?t(GW4yTmNv7MVJuc+ zLX~;-6e{i%59~S=d+G_0zzzGyDYb-*h4~$Swdhmi|3}0B{jDl?+8lQS)sD=pYb`Dt zTGUMm!|(CLbqCdOClXbf@bs4f5KTJKuz><(X0%evkOpODrw zSyh_a&sAlnqnHVQw(wt#YZ}}cPPbDkYm;&p-!bDhFS{qZ)~;>{4$-}d!XI}>y1PaC z=t@lJ)z!25IL5w{c1Vb~=o)4jwL-;h6L$>o*XuhRoU`NFn0zL={GEx;0SS(T%5c4(#Q|D18_I3n2f8oR^Flrl}M`A&`CTVUySoy|Mt9qhvXrSD>#L1^1_1Vli2CI~` z>FutXI6%t+xBsVy7A7Vl*rYV9I(`|l|6~|fWpKF8tcCAgpfnD{lu(x;CIn8FdQHtq zSbb2t@1c|!csqUdujY^TU3aRwa&&lPuBDDUA`3|?5#X$>p>o&bNr(aAcmZpXV79T{ z!~$DTLEfn#Ek&~+J_I`Y7>{gE8I4%iZ|#Eht{}4{Ou%XJ25c#cs79nyFulyyC@_9q zyR`;Ug36ihrySQ7r_xs;x;p&zU|^R{oLJxEQ5xJ_J*d6yy*AC~AeSqtMTtVmVO!UC z+C|X@x$4eOO|g53{s*1(5>~;^JVw@8XG&Pcp-D_S!JSZoT>pL+U8kHns}-C3&FG$n zQ>kBICe(~-u4wg~HIWRO`z!+v9m=l@y8e@aHyqsVPrl!O+U_6Bsua^J^Ch1R+w)@13k*OOSMdM@rSaB} ziktiVt9hbv0%qU)(eOd~KMku?Y~Do;eYDr2`fDQ{tncyw?T4_sb^*=F{Hn>D|32)$ z{jIqe^{~T=lSo`>MF>ogtd*}b&KdBOJP})+s`zj(E$#FN(%-FBSHB*jw{@uvO7&=1 z%}8%v-}@I;c|Bh_)-U{+jr`eD&9<H% zPpg}wH-u6?jssBB<&1G%(Sd=7j15IhD#QK4^s?{sh4(?-;JFC<0d@^H3f1UOIlxo) z%phkK?)X}x+M&P0nIjXB5p`&H(a?CHX9sVSEK3A@ii3jyN#=mckz+8)fNaCw=Z1R# z%R%l?&~o5d%R)s%!i`YU=>HYX$ULqs=a$H_Hg`95n1-Gct3iOkka0-|rN1EP`3;LJ z0wFK)zzITVbl*dn2)X8kXy|!1Z&MMuqDam%R4=U~qvVtEwtIphtL&jnWCRn!5`P7) zohP&O+cBZrF&(IDrMz)%o!&h4nj@j$o`<57v6RLPz<-`oxwnAbRS9Yso2je%z&I3< z$~@<*YQg|rBI+GAijwK{;sWim?-}J#5Mx6I|F^%{?q4KNgk*SceqQnb;*el(5>k{3UmK3bSAp7=3P_PYTUrle zxQ>nv+)MnBL3Zb3Tpx-L`2p_AX?JSqWralKxLLKYr@JGnV8qX;WB_JHr*WydtjNY! zW(fe?8pIbFJ%v~r?J~393lKTe(GK%=wEX0zX`1fcl-Z_2L&${N?Q*t}w8>+Jf z#sml$b&T7H`>Ud=`f1--|KsLq6UnsgU0+)g$B>`OlrZk)-ThLBlK$eV#GtZcUoUx% zE@(z0D);04#Of~e+sY(cNmEIPK&|+FaDszJ=mBX8L?kf!f;yz6_?9(091z?~fvL;F z+WP9?2Vhb_w6Hp?^EmalZxv#=JUS+3L;H?k(_{c#%HCdF`UVKHVF8ly$SvEKl=Bg2 z(Z9Z`aK}O}psCImWv2eH{X0I%1Om0}z~+A9`VVqY7qs4ka1!pY1__ool$3vX^8oaz zyMDea;A;Z_h-AJWBq+pPfX{*D@K^gnRQ%Vl`POkPC1k)VmN-kErn!WaKEWhi#q#g| zreb`XAbb+Zj6T4@aBPrKC6Lwa;P1cvv1m6gTWaw01=dPBErSay7a}Q%6yAMyX$o4u z4+2l|A6shN`q+eLpq7kJZ$noqm;Txsq|bAsdgRfFqUvRp&teKh$+h&}9($9iynCSh z_J*9R#6o??yzfok?z;>}V;T+6G$(g1t9{*A{W+-e74txEsVZ+z=!1(bVPjGXyMFPa z_g8j%(}<9#ELW^gD-CxEcYJjYd-!v!=CaOuzijBhiWt?Xfls__|Q*VxA)3we8gkmw@7M)QH#S-%O{F%cW zXonYXPlP|-tMtw{%InjtJ~m4VHsF6~E@f=K&3(Z#(IfEr$RkhR{9jDFtoEM=>z*?@C2vqN5@_lhQPz&MhNF@PNE=d=F26dz_A7jE@#e4o8FI{Rqp zb)n?-UqReQKW|-@xw3TkoJ?_|OF8fF#KWZ{kGf3(z_7KyO`;_xbxs|j_aQ3eEAuDu zx$DOGZ+yG7x)r*`ki059YFXrVjQ4whzHtBW*tPMo!<}bueYU7pF7oR8;)^h9S`xyW zDY45Pm6o3-Bc?*5ZUv%3_jE`7r?0S??Bf5#l&7?8eYXmYY>V0I^-xeCd|eyAqfUQZ z5z$}XmvivfEoW2Bzm6|J3(K)dZ2mHQB?IcFLltQr0QOHC}nr|edN&^%aa$cy=pL4Ju$k6IAsw~N)fp~ z#CJurS;o@wxZqS;msM+Ma^sY99^FD&o_y?CIj0lVGuWpUQXTU}i>eP27WvNQ*nUrl zXt;JnPE4v~e`fe<;bwlonWo?Sjf$9bp%2GSVa=&K*y$5!kjE6vw=pZ+1POl0m2M>m zGm(6`{U{%7aZs+#DJU=>U@It&d~W>VC*S;%%4J`hL0enr0EJ0x)$M2*?nu&l2J4gN zKXRR1F_AmG;p3Enj@Epf8(;2P>^6I!iqLJj!-?cc+vm(&2=27~>MJ-Iw_g(W>EX!b zH9pdZ&Q`^LXD`f$JR2HY+L@=$8F89@06=Ln$59S zAyvh&>hWW@V$!s0^R`G}rP5@jp_{~G(oXFkBW#(^fnN8#c&v#Ioaiia0G>5Tw+oqIPt*?BVaYpk3{QeQ!bp|Kz9OP|dRs25rUlDX~F} zfT2k#XJpF!?oU%OFkooevb4Bt-Ch^SSoQv8;+dbi;|t02E;`iC!OVO?4e?<`5ny$o zopF}4>MH1Sw_BZ%G=KQUSY=k5QdLnjm9~d=e5ocIxC8Y}YN z!sbpa>Gq|{hJn)+M~QX_WA9P~){I^M4xMnwkAKv0FFec8*#!I%tS~Ch37@pdW}+VD z)YCzzh%=_b9#&%;jbQc{qv z@Y^({=<5AHEkMg`c_psTk6XQ>kX^l42zO3gS&k7ok8{;|OfimYRK;IHxNs-=5q$5L z+s#Ee%iX%XOUfJ(Lq~qi|8SkXlurpV_M^;6*tR~cKQYXD!pJ$n4~e_4b{CCwe`Lf% z8LgQl<9 zuby9sQAiAVJZGexF#6BMfooS@@;Yp%&%QyuA6>Fwv>Z)9GVCD*qe~9AZ?o4g3uSfR zw5x|0nBd@?5oxk}w-eyv%Bm_Pp=9+bWPktsc^~ZoMCch^-BnPXK?dXH8;_njN?8H+ z2Fb(;lLU#jrtJ?NPD&&A942KB|H&YUpTX&mR(t&BiJ`+?L44RU3CKe5TEb2S zRkR&1EZ&9*BC_Kos?_9kx<8YSgJ38H8(Y-=;w7Gd{#zrtjH7dXQv71 zR+?|u-xQ=ej2rzIHgYxCboVW6h~S=pw87uqC&pUAU;^3z3S+%I*fFgb9rUV}byPK! zm7(R@%FyBWV`|l~o7ik9goDEY3SOw|G{A2_e*?LA{|tq`1O(No1*~J2ZgJNyPiDI0 zHbJ&CIUi+=>;p{zw}o{2&rM;V$${MU18H2jP2FA48GxtYH$X<@tUCAuQ2A$C{}tX; zWqwNgbF}7CGVGW@($`#=_dzS2R8{@0By3ED#HRL3tjuZv^Q;}K*Kkq4%6fDQ>Jo$a z2wY!HC?NtT0|p0x-5{wC(ssz)Akg_gju0`*kvFnv$?@mF@WN$iEjl#?1SZ-4 z0OnO-gu#mNuKTPQU~icXz_-HHWU}An=I8GK$s&e|YD5h1K|oDm_9bg1z>pFV5dq;n zOiH!zQb25yvjktfSRH-65uo0jdMf0>r&Fo|XM}s!`~xB7rDCWBhBCy@LwKsHs;V%+ zbR~2pg56)3>(svBJfSyMq&dF~R{$H1fb$EcnM}qs6Q)7Qf5qTh8kmxnk%1SMJ!uaD z0s#6Jde+no{odEt^S$G%8oi(b6DwRqlC*;+O*qldsJ?$N#pLc%Mo5afsirWVejm=# zj}uE&w;iTlE;;%6DgJgWU4+-zcPQ+W^$@iYK4xBQGQnC4Fy z)~`TD@K^=?fJKV^ns0) zRU}RjMe}QHtOFDuFw?<`8~Fkjq5qf6C@l@Z?gWG?Rx})_mRtc+c-*(;M%~5{VCsp` z;R9;n3375cSVdrAgZNRodl{@XV`6zd;GS{x@maGN%~KB~$M(l8lf6-P(~77!{bCzO z-HraWd}a3tWC$mYX0{vF-k*C!t_vjVRa4jflGTSDLm{ch@b@8@ZF*c;AIbSujia#?^hWSjR#0R`HmG6tOpdba` z7Yb7hH%fl07Kim-FkpElilquig!M|`@L>dfz0(p3idhttb|8WK_IOOfG(6*inetE~ zT7$pA%r45hO!2w%cBx2oW!2-=FXCu}pkX=fm4jK%;P_j=y~Fy%{RyXQ@b5dWTMZC@ zB;ey!yxo+pq=%$Ey7nCp_5d_8H3^T;G!CCp(bmVDMmjfC4xdzh8`|HT#ak+d!9}rP zxw@KD*c#apiFad*QHbQnEr!D#2=TJKAs$XV*4OKzguZ2I7{#Yu zbn0C7{`oS&?iNc@M1+`PJ%GSx6Sz};ojY-&HVQ@cgfqme%T-6Sb@iIP<(t9aS=;B9 zwENNT|32IO^>~?|;tK1rwwSwpND~5eu_uN`d$#_s1@YAU3?0#HLoi@me0y3Ri$W)8 z{MGxm@;5M)Nwdam^GmN?Ctk%aaIgC8cd{GC z*l!6qK6`S*QjEfB@>*)H!VB5W?@NYl=hVX;k@%2 zJui>uc4T<>V6;yM+p~J`Q085;+zh7f5V)mJt(mm4&nN$E#M5CR@|sAqpH@LB-KO`n z)#v2(ZM3BD5aR>+mL?l*f>yY*5i?B^v5*xdFoC7-rw(tFm7n*fqw(Tl55YD1S#294 zI<_YC_`|-+WbV{cNbKW&u;__T5U6SLA}1fv+fOw$->VByd!;LUEx$5k#5BgyhtAOS zsugddTu^4Lp(j2Acj11_U9*DCJ4w~MTs^$cO>&Lv9pxK4e#m&#;?xE;b4>zluF0bP zHSA5|KhCPBnFtJUlO9#3?q%)XD|=Eoqw(n}+XvRXI_L5r`qVHj(LLhHf&7Zk%5HDIc`E@YpaWi z6%%=4NI%g(MM+0rTvc;`xUFH){^=&~(!+3Hs}_$19eKl@Cno(Lwg)ab+TXvSppfNh zg1n9pM%fXlol+Z#jC$MCZpHzSd!4vw$DHZGlVix6)}jMXuiUSeg;Chc`bb^% znQJbz?b8wa+)%{T-!=k`W7!7s{<$roMdGA*=hxS6KXSdz<@K9zd`>VIx0}g^LNTBN z5M0FPC_@Sy@3Z|ok6rl$pU<3FJKf{T=BsLk6z`UqiOt9q^6i@w2Rtf&q|5%Pm3Dp7 z8PUL4XWrQzB2B`1Tqt(OzK66OGR?wNs4d~Q7wwR}$L!InkwDV^`6ln)Ld|StX^57D z96qUs5ue9TsP-cUtl@HpkoozjleA&ss1d*X9?ey)@wmOB$e$f7IiXVCG*Qj`FfBlU zFOf46<~X3bWI+rESu4AK<-u}`1cT@P_le?Yb-Qx;BI$M&m`ETO=>`G1qFCz2ZlMS zQSibfYTPNm5(Qf&*K%kntR40obbl?lA(+of*%T8U-Me&4NNb-QUkCAm+gS}e+?d&< zeMm6>_29Ik0A!a46t}`w9Wr$(gpw?5g>z0;f&$;oc6<3(8z5!#8v%c;Y+5nOdXAxt z>>{WCya^7;;1c`c91-toTRn2B&c?+Hhjama2cC+oihKP!s;Nl}`1t>+JqxU)A=ENE z?4sEWh`Gp99H`K;>ubQNY9&3%9x}ncvRK{o8!RF)*OA+aR{-mrobJvV{_z7a&fjLq zXl)UKDfAF~#n6X*bgl+O4kC7}dfZ>rz_<&-ukm9jE@lvQuX@PhMyly;9-CeNdd38> zJ8GCt{c}44N~oDfj)y6IJOg3Zu~Dw>?vkk7yB(8cSS_o1$%>p~{sr*_uvd%-Q%3um zn)FHQtf0T!+y3Z$-Gev{iKrRC9s!t!VLbgBjNqVwC5y}mXKR0wJ7@rq0`E=jPv^YT z1|~(J4tHK6^^4>ktN>VTgez9En*$;>PyoW8!%ziAk@jlv@q(QiRyv4$$*I>cT?2py z<2<07UE>%8xNFFoL4b*?RhZA2fylSPopw$n$B_RV8#fvW9DM>Z1afL97)FH(v+0;s}Uv>-( z%+fNgF{&Y@SU&;L@INc^Z5p7c;Gl~5uZV_dLIa9CWuIv}a!d5Jp>hZb&9|u_3j^sq zUJNae<2}iv9l4kla6b@vT*W_~xwHM7y@5Q;CNAwoFlsb{j+7i51teN=adE74>_$A{ zJKQdW+5X9bw&^YjUjW`ou7PU)R)OC)j}^Dh4U|lfG~kfycfVB}?;Y{8Ca*&asedZy z`I-uK&`Lni_h29dEdt^VlP=WEtXMW|Skg@g3TkTp+h@GK7PO>%j;i<;-Q|1YNmr?^ zh%_w8(8Fw<2P+zag1yu_Y=93U(i>3D7JfuVahpd@*&3fxPE;9>n`4JXT#_} z^PdUH>D5f6)S7!g@xcg>{)U_ge=cnON!C-;Q)rq|;M6v!8~YWzN}|o)knI`!BYUxN zt-JT@<)&I4Nli{-iRbx6yKXjl9Q~Rg8eFzRD=t!I&-M6K@#bw+v6YQHPwtLUst=eW z(&4n-dsi*oc(Sx&H9dnj7tAeGY2T?}SD32YNzdxy+b`41|8uXdFBcN`d|G(9HDgNm z%Kk_F^H;-|^6kR+H=Fa0BR%yg*j@)-{Zxe8q(Awd>6<6E9ZOMt>s-v~s`Enk3S(C) zmP=l^G|j};2R}Kq*f-?hz3~3rNnVNSWCBkuX2jQaNl@`|;~nfYb;~>*SLOQWgD8*W z@CBx*vfi!IPUm4t_ySQ@`vF$ACcARn5()9|4u2>q05b-$iMe93#})3qcmcWj&-7X) zxul8}I?rdtZJx`yMf>^OQ9YOA9Q=89E7yv|j#5hSwq~Pm)jZo~3_S>)+|L?|@jXd& z&9Y1Q9WqXZ+W3w#PY>ljy@NXV99k2zxUrQqFDi!p0N}+p+$sbV=Aqo6rm#j3AwUm%=F)N(d?s=n>KAzf5cjQ~8QY{pr{ye>7;<4Cyty+f9Ht6E_3Y%>b-&(%TCp_ak z_ffj|tnFE;C+}};$YH(*o8lVoD%%{#IEBs7O}xFD=p(y!ee98A%z*^4ik@Tq6%s@B z3H2peJt8P`>P8gt_+)Mk^|RF%@4}q;uLhsl_2GBSOzm{WK;-)RZNrzjc_%MlwrS7X z`^4<4I)7VvsPb@k^I$t_Zo3NlFwl_9z3Gl`>!yqhe zH1VTYjy3wYvT`XT=+ZwsYN`C=hSnr+q;uyPgAx%|$)F1a@z&psWtm#pwHEDvoT$HD z;bmNYVZS;#5RrKyXBQ@u& zPb7ke@_cTp&#CO5$}6^G`}A7VVmX0n6wuR^Nexm;kN&`0Y2ntlt7ev}VntSD4~Sooo)` zM`&kvcwc>IQ&>R0_asnKtG-*t@au%c{=Hri9JDK#FZIOlr0Cb>W{ri(iH>83iDpJ3 z1*xaTX}7hwGqvbbb5t*C7hY^@--Re`?iJN1{7oOSor9j@?CI_eUJX^cl{sdiDjen*%nfp0l|jtT2XP)SQGW7tA990q9QX@l7}$k+)VFwG2Zx;PRdQf5sP#j^ zbIxW}d+YvXyI8HO9v)K7CSP3@GRh>N#t%G8U{HdhX23KlzWRCquSp;Qfe4P5+<+5qHzW@d86{83wczyN)cq#A2f#$cUcW-Aw!c2Gef#k57-V%PEV+SI1P&+l z`*WKLN9Qy0J-~qfSI9EdaPVJ~FuB7G90&jLzH47jf(r;pL3k5z3{X<%WL~&7(*rOr zImLub+>KKZ$%TesC2oc^Zu0yK`9J@2H;}n?3Xt|sp0nL$mKU^!#BunG|BMS@C5AWt zHxC4$zkSO7!u09CKFb8>rTRCH^c60Iygx4=pCDhNe2aw|pUa93n5CXH!7EQfGxzDj zK5|#juh7F_DQRhP-u8&cL(VObN|Nrv4G2uR5Y>|ZU&$c3;~KzO@UdvA!h=Sh^K>-9 z=>t>~5?a8F4Jj_<^#>>^%x4fRBTv+qhyoFxygc8=2&~HBh{peqrmFy|YHQnobcj;Y z-CZIe(nxoQbV#UlDAFMzotN%zP*57AJxGWW(jfwZbo0M_GymL~J9m_OID74V&U)7K zK9O=G@#Yl?gJH`2$rYll&c<4HwcXC<#WUSs55G@5nHW|`dtVUPnniwc{W{dA3z%Wln7aiUjFc~yR6#wRg(3 z6lII~fTeJvHb9ezkDni8$e3XG0s#dGWMThv! z35OZJ_HMzbG2*`U zy6HJcOM+x0H8r){*l|N6qvce;%~T>`?qnr*QL05ZI1mFNJ1}cm)b~Hq&*`z22;DSEPE;9M!@oE8;%v1&h*81~Fux5* zXH|+sFzjT8nm=fLaLW2o9>J%K-thYaog}A6io8)+pxa1DUT=_N)@KbW6Zy;+1HrD; zxHt!d>(l-;o!VXhK2^teOq-B}I{Ik!7@px=#s^vpVT3cbBPQYkuh$-YKxflPpn8Ox z*s`7P%0tTahAqP&FnnaJlx{TJet}tkUdz_?SA%o%ME$Vu{Xjw;y)>IV{Vf5^?}9`L zig{)C_H{0lvo55byh$U}O^|x=B$%owGwfTv2@?gW(c_0Q7pP{R@@l?L%N!E>emkj8 zy>G01qufF`8O&{D_g0%oPJGpfNEm??(7H$2lTx{!7)WksflIN?j$y4~K)o$_6K=En zWV3er;lO^QMdj0}uqJsy z?J~YXph7vei|766UlM$_pco@!MHuf@3VLq@{c`ij)WlmTNLyG#WX-0P?&uCG{4lcC z{3Ti8@xDLS|NU7@>e=U;L2)zxFGz2vI2={(GH=Q~x!!HLNsN`3Sl0jHmv!DlUV*R~=qFe4I-?mR}VJX*xVHeRLW-u=xc7}KJ0 zZ+=*XW7PA`$`qLLa&D{#b=ep4JmCqwdea;`KT6j8g4MB0I5o5gL0f9VDqq*eIwh_! zQ}m%txQ`V1p^Sz&zWpCc)h!g)gYrDT4P4%0TIbU{ck4zgYwFcz9wvp5w-|5y&&;v#O0+@WnILX>j)Jhl>7q$;tol$6p*RR={ z`S05(=)Q70aU$T2^@&*# z@);XHuB@US7ggvabFy?saIg&fl0I0Xd-$z3OKPmeJ(HWr@+rmrs9`IWuR5EVo@a?C z9~ICS!v_O$|6dD0fZw%Z!hcnI?b6ZA^76m7Uv@T z%puEZ@iX}OM34145#iCe>wwZj;~PvKht_4WX`^>MH>4|(-f1J2D$+!FtVy~2C~Hdb z@eb)y;~UN23x3r%7c%M(PVqSZ9Eg|23Jzk5;1a55WqhZ&L&*Pb-;l?BKI_@qD9d0& zY=Cuep#R^y7cmD@!v2{PIczGn^!N*w&WCB4+-{qHaHFCGoW$OC_nk9isD@LKW^x7n z8;!u8c90;OIg0i2$;r7sYOWEEVIzt9^x<6WYLTs4hrNSN%~SJ{E28XNwc@*_ySq-$ zAI0Vdt+K+-Tb&~TN$szf6$Kp=o3)LNx7KiolLY@TxM|49$TXSCU0YO|jK1IV01N@7 zm_2I+Oql`3xmqBh71|4uW1|{4K9mTRmg+&qb{=zRYWCP70Y8lI{vZnwjvg~n`H_^f zTSr76M8w2&(Bi=fv=b@;Sy@yxcgG1V-$~n3F#ongCw>*}H#4 zuW6ZhkTPro8@qjz(RtR-I97Q@;m(N(?WS;trt*LozOal(uN;Iw0OlVYj0hvyIk^D( zyIkf9-~zn2y&1%C*Msi^94=T-SYoX3elaiJ`f`5%R_M74MS=JF z>r9o+ySmIFR_;EG-2uym+Eg}?2WcjKW^65Hb;J_$@b)hKKyUt@H8Fw;>ymLuX~)xe zsRxiY`~pB2+8&jlF90eQtT7aiUV=TY8!+hUh@E&3hzVf1Zqoy9*I@VU?i+w}g#C3W z`6w0f73?EZA0rZGnQeie^Vr184)GReVqBbOOuaK$xW_e}NWgj!I4ZTgp5i zKxmVZZd$ET6^f~x@+4Xj%`D8vMN-2I_be3Aq>108yiRi5+1@VQUjl>)xC7fUf(vOz zKjeh=TTZ6->((3&rw8=l!0ty- z;bRqzk}qL%0@m{&U756@V-d4G*U6$Q!bR#y_bTD)L}P|U7$vU!a=Ogn zz^?sJn$3TcFf}FRHi7h3$N}+GjEdc0z;d65I|oUoP`Sk`Dq5~ll=Rh{cM)PcjCNsa zvG!fx%*Mkb86H{a(t%q8c`UWHwYM)h0BS-r8%TTtvLDVR-TgHFl}quEB{mJI?klkp z>w9||7vxsah&zy-4pIydHt+PW2p5}hSEwr8FqOa1Qp@Wu80i2i|GR_klDEB;>kh0M zfbIQYWRdX6_oWgqU%X&bXl`j4tht)0DSIZNF7agZILG(5f0gK})7RV*$w3AJ7I$jy zVM2Z-2FSPU`w(~<>IwSZg|`{Q-Sl&^2)Glh~S6e#prBefN{&s zsJBb;`*(P@(}O$|;VEfTMJe*8h6>4p0~;((k3^p;q>gzl#tR0;_xiAV{G}& zN1lc{zlhgYcb>B6E4{3){E%fLkDOp*4ZFBCZT09@oGQn&{xbH>ICHL)D zhxsSri7vYGY4M3Z;RMF@MD=T&b=#NwUf0LeuUh?N>8Lem1bIn?hA5JpB4VFPSQkqS zFL-ags=YFYfFcY#uuv(W(o(Q$*iMW_9KGE-A}!pyAS$9XQ9ze+TJb0K-?+H;QAzguDb zYFz1dE=^f-LTTq3o|r^98xq_& z+DeG(V8@L&Qup2{kGsr7Y8m}T;(eWcZ*f%o^N45BiwHCfL<1-1^I`<^T_GOsjed-D zWt)SHB|b*da24@bg&hBED{We_7qKlhVe7)oVyv@|G9Rt?z1voPu$|hWGdD^o9mlCbkE44Xc8x(L&HGgGy95Oz#fOTySfN51PecFY=7w_X!MMmQRVn^m zJ^Vgxtx*25R1-Pjsx6JLT-us3u5VunPIma%)T7^A^W4mcp#Pgl&F-<@V0kNqUHo@+ zLfv!UTn^m_i}bjM(*Jnybi3K-I89<_H3u2ZJtqI1YfMwS_1{4W#C zdxNvUsyTn6pJ!hoyXAFhzJTCz+9x&*w=h1-zKBu+Z5CU~9^n)|0&?M@yV!_u?MK{w znw|Fu=_1VtS|7hH!nQ`w2z%vuJ;P1!T8GcGOJB=iP9a?G{jM?u-($MJS)4jonf8zL zBnE{xdo-`aqn@E6d!^)%_f0Rdt7#@gkY%FX!gQj=@HU+^t^`xX8A3*{H{UoyeoK6x zci>vG3v)>YTqb^E#Bw_E;@2f)2}Kl5^bGN;1;LcMr&)FX(BGe<_E#Z)e$3^Wof6UV z&Vr=pZW(eOq z__?vVNc4!eck13Orqx?-HRFIT1?i5Lb%b|~-G1gXL{LSz$WCe2x*TUdYDEw*Kd640 z`NRKmnkoI2QF_f5zPt+Wb-FHP}Zo+8=(my7Y{*yu3U@%*6aVEey93Ge+QV^$);{9OO-!H zD0o`lDD*F!oJt$CDG~Y1+U&{Rm#2I{&WQQ!-_pRL(zjF!aGn9>eV9bnRcnWbL{_-4 z_bDjUv#4hyu}(U>yY~Xp64mP=3S%G~z`P6!VMWD4<%f<&5ZB$R?xu`>%{w&l_Bp?P zU5keetQ6o?uIz&~z(mLVNJyyJbLYQoW6G7~xCgbWlzS*egQ!i@P7c>= zGkJG>+}yN#Rw3;hru}5N=nktu;I+8kN0O#IzNKBEb`LZL5GUk)e#qv3+3#P8@RH0c z;#JRkuRs=p?F{WV|u0l7J_V6cc<=u;0Fm)J*G+E2z&&s!Doainasp56CqS z1v=^<{vt}B$YZf53FxWEZ1q7OkswxEVR3Fj)Af!mXhzld~g#PhQFhj;qWP~~OZ%>hra~(hD0S^J83nbje-JUh5V&9O~iIh&83#KFt(@8qV zeqq5&`kZy<-g!JfiGmiwkUN!l|NejsdKKJi-B`lenYp=1Um7YZHc~dl^9kPUGe{~@ z6Hy#eBx*+$B{onMr&y8cM?l@6yL;ghr;W-zZ_;n@TJek;g@+sC7z*jbbqVSNGrhdO z89Q?i<>*iuuHp{M2#iFW@Bs{EW@kIld}wJY)5wm-v%tPk){I9bavg(!w>JT>HmGAKTwTZrEm!Ki3pX0`!G zhT8zt4XE=hFGOGcqm%oSH|rypVuHym{zWD40uny8*f-}sgvj-2><#G#B_!7`!_XZp z|0qCod&4Q91q^W@1n}MK!hk=m|M(Fk63aUu7uJ*YO+n6GUsos9Fs<{Y8tB;DyCr$} zdAEHS=KOF;zK3J-U}rb8aB@=l{uf3u#KlRUW}wo3Fp)*HT~S0?g5{VsGM?@y(;7qh zi=)@ih8ZYdb?+zMrl2=og7FH@K(D`o+Z~=NNd8y_8S-miZ-hqPF31+n&dz9Fk8S&$ zD=ORme)fT!WvhU!l>Pz@hZZ}=dLfkiVWMbw>jSmwIFVRiS38m%{td19uN#M*PWaQT zwLg94+gt0U*WE`S-}oY;D;1tj%e0ww)*Co>dSi|b1_dOVWuBw4JUDX>TmJT*9tW}7 zCoX?1-YRzxjj@A^MjA#Crgo3o0#WtrQeQ36?!s8DV|-*e{c6(`U66 zqF%(^E@#^7uU53RG-9Q=K5x_4%Sq8{I$$Bw$c2yZ^rh#vOYfx%-|DEgk7&z#~qzmC)Q+#!HPt?XjAF)kmMa@otyB3vs0?V z4(gBXT*kfzgpSc>&zrPjxQ(+$lRb>knGHh5EC+^oRq|AA-}X!!;hvb$xTk9*+Gxj@ULPl1r**s{l6lhv&WquK}zQ#RrIOxWh1 z-z6rJ?A{E14p<7U;IRzQ7k@L9+Tq<@bA|E7_iBqv?QxjCgqKnsX2-u1i5?7^>r~(M zFaDjsf3H-AzgPLQx=Wam)|U0`dh=t4YM#O3(IeA-5qUc9hK|`~ulB1qttV}>xCvIv zmI*du31Xs73DC;8kSBCb;J+*JYsoF=aj$G}V+>wHo5<5d^pmH5QDSP^E*{>c`TK3x zv&+cD(q*ty1~Ve09#7g(G^0G8i7hQIP>*E1HpTu~kz1;8%y_%dRGos(g0&a^3v$cE zP@2Q7<}&QW0I_BNdx?+ixA<9|%bn3tuYAnyT;CtcB~9!6o{uB)bb0yP?K#A2Fh}w; zeeL{@&XGrj)xRg6%esu@YV3W> zJuH!VL{cw7fY4RaMy4P1iu+hQ@=T)^1uJZ&)!+8%)(|$Y%+C{yh5&bs$b43e1gvJ} zxI`kUQepbMo60Dn+?f0j;YbB~8EXc?kvgpYh05JSE13Yq`Ug9k8l=zB==NEmSBZ%5 zMmGv-{02rQ_JE=Wx?FYM(+$pNTg>HvUs+SSkDpnDr_IA1Y-?J zIBBTyI|T7@{928oBdr(}Sv%W_nVVYL&AIyeZSd&)Om&=ljcCbmQfR_oNH;)PHkr>E zm3fMwh$oRzmRW7K@cRv-cxPU5+TlyF+RZ)I;hv8u$%Dg&I1%B=SD7-4^8O6t?Ul+s z|9vLn?HT3bL?6TbH))Q#N!cH+i$)=0dC9c$Gl!#(qt+JNn?zogD9rea_bi?x%fnNH zNzd$(jm`AIkMbSdnNMcL)g@ZkPzQUxmcuXxcimdUi|gxt=BUr-JUY0DcNKN7ZfH>4 zsIN^~a}C{0C+C?y-K`mOK0~! zW~v#fou6N1ux+?J{s-@U@9-5p8cHJUczj*_Mc>k4>%|@ldA?|!NKUSY&HtA9IXH$7 zFR)_ubM_anMKQi=qrWAaVOSP!mdH90&dSJsbT_B0%6vYR^mh@iRzyhgj<#D2IUgE5 zInnb)gU)YEOKI;Ia4&?jQH(nS1&Ew*gXyUpNo8Xg_jw!rn?0L}v`}ag_`4;<$@Dva z(%&oELb~>=+zfJD33i$aU=Kr&u~$GhKfgy)^o9a^3{#shiU_BmQC&?~?D@nKkDpTI z+*D+hbuB(MYP8m-YpATl*%k!@H{SUMtPqsR7q6J-LNzn0>JxB-@q*`mTlLziaNc)U z_gOionkD4Nmb6`bNQveuK>|Xjs*;!qa-y$1TE3KVs>isug`%cwFISqa6e!eK+5Z)e z-gI4ac(2r=R4`RwWN-EQnF4Md7hi2mHL`Y4w@N(1B;1<+U&$}D<4!6merHojJm*k4 znGvNIztLnSFLQjxJv4mo#yjEd5C%PzQ1L&lu@dFE@qfJ-=YPyWME_KtBRcjWYbpm6 zt^fB`sHDW9scgC6l9sj6FnpH=cge_dYT?E^^~OwxA3cFF8?8gV0?}MFGH!c3MML~T|;PRNjW7@p?~6D3X(&U98B?ubnauEf?5*b z8sv%Nr3ycM_~rL+){cFSj_yYtXR5SrFH@D6Zii|vyYp=V=^d_X*f1C*U)RdauQy0y zj0lU$$jmGpdkz~T4XZB+v*wd{oiZJrHOyB2=#XFvaWyRvJVNmy(1_Gx-f;|XkiRBU zLQh}WcZWZ%4?L(f$whfo)zvvNnao2?WV#y^Kf&k`_>zv}AJ^pmM>W^F;wLSmKuO;2 z!ah)ytSiOUni4{j{KEBptuI)$t6SIRS1*9h%sg<=xW#&Qb}WyuIy|=Y?jAe;rye12BpKNSqo=WuxyZ2Ds~4A+I_Nc94~n{kA9fx=k8-D_K`vk(65(| z>>N=ZhncVa{#{z0hV@ercj(|6tW&Pzpc&?_XWm zBM(Gby=ljS{^RttG;=7{A@=J2@c7|FxjYSx3*do^3^>QPj&Ac!M_6)v;Wug9P;18A zq3PCJ6cj0e;I(-`z;1cyGLH>SP1gbXd|CkT0&$@LcKAtgiP*P}UcW{x`K`f~!hF`D zy{ZXrC|(s?*{_$NJ}8hZ3Asq-twxC8aj^YJ5uX()k*p|{!J=e1VPLm_$bAT?Wshc| zJB89o7*1rhA4-2bKa&TY$m4nV0LeOJt)4A5c1$Nkhi#Ow z3k0j~m&ZJc&1z@uMpb_dY@5vyBh^aMBP5nZFYliN-^QN!5|QBAb7d0?`{FQ92O9U zzVkjCRGmM%c&?Xu_HQl!zB`U)JtF=sWppWwNrvr*x3#Nt)hubGwQ%a>O(u^XSs>FnbW z{XxB(rJ6pW-)(aDaqs~hLBpP?=WqW~*Y%*$Kc=c5(Lw@!-HLtdQhkV{x5Wh> zR%+-nVA?3&8`tU~4_)$+9qhG67@T>${BJ?UCSqhahr=O}>mJ%(fN##lTAn1q24$i# z(daJ+&+4V48r)9op2i4K!&3f~-#46FFzLO3N9VrewAXpu=`Qq6ZPbF=~tj(-Vq2W=lu#22H{eC`G&%xI1y7BCF99p6; z@u%$_=lNhBet}14`%e;i*mn1rqT0_=|K?6VV09D5AxpB8ZQ-~gluOX?VEmy!C~}0o z)K(am{d)IVHFtw3;=E+!Q?S>jh-+M_n^6Z!Rs73|t?3b|5h2sUz$ zVTzijGCeARiMQ({Z+h$2y0vmf+y2{&y{WM|&ZyC61_b?A>mgw_;Nn~>`fRJpYzcd9*``H=rkx{D)`csZz>cR!e3 zvsLRm2VNCLsY;|OxmFy#n>6#3tvF4WyE;N$ ZnwS}wP=R$}-fK41NQZ7eg*9ixyL1AdD z(1z6h-SAv9O>_&Q=p`z0Nw=TOMbaemTE|b>MM@ncql;>%&q0!fyKXU2MCj7p%A!|@ zBKBHxBO%2g$0B{LQb8KO8Rm2cCpE<>=5+q_<1TxH5kV(A(%)L)=vfjrE4X2FMc*o) z45rZtB8d^v?yR*YQN=rocHIa(789^pQ4zWs*eAtn!%uDulX1om{}3$~&&mBEx^y&vu^tGFW%;xx)*+*30c&qU)ltZb4B^PyO#wYnVKvu7m-zZ z%yoS1`cv>M#`sA>;A(f=6XP>GWC?C5kH+5RaY3H9>-_pP&vFf-TfBCWY5cu&N+|l> z)w`JQ3!iD~GOE9@Gu@a{+-r4EK;{ODyZ)`ys(jl|5qdkel~POi$Gnt4^UfddFZJkr zE}{|Hx!$x*{OX=|&wc?YXV zOGKABBbU##&|`A_>cmSRmy>NVc@Q;iIQw6Z=)m^Dw0)tGO`}nPQTk#d;lvz`bFDVL zB}oryEyh2gUe##!HYtO0gtcCH!{#=fe}}!|#lv_VE;XXeD>oNpI~?=K5pGUR>ME=E zYq@QsgNtc_imW0=M%$TjmF@stEzAuGKKq zYBABZ{4>w3a7WEo<-?ZXBR4I+&`U;f>_=3Y2McoC`HuT>v1*7@DtSYMyN zG`IRG51Z2ao|KcFg@shICV)A`1lg@PTcWoA*8=!DI4FIe4$E3Yh@kb}j#zVYeuP?S z2FIVz&CHBD2Q21=f)yzF)`0|<50oHu1cA=&cEQZfIQ&CLeb)tGXB9vH&Cq^S^~wcs zp>7m0qoBe?$F`kob_oWK>{j!bI`W? z7Jtv&tl~R;j1|yUx1-9^=deu!R)tqVh`_`RfNp4Ls6gC(>kbl9y)6#V)InpUukXmu zpJ`#;K!)A&OH1z`%`ZaE`r^Np{#!Ds6?CQG{bFBzh>IB%&dO9nfY6-0R4O6>2;vY0 z3PR9{ot`$M(ByGpE7(Ub0s01rAh{zsMBj=4;aInuVgdwg_W$`)9^{#S4E5@@Q-9iE z$hY}cfrjzw+n+xU+`h(`E=bt>m|_jBttxN@k@Qt8n!gf0EIb!%ynNGkTNe%~H5Djh zU0pEk%_m~Hx@ABC-{`O>o7^-2i+RGttM+jgeB*IlZ?x3we|rJ7`f*nGr>qufv7ic~ z#e_QgU!JyHmBNhj$Jy^8x2-vO<)(h_G7^$CaU6 zQ2-*(p->5^QIl5hc-F{61I=7cB5Y7Yf~>H7R*r8MLp7F0VjbcJ0`zqW1AKrkhK5DR z0a8q0{mqgm^u;rQQF8!WOoiob!Os_%@08A95bQuhzr-y=aX*eT#tMG4N>BM>9_Il! z7|=G4Uc=&SAb76yp0g~{9SFxfRM{LKPbl{y!A65%&4--8kvFbu_Ynm^6zL!D^RrR^ zY}Xbjm5LT$^*wIL`F8jFywY~b?pYu{p9bjiP}XAiuf~S zICc2>Wdps4Muj&28GtMt5JA}a=W?+q)pVTiqiGEYNJ(jEN=&#p#Hf!K;PeMM4e!8T zHa<=OABCmQ3s==)8>skSBk4Ih9c$W(^FGu7AwGIFHwy9-f7Zu-*?yN3C*!=SK0g_T zMB2hX=HN{{hY78)S9bEG3%fspjda~)Jp@;ZcdPQcoE6uDZE3LEIkiPYtV;wDK)>*+ zh~ujb`hRh6u8-(~gF>JEv-?j>G9{T9nUNW17ksRQMuki^5&z3CCgABrMAG zP5ungMa(}WPr^TKSa;0%yRElKR4y!O5z+QUG|bq1lgCW(k#G7cZL)4El{V~VQGeOp zsquIGGBjom>73V)Rgh5lQg!dj2R<~6C(6=juu%&*JX#9!Kkkc2)fr)KOF?;{$(-zu zzMOP%r%IwMs?u*lZlW_@>Q6E8Y<#dZ>DM%!0!9-_%0C#GPRt8-g&VjF8$&m(YtIh- z!rm(`W{>2*H)~}P%fZKEzCxVw8WuNNcjF|M(a?F2catue-DPycHEv~S3S6WPYmr79 zayB|qo4R|{u^>Yw^0YflmT@p3xaUqeL&4-0p3)c0Eic5M1!0o)Pe3%kyt!Q6qK zaQ~>6Clr?jH*Zr%=fy1Ja2wmJ?#~JmB@!?g+vq_f;^39bHtn6k1b6B*+;d#?w=l8p z%2nqlE!;(;r}(C>waAHPoIs?YTDa?F=YN>D^3*cCFSPQ5KrZuh7L@hXbCaCjc2wuc zWzN;iAZ^R2@fz8>FeyRJLYqXlb_F($!|ld58l5r@UvV+&RI(%uy%LTjR)y|~^5EX1 zD6rtL!n(sEsYELD3KKKxFj<-#B}6eD6)7tvDlAMT7AL7)&}2uAo`6&?cwr zrQPv^PGzY~&?KVr8qs}KmddS{Mz6#&fFd&16eS`Yxf}7Tc2Xp}_Lv6#=sUEmqIbk? z-bz3JOsA0&D*6?vTFihXnrZyi=Jm9}YG9Ry9=%v<>7ES_@~BgJHS}7tLS*vx-rreYZIK_l{w}iM!jhRH=RMO%J*yvd zlJEYz?iWpmZO)%_cVnEOp1%nX&u~+V>0!{fRK#+C>^7cOTJ+)1Nv#QIJ++HRn?wyp z_xoexVL}p%ogt> zkU?xnip$ybI)Unh~6LXKd!d?;+R#y#(^=VPPPd7_j{F0H{ z;_Z_yJy`$g{N3Z-Up7{4avc~Ea&(cq81=s7D$KE^D2aIZ`~2<3oKLJajg%iKQ}iH* zy|w(0xmY>y9lczntYkW}M{ZydB0%$evQCF8sj|SFPzBr2kWy&K{`u0o@qb?}-uIB# z#^a}N_J2fyX$5^4a-?nsi7eMUH8xqMVrCZaweJ~3kwAoH?^}B$PUSI>o$?`;`X?$g zt)Hmc`BZ34;6pSDeh66O*j4jFqUGndlDtQ*^#h?zqpJ*(saxu zjtq5Z?ijd)XJ==jKIWG6N>8_V@!~yoPcD z#r!VQjH-&w;{(w03M4zZMM?tDP_zd803F5YAObdYC2WQf3>$2XC$FJ#z?tgdeZkU`W?IsyXdhC!Zi92769so;L!lU2g0+8pcr2k z-UPm+a|n1y2jwU!W*;xPC7#N*>^dSMI=T zBrC~D@z*hFZV))zSX$DTWV7;`)%>vX@X+molS1i|1Q4>5U33=KHhV6J@MlR|gYAHJ zJU>^lzX5fiaLn}FoVAOK<_Q>DfHJF!1-tVIB&pq#~sXe?U5y zWZR$!@KIDt8W*~%S-(+;nuD4TQkn9%N3O7&>vLjETCfrfgrMB-Gi2!+lQ(8@Uhm-xGe;fPyhN=w6N>=bKz-0-XB{O z?;+vIO?Qar(nV4@#|&g1UgL**3qGN&fLm|`ZYVsDvm&0in<^LQ7Kv_#&y6-Qiem4R zdOJEQ>q;_x-}2bemQ_{#tJ^2aMxjYIH#=KkRF%M}$Q@#vW*xnA^!jqx|BUBs%m1pz z4Ki2ZN^hx6H>K-Nj?Y+=EPovG3S?==_8Nq>;ZA_W7K|@wy<113U<H9E?QK@!`3=?|XCo)`LFcQ~J-e=tr)VPLD-I#{OxaU+YzTfd_(J1z;`AsbSV_ z^b-CBGKTwdn$>L~-!|bj;TyvD@?XEvhxbnzFv3Ik%&YWPvb^RkpcLrVwLUe45Vp!G z$w^q9q{^Btrs&?#7r+g+4p7Eq3cZ$K*?2wWRy*u}FZ|k2{n^W!k$**IVS6gh0oBPi z8+d{IhRefd%sBoJKCR=CSPAfsq%%G{5j1UK34KOy<)WG7M$#`epxpMsZTdyFjZRR# zPLK| zR9>EXVkk zHi}n%cU@&*IZNba>9EpAj7Y15gGu|pzV61A%HwayPOtdeWz5iJD2d+{AjfZ(XvE~) zp`xL2xj@X4S~b`DD*D^kuwzSF5}JN;8SuYZkh{F{-$OZ}xfV^;yMFY?3jdvp!f#JA zFDy+bVTYZA*y~vT-y5+mIl`XiD7p+QS=v{oSw~G~w$`g#mmhDA#Ch6&La3Gud5Z1@ z&WcRIVYX-UrFr^a`+k``lo&kp^A3sMV-M0e$xzuth44Jm*=ANvwHlba<=XuZ)%X^W zMv;u|zxVc8PH23gmc-o8(sRBmtI(sMB$6=@Y@wNpEh`+nTK2=W5GDCetfg7@I@@6RE@-jK9 zL`k}Z%uZPh(i{j3~KLOjwpWy7Uk)JoBP=ox)nH{D#)rdDmXZycVy z)qSnhN8x3QSUNltk72+@(|i>bfm60`Kv}YASh$x~S|55Ru)N49>LHep;*T%A$GD<5 z2pK!(kE$~%F^Im^?T1fhHC}{k7`3w=T)lAKNceHDo27Bqd_;T~H@!q{SACsV+`W0h zFB|10CUZukIG_E3L;d`T*n_C!jRiYyTBbGUY09I_w}==y+!ygDe@9YZdb1S145Doe zGa(zm7dXT~v&fiC_wW;c@Lv^!HomsEL_Mh^pHSD&fs-x9c??S7l<%hDNPL0La-p2> z?I=cKE2ZrQ{P**keA|O85QT3G`TVj~%=v}9cRS4^aK&4NBOWlsFAF@a*|q4!T;W6* zWX8w!bBB(1f4C7FSvxosd!lZaD0X8Vv&M>q?Z4+%_$sJs+HE-&H$Ht^Z2D4qikSW_ zevCAqWuuABM6{ z#Ml3=+zqBq!ZuHI54qI#{7oTtvYLsX;e?mj$NP?xWy-|~7h^C$HIA6?=Y`R51m6Y8h6 zgw$0Mhy81Xo^Z#E+ucVVh+lhOsp96zeUP}cv8!G|D8nBxaSWx~G9RCPPkh@FoIAJ%%DDbjvYcX%W`OuIr^e=Lh&8~NBe4&b%6`KkP zU%&X{F@hv+Ii2;WG?(Bi7RK)(h2MIrD3*PKDKOaW^;YtE@Dm@@dT0B&CZ0UT=S2q^ zm3@sp>zFSi}arGN^wn$tA=yacE=cvjOb!JP5 zu3k+fV+Vvq5jeAlIM5nrCNUx=0qMmoLr%;8TovP+?x(*CVnJpOg~~bLWDR|ZD)?^2 zfJJLx`2b)16v?rQT?Vpa%IPCYO9IWF-wzkfRdYV$yzAnU0xVA!>2tU*gx0|U$vhxFI*pgBrc6}3t1!0mN8F;xABM0HP%&y zw4ST7LWArNh@*_EpuKSIAm^r)y&+J)5^Gm^UinwQOXWslM4<2@6XYxAvknEipghJ5 zpi?B;DU3mV8P}?OMqvdUD$qtNnN|R%^eT#k7}#AB@BXDb5At0Qzs`Q%fqA|lNe-~;3oCwlQ*!VwjHCDl(8yHi!yGqF75CaML z0MO?~H*%Dv8K!a=ZDFHTi@K(0lFsDM{_N=Z&QJpxL`cV{))O!bizr5&iLsO+Z! zeLYWmvXRM7rf8fZ8o!_TCN(ZI0b}!3cwS3wOd$^*o$97U#rN{^V#Rbt5v5;B2Kx5? zw5$!z{Tw)HH z4E&3EFeznXr%bA!I)1d+Q2dz_vg2b=^vc>=_F~)F7jV?AV6XN1eCyUe3-Ig-#2$sr z82>a2VK304v7o@()sMmI?*o6%|E} z?dj^O1r--Oe(?*}I}632`vX(NZSkKOM6{6YNv4GKyb#I|x#weL6$}r*_~o9A>Dwb+ z0Q`_3RIspnFvL-FD>Q&vucnN3d6VB1jo@%Rfvd1ohWj$;G9zhZ=(YDiw%>V4DZ(Q+L=ung93r$o=Iwteh zgH}|o+k~Z6L*9!SFsq$zC!0_3ar2jH#bVL&Z_#2?wRXJ;qsjP=gs5jLZBHyOamHpL=U^^tR`AfAdg{erU$qZ8ZV7h6Zw@HhI|xNkaY?!T zORCkboU*<&W6C$jQf5nGre`HQO~E~|Xv{3^%T#<|&o@7oF6z0$njcpl|64jdDcwz$ zTUz%dn$8uSBAuwS>!x1p-}U^!>B+UADGOsgdWJ0HrjM8c$^F@Pj7r2g%Q{R5qmE~J zD4G>6E&Jate(VpDB!w#>U%hVD^37Wu& zi@Ba~F3~Ajqi<(*l}hS($?1RcDrbMl&iL^4otA%-DR0FoA+~)m@xp7(E3&^&47a#lxz6~ntz)b8&C=4yTs;=9k_he7a#oo{^lqkv zGLew7x22#xuvxl_uIoDZFEInVo5uE_1ov13gE`Sf?5Dnyd$U9$pG=f?zuTip7L3uj zJgu~Y0$l@L%MMYyk*{#{bKJ8crN56?9Deh^Jna@#;<#UUCVf4%p0 z)O+KV=*Q#Ca=QAkLwyQ^t#<{r1wy2W>!SwI%JpIuSLfeGrro4dN`8w#hWr!t(TNhq z-Nz!YvX8DNrq2w;oz@#pE~G|Tpixy_p!0`p%$QNSa_R=4poo8)@6@~!)&GiH+Eol| zPK;jR#51_?iaPmT`bDr7~!525fxqy#-H+beibV<8v8h&?eyLh z_k~nB?x-fJ3tPTUWQ(^;_JitYwA{kfRpQHF3$t}=xN}$QB-TtIqF&@8HldqMO89BU z-WziyT+1GN+-ED#Df$Dqv?DnYo@Jj7Urhg5S220 zbB#&y$m}h2{wTkdFtAkMO|Io77K8f0Yuq=cGdI+&fb^+z5+8P=ZUB9eR=fjOv4JNg z^^x$)qfHMFB|Jn8*Kc1@uM=+8+{G@>-)9E2USw}N)a@}2GVD|%_vOvSkn9P22LA=T zyoi%}FeA?Zk2EX#8TP>q+lHz?DoN3cZrhH*0~;$!q5VAmtC;II4*~_AsEpl}hZl)u`5zK)mlFlfalX3JIe zxCQTOlS!gDTw)vH*SrzL2YT#79VDH%a=H92wOh`!RUME;c z-$6Td#;f*0*v@@6vbQdnqOBM%&k zr>77`Cngl(3KA(nUWOfTDpWOem&=*>R$$We>1(0(yH3wJBlFum@lzkRH;7;B!IxNt zA)>jDPx{5l?goNRu{%WZ=Tn#Hr~~m4iB2Gj)N{nYifq{UE4ok$08cQ)iINIi55_>S z8pQWOrSt7D3D_bS+m-Sw!i1=0v?q@kIn=dtHilKMs-|YEEo6y%O*H==26cDbTQF~o zvStnX0Ua@XOE=t(-2f@w_U0ZOZfajoOI+9iw8+7c4~fI8DN}o;c_1S}Bqt~~>ugLN79`z_vF||-QAe!K^a~%2xNcdyX^nBnaYh1COk|dT zShB87BV8Wp(MIMv6K52}m_RT`sRf~2okjvBgG1<&7oaK#>NAgq*&DyOI7~yo{wn#Y z_H(Ld7k(9QUugo>sSsmuK~jxVA`yy<7Bg5D*fpM~?cVc4cKrZQ`Y?M%Sns*&{>|a$ z#9ZC~arKn}QElPcLrDrqmw-5Qr=UoPBB_#6QbR~6C8acoAV@a|D6Mp((%lNu64E8z zdEYtryMMm(?;x>f?=`cY^}J6+0awL!ynpHm+C@z$MHVxwWN*ldft1F@;e!7<#$_yA zn_aHtJ`3tqPJLh{#ItEKR1SkZspENa5Z(c+_oeUnXdA^S?bQP_Kxrke_-=yRUB`hY zX(m6}fAHhKunGM%z4?_acht3LWbguM`*evjs#9k^rF%$=;sJz}0Il>N6tO!Wwp-aY zQ5Y)z5TqV2(>^>d+@;ry3Sp4Ga|gzgUtU5&i;0z$Vrg>GV!!okFrx6u+JvYza{>Vgf$w?*p_8okN^t5lwb32=qpB=|$wO^k#zCry7}GSVDiB`-v)y2aNaQq4*EftxL^8&&$;Uk${}*UON|q6CPmQ~ z*VmV&_8rkn7VZ#B%X1C&${#;3$wz;eoiM1XGrBn^QK!a zeDu6ff;C1X#MNp9bsW_7!`;QP#Da^} z?ysBXs|IBxv=A4Iu>`Y_(MKXLJk2yld9;E{`P8%Mt~Oc-cd!%kCXbcicS~|mPx2sw zZ$4OaocuL5e%I#n@hv%<+2+nHQdKGP#?#$(UIROls>H2~cE(KE`SBD68}-~)@uHK( z(971+Xq0+FPYcnk>=zX(ZWSupxn_HsW;K9ZRnsiAMAdF9tF#H72nUgw-dn^+6W)Xu zOPBkijD>O49^2lgul7o+oVjZb7|&Zy9@yc0&1C#=VSol{ASG?0`COhB{#ij*NR3UHjbME^T}H>+PX69V zB9U0MSHI3fzgF>w6s#b*0oJ>o1Gv zboASB5e&_26CcW#J@+tdrW8)^kmsF5+^(3Xy;JSlo7KIOk(kYbJ-geGc zbkoUviCL}E7Oqmkb7sg~aOQRVrk6jWyY6N6*`OoQzrn-fvC87Jl$$v30#|)`(sT=g z&$Gnlq70^livi6JxZy}kWZ_)6+D<+l z-9;1HS9?!JGCAX_QEQ}4TN_7Ed>^KhXyoc|v(=)bA8v1dQE-H?6cwA6nhMXvVx=fH z^U~X2V^gwkn~qoeDW&z~s@$X#)ojpb%>F^xY!p-9O8-kd0E3j$fU22v-&;%RfYh{| z_SHnE>9-@NvOU~sMGB8sQd()4w6Db*7oe=O`xdxE3~Ii$jJmzmwh3>4Ta6G}_k>cz*<&T5P42~hmv-TVi6Uv7RLr@2<;-|bxM8|#oQC8y0KDsh{^SS6Dn zT*}+wk=5Y0fNI3toK~U1v%jl^-4r3kl@|$bT$ze5GUeE{e*0af)!xF7LMm^bdi77D zI(39@IvUxmeOcXD*;ujK6R{9TAEU8tlOe@bCq-r$ld&eftd_wvV_Qvs8>NDK-TCKR z5pw<%tPi+Jz9L&PH;IrWG;4|SMT3(=&z|YVYQ>&XK^hV5wT+8cZWo>xl0r6OJwAwR zLtV}LuidKa7v4u=%ETSn}T$uXQ0LPOTU@;4Dz_D(Hd-C0UG)V_8Xy)#2eJTS>z2ycJj*gUI}M1qGzItJfh}Ltih0-Lb3p~rN znDHBbJsO@n->)_aitGBV|DsFn?N9j_)!@G?IL&3({L2XY9`RL+D;7WI?PPBd6YvqJ zq-mpIHG*k{WvT9+9IL2;-sXClC%Tp6SJQ86WlKEE`IW1|rA70Br*=xv z(!se}l+dosE?TeRt3Sili~qH(9Mc3{%wBu)(NVbuL3~?-VK;4I&Mzg1!wVB1Z2SU z84ILqe}!ms8sc|)+9rZgj;xAJpm@3x%X-`p&hcJHN2eOQjT8~oadbXefBK)1BevBB zAi~&KVDqQ0xG?#f&^-c90hjNpQAn_&1UBCQCH!}6A&?P*x@i_m3x>v87mnf#5DuqW zHilFrgI7h^BL)Mfx5h3Ii6hB4Xe+j#1h<3hlCoV8Eq$Dw^#e`3T7fpiZk?%KOiiD@ z!Io`+LG1MD)Zx*b^aToNE?H8LPJ)WC`(}Og?f5rG=?oY(@bbQR%!4mx!4bx=_e*Wn zskT5J22KjfaX{f;ZEuJRL@H=h>hYqlO8yCwA4Z3uRZB@rEBp3M2|)VGmycd#YjQy} z3L3khBRobRtkV5_e+2ZFXa(QdE@0GSC;$=0d7vn9pG8nrgP52Ym`5hkgc!9Yk* ze=Y*qzPXYXkolwfX=q5xeCyiE1OR0m+}Lh&bINEbst1vad1JO@?Sg=fx(drdY=*+zCKO)S8zvZQ$RQgkvJfd zj6|aI5aByuk+ik8;*1m-EkQIN+DQSETUbj_V-D*w<6$@$fZ6dd0o%bV9iL|9_fc}0 zf;b)E=YUCuO99O$yb<83`0TpE0)&9bY8}3Kd_VBky8mxPPsZd+EaH^&XrE4WSm4=i zKL%KF_6z8$Q1`i4Bvcs zN5TXaDz~Gp8|WiamEH7k-9EGhz?H!zL*lyB#Sto2gSa^YsPT{C=yJM0cUDpFb`ojS?@1rNG@a&f2Zac zrR+_;lV%Ph=g*~dldb#epAgMICex$)s`>|C;Jt`i(&8PdJI1b2f(a^&k7G?5vzrfQ zSDCS>o=skf-~EV_P!>KOs4G=w#QpqUBl(jbm8o`nx24Np6KFX*3kby;TO=(9K2BoG zR7?^iV?F+U_?{eBetTlNf~n@mKvv3g#iGim1+GSIyjABi6a79_5_~TT5JE*MqYMGM zcqz(KXRrHrDBX^oRBqi+qmg)$h%cP%aI8M@(-H5PSDW?c1mexIQL9Rl8Qk3F2ID4# zoc1FVDf}Pl6`iyiJGaRs3VF7!D@@K;&f#`OT1T&OxHVLD{_!fStyDI?cKo!1gawys zp5N-}&PlAX`%7|DUWwcX7!;ZDwj;Rpcpf>`4^r&XjkFk#jp}Z3y$w3NL%mOW`l{hx zKa=va*)UecdpU2EC}N*iE&UNKeI2>>R<>(=JYj!7rmEiC|KCS`wIXkstnndIKiM;z z*+M3o3TjkJ&&p!+w7K=F-H!CxR8Udv5UT*{RaUej-|ZlzS(JWL`jbg>ZnT7!CX&-X{=ZWj_$CKA6$F0bv5kjiX>+wxN(+PWWvu^ouf|rR0 z5BEhkWQxsL}s0~Ufl})W5x8_G2&iRt(VzC4Q6MtCG*9uLO-%q^zZBCYy67k7odGVS_ zn|SUnUd6+Vg{b~kf-+s(YCIy>={I$4!Y{pJdhY(DED_i@VcUJ?KDoLnS^qA+*@KbW zNz*%y(k*Rw)BF#Gw|dw8LSSz>8Sw0AJudZob^!E%S=9#-OT754m zz?kRCA+y%=E+js3jwUo~O2DALrYFAMBmQkGRZdR(pVM{5Luu*R{A7!;DU3FTbY27t z(KTNO8D#PAHOj(igW32gkGF{~AI|+>Y)qcUw1+>IShLU}z+l#IxWb{c@$h%I7V~3& zM93c|0ydPXTW1?Ju7#Kmc|-ul9J4V^gFtyGR(FS9-(U5fV2r!*wQhzu-E^Ga_B?!7a9QXB1&FayVo>wtw7q!rp?{_;lS(3nN_xyT*)th5 z_(&3sa!b8lB-I>WnRx8tel&ys?j1GlMoaQ&NA*gtu0f|0X(CD@Zj;E0s6y{!&D-1D zHiP#U66T`$4y8B0nadN5;-QqPai6VIk~8%mcq`n3!|(_0mS&;t;zyD%Bgb{IRTdd5 z#QkRQnluDZc=8D<7Xt_rvDtT4+8?aMEK6jEAD6z9h>l5Th!P`zj{4nVbIS6mH9< z-8lDe29bSrekJ-VmGj5W*ud`IAktlDq zALfxWwTDw!eBHLb(R3<6nRfVx`^zV zco+n?4bL3z?TLUmYTK>n;-U`I4B*}s4fe#4ms3AFL7^3!uMbv6y8Qb04$6IzKU9P! z6kdbV7o+|CO(HIkxDPNF|9K;1C*@Bf9`||MO{Hpr7yFEr7De%U(VysSGbcM+{LY=Z zR);LFDGkN|if%}RVVb!xx&4hNc!tW%uK}p&zMQ`kX^FMe5{*Ph zAOkOGEbw#sG*7R<`W!aESi+cZWNf$X8`AB(c9S7x4M8lh3!}Dew3!o1072@v_pPZ( zD^C;L#7IT7Rtj29%#JfRa74yH`S0=_pmgq@4D9a$G#sN#XJ=<*K_oL}5E%7JrNPRP z1cSi`wH0|n+VGSV8#HXSbqb9H_NL%QMw?PxzW2h-k|o_*$w5zP(eZfC@PMu4cz6e5Yii~^h_0TF7(M-%c(o+Li*{5o3cQ|Dpz11$iA43$Pq8I0!{ zzkY~woZ`Se_|Yz#K=1o*2fD=S%bSi~{QSa&TgEFkJ|q%ztO zj|N_FDEu%eCC8Hx+L?SUIbgZ~sUN|MqkIZ%49JTs5`{c!s7;0k40VvqRaf(>1c<<0 z3pt3h;=_{fQ|8?ywW)5~6fCOB)Xbtz&+Ddcy=MVqZ|MxQ58*^W-y+~Y!M4svS7g)o zUwL@sd!Fv?X`X9m{7RqR)BqDbavhpR!TweUAvbr$*_GZlT%zB9AqI? z+vsKkGB1teJ%x@F7-!rhhh0d$*Qx}cAkH8I{R>ldSAPh9?CC9Nb*!oaz2>*$>3=Si zKk;&nBE0tCK0895_Y8adx4m|@=_-}+@iLmpLesT3+DZBBR{n~MqD<>|7{j&5T!o~k z&o^9;Pe$tdAcO~_kRjeHYA?U^s7_NoDI0J<`Gaeip%jY)%y@2_wTGaU{k6T0D}Cha zcLwR!Xuk&f%mG>BKh6&(K)E@%dFUJl8PgKt;>IAVMI$}%69c}iNC8}nme2wc159m| z1mC3fNW0CxBvOC~<_etP83JIty^W4w3T;QBGyjYQj9p#h;Rp5!8(6n)r~4x9UvS90 zwBN0O^$&fNpkCCX{R2lUXlDd-H&Rg@(RX_ICe_P9gRw!xT}H53em=w~M0A5wrj)s) zV^@{0GV~=6rE8=k6%l`eqE{M2y0AlC+CzR7(c}1wS;zHjKWvOl^{RIsl2e*7%ovKT z=KIO2RO(_6>tOn+5OB0+`=U6y#ma20`6j<3G>=OTQ`x!C-me?!;UsfQxqCm;6Ik+X zy%+TB&N&y+2#GhQ)93vkVp?*i+uVQIRa$LMndJo=I%QtV67avFwYs&Q_2cyX%G@TF zDz?=E$-82XK)f?!JLaDIg}#F-*}Pji5$c4Q5p*}PZ*JVm>pgHS(0HZr=jt<=X){@G zf5ngKCP{P(22bujLWWbR1Sm%FAd)S3o?{LW35c~`RUCdXo*k#z@Bk-T8;jHS3tds& z*BaZccZJI=OzkEcSut%sil`V1 zWFnD$S7v>Xp}}(OH7~ai3iICdDDh3_$r7(H|m)mG_tNyYm?s9{~ zaK7yHlAV9*d^&fevUI)1MxqL=iou?&_Lm`-k>bZxmxq_mUGzp$H&xpcS1c}gVz-&G zqV87rx6a(7?HoY%>2}JqSkaP)w};Lp{2IM$KjVXPAm%C|7D$SU%5<-3+5Dyxhvlxz z&CG`vb-$g{m$E}Xq0ubLpO0hqM4dQ0(n3^r%0=oYH?Em^kqY09CjtSdszFC$C4&se zTpxxICC1ZAjE%pyV(~iMaON>wTjU0zLCC1+9(UDt*j{p)y~8=j}~4xj8Om7k*q{)~j+eW?A$9 zL@-C(DkxL9@)0HD8=z;HnLkzgV)0M@b{mDG&r{4WD~#I0IN9~V`2!2diQS2bj_IjG zUxY%L7>Cr-OZy(PR3m}o+{`8SLrjVvc`mCX-iGGnow;|YEIn2lu?>tMIjkXsS&n*C zRk(UpYoO7~$>_wwluzr(%W>7L_8Z;~)BKzt9ZSNWhmtk}Sy4lJ)Y__=ci-Py#7+Ol zh)tWTYKU<{>bE`B8oto*qNq~UtH=^(oX}i^oaloPdx<#P-LO1YZ{zw zfr;M&P+Bp^sh8Xfw&l7JqV`Ud=M!3_vNI=&5p)9haSi8U3ZmiI_*T}%vNMZ)GFk{a~N^_mxH^$ZdOhbt58@YmS5~H3+H(oaQ z!~T@6`)kO3wT`)h>+lKCHMMc=TqPvFX(mja38qlnk6%C_ltf3dq`g7b0& zqVIJ#4`vwKD!7E{JR~|80{1o9@sL$nK4Om(7CdBr2*%sYmqUwY~|9d^&$JpJOnI8hdLms z$m}jcaH2k4Z%l~MyZc$<`n5PR;_yT9+fpn`nxxEIEq<#}t|wL>r+4?t6uduG?#6S` zdM5mSyz{dz73)4|u7LlM&xm|u$}>?uJ~@d_eFfM9X=9E4xM+(hI&~r^N2^YSrfNV0 za$jZBEb=wE2=t(cWf(&Rv+{!68SI_FkrjGG_nO@~FYGFi1&yAS0etxNE3z~Uf@Pt%0KNwdAy8P@0O`dbkb|6GsJ2zrFc(Wq zN>a~Gg+##I{44<-*qhNwc|iIcKfPQvg50}4z^b6`hbuAfkE}$uDZqpr&<9v0yF9zt zaui}KCtko_N=;3zHv;#mi-vv2qv`o8FR#A+wGqX^nC9kY%pmAzxG(DmTO;&RTay|g zxU7XH&l|c~(n)4ik#$FM+|4It4Ida z76<@CLI}}B&u_?}p-|B(8i6Z=TDW-lGNgZ01G$Hu83NM?plb_=nOHZ93GzGFX3`kA zW0kqbo-q71|!)Yp6Jz<>(|OCX_ovo+)EMBm17#7A^JYa5Kbm~rsTs-2dI)4VTg{Q8l{ zLP-(bT<=L%4o{)f5i`BT8}sST^#|8r>Ur*q(DK~sg*hp3Q5^3zHz=QQDnuHV50?}} zXd>v*Fr9%4wMs%8RX~h*0D8){m6g1cZb-I1Ir*lPo%-=3r#%$cl+@QhhQ+wGRg4IQ z!aMM0L?J(cT&}DvV@Ah>m%`%E*s)2Z%bt{e~5?d^dyRGZ|Su)dH--^8$b~NlqODGV|zH$S83pB7yDIKOTj(l&mhjkgUS~S>l6w@ z?O#`aWD*+f@JfINEeZr-Wfz;$N58dj%!U{#q~k9*cf1t@#h=^@4k9`8%8BvuS#G0a zg8w3vfa<;sgWzcu;|tLTRQiRSBcxl2#T|g6;mHB_20+ke%me=!h9$wW!T2h?o4_-o z+(l*Y;?f2-U+{7Rs+KyM!2+T^q#_Q6`Dh;&Boqy(j9nG)COn5!$ed$qox?y2ln(A|wXkMcZ(H+fdXTP?v26 zKK-@zv$K>tt{Yq6BnF8JOuc;juHPSi>R}Bg|G@TN&+peyFM%Zq-l4E+9T>{sZVV5{ zg}tkr-vB)Uym#-bWy&lptx)sd4N>f>Za-BhVC_L%@sgQ7S~HUIdl&DrQR>5Wks5o& zVIjTu*0tK2=fu)GV$|m&S_?IMm-lrEnLk+?B6Md?FTdNE5%!8WmrCVfFMNnD5csp)W+U8MzpdN^Own0JjB2m=ULXnzL_mnWyF*pnfGg< zCL$=?==t2o{MP*%aik1?l;)VcE1UWQW5L9Hf5lF}nj5mliUS;k0^jMc=pw{a$#GAV zp2@IuBFr43?!K_#Atsx{xJndpdq%_B0b^W+1)E$ZDasV0(6gh4Gz`VwTr`b zn+Xu!Bnx%dr+py%ynwj@2mkZU%_O_AwqCz6_m)2sBL@>Vv7U{7en9nM)Y@Mu=+9&M zOD87B)Z(*FREA7!54(5=1!rK3xJw}iO5&=D4=wI7+c(=q%Udh^eMd)gBzVn1`}=DI zT?)R;-6k|_9{ar-7xmsmmqXr8ANr*(jjEkaFVn}|KBx04T0ztK)uY+QO{ekWt983T zj_eP49i)e-eHZh^64oV}c+6Ple(5Any@64psnZ#ifMmS0HR?8B5>@kVUw%$7!%c&T!%x?|s_Kl>VOeUm@v+bf3$9d@IEs`@ymq zJ2RBl|7v;qX%3~><-~55Mn+{}}&12cKU&NU1RhZgf6mTZJC63g;Co^jVqn6jEAb^heo z^J|3XeRgmBiFx0S`Lv#*Ovjl=sOfjVw136QIOO-i+P%TX9d2;*@Y3<~cK2#+za_ne)<&Hx@uItm89`0ya#2e~Rr=>hQ^Z60ksMfdS ztMmRPC1Je$GG|U=eb{3<2^fQuu8Gg0rG5BFeu&d6M?AJlGR5+be*Z|Zz`=OjBVg#P z^K1a&i(gdOzqI218hFIC+jmh$e`ysNyN(>95I>p`c~H`rB~A6pd6#El=0dx49n|5?LwLX z^ZuGrRVOvbM3QC61lxkSy7DjY5{ri0WR(mY#XtQF3FaH zxz66CbAy?M4f!b$#c6{%NcAn)T%ifCoB0uKK-?}F(Z7VzFxq6nQ9)vrSmPi(D|Ozh zi609}i$z+GkFTAF5L-o&1|Bnr8hw~|x~F*DGhsBhNNHArZK6=4$ws8y;?TqqQghUu zyY7H+m0{P|i7J_%=>DbHHsAK{k3@^r<3}cn#Y8?*7}PZ6atFmK5rKFKM9f#!16}Sj zAXtn2{*cpl6JV<*BykH?JaL{W86x{-d;dk{y{u>1B3hp$hnR1qPfO=`k1zcgxycyL z`GB>{!DlRt=Fc6=J;5#P<=Hqh&i9>Vf~53**g3at_$hbYPbAn9xkKp29ygO6FDX-z zXa1(YRxlQ%H|RM2Pl(~bannMMxkXUmTOCWi=c3;{Jmd?%fijs_Ueu+-1w=O^wS?PX zxBEgs|T4smJeCA+f^^#DjoU|tCxLePbYic10$1fg+Eo_lJ4 z@l|R9eYgU6<;_UJl?dceztpLUc?Hsk-!ZxQZ$xcvEhf1(>?#dGK1f5izc?^kZ6C~e zOh|ddn7xBm0=5@5if5)TVFS~2VZp$Llw#@z2~ZR6B8dN#*4IM=nlGj!z+Xv5ZVnqy z&yV10_(G8x^Dx0{{=~mg#=jm0*#z3;Y`_jJ`coJ+0>A;NOW6U|04VKJGfpaZ$Wk`} zz7GE64s5}kccKvT05{xW+}8C1Km{6?Il=sqzwU^|$>~ucxb0qM{m|nqtHA!~C8| z@*I;QfOQ{2^pYw49m)dUrv5&g)lro`G6WgwO-Khu(JvwFrNg| zMxa4S+qYT8MDm{2*ApbCAu*Uhx(GK42(KB?D-ykH#zfeFHT$o9E+P-92xe251w$MU zG=XSOo1=w@WtElLUilDY0*47V$;Dq84`D1{3O$w;acHtMT>3)Ca|X;SfLg1n+M&?{ zQyI9)@|Oh_0IQrJeww)oP9MM>`jNHI2?AMZ1fx*e2Y@bUD&5_WM%57N46gnvZhPbhX<$a>t>(r9WSMo z!2(8SYx+o2C)f(m*gH5hf~FA~ZGc4tT9ERH=h*1kGgvD{0#r~2SMd&num~Pne>j#@ zyAPH)Yk$=m|5te+EAe!-SUt}kkQ>be;vWjr{&dEl#O+_j2$)$G;26|?lSyX1|GHWJ z*2E(n3^F;*79heB2w^ymm4X7`fVy1}`2O2oApb>$ns|E~EkrbyM728P+qz;F0z?OJ zx$g`2-a45jp0_6r9dZL|2N;5{p525u0{t_H*^V3NJnr4y3yBVRCXX2vrg&3J9uGsR zBT3f3kZyUH@Wv;)$VY=RNC|DLgIeJ#(S#B6T%i}f8VYlRP3QCYMRJvgVlEwtQPm8v}Jg2Qf4an9`ed|u}$MlSr+{v z@Q*-LmZr})I+;hxLef9|ajh+tN5qe3t2bZQdk9Z^3;ogAd`~dYamE|il8r5&X?%Ug zg9ih%0>^I9@aje=)7i}3f#0Ryz7;y%GVktM-^-%@em3V#u|;x`vnDxuwprtKewp=a zw55c>%)*LS@y~o`^ktI3iReYAbeE4Ab@M&iXT{S#s$-MxUDRowAms27iOx|)wJWe0 zmpZVyOZCxonHrr4p}4t=qyDbTdwd@X?Ck!B;4qWH#8B(hiF~KJ$9lg0u9giM=pX9Y zL-)0`m22}k=3TZx_5)j1j@U_IJjb~`UqM;YWpR@iKD`NDM8rsn#1!72G;&F|7ZE7+ zk7W`w@M!N;GA1j^a0j(qv350`DD+?6IRc=f01rFi_A$9 zHaD)mr_O*DXEw_Lg@Uh`$&JrrR=J!?;;>CPL<#uHSLH%SUtJM!Oxr!E?Rg(~;@{wg z3KW-F!C*6@zf-j|EnRf~#br;uqUW)U6;rx!r_`r>N3MyFSY74PV+|iZ$rqBF+Rm>3 zyaFp`PBC3Z<>q5z85Kc+`*0Xp}Xqz1?PY2yhbI9w;=Lekh+)N;9jAu zMK`&L;au2Ks99n?9$P|(kffm(4+#xc&6qxe#wWjyKN!<}*YQ*uu!nuSVSE~aF|mK` zQycRC1%>kXfZpxqxer4#iROP@P}5`qOJC0))f~GzkV#hHZ++eKfZW*{oI@ zo>#k~22`d*J5DmzMuZCWQ~f*98Q1P7-4Q9_uDjpPa@VVlI%m&}?ZgMND%)9B= zpxkR*Pg|xhSDRPYB}1C2DhSTK#sVc*@KE4+_> z-j->5H<+Yp@tT>Z*E$ZaG-YLFc_*0Bdo}$ohr(x=RH6Y)HS97~FDFgGQVXmH;1CED zVa0!N<%NSoBydwZJEdK0z)5Wn>)Qb&)nxex3P}JnrNBu5kI4UH3)6&#t6CXB3cH+| zO9>35^TlD7R-g^UCfD?D>k80DS^&2SmKwli@Jo|#UH6aSAFG02(AxU86kE~fDN=$J zKjWRxtyyvHt#?f8IPBLKg>!(WyGm9M!Eyv%Aa?8uMEVe!JOTC*#<4KTjJ?rGlBDYA zjIAQb7%m$0XXO=IB?ZN^beD_MXY|1OP*AY&@B$)+=<1F)-zP1Ag`DpshYFQP_0ta% zN`c#zxO><9^=rLG{O{ktgZQ#`8f>|~Z!JKN38FvPs=?U|U=Jt77wZlFlbQ8(m0dIw zgHEf4CbC|8@%hu~OR3Ah(r376=ZCrK=|NRJ^he+@c^%#G5&8`D8~hPqL%B3KOTSnp zeeuMWMJMyo4nwUUz$vf-X{AT~t}W&b?lC0A2CW_3USaXGt^Ek^#EX-3Yk;ugd$h>UhZLTnjzohdJecbJJ+)V{&w=4crZw?=C1b zmb`!@761%@M?k)Mu5bHVgpN|D$pc@_NJ@{o>0E;r-ecb}I*Z5l!3h1Y{;RRMsFK6Hul+pRMw1fk)asnFA z_7TV@SCBC10JLUDi#Moa539f6{p-sFA*$C$<0Sxi)DDV>r8#F^kVKiNblZ&yuZ=@r1| z51MmDpGN2?uCQBWaJ-Mfun}i)eEqr$k|QzWGF9K=D2|RN^;-C{t^#HoI}N~pX=g`* z!Ao#z4i(dNKiBqS1XU3JZ8YWu1kGr@0+8(o&9DFfcMbIc7=;$Q+pto&qPab@!L5{> z_{ZpE8J+Ej3q&c*lHu-xbIXKAohx>46H*4D=r|^^2w2XHStyk@p`mKXg7?U;lXJAm zI6N91e2Js)d2zhdCC@Hp)aLsrM+5KmQG>XmRT9v%*`AZ}(Q)-zcCd^EP5e-?`@#yv{B!jzdb9I=DV~W@w*2u-gP4aOIG|1JX|;_$yl3+6}q`OxVSI|9G8O zCcYRw!jOe<7^SSJ(igO-m|y5q0mpkZkcChpk2(738FZ~OTKZ5t{N)c?m5a`YKd-tJ z1LhrlYSZ0=cy?GW0O7;IVPrlFI1<#-z<9#p6=ae7IN%-X+FLH8?h^MrKXH!bl!E@{ zf~qM~K;KXW4X1|xg5A+D{`cS;A1k+umDin&Ykz+73tG&5MmqD#UpIAiwkPEQ{<4167%RYql-snh?ohV*#0oVe7q;8 z+tEXASub-E88ovRFrslDi{@JI_*l<~nfY@Yniv;~GrqRvJ-*9+E9rbWtL>nCvb1s^ zGf9f@{pEQqhK=iILnEr#i;tc^(?d`v|7HypS24Ybd7{l4$lJpT+Di{-OUk#%#8@$K zB)N|<4*zI>pk9yj$?~~h`c$@w_vdXcfkiU}cIk&>$z|*EjS5~Q|8Y2>dy83=wuuZ4 zfx?3w7SF3!d2q>W5B$38?rTSmAxRp#kMBuk{1__Os&1a+{gPiPaChv9fMEzS~@^b9X5~&^%#);A2D41@b{B9ZMN_Uo!Sx>XA zQUAR^z5PO?jSyol3QnA)R&0FuC3Pb~oD;Syk3^%Bw=U!O<%d$D%6}r?r{@!iQ zbuJJo7|)PvzUx<|NtgDPEl0GiEE5)@?!RejLj5yua{Ty65bd zk~#Lov13%rP$$(X>L6|0cl>7R#|4zj6h9~9p-1?rA*q>@PkwlyY{Gtbga96X=o=EO zZMhxSgi}8AKtkuRo0Vzd`l;SA1j;yOGrd;%y&;3;AY_Bg3!T1zQ8ncud!T;!p(2BY1J zlA7ay^GUur69pj`6>$^NYXK}pi^Kj_x35G$$-C0Sui~_JKv!j0-MDU>{Aei@H#ywB zyhiTuRe-9T(q9VVJ(PfN&jdEjHDkOyZSEfaVfViqEJbxL{(7kQy}04WdvpAw6W0a4 z{nWZX8ub-N_EqO|fs&UV!^&+zrXOBw*xco3(mx|iuvJS6zjHw{Iom|X-u{nob#>tN zixdQk5X)v6wTy9>$5Y*uxzopr6|)OFhEwgP8G+o@Zi+aeCzxGSU3s5OxnnrgKHpQI z1l1Qd_V1i-gEuDc-wq|B^Lqq>DBG5APZvv7bS{~nllZ}r(l%CUyPzPJA;ZML! z+^3U!!N*Va%Z+S*)(JPSf27*4;EFva%l_-*m$8v>vEef{?6YBM`AX{c!cjA-PrBMC z+=ri8%4em#>2-C3qloI^3TJIIw$n8=RhyU~1J5g%I!dxKn~8#Yp_Vc6`C9)By>}(g zH8~YcwGN|1na+69b^9IfjTwyLVY$mx&^hiNkSTMk4v1JdIfXPgGj8MMUu}&0h5Nxw zTG8qG&gQGn`Ro^zkDd-)KO5p7G3pnodF&$?U~-@HeM(yQ@GBFB_RA-J4}l8y6RXE1-OQEQSo#uUBbSVnl2hK1O-_}3b7@y-oT^b}$!%!6TdR2&5k*7+<&oK8`cG*G< zA{Bmc9jB8kdI=Z;s+~hml%1T)5Lcq-v3_U%YMUz&!pGo39nJ~7MPsPgSV~|MkD$V& zyzs%Il1?!;Gc%$DX4tV|(UtLHkyj0w1c3M~83v-~lL}{(ix^{g1s_0+iWI5z`$#Et zpDd_A*NiS<2W-0qY#n%Ewht!kcF#Ax(+UcBfjp$>5e54%Oxn>55n8%A#}dq0$u4^c z&Al#npd}<7JCAV8_8OJ25!)}jo1EVfSRMlAG=T)RWGfPp-(nm?_7d#oz%%mi00=^K zW!m3^e-mhXLZ($0BzgKEsdbOIjvL&@+9Tib+q!Mn z0eLTXFc%SwL~P<{-en-J0c;Dy`S?{&A^fk29;q=KXYOnzt|r^xty8Xbws(4HamC&{ z1?@;#NlD{Un)f4`K*#_9D7xp0K2D{Z(FDS@nW7Du*4gve%V;Os=yLWnGu-QZ&1ebe z?k58FQ2GPo0f3%>`GY?P@p~V4pG|n5+Qk;wz*!5pb3n!g1C>M8vAerYVCs4E<_);K zxI*+GpAeis_c}^l3w{26n;>P9$YRX8ZeO#x^4gDi>L#c;X_4$2(|AFCm}m!EEs?0BiNMR8w*|H=UHk7P#g4A7GYtK&m%%uMpgViNaQki zMCe{PBS-mU-6l0Lucn@CTWWOZ3)a656SSs}$NHt+KXkB*VZ~NoC74K)o@g8S%5=A@ z%pON;j7UCqpHlq;HMJMY_HUO2O@WS(s4o8S8>u$j6LI=-oO+f@j(=2Uo=TVt4Wo!57)(BBtY7DC+0AV~=6-*9mBNb&D5t@=bCE^O5u ziRhFMeRwl)?0a$4hf)bwhV~Y#&wB}}sQ=RfNXdA7$23!a?={-~OfkI$_ua9S&V?eA zu<2tA*=663rk}gtKehjfok-}EG25x#Ov@@b-xl8T{(2DQf1BWK#C+?}?~e;@`4$a(ocgTarMJmSP4%@_}2wm2iNL`;Gyk5mMpP?Z40qK zyppSTIbtO4p!`%|J_GZs3J|LVzG0} z`}Vx&!FOeoKWcZl!zgiPN_vzf-;gouCSd5}@GPD<<@N-bh+`nhWwJUk%uY6j!gt@v z8Y+s}kuW{6D3d?Lu)vgTDU&FfQ2hD4QTy&zX0MF(gZhoMJ7dz-zi+i{Q)Fwsb)AdV zJ^8$Avak1H`s7aic{ANPHQQa>Xmm7AztH*5#ujCaHgV>-3Nh4WkZ_!#vZkYP8M36s z!LK4r^){EBjmvxbTO&sU+^*2MMA!V+=QPc`@w}hO>6M6uNO`6e{s4!*#wbw=mCw~l z#+Qz=nx#BEqVC%ZYkxeqZ~q&k!o_{);j)PlF6K&;!afRa$;ic_&W^X@76*vrE17xv zR z#D8Ku=gM3<$7Ks+`=`rn^s8KMqEtnxntqdg^NpmT!N#yOQDDbg#>Qa3@>(n_ty3q= zVW*GvUN(oIT(HZ5l$^r#+(>oY)%(Bk6Ijw?tVG%Fk8zbNxqoTul2<5m?t94O+0*CJ z^WgE$KZF^ToHZsH`LdjGn~n+{*=PhauWx}50Jf`S*}+zk>Nh`plDOO4waUQF&3odn zap3ZJY;0rUh)Tb6oZsjgK}3&n@rmyExS8^#tr)e=z|W{8uw>gi2RSe{FWm+h%$`Cd=D~vS$z#FXBG(D-f{o(0adA&&Qy0Wm!v#$ab z2HCgi9ZmWr=u-#(?JuwIFMIr&JIWw_H@#+m@+f@Q6}Ke~S&YAqc-X+F*^cpbNNi2` zMIQ;V#2p5~Rr;pl0DK;+2-9YYd&;I|ItDb$xA|}NakCenyi5>TVj2mTd>r+vHomvw zg^A;lhSAWQe*MlUKL;-fBCPD}FFpKy#g&5Hn!S!5jy;x#sSu!Mu{(k{@cy(m(vvl~ z9*6ue=4wm*s+d5H6!-Ao-Mx6hMBAdqzuuoYG7b31V;S((qQob(&TpZJV5+BMgC^g^ z8NQ^%bf`eA4L9>LY-1ok<5b9=e2FekXlo1XDw~8fx&KCxQYYxFUmQkXLQ^B0;-s`R zc11F<89>^y*yUc@g+@c?ZLP0EexcLASC*RT+JFWUt!jjy0lXx_EScCOfcB4IerY0O zL%ahD5l0bHm!P@zJFv=yI$X%j$C!_)c`Er=U@3_UAUl>q5*w2t>N zi90}<2m}?^AGy`9L)L<@Klb%K`s)gMtg{{dOChlF5JaH;2r@qqCJ^cDz`(81gU(V8 z2ELNt*W63z8^8geX@Dd%`eI{bs42sUD5^U_=lK$_0ZqCXez6=rIx(Rk6Wrm($i(zD za|E4Q1oL`Ow?7t5=O2iHksb^Ragay*3+y!)TAUz+6W&>vgFm3vmam?dd)08iC73A} zVqt1tNn^A@zr+p@woz#;?wS|#Si za3u&Z!eM5#&+9+?F#rcWjQQEaHzju?#oik1XpbHTXxRcFd6eVSX@PbUL-pR?=Kj7j zjMc&Q^#5EHfMMX$xNdQ#cfjoRc{@;rOnUVo&hx4-I;Pr+*gIs#14R6~hbE)p7erT& zjr|gooo9zoXi#3Zhce?m7oj6K+dVb@I`nyP1qwp6b|@T~(V963^aETOdyUef13fW? zmS!ks$q6+Bf(!mX{l*IFKc_9Ys|c3K^B$TsLE#-ixlPrC&Kk{Hiy_V^aH3gc-BG}g zgB$>e@)yk@pL|~9MVF^+at{7#JtpQoP$iNOqjy+>l+$sGuu!+fbzVn9t8GJJ^0dHm_uJ<7TZ-#fTS2LT?CB*{0cyz zPrwreaY9G&mpev|K;%J^QK(=bgof|)d%h6T`l=QCmWnxBz;1ZW8I%OSD_f+4*SW>( zoj`(%nn8;0!OS=^g&~xcoVWYJ)pt@vb&~E@^QY=sIsZML<$Yqy(h9MY>xM2@#MKL^`BPP$VQIrAxZLYoF(P&o7Un zGkfOVGwWX03WnsY&rEDsH26}L&ngs`lbHjU136i-qA>JKF^ROr1vc7Cd`|3c{v1DUmA=L7z0yrRXOS0#wWt(Z_ay=$mc*LBUnve2je@Z2I+Vc+2q(my0_s>+nV5R0JXUd>= z9&H*ddqUIttiA580ye|%(qO0;`W`@YdMaIZOzWroY%hEk%{ny_x<+}gizjw}`|5md)Kf@7li#f!g@s>U$0fpVWFbgZkKQ2*iaCz4F8 z#FYa17pG(`hi%;#xhr`&s4hd5CjkE2@7mAsO}k34hO2F3ao$o z6sT+$!Zb;VQQu^do7d_QWzvrmuIOJ0Y*vOY>`deOol@U9a+GQEPmcd|Sb|nDd@R)%UCU4?Zv3U~ zq*C9fVe^_bi!^=bGpqelB^3mg`xh2OOH3PiWQMNx_YXO*lrScct4uei;8DRjK3E!~bf;-bcF&Vkq1y4k9myw&&>L)Q@f5Jz z-&hli=&gTUy~tlNl#`}%rfK3}{6Qi-grUOY?D1(Mhd0+ic%x#;fcq=riM(2-R{vtv z`lJEWOX0D{x%}5{vAurm#IZ}n6ccu(Nps|F_WP5^z8S^;r#tjK+sld^ps=*G?pcv! zjFKl|VJqOiOVBq|gw2!8)-j+G`jpG=<>Cs~mOdrA$G$~)kvg%Ec&Nu_ihH1|%UB%w zjeLkaq&=aN8+lu@*S%r!h_;U5Iz~rpNvl04xaRk4`Xwc2{+70?y)p!fZ zaAZ0L3=^l_Kkbe7->b3yvv%Ywab=Nu*+kUgr*KO&Cr6JP@hz=V&}5H7CN+QV?PKpJ zTZR_*yMhRBT>d9}=$g?h@Uq%eaWlzH|Cx7 zZJTi%Wt9N}Zq*1jruC2-oOH%~)ra9}d=I}y3BT`_unx&0({9sR4Z0O<*4MiS<3L}L zBHTq%JgOU3_O?}|b5y@~x4R}#a7IxQQ@BHsoN5&ca94W0XkCKB<}}ro6jPB*Cwm8{?EGUy zVntS9@#O2`L-yXhyN1LzhK^)|a@^?4FJyIiqd2j$jyV-#y0UVJghZ+Ngwzz@2F+l+ zMZq?WdG`v<4P}irgugvO>Xx>B3L94_{|Y+?f1z+zv*~YFZ_NGO;5cFIF2(jxP27sJ ziqMi0J6?|hf7Su9@{=piGff-b@sHllk~s~%MmP^;bex@%bZs-Z`LlA|g+)Y6xfK-1 zUK6lJ-XWV-WBK$Tey&Bp<;UvL#S=EnFuQ9O><$r>^zVlhQp~86-=FK4x+3#a5Ff$$ zjOhVpQ|L);ea^3iV2$rdazVO~6YJ{gYy>hfZP@F>#p;)WAHWppvGHakSF;8~68G~{ z#eHutuQxpM<@Ql#Ag}|i3wA1s8cfsxq!^>A5Ml)f9gqsJ)i)=NwUjfXzUpaWmhuKt z0np3|j9kksQ@w#CV>?J?t`FxjVw*e9jW;fLzsve@ZfDG)&JzI7XEk_rt~_ZqY8J~_ zdMriLF2W29(h6Cwf<+^AZU~f@q{T8DK`u71NPefO{^|bxy3Lsvh&7@&fr8rhAwEi;ls8=kd!|R2NS&94&v-?|$|Y^lP+q{wB^M*wV#<`H zI}9O3PRQ(Cwr%D5_*Y7D@_DnI1;>tfPVo8au!+UZuc$=Dj2dq#s7bkI7y4Io&JTbo zxrRA37B)7RNte~Hmec_s33ZPkED0oIp-4?a!tax++?zqFeh+3(;tl+_#1eRcf@rOA z%?x(xOqHy29bSTn#Jt3_*}1u6Pm)&b`Ti%Ish$Ueg7r}Nti*=AJL>*t+FX%ToFd^W z-hb-bt8iN7&Jt=sb+?z`)I|l;M$+B5@eFW8T>m(MvE0uWH&N4(R|lDCd1g7$EQue- z;`%3tlh{s?ndv<7hpJ?c>ZaO~ea9J*HqI`@r4SGjo;uT*JGb-;7uYdH-rIkvRhLkt zFUt$2E7X2x`n^YD~J_jBB14zZ$uXUr`NMWEO_ z_I~%HaFdIHul1b1w{A(93K!GjZY`@oJafeHM#96E`wUNthjmNjfWp+{@PdtZV#S-# zQ&cdM41yWGzV;xG`4Uk|Y!-cEI>}k_c9v%`%cBJB~|U?ON^-g^2uV0NJTOnn6Bl zaz6D7ydS9O=;&hJM+4RN|IvELDjEleDwy;mHNO5AJV^K0Bgr#T2swvPptlmfePGU^ zuMQ6j11OC2FM~K0nN0)gS+M#*NleYS&-wJ+O1R_&BUsTv%IUnfAcs6Ml>bM6I zg?=E|-2PqPF_1P4t1volGiR6o%*cgK6Lr&;RmEPEilQ3+*0tr_`l)l z`n5GXO9y})NkkVF>6@4wb9g7fMoj!}je<~%N{d%7pL{-B#=@b#%kDdBH`r zR0<1I5)2JLdUxF$XsDadUQnSBwGm4Pf0c5fXO*@t6=bwka!d0@Oys+njel3O!PZl9 zDwQ)3KE>~@Kx9kTJ5xvV7Gp-&FUmQ|(pXaVL=(&0nP-hJ)?&r)8WjpC-ZN!$wADJv zoiNi7d5o8>l;a%m*d47P8PhH9+t=i$49D|0o==X}Y|r1H({h}IO7Tv9H1fV@jv72K zg|)AB^a}CW^;55u)2QE)1a_-f@%ruu)KOIZ5n3W2Mk;zWRLUs+`8Zt&iT9_$t*OE0vz- zaQHf)+}J~Et7gR~bl>U@roDjr>F&_EgE%W9;zoiHLh-k_DHkH*z5>U#D<8Lhxiana zArW*#pE^D(@Qvz4?M-qqkY~fMY2`heh!QrTIw5EyJ8jOF8RxVXeY+eJB|XHaAfaw` zB9=D57atLlcjW!0IU;cYmo}l{ZChsEwe)%01BGJzhYIgTf22$brJ%mg8Vpu5npe1| z@&Z+JwkZDCaWw4~KH>(2fSC~4^dRPJjk#8$(%l2|S%E60DqoeS+=hW@5mok?htatP zLDKSUV%{0a`%B*xFKp=JINT-D!xj9KOrNgHv!G_1W-aA0sy;@vq}}53&F|z=Oa`Iw z$kD4^{nOxOm-&kvzP$ALoa4kkjMd&Q{ELZqmpgQ=%hT=Bp1~I(xeZa$(VIqW-JF&e z4Hmy3D@VIH>waYR35q!bW0|(6MO)CBSg@`~l$P}AL&t1K_hO>C9K$A00#64Pmu=HB z6^H7q4sp@=NjDF_dX+iakJk-&l849mXMDG#?Em~_4nI?E`*KHH$GRn5_9NqCHg?7D zRAksp$}?2YriXcL$n!W3&{T%fzYN$r@3cL?IS|jR{#J8f(D(cWp*e@fz%Y96P$s(T zD9a=DtK%P8EshFf{BfuMxcgZ!|^Z(lLTD51yL(Zw9t$ zVu+{~>pWOYMCag8b2{xKyYpES>WaXF$}_AxE+qDvCxV8PmfLWHTtT{fd$t3GE%cd^ zuSHyBDoeeGP0YJCX@NR{djB1sSh`PRTdYa!R;L&onKA9+YcfhI(v++e{E%9*Y`gf| z!!@hxA4zyPjnBV7Hzb<8J12{~($I2UZ0VG!1y?UHH@1aubgnvHdTP(n9(w-TyFpLL zY+7@BS|LJJDKW|S9KQ&sH`y#HO_TfqdB^jQvgB;s50%oBZsEFWWz>9dR!PT`!?Pp( zZkDv7-?{!G)_7{=-v_B@&s0bgF!&=H&bgnv-z!!8j$q`)+R9fT%wWEa5LjfkLhE3D z<77Igs>&ZvCtHG=z|6F5sm&_W`trqv(Wj@n6$iDQvtLX#mthm=Q6c6|~?sU|QqBNowCAF;`mb&)+>zm;QtbIT=L zGUw`ADE(|>II*d2basv+5>sA&{kc)T>(tWUTxBxRJVy&xZc}D$=fu4y$9i02{r|4z z_K7>6nQtU)PGw)JJ`2@+|NR7*L?J%Dj=z6d!FK@S9;i4)8j+!Q4uoOI{NV3=iO7tz zGDqJ?P^Tj$acym=F!Mo%Q0tZ~-=%1|Smvt!{P`Pn+d*}z-*=D{e&^dHARqwlWi@yO zToEw0LXttCUAsP^zcvT?6r?ROD=ttfEFHk>uZwE<;{zd~o^O$q(9&jRXBXwxuvPF^ z)=L?!3kAe*tOa6s)T$@{je4~oX>+Dh)6(XTt)1}3L`QoTR;d+rfHNADQuR`s@X~_V zVv2xNZ8-O(`FRxcDC_h$i)l&)3;Nw553HX*?@@LSoi9>O<@8L+fb2$);L~5e_g~U4 z3&}2mRB2w`h3JR*cpydlwc&KSZ#kSa{+u7)ztGu6U-Rkb3;1VGiY&mL045het^4aG z{y;4WA7y~Vi)$5ODcFT<7lw-mHwe;! zfN}&G7QC*%Me25y{;F121p*54u(yZVI3!@a2RDn4o4a*lf(qt%kP`mMu>N62;eWa> zLBB=8lWq4FWw6|UR@47@=j!(VQvU#|gMtw_N0XySN-i&wa1>@3oDcK7zZoef|LBqU z-#iUgh;{UB2n!IcP;c1W+JcU_CHwXN#ofRS07V#`2ZHSl6WrWo=gH$@s0FOl`**1^ z#6^|?&4aT?UuU+31KPoTZoQ9o&k^R=9q^F=xzPP%T?VT3cvA#^jP50`u<+X5+wWQT zOeb&)nQxxc-SbfhIW*KYs{hW%t~~!-Sd_uzGho z4bV6?{z)%cx+v4_pMLZ2^jYQKjddt}-jmRi5``;G$NZQxRh*kokqnBZ=K~+YLVk;@ zc$UHw1`&$zFcjl6dw%0ti&=whS-r;|Q~1T+uL)ht>b>Sv-WS6D!>~ zonlsO^oLa;%k~YvLC|gjt&MNKF|Bm(;?9vj{u#XSx^#eboY?F z7J?Pt4{N${3!E^-WH(=e{4Xn&A=z98<~-RJE%NL*>WNWNjmTmVBtA?c=SAJ-oFV82smBjGXZurTuqsUY%nf{!gFFR zqMV1udU_DA@4-+URku)n4C=rx!REI4dDEDJPmprTK|xJT{SJIdARPqVF0zvu*=!E3 znTxBPYYE`pk(cV??<2_t;;VUJBam|54DaJ@9*_w_emoG;@PGkr1yqx-4rPmi!q!tN zGfKGSa=K*@9!e1AgiOCg)>8`$E58433NwxAI>&>}Nj`{vKRNfm-T`-0XY#!#V&;=b z*&)a>yPi5WeFHp<i`)x01UhrNhwbl zkhPd)51y18FN1y>a6F79oTdECb`wQ>*j!Fa(*4f1&pVqYxWq8td4{*)200<H1@}TsANfr+6U8U#S&#%Dj7!!HdDQ~JaJXBF%5k+G|^(sq!Jk% z*7gg1;)JH>!aX0)3HWdOaMxXnNZ0Uu$Y5aQI$WBb^w1yc?4OAEZD}{nOgh=$*>7B^ zcEk(ullHf&1Wt38hokVYP+!PV@IUrE%A~EvXK$HlY8M&6l(dxAxW(Wu5pGw212UUC8~m^-_1cN9&}V=zsh?35(S3PZ>!F7Vqh$x zFIt?An;G>Tzijb|46VJp8j%zbROQZvztSeobaQ?E$1hEs6OFb*!Z7|1GGbJO*xY*z zpL2cKJ)V4Rx&3)qS#2Rf%7N!;5V6lk-(Lp#{b&IM6vH?AsN`c9`;{rea&r}e6>Z+W zg~u}Wr)Y~K`X6#MHw2rmOx}JN2$5s{5DpyBm+@Ol$eVgN09zboFfdMd_P| zudX<4o~8GMM03P=Gj9iivS#z}YkEi{dd8twr8!@<>GcoAxk5DV9@i8JQO!xp&_47o zCe?ht`U%$O`0?@mwe=zdOQFfMl=T5`OZrK~QhIM-k2D!9@r+Gx$A-ag26lGP*PXHHa!=l?$~0NE0glZ{>Ow;Xjk z77YRH=B}C_<^n?@F6jfDdz&ezJUWc*vQwvVrMOiB8Xx_$I&$vSlyEO+jNe|eS3e6m zKUkDC^-dqCHz)j|d!%=-o9^#QEN^V38|(hCL#bw8aB4NFe3;*2P#3$czhqHWSVFIs zRqiLh`P6~ai{BGeg59;e%JLx%b3iBN3+;o zw;T`~_ZhY;r}qO~KFd__9I32g;LXl`6{XcRHy2c>H=-*~EJwzYONJ;aF>Dt3_IX2@ zKo@&*PI95GNZn)KBf4pZ&&!^bye5%I_xa8GJq}dMcOp)sGB#9YPdpBf$OMh`a}CNW znrpum9jEB)Pp*`v$04v1!(4RmleCzbZDN_%@;<-QVgtz0^ZQwJX1Ut;wELrWbWW?m z=RRk>5|6M`EGd};u`-&4%>)ov7i|4GxV0fW&D+B>I{$K5THLQsFS-2eoOYD3a+7-U z$wxyTCgc(@WzffvWg}O4_&uLU#cJ4c07aZnZkQwPCFz$pD_9!s zF9&*9IXGg*(rB0FO`{K^Zyz10Z)UZTYZSibjbAORtn20-uHXu0`WdEI#H_haN9HV$ zPaglBJb|~sBF&jMO5lAfYnWz|agorMhfa2(3p(Lb1-vqXkw2QX-d$}3lRL^B>L#y8 zvnThXGvDFa(#otpi2}rPR2MVh{jzo3yMeZGZfR*IZG3v<9A^N1ME!vs+YizYd?WVC zeudf<``L0eZ=lJ#o=lUI@&kb^!A~qIdYYo?z`m5Rc`wE?_IXy%qd_X}DA`Xm~%uic7Fj`lB|3pU@5cw93vQ<4=W zU;g;}_XBBtDX=lESnOQJHBq;~u>$TB1OnkqmKZ>+cU_wQ`G`yd95oyi5UNMV$}DYL zzYT9=_??oUFf2aU_d^;Jke(9&*}CP`8baNA5M&Gqc!o`0$#6o*SQDbp4QFrK}FXZ|`YKrn_gF}MHIp2718n?jgb>q~IILPv9<>GG|pfV0twJKX@G0C$|8-0B?uUZX)8VZ>$NS8ituttsR(2U|e{5d7bes?=wei5fTx3 z(X-kBWH2sIP2?oBM7tZyCE`fiO+Z8hV$_H4zk4v2nEI0ycU#Cg<(k}n)v)rV079`VBu;aCRgtNT6{VwPjbB)}x32l{ zK1%amw4)C~bdvt+551S-B53@sw@ifRc;8CIV(ylo)53*@xpebxDA#Vc|3!E6oPs3e z$AeYN%LKxd00JG~NCv`k=c)0MIv9$;o&}H;Zrny4KFQ}vJLf;`m{B~SHslr)QvsCq z^NGpw)#W*CK)SlS#aSn*I$%eFTxqb%qGDo@1SJ65Y_;y-kR0G7VF`f}6{)#^@@nMy z`duv2yX@s*Uil#>+>#gJ*HWJi?!IAy{$eOP2MaoMn`0{;d5I&-`@o^EN$#mQ1i}pD zYDHGpfNdTG6>vTtQh6x*%!5Ni&>1vh0KR+x(}vAH>5pRRcwldMbtM4`OW23OUuZe9 zZIRC?yvX!FaCCP4n6y9Ot;7Z&u^%XOkmGTU&0YO#xpKS~z1^KlBb;7BkjoIb^w-c- z1f5q_KUaKolCZH4g;gJgeK4>$q-+3-<9;rK+NNqGMh3@jPvA}2hxgSk230u*gd)tl z702dh?A=#u0>YUa*w(QVeLt<4P!Rm%VCPgQO~Pa%$Ctyyr1`)_jtB4QZ_nELdHZ+1 zFN2LmlFfnjm&ctawLka6as3D=`thznU^Ef*sbw_0I~`+FO-) z^9D){z7k$y9(F_ln-MX`+GwP=@xm9%r?`#A<<`ee9P;fGzc+;I8z+J^w0^yf$gB=& z>vbtBsNqUXcG4!&(cEnfBaqeV3HlO`srMYaP(u^pxGEjPm=@)8x!g+B{HgkZ1pQyP z+8c6H)5_$+ampxCy;H*8r;>B2WKoKSG(z)l8;gh2*{9y$pS_(7Y^G%HUZj#}6zia@>_f%tIbL z5Ns*Dl+yE|ZabUTDpo1hVH(9GW`)K|g?AdSB=Tj8^_&-d(&10)cbYUfc!h)pl1u8S za_n-Gir!bY`4ya4Ke@)PWv6L$y0BF1WAQOOi@SC@B|aJLO|9H?*Qb73h5-ASrMLIk zxmiE2mGmAr-}Y#66i}WScBG__6LbjoJbp((kFs|Bv)1Yrd0%)Kne3@kw|?c0H=R(S z^Bo2%v|W#tRA&xl)UQ0VsC$cw$V6jrKudWWsgCI&HZD7qu8A7KAJS*1vC>p$rUMq%=tj%;vi z`ncM)|3x{=ZR^WYnrcGLBd#@4mhIy&%3N#lg*=MuU4=E)-85Q`kCd2AIx4^8sgB2%3u4PX_4HkzKMRT^lc}t#^wT-*s5i1x zL-hFD)lswpe~#)7_}VmyLJChA`~8PAh&<(bKP9pR8W5 z9?)z);kaDtmR#AnY`WfVaTU1IMcg@1N~YKLn@k{NZ^zI6-TyDW7hU|Nd7zTUS8Tm& z%3}tngrjfIa07mH%92K@>ePGrX5goGQQ!Jl_1UR&jOA%*`L@%mAB8Sf!zLUzXU=fR zvwpmlZndc0T0bOp_-(k*buW_OCppbV!*9=P#(VwV{F%7Rd59RoF4nvcQUbp!T)r}Y zcFJ_t=QE&xw%1OOTCU1ntx@P&JNO=3)aRm&^U*n*VktKw=!fE$oXm}^xuer_O%!9i zpx=_-bIoO36W5-eJ<}}%-^JV|`ly(KEvHiYZ4?am9%!hVvIa)z@#V-4yid zB_Pp$7hTvPamS9Qoqe%!_@=}>ueFY}c%D#W`|b(qOgmQDEYX_g`eY_PF8K{P#)#J{ zK>`$}R+wGNooiItC+tQp(Mct&pGcfYJ!A)B>npzWXPV?Jb{(=4(_cT?_VGx4)Gt8s zVT_FZwp0P>6i?0z^WWn2*|&?jc<&y+dZ^yrDZ5s`O0iX=&G+UG#T?s@6kHmu59sYpY#e6=FSgq zB}#i>N;84>88y`W^(dO0{bI4=6r*B8^ZlDrAGr%L3SY-)_1#p3P~PuU^L^3Oz%W2t zo51xU%T7hZG$N+VD8IOBL+dZK=59y(0>Rv+=v?8L{od{$ zUx~9_uC-TW_z1pRD!BLu1g#eG>!sJfhwHg6o~9cI^b0xo88@-DR_kn~)&!bK1pD%uz?83_!NFpFQ z{%4DU77j>m6s`!=>f=MhZM6hk=Ul(39}NtROM(Mh7U^y>hSE2E<9g@NoU4CDQdlY^ zM`^$l($A+<1!MXtOrp{c;G*760N~OXLOGAB>P(2+scc|uyt42u61bH;2xat-)+&|- zBzOw&0z_s0mw;ve3s+tlN-t!Cp1x+fWG!Pn=$ZkFPPT6PFwoiQ6O^`CLe4fgN=Nw% zw2D1QMxfalP8CL%E9-f{4|zUBEd?NAvdXIgZdhaQtp~vBK_U{2O{41O{4zm#0Mk#C z=cRA}Py(D@D3M9c0!f49eEpBC{ZnkYY-~Y1l=}!|o|U{NX6J`6&dKIf)%M?l5|`Fi zlx#KZf}}ch)YP9Z9@LBjXacYSPX%kppM)_u#4aHVWdKeAodeh!N`@D^C9ik@5yME_ zJjzL7837z6kUxC<{GGG2Z?P}`p(}={mQ8Q*{^xxWMoFw_kB*8OS$j3q8-^z&v+n5b z{wo-Z`N1th7|74J^pAO=`AkhsWr4nKMiKgj^5?*aouf2Z)yhEC^)0&nVFHTJu4sG-VHfpfwh80e?OCbBK9qZ`}fmJxbZ<;W~vSB0@qSjysq8 zQ$6>WBCJ>LrS|(>8<(%P*~54o2v*oo0KW(L5m;{IDZFMMNP$jj2#(J>2u8yLx#rtT zWj)$ukx_>PKe}RNR28L!v%fp&yolF1aei#If?{HuZGHx}z@{IUgGl8UF(&h^x7q;( zqqSUUZ}6npF#_2OkO@UV;{7*1pK+f%iMbZcrRbv z#V1$1d>Am4=afdC$BKU@i@+b3o!XJl|4jUY_4bq|#eBSJJ+2fj0>wsQca-l=9H#$L ztqA>ZK3~*!j@D$%ufN^sYw&`;Nt;ft9=gmlG}y9lq3NG6eAUIMN-0jJRVI`_#w_t| z5@Jv#$NH`6QQ(qFAseLWJKbTF)RwCu(G#2a^%awE*O$d=)9U>*4L4GKKLHCZlVPKO zgwHV()k*sXq59y_xzHvIjqdcJk5y`ec@RHdR zNM1iDd$KyprCk#-QtXslic_|k*l8d<$&sqgb@?GF@z<--j6PGXC*2>*XWCtbk`K)c z-+or|y{@d{q#pbn>@*kC?d=G2Vxo zeGkHnPSnHQdWhQO5N@qb|L$|4#4HYl&(`N=&y)LphS&ZlujVCCOhm7+l(Us_xRuy8 z{$`dT)Klmy{VOt2gOYRt+Zg50YjI_LYWm-GJIr^qO%2L0ApDCRkn$^}vQ9pd^YcCQ}^?$Tm zOE!UD8(YXZk$7usSyxdzY4k{}FD5w!Rq7(<^P~>$YZcK}9Xxrex@teQ`6Ag)t;9-C zIily@etW+JoDrc#RaduSO0*i3-u(`a^cy%fpFW^CiN4M`l|jW{aqI0$_$|0sOdZEZ z;Fb2nLgJpu$ANKY^J3A4Dh{Gr^?L5~cH+jAL8a|XbiviL;C7xB8(xxF_Zz&=`z}3% z0%#;_OLpsWgeO9ChhJXBsZxDvcEC;%VBoawQ&vytgLvP zR6eM1-y39&sv=A63NEVpwiY+3ZnL$Nn(b4fnXl!jwW?M>S%P-j@5Qp!mwI@5u_K+? zyXRoM!L_VRYVdSK9!pTtL;6m=XKJQO?{`iUA<69CxK$#;s{7JKxlb3R^Nagq2UOc7 ze_?B<)1xTSaNoK~9aUk4b;VZ7IX%7_X?5oJWTF|-EHOO(XJ6%|#1pB#JM|HPTs{I0 znXQf!SD(J;=MVWsy9MyKK3`t`7_F3DX60gray!7vq%d{ufW@q*rp>>h`G@4|Mink? z3F@7DGE!mkni$VSbF|-d4%#P94Dql(9-NScR%~l{GQBfouWIrfc#pkNTDCnRwiS=S z#6IJl^y%i&o5Hr#A`g3p+r`q)Vf4}Iu!|}gwc}_7l~~fZYm7ydmX4|>NXr71nAaV@ z$gYd^w+m}h-<$MP_Ebj#9zj9bhUul=#oOC6GgjVXpJ-&`kBG&VR+OD{?r$didA_mw z-EYb+)?GqW@rG9uvp1E>(ed)|3b}!;AYIcJBZ=!#Yk}~ayNzuc926RO{`3^KmaBiZ z8*R`Km0Q!wfA~X#Vn*2bRomIwWb&gltW<1X$nz=4#xlJ@LzhkBA&(HgBmEO!hbx-9 zCSNGVjVGJjEdY^5@y~!HhgzvAL<_G#=N*~cN2X^4mD^_jaPyzC@uHlx>=b;HLz-%a3&VP9Fo4BzPL zD7$<#>tH#(ie-05XglgC>C)Z2uXvla{?FCDB0Gtz>OQ9B%aWp(4}Gq#gx-+;aV?tD^5aFUkddllJ*@tUd!ukHM7e;NF6`E(pv@bWg(gaS9NKL|~RRVL4B zqY6B^Z5T1KaYp2&6r68R5v2e$4aRsY?u~`ayT*>e{qS&U8H^tgZMVn4cNrybU<-f| z$gCNo25w;iftATZc;CSw(9FUjWXES!^rHLvgdSBal5Af874#*7YELOf@$b@7C$@GV z?Rz!7BR{N^xb`wh2tGe!*(y*`OgORq7i@*}HVo4Qyd3C-)3>d>LHES**}|Yp~^Mx z-Ya1F`i&)G_3?IHxmqHPhzSWjE1otPA4?TkRj&o+gDHvbQAR8HaO$nW?G$OR2POfO60S2$EY9N;I`B0I~a@w7LO* zK{Mtg%j9P(AD`d-4RA5twlb_!@DqD_ri%Qx^3FlCcp0t!PGk3orIjjv+#4GEAfJ4e zA~q(bQ5`Hpdv3e}0$o5=$H=MXM`8Nh(fTlG#b-_V?!GZhp=V}{h+C72=zuPSq((T@ zsSCv2OBUahY-nkT1%+eaL|IMnlIlffK$OfJyD8-Zafc9}%4gjTLU>^+U zgZ!#}PwBTz(gNf54`qofCHPr4X!AdTHI0d_kMmXHhRyS5{8gem2~9%kIu}HY?|gEQ z&C{Yz5@_RL%w-TQ=PkAsT-O;ViID@xoVTBR2+fWP$m90fW4CWN7i0 zZSfGwExMkRYDAD&mT&InCg9uBlOKGWRV58a96i5c_HGO& zS8x7(xhdVH`(p%lA?PGtg3P8Q(whpIFD}qh$MJ5~50APt#k-N$cS^kw!n2?cEnqR_ z7`w7O?%za+J?T=Rz(VQNO{xszkl^Mw-n)UeJ%WclP}3%|cF)*YZG186b2?OTBvl>V zJx&-;Eu4LOsb}5(={ZMc0D3p>*asBD(y~RA$F=R4fA8epm!bbVen>~2k8s}f z)3(#X>}LD*Nx1&ml1Hz0(lXna^m$^$)e9Tl{8qOcLU;i=d6UvRjs86)J z{DpDAziju=mU;~XCnR~xFB+wS z1pO`sQjNN_7rT~9{erbZSdtIKf9dC3e>^*uS+UsW4;-|>Ue4sR?jA)HqyJ#vT1_mj zYSufg50J-z_8G6UZ0?4kI*S^lS+;tn#4gOws5I>LtK!`Xckrl%7aIdpSK8zX0w1A=57hm6vO0IOyoAx=(67 zJp410m(kT?FfMMAc262olBGJj6Pq)#Y#UmU<{X2c79tyZr5P^n?Mz;_(6 zeWb8}kxj+)o^>6q;9;OvK>!>1K`H20kJiU0gJ2l@srAirf#Yg{=l<_0j zf~niM!xpII!pYtw2*_%xJd6~w$F`+pGq@YWC?=hl7au-?^8W9U7gb`OwrYMP>-(8% z9k+||d~$*$)rXV$Nj$G0ToVtSB@O?6LizIy6A?x>cQ%6OUW%z-(nn_3ool?5j`f2k zF?>ImcC=>XRZzASx784=rMK1GrpaRG)#CsXKOfQFN%~x_(h$KO$oS56yl`y8>}Ksu zQ(R{2;a4`6?%Qs)nVUPGS)bqy3`Ktz6P4C1Fr>Y^{o?3Y-KNf*$$o^ilV@An2sOzP z@mFj!h6)L~E6s@4j87Vba61wc5s}G} z&Nv80?qyswss1f$cdwWH=iA@Y$gW3=bFS*JkdggsHdCnu*TL%Kv^#lInreA9?GJ5@ zfAn9^)$3DKD~H))lsg-!Z9bFC1O&QN)b~k?R5OZ-_|+Ra#aW+s>sl{u^9~M$4;Vbo zvDKayXxf~tOdlhgB<8~NNKI*VLfju4+tpMr3 zs>=;C(2j6q&yJL>DriIlby~4yLPPIj821KcVEn=~B*}95+P-UEw95g-s)U5GVETWRLgM=)M8p)kff&-|{5oJY$|PfObkxOdtN znUDaMK(R>Nh*n4*23x*UWI`u!jG9VLP+^#JwU)ErhE2~6%2LaI=;q;S;rH>_|fhRX9QcPGn zn?x!NgU11_cTo{rkp%?RL`<}S`~T7cW|ll%d^NqUHRH{ykT!`NyFY7hCZ?EYDs={w zm2Z>LUxb1uBb=`>`pVoKy&%c)9C&NkI9=Z0a%|kg0>$s#S=k)gZs}8i+;Cxs^^Sw- zFIwwnAVvz=)8yhSbykfsdluM$_BL?`%<#xsPUDzrLr#~isRzS!b=B1}<-Zm|MG2%N z4F4C~n9!ys!Ts;yF%c|>Ny{$v9X1?qzA?dVYW4%X4EYYr&}s<@L`dN-%R9jJNS9Oa zxBs<6zHQ=q!*tJku@x7t%{*L%S*(VcPj$zjKLMdI;Q8j+&e)Jvxnh>nGUIY6oM-z& z(`8j1F+SDrgh!&(cej=SUy3Ok(}P460zm)MAcG#*40N&9!*3zL5joBof)xFXgWkB_ z?;sidrEKI!k;aj9MM%x_ZBFr0aUJ_*sChCE0vjvdS#fUNnskGn((-!O25T*o7ZI|G zZ?7*=URtVAtdo|VU0_^(z5x>mE=l%WanyOpM_RgQI9Y^=h2$KtCC9$1n*xo(|6lSs zYqGtwgUp_vm`F=ijb2QHt%(0`5J*6;L*srQBqbutsCF6;h*}OrTRMzckwR0z!^kNP2w4B?8Hc@S_wvgzWNE*^>WKgpp1bjhOK9=2J7xJmw$TB#S)8(ni>Q^AhqZ)Mgj{N zQYHZ;G(_4TN?gNjhPVWnsql1xSa}d0Meucn&kxHPJYTDj8YbqsAA-z+y1vM{=7VB@ zFJB-AbRWO%fNQK=jjW!h|B4|X&Q6V;f!93hGRt5@FTZ+gN|wsJAl?~2bl*D2Ju$GC zmm&Qr2`;rgM(JHL9b>%V+dJr;M@m=A!46~JU042`;i!TEF)nmQFb{kPGCX6pnvK^rH4X{ zW`RQgZt#BV(l0*f#MO9GmH zCILIu;w<}fZ>hvU{)aS&mdepal6VJ1SH%`jli5)sEp8(4-O!jfQsoY$&@H98G3!wD zUXEsJ#-tB?8Sk9ToOnI)Sw6G#NG37vEB5;vjuq)!x6HYxcoJ-Ei{fihNbp(l(FW)g zm|Pqnf_*^UfpI|Lypa8Q(104|Yeo*n<^mlYoSwe*{xbB6*Cr!wO0Tt2(FDc<+@yH7 zws(^E0`T-T54K2`SKf?isI?AOXwW~w{*{E-hTwX!~Ea7ccA zl+dX%IIw#5TI&nT*=Oszcr4qxVUK?&+HUT3XuYP#WUYGTkA`{H+?uj1hnumrQuiyO zlj+r(d_L|dH@8?smZsDzzl*L$U2WiauiLe5-G80s&LYQ=Fv$2^Wy!+wk5R*MPxdfc zSJlyo5>@}J9R7S+9Nr`PM*qDS2G$%8mpR7oeW$l9OE0OGeLvJa-YKaXzcF7mUQBN* z#yb{!{{+*bzKYk4Io{b~w99ldsojsI?dEhZh6fp%L_P;angwl1k|k!J=Th!Qh@Zf} zX~u&{r=d26&2(P3d&3JWoYc(Vr1QFaXg?|#a^frY`mR*RnWkAa!2s zeN*1M>W5+Xb8>Q)K2i7#6Wbt8(yp`4e~Rj!{(eG-{_I1$=?mZLtz%vjlH8Dq0>b$T z9w{m@nQ>w>w*J6Cw7F^e4$TY#^wKIX{BDH}wKDn#&9_wq956Z@95|U>OK@t#dcO!K z%yf%c$5PU#i}vFaSEo{%%(aO3WIAm~wbA~)Fzji;!cq%W1u0v|`GelK6R;4Q!hibIdWqeAYR>uB+w#mR~?w{CFVpCd1 zTh>b6i@4>Y{J602%_|Y;BCOT(^y!)1W}8uaQy4Wmh2EuwZu6`gy^KR!H{l;^GGSu0 z*{9j8KkeTb-xO$rSGBXLMa;tG!Mm}bXO#gFeK_y6Zt>n0r7wjIWwFk86_xQXZsrN; zlcZBK;%_BpSH`^0?Hr}bGiNeM2mH4>0?D3YroYEAl?!NV5-JqYSRO6tHv}K@+20S* z_wsRJ{0d3hi7frdIdIdA@6ePrRbttmx|$k1juap+`cFrAO@{5O2A<*rF()JJ_AI2kw||IU@_M!n7J?+%-*6B1HM1ZYpGx-@BXZOj*v#)vbv@6pi9%>;QLIAg{yD$k8ZimU^VtI zNFLDY=+zA08kC_(S?4gyK%aRpz^`oY5woJ$_lVxF?`(=l{*X0={{yF@($xxcTBfZf zeT*J3jDCKB4n_Ud$u|uKDQ?`j(Rg)6377$ySO_ptC@AFQ_r;@)*UxzNZNH#(($df@ zwuj!8moF6=#HRO|?{Q7?SLiE8urK~{v^3`Gv&r)!>)sO%y=PL|d`>WJlGJb=bKz+@ zcXi&HV=Xo~KFX2H5owuj_&5jK=JK(YM=ZkKX`3!4sjZFab3D_`5NX*Et|FN>M}RIS zH)fQg276Q;>)A%+@a4uqRqEpxdKUiI>)VqzS1vl<0$N{6C`A?HIz0aV5Zp@6&j4ge zP&K!-?4V+z)k3<|{`@Dc;!dE)&>lwS^(dP~Ea}xv5Aqli0yip99Tz@zBvt~wp>^u&DSd{g{g)d6p>I~$<4#l20&nSSeTD*u^S`o-py+{&&>;OoywgLbS$AD5KDG=Y9 zT=o0+{w#Uoxt#puzYy+G{$=O{LZWq$S%Q(ATud52mD6Z{z7hnd$T%WmAyNdwEa(=< zsK8Itcr;}TfO!`}OOYrDQX0g*tc?~Z1ApiJvIAm|fZB_SjrA5_iT5Okh8)y*z)_Gc znaX8i1yWul@N7I75(Ux`=?SB}b^G?={tKqZ?w~UUAqJ!iKvfh35~)<`$=Yt+Z3H|C zwKq5u;NBSxre0lH(E}#2RM&|X6fzStGl%y7kEXK>i|YTPJtf^B-5@3Kqof<91q7s| zOF%*-q#G2aQ%X=u1O(~sPU(_RIuwxZyXSxJeJegNbIy0p?D(v;I9u}}3C#ug)>eMu zCP)Q`3f7x9$!G_#6);1Baubdw*MI*BNK0$f%v;0c6|O4%E_rKz7!EnYg5LT0)(?;( zTI44t`E!#&7;q;{Z!xUEqUyg?b~}IsplSma7Ajwaa=)Qr=bq3S70L}V&QY9{D`=O1 zj%aNB6sQz-0L|OEgyNIc)YjaVDfFogyM5?G6YoRF@Ur8O<~k?IF*D26fO z@o{lI_mv?w!PfSzR^ckL3k-ANXu)$;<-30F{2xG38qsny5Slg9=H1loPy^*{4-i>a z31&-ATR+0QBO*zXTgRa=CDv5$K@Ad_+U1q9sL190fLpBoQ6>o;lM$kW)l#w zG@qgN7R{Dm#Do z5&alaRgXfJ6sUMgYW!JLb?a2)vDojz*-8!r}zB1QeF{ zjB&z1&eC?;hqzUcSBtd1z7FRb#>Nnr3ik(Y6n0o}3h&Rk@}MF(b|Y^&BJKIJv3gzX z?fWZ?u-P@bX()?w1K{E!yP%XODOVs7we^#lLdgu#w&1@HvcJnycoT4h>ReXP5xl$^ z@+c$D@9SKVwk}V~mYW!KY_WY+SNNx(iIq&MH4cs}K3S}TwfXji)4SyKXKl>LNmLS*@B!n8$nj3+5 zpPh+-el1Uj^E)&dz`*Qm&_e(fXi=fL03zz}-yk#zaFoyMMlbhTG)ku}!E_GMBS3)I z4C)!$!|KLHT>YtD5IRDuR@(V{bHGh1ubsuL4B63=vT8V_*FjSSshI4cO`FX>oeU3L z#glwpr^HUd&PZv zh*Em~c-FbFt-m-TF%9N=>V|Tw3u>CCLYkQ$M`{R|ejld2$Jr>w4K3GoDngs``*F92 zi`iO7DsWe}j`&OuIUBd8)Tqw+X~!G;OBA2{(q^pf*%}{0vt;RD4?^(+J?we0-tZPD z-LqXEO};7IJKm>_zSzqhXUnd(%qNY7DOm#QOC7naS$Zwet~VSTTuOAo`0cG;=;3|2 zJV}c%qdYe*c92V zBFNc5?40+DCNN|JjWf#9R)d#(<@c~P`R0n?_hs69>z^CBZS%M{``8ml!58FG-92`DCvWDWd+p|A`_|;iqpPYLy|4 zKcjASrM-L=8|m`bUuphisMV@_9$!Cz&`Ixa4XzriP{BXcXnNsxawURS#`+R<;!-rv z1*q};S!r~vzAnE|>}z3IX7HQ3P7oWQCr2Z`=)RxFPoGtn`!ay?Jql9gz;m*rL4oJJ z0WC_Ua@iPm6f^Y79b^0H87LhG8_@IgR=0;_UM88D zkOxv)D`9KX5AU3Bg~ibxUO8W%oCY(aP7WJk-7~FgvNoDNX>d6tN}v$-pk{lX|3p7o z%lzo!y2v;Fl1xKg3G@32e>iJ%{YF$6EJLqc{@m z*uZ_vR3!fDu*88bAy|cyhLcaXly{WE+_$lN`DMhqGGu}{PU)S_E{Nv%B@=JG)lw$9 zi%pT>-Mu7IeX6EBhMJ`Hje<(Rn#Z)rW$i-5h34?g|NR?+Xs;8&U&UBqn3v1(WJq3e zX{-kK*>}C)jOk#gs0m^l)f=vDA9K`aet1qWFHsxNe!(fI!SJ{5>SuFq#_xu%Fr2f+ z&B*Uu?kaz(;)tAk&0eZ!*ERs;E}{RQD*!1yoq6=#MzB z4ZP!Q6$GSW`Bl1c-XUQPA${2DKFY2yIQ`}~VED?ExqUC>jgP0zBvJ^@<~9n2^T4;k zUL^w4X!_Ir!>-c>{~aMQRwx=&8Scq0yB<4SCHauP?6oR~YU%Lil77GKa*xCn4Tg69 z%L(+{uiOl6ERJ0LwB#f^e_J-4r0Jn}7Fp%X!mYCLsnTdKzRu<)0mr*JbV!BiR;bNIbNnyFy)5j z(a|W*&R~F7We|&!|5oXSn4yQ^&?G)G{WAoq+%^)3%MjG(_*vATYh^u;0w9;~5+6-Rsnv82aRazCj%###^Icfi+Xb72+X}js#)d{b}xL zl$%&o;=9Ov!xE^mHjghmuVrnh=9zI_5J2n1yE&(Y{)~<&{&3n|J zBi}xK7Vc9ki^)#Xx#9wtG)xY2miEHBtlv#dH?BE%eupW3ybjEht zR;9tWHr1no(s-JldztD8H9Z%Zz$%sDsm;eHmm+#xLUCtGzOR_E-sO>&EQ&_0 zV>S6ld1^7`((_{t?AypY$BN?aMqOj~p|5XW)~nVK5I4UX_s#V08P}sG=bLta{G&>r z3*HD~k~zJTid2k#pPP$oe{&QOMT!s#LT~{jKWed);%Y0gCh%p`GosBpBrD{Y2U?x` ze)Miqm!K2Q=FH?z#f79wn8Le0ZdEdY8dFdPjAa+f?ppIxqT-J+pk$^Ets@D<4O{BB zkDU5-e7*C*Rq%(Z0NvIe$iBARAYoV=@B-XzGSUX3hq(U@*^rDJp8bCRAFd}jWe-?Hs3Cn3b@JG7|8;weAz-BM64{#*HO#IBXy!z z_J4Qbgz!j-iM6}XbZi1IW7!%4Gh`^%Aj|WN{&ppx45-sUj(VEry>v^e{dhIj1HXVk zKejj}aEa}+;?Ey~fLdInuUds=m6f3@BH>N>U|Jm00~MiFg+c$?KctYc9K{%RviHz@ zR1xB|sb{Yq!&^}kC5b@G{xDa$YLKVJm)>1Z1BN3k3Cds$k(!zLKn88(5V0wN_6hY5 zmP&QmsI4Yv61dDN%)NU3ntbUL9944lxu{N9@z{%|ca%6D)7y&=*i^tu;NtqG^>y0h zf2nHtGcH2u_vm6w%L%wqi%M6#=<1AyXCPUD+6-?j@=4mPvZ4> z$zRmN*xrht5?WKsT$3tV1efv016=4H!~+&TSw?8D$<3}HA-O&>G7?3bG+^B!lz06e zeI48kV0U82+!R=DEf|E%%7*9RSThgK3oFmu3{6diac$r%!Gu|!psA`V&xygbiQfaU z2pSxWL@tFutCf)lwZfPvmN?Me_)0nJuLJ)Dtw7`_eJ+JOEk;Zfi|-%I^Tu3*t5@L1 zGX2^5*sou|<{-s}fizUcfa$Z5X(u+rIt+4T#}(l1&7|hYd;a+j2a^oA5r~zFVlnnL8DIp{#mm-qnDMEC;g0z_JEr*?P(K6UZ2k zS4s{6E{7X3wpICkfdLaYTMM-({GJYShf$$yPPMVIk&$nqT8X3$#IHsfdw%Tc>NF ztx?#3m9b>rA;2*~Y}SHbYE4Sh&*5l{Zn^bt94hdffWQN`eiSmhppiiM{SFNsNZ)SU zvLvYh8uJi_UJz6PJH7I{x;}&!1eosGpFbhIi)`9GD)AK;*$OOW0BT2s49EB%F$?%Z zCbo#Ls4QrLS%2=yldLYBu4f{+T)_dg&x zlX5j~`zzk6qrMN`e@&zverJ`Rbjw3D=k$sH3EQQUkt*ga^&RXCHdMBsk=Q{x^2Jsu zNP4mp=ub9ZurpzqmhYLNmVJ&24Js!H>_1BWaw9gUGwS2I{bMqn+hchK-7FR9^WPAe z=_m7}WzR4Cs&zc7q*-+8tF6fPlO$qh zMr_k^4Y#iE?6K5MZeN5@@Mfw6qwM=j`bqeE^@W^H<#qghG74!~Bk=rxXz(f^Vd3c$ z%VI9`t!VVc-Vu|dz9BNyn*8=Mv`!XXC0YfYA2%T6WzJU>%}Yo07Gji8!E6jRH0rQO zXSooI)=?RLJT7Kj!&2%E9k6O}LR5tyz5RJ`uW^851J+p{ai{ z{UXHlK-=I8DarQ%eHj$gWPS#+1y*E!Oxf3R%Q#ivJg&-2CCoq6CPwDGK#FMBcBD|c zs}%Pqa3PbtlLX6x@hzuC*85eQ5MG(dEsy={X0Tsw@@KcCMCrMBms&i%m#TMUjK-?H zYb|x%{2T`8cLk29QE2og7i2@&lSpI#{0-ZBfiZ1yJl@JT^tV9Pic={c*@IC#HMx*9 z?ONl*NV_{}E7R3(Em3ScdV<}oT37ZxwOL#pC5(OtGgL!tVH(`zm^l7__q7ahFKm$v zL{e}?>lqR&Cm0-7?mL(k)6$LdHK^A=o6@UwtK{CUdu2;Eev4ChWi+GF%OF8!kZ4DZhbGuY zQe5|JB*MJghDJe%xSq5~7Ja(NG&#JbYFgX$W9PDuBmKonS<}qQ=*JlDOA^*Myn9G@ z9^zecGiWAc;U-3jN5|nrvqPUhJ4fyp<*Sz;vA;ZfVNV-+>!@D#o8&U>)}&JQH2 zG9_bcW-Z+(x?$dVss+rOJ`4*;!mLpfi7S{!lsyUYt>l=$5{B#5)SuT@$33^^Ry3d3 z=vx=n5dKd@6n|5Y)bqZ~a`>iG*nch)@=9NP*c5Ben&00aBgHmIF3mG&Nws#6XiFHP z`Y-E9)wJ|1X*{pk8RM1W>CJ{#AT1t}h6!E5*o$D*wH)=cszkd_gI4xTESu#iV z>_TCInQK)k0@+4CKP?@Kh>I5(7LI{_j)fTJkgkX8kA*Mwuw2RE@p%xo0 z)NtBVfmjF1!;v@izO54zf^RM{GBS1dQL_#r>~vG~l)H$Jp3xd6aVnO4i?4ID1V5*L zH*fZy6i&12ebu3U>`qUr;?aG<7j2qZc5Iu~w83+HBO!I)jpAPRL%uAFYBYgVsgerR z?LyWCtN61cikn)7?>|559Ut(p{3G zN0jb*l=a3a!-^AKnShx6tLuMP)cRRaFwedD;WNiP^+!M}gmQ~_hmAs>Kb$3Gz>c+T zOC^4T+K+SKalb0@nBSMsD{#xV}%zJ-tOB~tS&@7r>zlPE>B);AlXgvM#OGCTYlwj zn5R_|t2V^{Kww08(d$j$82Z)(aL@jsi9hy^33*tw;~z4qFN>o!V+M)Uc7qiCWsb@&ON27`e zE;K*i>+;Y4_yrf^6vL|U70jHM`Fr3=kxz)+{NK>E8fTIP451oc?~VOA@jS9k0Mmf5 z*8c)tF17z;nsW_iA$yMybZu{Q0#5?-XUMl#t@H0Cf0adC_ZDmJ%ES{m})J;pq0 zF_E771k}(G%<$`g~ zkI#_|W9X&x!Ir_z&8n3?(0mxV%hn1*O%O>HqvZHGp33(G^f$-~oMVR)FlV$_J-z7& zI3u`%Fxb0WZgWWOf?rs&Mh+pT0XMM3VT;QcpD~o<4f>~%Ws@X9ec5S)Y3nmX zF%8-)X)&?i@J%0HsO;G8z3w}N&YUM0{o`iwTS9a4kcB`7u=?RU^$MT&fui_X=lTYw z^-|YI+ACIq;wjC^JM{>57zBM#6_lE`tp7jmm$g?i-V6L8{7 zHzze~ifX?%21?A(1E1*I;rE>FfaWTJ8uDB76wv4uWHm2q)1}Z;9 zQ7>--Gj5QVBDxuVsQlm~PaQh}W_BMkG6WqY!Jp2-(UGz&Qc5pHHl$Ngp;!)3&Y(>_fmYB<>R2*q}e?h|TfqeQ9W9l>0wa z1!K2MeeTWH#oQXTRK7Knu#iwB9@MG`K7$Ht)T7}sQylM#)+HJqX~m9hO$a)NGDnp0 zobn~@AMr}uoaDyHo)uJo6!f0@>gTj?iR6@}K4xWskK&`2CE>9c!?dRrl#rO>y3&mY ztBaA3k}H6RWPhw$^}WmL)G zU7;dP1OjOy#1Qs%AUml2f&;Cpji_(Uw(#l5;b0?VKVSv72KpWwSqiRpyx3g1c%6o) zc3PFZJ$j97@ASjp9Y`kdT3IGnH3rA@lMIA>vEup2;OShm+rl5w(}DPEfuU817U=~Y zWPp?C?zwhN*x&mcd4M3akE(kc*(VRv-|WA+8VET550Q`tRV8$4u*bneYJ^=`i7pt% z<&N8}+`{J@N_I&9g?|J2Be)PkC~zd{HYD?!i-BNZ1RA(pug>nuwo`#qimT=t~B)oMXOyp!fEGM!_xIP9C&>&`{$_plh*T_!BAfVigKUae44x zmj_CrA_<7^`%eyVj+n9EZlA=j|18sCB_Kk#zZXP^`pV8DQ>~SPPsj4O1#9v1yelS` zFd<6yqFp!*?Nv3E7lX$5Up<{4Zu4s%loC%rTxYf6ky75dDOvJ27(2m=>wJYaRenf= z-I;dVj#Ty|FqAOS0@(RHE_6{Cy z`p`*gl(=5{X_RaBA&%`ZU^E z_ovJ1ssY^@w#<_2-EwvV`ZFFv^4YEE*vQG1YYeT-C^TVXjPXi;pI{20Gn*26VN?Ii z&SKLwQ?LuP81tp)OW0afav#D}v*8y!M?sfx?0L5_*QczdG~z!V`&Ku#-}2p+DH9L*ltKxp_yxwMfm1V zpIth(mWj^3pj&%C(HFewJ6(Ryc=$`AUa=?cz0bVX<1+Ld4_3a|V?2nK4`6b~Q4#35 zuSasBDY;?al6N>3#k)CC6^BcPhue`PxumdDKuAc29`WZ~x}VXIfOp?wGvf>UXa@bw zP%-I(U~=*M?>xSl=n7 z9V5otCasQ?KkyYF){F@J`)jzZTY*fC%17%{i1S%0F$AMo-L$}zfA-X=we{+DKKW>| zz&lVPg0|pdDRuY!uP~qTz@Dfave4Kp%dA8ALnbG>Ai|G_u{z zqFv$g(<-SWhZ&!s=*Y*#CSUjMP}io1xF8j`uQUUhYUrBl=Sz0vXp)Xov}h%M0lnpu zKg#PV#=|3NM-5ozg_Jf0iT!Wt6*mL-W6NU_dA^ab(P?~j_wbZ1I>nptlZ`Q{iFp`5 zWMyDt@(Uqrhb6mxRe#Uz4l@|i-X_C%k0)#8PtD@`e>cDXo2hL!|BZ+71_Kifkj>(f zQpV8b<>f%o5W)U0AzBqOj6P!^yEPj0;KQ#T47@p-nL54vxDltudOlV27ZDqpFtBk3 z-igosuMT2FrNo$|`P)mbB^T=t@dd^!etK=-4;j)52YQsK|8(bgtX5WEt-?U#9hAGF zdSN0{G0H-u8mFqZpF=P4`)F6d@ELi=anEMlJ;vW^kjvf`;M>7m|@@;;pf{8LQq#|Im}SAO($+~(wW*o)lbjz#>7WLuESCuKcRmYhei zjOv@MBr>gCwy3m89Qz9`)B1#5Qtv55f1vNNdmTGOW>WF^`m<~eW9m2A&v)`%`)2N_ zz4l$-r;v?Tj2+2WHlk;~mBspt$@yYKM{jsD_ugkte3q0=#vdk`Y z|K$)u7A<8Ijsp||VX_dU-`_<_bf{a%m!Gq&RNM*nCof%FIYPB}${bo`RgdkUeeDwc zYyY!aDOa4Ia>0_NuSIYmLnHYFfxc+x3KmUI*C`6s5Y8NTR!#?Ys@lg7>8x}bpXm5s zzh$$iH6~|7c~vJ-w~N`#W>@9yCI-$$bRYMaJ48Od$E5Ei%pIq6TBv^vAi?D^+3nf& z|AJk=Ynu7_g#cDcu%w4;vi6SyCcSxi)*u1nSvntn4aNc>hCw|n#D!X8z8803JG%qMG=YUdm~9uX$~qy9z> z)Im7Hjo|#;i!?$NjE9-tzgJy76qNyy+Dd6);kzqz8P6UUO}K@O`lZdvC#i(zivu zrJ>Jcr&~t3-_hAQJp?31PKc@zYA@yn%qL|A;xx~+G&Ba&@-;C^AM9@w@kli+{B1>= zCRV>am%e=t)n24T9-)0(w(Q*`73)?GTvS81k78!d;*Z6*MgYc5(GPZ$IpNHne(JUP zs22ZYzzX%!G9ucvr7}`4sLKCI8W{N@F>U2iP9xnM(BBd*ot`7e@SCfV+l)Vd94)?6 z1VFlo@^}5!^rb6Sm`jGcZ$kBkpz7&+H89&CwhMPzKBNtblO~fGpcOzq3gt7{cNoPh zR3z9OjClYrBU@$o2=m_S>bg3wE#Hwt-2FTlAkj-)L+;=gs1-by!7y4ArwZ==HD|pbt@V_)d zRg*z}qpM5${sX!m3o#am{vM})gDu$Axoi0>7x*H=6(o-64D7te9%uv{{j5XUiXqA{ zU5*?kpiXd6t*ouPX2ziu1!#v6wt4w~0A`5FX@rnK1d;-L10X6=m%A1Jm57_IlE4@{ zfM;f0U5HmXKuTPkIctP^Ih!yT&MEknWU8|nbv|lVi+ONufZ^((JPTt@kUGXB#v_dP zxDogWnCu0B(J?+C)>q_*&m7sHJ4N@ks_1|G_%R-@z^wnmp#;JpI%PnqaP>dq=?4sB z=7fnKHM9y7k=gB*3NOb`MyMFDvERbjz?9eKKf7>o>K|VX zkhKdZT0c+PG*-@EZzvo4Q}T|X$HQNsG`$?iHUDwI8@rqNda=%G1k6=XT_YSV39GWC zSVPSK*#SjKM{q%pKQLVg<@345?Upo1@OxHzVxqV;)YM`J)(}^!%VKn99PEpsqXN4< z3SEB98-H*LIm;G*{da$b{`Ld7EP^N#KJoxg{o9_rpEi{L>8TWW!SC+kBBsiJfLwuC zL$DKs#7JL{OFyV)3kA4nsFx>2<(|>BHHg4LmjP0%!dqwp|1Udr zuyivYUv**J7@L0)pFDc(#P3yp{_6~Vo?ByvL(;$;H;nTiFwNz|K^BxfZzk^1i|+Z4w5dRyJcY94jFfN4w}SFT3n8j>NYYfuHoy@^LR!(TQHR z;pc{+;DtKyJ>gB~ZH>g{L_^tPpW1t|u4a zyS#yeiP>!qFH&<21}vI8ykonTPd+R-J>%j{MNOU3c)Hvtt9wv5vHg2g!aIdGiyY zy|d+WlpYd=egds$13 z3e^n5VeejeNG~otw13d>GdSA$IS&k{-A{k7m=L+8XI}Sp-<#+q<5iLgMz1E_7iHjR3EiAzoaFcv@PSZShlcN(Z_H8F^8&eyi@3vS-3#0lno&d>Xo46QM`MYcgG_!SZ1Uxx)tv@y9(15?QK`N-&2*9rQ8#j zx#5mwbCJERaVYKK7rwf+~2uMB_OZYr)SJ8BwMqX+HgGC!}n~begtbgaY*XphME^&2R;#SR) z>P#O$&A)JUYaD?m6^2C7x_yV$dz5yB=0!VaSN0@!h8ofK-sVH_F=OCT;c5!2k9%AnSbA zfX+!`d5he1`BaiDIfWxKI$>zT&clc1V@6p^OAiQTExR}@65dN(T_qNb_@!kM8ND-a znAX>K{)Z7D*j93CgEeOGYW}fz7@5Uj0riB4=+dt*DeHqRtpnnMW5!~K#)c%0Uvb>U za2&laB{K{ozncXYno$*ew7eV@tx92gxh+4r(KwoO*rAbC;j;S-Cy^_jxz9rRv6!|5NZ>=_{Cu5 z*+Ko~xU5xvtZT0Z)7vjY=J!)`5BGPkahzjs%`#@Z;`O=ljQegz@iYB1EnGqmB3u*{ z-&<9P{yuo9r1IHe^9on8| z(Sw<*Sl|``J_y6fZ=jT`U_hYS?`UZEg zH#W%8{AK)EMnLT6xsmxAL|$vKeTLmJI28|qMiQ)hEdZbXGNHsl6s?u;%)sE+^{KQB z=3VBC*$wF&t*0*B?zhFg+%S-nM~RS#c-a24Asyof#mQDb&esQYEW|EA!T|lb`bzZT zS_)Ws*#48K?m&jFt^JU&cd7clq!cMSG~%UGs3HInb@BKA*2~_0+=92CEdRnqa{5Ya zDxf_gPOXz8>Ta*iKhNtxg&fs}yj=gg=lW-ap_uKL)usxp7kb<|-wOPD(PD|Of6VV0 zj?H&;F#NK;W^DJ1SSqgSxh*6e*f>P+GeMQ0ZaC|qm#tVRL{|8khc$~quUnJTx z_iLr)7%sn|6ZQni#!WU3y>b(Q*x^iiXKwti%Obo^p4kda=I{a^qP~T#1H_gX$*c6i z$hg*hXDSKb9JHyh{q9Jvgar{4fOSUE_Eq++{D!ai;*?%`cqoWvvc@SPLwXko6 zMd5M&;F5;=6{g`Z=Lb6&aQUNNUVsW2x(u1$&fea0y}^&w)v3H{j4Ia<=T*y zEvnP5_jbL#mkQn@TtKJU;8>YA!~_VX3iXT%Yq$i;RI zFxM^^Up+6+{QoS#7B15GFwiAv_NCJeXkQ0yDnz0MTF>&vAuc-7xr}mkSMaCqwST}e z)ku~!2D+@MUeJ?2{1B1eG6Ft@fUm%vrt1C#B|K2$r6x@Xc`dq3ZXP8R(Rm)V0k_R@ zx(oC3)Mmk`xGTD!GhU!e<8fPk7?kD)fT#{HcOwY7IYOc-(7m z!%unGIR#ib^xc8w3sA}fNA7j-J1j19!v7^`4o0LdBjL2LCVZOz6F;(1S6hqlUg?#C zYl`5XJ`4&H>ZtU=8PoVEVGchrx`i(WUkI5NiI#_SBbWoNjcZ6ha0oKwe+>t)a`fax z2-qbx4UGWnLRIlu8Jl?w_y+M^0!GTHZ@=(fWYOeTFOX`$UjWxZ>eheo9+AN< z=0Rj2q`rg?sn5@Wz5}XqR7)>6w?vx?I|^3!O!qNiod0WU5A9Gy&kAD3E+k~r+LG;y zAi3bhoqdHN6d@Xb>tj2|wO)s;FiU5MQ(_2Ro~?KexXXt_iIEj}VzG{Z?z+w>UxyQt z#QSV2NU`tuUyNtH0*Nvzev|tS89-l%W*S}r#>gSiS_(`jySsyfS>FDS^R!R{X8?r< zDLM2OzEUGFvcJ7qy7d7+^_w8)fXjJ!yYYQ20hcuapw2Eg=gx#ixne|WvK- z#Q?Gey&*72xJuMO#GJ<4xK9KvR zKcKqfh56fktl-TTwf%%&#C;2C9I}g_?<&E-x%9=gu4#QT# z=$OWnwU#B6qNOlG*TX{_D4EV<&%YxV`)`{y9=Gz3%+VOl`|!-OpzH7P@}Db*JR{f)AKjwxP0 z>#m&#gdKmW!~1i)L(r+sgh(A3P^cc-VEpMgun5a~yex#GhQ=uH*4aTiwz=yqx&ME6 zd6iV?l|3U{SMSTcOeN&EV8OW+Q}3k93+`dM%9FXvw(}FCX>>+uWHg{V5-LrOR-S>1}I(?D8)Rl%?1Eerza7 zVJS}uzSsxa;^OIG<~p}peY4RdVFVXrMwvl^Lp>yZX|!m(o8xwj|0><`V*W$DqlA+i zKNiQnM1Jw`F!P{kR6oA{_3=z)U@|r-S^3+r!152&%@)`)WPAyAtUq=z@mR-?-Tw>f zqfs2N3}?XYkQ1uKDh#r!k3?OO@V)P5`sPMnK#OCZBJo`Vb^$Tk)N8HqT7^FW%+wS9 zyqGAtIdNK}tF~9}o2KsQ_NeZdB23IOPghgiQ<)0IeZD16ZPt*KW4Fbs+i_C(ZV&h~BO1Jj!rMW0!nA4(|Ys_)K zepIs>n4cr9OlR(=xY)xR-qvGmI;wU|G+NVCH5Uijd!{b*fmz8Bv z82{+>IrRHZ%176RymaY8ydG6QFUM*jQK*h@J4C-)NV=c)#W^a|K(ucY&2pW;e)wf{ zid1^Nu~S0t$0KT@$@%iEqHnn&q+^wJNyXJV;~HiTvOyxKxjH)s46$fTZ`sAGm!Mzwl;z>(+uq}o&`UG>#H^P7EJyKn`?XN^iTlN50xym$-|7qhhIrba z(**3>=jYRL{rUBcP?T3O$q2g)Vp*R#O-V1>WO%R2ZZ}LJw@&Sxr70v=*qm<-0=~ivo(v0v+I2cY&3K<{95c~)z#f|7h;7v@7^D}!dkWV zaQN8-HJ-vhFBlagGRwvV1bP`5QkCN2g+_OH7IvO>qE*>Pfvp6LF%j+s2!p$Uf$4p} zEC(S)p`zd4o;{o2-E~OUhX*chMTM(XIi(hC+RmhP{MxL6QX5nogzm{a(*xb{7EZiGI+PCid!#*KWFHXd5 zPU=~brHL=&`7gy%ucjRmO&0a&+?SNp&aQtR$B6G?IsH^0-R6M&vE6+#W@}?u z_gv|}NIJ3)+*Su8r-YgKP8b#@GQYVP4u7MZSIRk;s-BYmHvX`0&KfAED%nGdVZ>4; zmvN&IbSQqua9Z1F5G}*X&k&zw-sKCYS9dP;yL6j z$*WMC!;G#j$h9L&&7gR0l`F#(_mE*9B}SoQc>99?l-^hF{OH401odjUcCGq5Pl>L< zLDCwh7FqsOC=e164vIhP-P0EqB((~;@(x_=Cpo`ScN|JW&k8k4WReOgWN3z=peQrZ zvBlK_7vjv%ueFS@O0lh(gZ?_dAivJ*P}h^-J~YOl9gK#&55VRThXGu)Q}ns$x;=Gp zAzeEyEX)haRQS)Vh;g0-~w$S3FrW$~gj9hE^JNGS$cPkrD;RE8FYL--V%vrA)q(HD}FVSUARr?1nfigh?i!gzQ zz8_F!gv1vHAH)%8O(r8~1*P8Qsx?FRaoc24@yX- zJS`~afTxc-N=Lt_ns*#utoN&GekGLt;JRSvtMz3lY@h4|k-85h7QJ`4LDi`b*43CO z-~o7kG_C=|agYjAm|60q2nYcb0W}@!HO>33$jtL*4GB87R2{(|U`7KZ_$N(@*o9E` z-co~~K=r6eQSF+Cumg6CoM2sH08JVc|D6_m+Uj^bqh?j0GtgGgtfUP=iL_e|LSIL+ zxnd=bP{s8X%K7=UHN=QVv0|1bRSj%bO3_+_P_+K+?#7O6Kt{c7b+vh`KH&D5>cE63 zuqIFHL47l}!`W4bJK@*EeQHO*r_WavIm+3`dl1Y2_0>u0a(9In3XUBXboyXoVW zFe4g#S$Q-JL5l|UJp$T7dJ63WG~?iwwYytv_uf-Ns(Ch$TXXEZZi8SZ8^c*zAn%O%AV^X(Qu3#MGWW`c3%LNTA zNE_&+e3e?33QS5@E~Q|?0rFb}id8iE8Cu`cX@K<*f?WXZUIIqS{G=%8rrr^rdXLYK zjBHVRzCz0+I-mY3?U7)nI_S~aQw9)P8}BBk+*cK|#a?3@I|Y>iueF!osG-O$Gsuc5 zJ!dCmo8aSi;dqF|AK#{9CUCd*m7F6QNi8v|C|>h)knv6iJA(x2TqTOh`d-9YJhPGOt>m_uVYYeI zwzShKC4X&s=loCeb-aJY@98wmZ7pIWzn@O8NH!l(8Z5ti>G;K*sa_%oS8n-@2b#;81@)pMTL<}{$F+>BMWTz?Bt3}5#@tXP zZRLu6($rDEd0_s!IGLL0msA|)n#6@R}XwqGel7_Nf0`h!yprd|XDh~fp#?HQABW#Ul`tkI_#LphDJ_G#)MB zN8;r(BxRjhG;gxqT)pdPcGBopx0xyVWPama+g_L%QsmvXI;Iwh*zg0Dly4;tJ;iv% z1M|CIp3n{nI!tOe)ud$T6|_lJI6gi7NUAPUePk%+eFu$QQ@^+0%vX^RrLWzx8I%5` zb+Dq})F6tYI?AF?`*IJJIQ^GbH^JPH=rY?Qs}?yQ6(T-$bi;bx7<+Ty2IT70j6Ww6 zj+76+HgzX-u;KgiePGJ+_R96mY*ueEq_RoB`ZF&du}$(_RDSi;Kl8YWvvf%?JC)N} zPSmZIm81AKzPyCCk@)cU@hzuYR>$pf1+AhNwSJ#USwSA08%( zc$nNJEX+=(;(Kr=db{5g@Oi<`)zSSUkQeV8_7?7?53O9r)88E4eqM0;B^Eq8YbSNJ ze!2U%X?4>!ec`%ia4<>#*}`(j>Fs|CuUxN|0&YjH7M8AGTM=%UUjL#$SlGKkKK;9} zvi~wGCg6yVz~38DkMlsdgk3~)0jajfsmYJ6$<(wA8w=lvxGPK_agDQPMeuztFB|=@sTA4oCLTw*>*{{vlYD?+ zZ%_B6m-qMIo}b@g?Pl}5%zWLu_U~uy0jtJG-?r6NQbe8$BwH9s_1rAdAx6tDeBS4E z-J85S+%jeGoIjy}n7kZ!J=efqp@I$ zb~Ap1rjiau%K>byG6{#m8Y}fmjq%+>n=J;Nn7xMi( zv1Lw<5+z|wS45W)4-aRjC17uC6j>C{o&2Lmzw@nMN}9ARg44=#XqwYz_JK3Fy)eCg z0j$l|aXqlu0^;IOjIExXy(N%33xwU$zrPK8{4l}9L<5T(eQ=wD0X~BFM_~8szj%Q; zIvq&EU4yVA-?LwDIxSrOF5M;~EG8mL?mPKE9?PyiUAhf~`5w^6=c6(HopW_Mn`;V5CCM}zi zD%UqVM^ClXFj8gjbhslut0;kj2Qbn3KU60%@B(17R-*gfzh$Ji_pLeWc+1GzD^xRn zJccn`Rx!JmF(u-qA-{sE4ic1Dz!U~yn;2*ynB9gi5rXaiVjlv*>CCV$`BNX$vP^Ap z&Z<768b{a1L#1-d_Scu<#zcX>q#q;=EvG&$J*L-_rg)XF>x}5wi*BNv$QyR+zoo@N zIYZ45WMe$ePz)|cU?d*bT@fS+$P5Asf~h?!Yxw{qjz2Cl-AX-$4=sPBpqQNpizCK` zIQOiz={Wih)O9eBhDOB_T0m#Noo9$=(n6lpsE0*Ojj=j6dA=;oyLYakkY5h10P;Do zOpj8Zu~P`u#z?D@dGJ?*#Ui4knk)&e1P4 zGl%8p6`M?iwX(fs)B3D%EkFMKZwN^Tl*$y4429cUVqZqeUR~uT=D7P%;LqlP2=2cL z2g7RG9e$HLKgVPe{-ai{UxWpXK9^1F!+N8O3n5MQlyUTep`jtXndroL{}v5M6igW~ z<~ZjFMMR6kQY=m-5A0S}3Z$<&pwMI?jzEr(a(w3PvU=Ifk#1wZ>n3J{YwJ-ACQPU_ zA#c4j2h{DKmCb9THiuuUv@AV`f)p^gf9H*qFY0L#2)nqrfR@(!_ug^EIiKS#A{CPal_)5!APp7%0csVb;6-SqA@;J>^DqeT?*L!~ z!sE((y#sW*HJ?8_A(dZj8ZXdwz<4@=X6oV-tl-<^`Kst1+qj;54;$X!`d{SnA)8o42a0`0-k4T^L4l z6)}9Y`3rq)L=@iNvOxM7;5w9ei_|v@KHgS z6L9^f8PGS@zdf(cxWNVA{0+`;=pbR|4Ac2LS>E2>_8rY|L4kr4b_3LZzyxgd+@8-_ zZ;3FFIt@O%Dr*-!Q(*T1g+4U-&|5%@0#^tu8Ja4G;E@1d9~{uOlMgQr=WKGv9R*@y zz}wN)Te1}h9(=ryeFN2`9QU3=j2Niu09|S)6;Dlh?S8SS z8W?TcgZhp#kncENNoG~?L2xPaI99NemNGhDQse+jJkcjbG>DnpEL>i4j-Ensp510Q zbiYsRm8|3y5-nmnZoP++=7!ASd7XHc+@mh`JK`4rEJmaxZOLRJ1jOx>$FP| zynRijC_oyY`i{fi)98&a?^&E}{wDh;B0a}kypKbAvqJG^SQ9%)_!S+`-L^w?j&P=k z?pf+!eI28DYcD3-5fDFzfl2R7OD~Bea}Z#CKI6nzm`L1pl|t^RP!mHXrM?_Wd~>4LCzxRx+tz4Lqk#=jw&j_cYuedp4!ZPyWI3BfZ*4m4woq8tp0j~PZHcM>+SJ0DSrDGqvW*f35TCqf+f zK5Y_-=i0R*t$gWIEOM+cDg#fH)i6qu9mZqS8yBVsbp;{vJk^tw{3x4?$Fln$+FC6M z5=f|#Fzji`krX&o>VO+dB&_{#L}CFSXgee9RXon>Hae z+39YngZZpNdV$6f|I_2m*Ngk#j<^j+Wj9e)=6lx3vz>BzTOVJ9x?sOkI9g^`nY%Pq z@ill|#-Eny7@8ko6QVVYlS3XDyjPTDR`~3@VvCk(@7tWJd{%mtL~Q(Du~Kim{S~W_ zxi{jdJEOJN_8;;;d-*f+qSHOLna~p<1GR-~!>Z7eU zj2Weq01J@Thn$*M)pF;50(6ehU$jr#Slfp_uTrQt)SSUPEy)^TE#Ba<*|I^?Lcl0% z^i9po5&(vLw0wiQ>e8d^;q2Topp=1la*{?_d^EiM!|&4R=*}JBj}a>NZ^=Uh27Yg^ z@;ghDoX{S05_*`kfq|)%ds_s=J?S|)tVHTu5)zMjGAtpU2F!{uN`kE>C^caogI||m z&J_#K)@={bKieRMo6T)W;{*EyKK`nKzER%3*VQtnWZv}i zy0*5j01sBQnP5(IA&C-^l-&Bco<4U@)vJt7ToYhiC3jx%WjD>H)!XmQPtF9ZND2Hr z>BiSGjeDzu9NYT2O=wlqp^pP5RpL|gqnYb0uSA}U%6<6FyI{m5D$q-FsGTF2tNr1d zEvA#9U(!nf6{eJ4C1z(5mv2j|8tQ6<>!Ox9IAYEJrv)$(vdqD?JP!X-e)O;FN0#_N zf{{&|WE{(>cwOyZbg6eVpYuLV54}`j2urT;Vu{(5ua`qZ|L=%i&DmzgP-_dq^ zJ?-;x-xp{=pQ&n>7D?*#xDC_T^IvtNfEfWsLxTTl*uPli<}aYRx_ehGHg2@K0?n=N zn1j=ZF^SzCz0tK<^__mV`|ZdcoUAMw1h25B1|FfS^)tq6!MASkd3oL7u^rh%+!kWy zAFhbbOcNoC64C8J3vz6>wEIXOGaq;_a%Q}gAJWG#WzW)T?*8&cjJQNyjhmmp2gv0h z;BUSB{pr8I7dz$fBu98ffe;5LFu&7K>GqW6oxB&!b9D!mTnmgAbqaZeQj|yRJ&3p9-PvZ3X-bb4x8|C&tkzOWnO22r_9A`m2J~6_sd79SQ+t-FUR;#b_4T32T6LKJ z8ytW9m^V0yCa#+5#z$@Ugb7QE6=&+5e!sE*wfjhV1E5h5`ggT08gaWj4;|f3=7A71 zJ1eB;Km9moE8AjMOI@PmN{w8!e*1lIa@o`JX>&+3SX_Jt#B(j>MLir2)7U~Kq`Zul z#oxkS>b$z_WQfr=i1K-T9lgB`RruS^H?ts@K+j*V9R1=TX(pq!4P`W)L9=dHIjDN^ zxe3-|&1+#=f)g)g;zOo^xm%J~@dytK8|wCgy2N?6RG$Kk5g~mY>zEQtPe11P8Gj+h z$T6^4>I;g?KF$4r6C=}0WBO5`yIO>lm0+X`)~dw=PmzvEC-0XpN$XIpf{Shm^cl7< z%}l&6^JBHh_g>mR1zi-ZWF4?a5h{@@Fm`Z*&IIvI09td~wSH$9%r27gtOSrHS$UNr^4PmONlbANg4t z;88Y=GnLm{%63F0SQM$m`@cxHa{A0jvmA&wD+Re<3Kc`&TN>>L4hg{JKg zdS~&p@9q93!AGP|7frdA8$mO34!Zv)F!O>|#$TN&VQkq1i#cdvPXMZTSO9@BfG-># zqU1xhd_qk|oDM}@mOKNUot@46A(8Q zMGC7RMoNaA@;Szinsa>6+}p+nf#yGWa$=KRG#-TqU{{gUXOCs(1{`!*L{qxD(jomkC1EV?g!;J!es3D z@V^llB{JvV&c447%CYYJ;!8{PJI2&(0O>6;(j&P81DOy%oKK|p(d5pFE>jb1m=CF@ zSwyHeEnutpfGV((d4hQUwym&~_!^chR!{OhhBBS!g0wuVZwu_Xn)Bv{g3b-na2P+L z_BJ|p+)768szrBtZ|VD?+7V-6wp-?|d3)4wNAja-E8IBrkc-?7wbxBWo)K`^L-Gd-#+cl+d4!U$V@o!`Sd8VOYaqnmH#n7v9zdA%q9bhebp zwwauo*!FE2v^>3=$=D#z(>}T1<@4v%{+FtN-PzZ;(R+t~y>2ClW^Z&v1~!jx=ZN{@;iYE}@ratN{`AbsGRdi_ zbL(FG^lENSm??WWK`E`|Nzpyh+ScQzGn9DV$l9Yiz}-;0JJ*LVZJBzTgSmH&D5jSU zWF=yLAA9rb``*eJOeyqf27%E7iyo)FE=CPk(XF zjq)O4K|Mf$GwjKGb`!ti9KDZeNpMn1J+tJK1Pky&tzP0FkH(?#Ln4^BAVyIzUCt~+ zMj1VJp-n3-Ej>WKU7*FmD&a$qYD{)ZycNt#&=KjP5gU7DG1t672Clz>UUHdin1FpYvwk6MIkmgv7 z(|ai4DsCjMJ1EtDy2JA~zO&;_-Hf%*gee1uau<;~gL5xAfq;^ct8pX~)x`6ZP;(r~ z`;@|VJk!EELseX_oI(e8%k@>Xx%Rd05hz){VJ7x9YWaB0$d+KrIeph8d+j6IqRyK) zf-y5yD{+Z@`?v!BLZ(F;7A;0wgGMMqg+17!YihQNPa@MYhB$%qp!Cu%oHbZF%bZiC zQ)w;HG&(Hn@nQGEa(UP-p3#U1FGdcU9sB8Ds_WgeqBnyh}HTy+ONIx+V|76 zm77JBah3YS2)Aywg|~I2s>tZ!IGaLWn4{Ak_%LCY?l@#+W0TwdZ(aNMkIP6$)~-H! zf7KcdbN7?7Cu8>fSubCUlZqNhVdZ^~>~Ke|{{G{J?z3N+w%tw$>&^c>x&&kBa4u$-2>>XJM_xZn`ZH*eoe$s3C>8o}oW7Y%_Q?7^G`tRm)YF8W9+b#e+2WKR4EE(0HFQy>F3p%jikE2 zh5Zv`OQ>ce<+ZHEzOWhFi=~WP{?7YsMS|OPHRr&D`P#Zts74^wZZsXN2%4{@I>PPtMQK z`2L6JPhr@8>>rOQ&!_i{#<`bbZvp`EB>43=GRMy$keVpYvdFTldOIUDM%l zwl~vdikCmN8j#5>u8%aR9@~iu^|FMh^xLM$V z!zu&9q*f90W>E6*Dwn$5P0Cy+6*VcI?5yQ@fDChQ*bbZfYpaXiPp;o>nQc&mm&LP$ zh9ACHxQhUzahfq2hLZ~q4GG$p3%Xcb3_+xz)Rur4|*G+>x{|RB{L;d7_WvlYX26(JvGx^m3#JCn@Z}}ad-t78cS0QLFr%V31`+ldN<{M!J zx%V`AU&E=ax3YHBwYkE#3T0o+`wtcy3os5rx((v1YNw}5zoe0rLFxj(!sv1zaSbC3 zvY`2KS}=k)RMmD738H+Ff|)1Lddl8Y4Nec}JzZVj?^g8AKyX-hnu*^4m}L>nSQtUS z6!~B<39`2{$lvlhSPo3x&d$!Bc3brn0}em^(kUP=Ar`H!wie~er&Pu2SlL`VPziDL zmIg5)%N3qFK>xXuG?0g65)~B%6YFj6f}JADZBn;F^97!&cbn(XbdJb=+kP1o6QqIB zys(ELy2CBy{Z{s&XT^q1N;?%EhWBIm{=q&18@aQe`EmdKg?WPK$+R9!$BUQtcke2I z@fNZJptat^TmlsrTzKFrM?n2Sjstg22!mJ!>?GoFfOzMB@-XPi5nkg?=>whlELbrg z9wM41xI!mD21AMiOD5PK!FHq5{n^Ae-`Zh17_6R+$g{$e6v$^6WM+i z)xHc(4NM{sZa4^IgVl2}1YyBD{m;DyeEl3r|E~^JpXDLo?3MrND?~W$#mVkf6}-C53UnA{ftV z(Yzz_XA4ouh~QwcAN`3uDQOhul|=xLyDIe-<;D#1cm#X;g9oytJ`{`$iuzB`n6!@! zYhF9$`|1$tKW_NeU4whd8@>F&OQ$h{ic;q!;=%wG`DMY(u;TG2Sp`zA5TP#lgIx+a zyYchxU6K@hyMV{>foPc%UQ@`pM9MPgCUdDWXy+HYp5!@5L_hhc*W@<}^-X+8Q8mZ@ zwl#38*CeqqWK>ZOv?38Q_i?{r!)KU03SA4xP>nq-q~}Uuqs;gdzw(;b_O?KtpRUDI z^l$Fvq1?Or?IFLMCU}rou;d)bk-A=L7^1gCtW=OnC}FY8u{^3KqnLNP3P%wke4V0Y ze~^xMZNd?TyQ=Zdit1ljsPSVrg-!~<3mSM=)6B3Gz*%j&}>5sk0CJQPE z7OQ}0gN0b+feJ!JiUBf17kZ)#PxOZH*iyPUKN8+l!l^O`i4~g=9;`1uWZ|}7?#k7s zX`T<$>!)^N6)gH4{J3ScrFt+Fie#B>QvIe;rbtr-<2WFG+^Y@EN0Ry?HC$?Z5P9fJBBN-ba9HTEo5tfnl;5%`k*)9T=y4RS=Q~0zl!?!j zHv~iHlF-KJOW%2vd3YO7npWZR2uO!Z|HI1P^I>8w!&0P9`a^JOaEbP=k_QeHa59@owIZ`bkNt3WJ_kb}@_6g%@l4D=AEnEB3gIJv`$RO=G2><2?2tU8uWLeM+k8~7 zQ8&qf=sgNCF?|;oyaWWXz_qt_Tf_3{f1IYoG6_yVEq0SN-*ea++=d$_L=nm`(u<|v z7yBNF)wj|6wuqCdF9E-o7n}VbIB72k>}LiDZSn%-r(#7 z0r%9D4&||0(g@lP&YTf&zm0v}Gh}^&Y zgH~znSIEdnaYbA07tdCi_PbuS9{r;dCR+ntyagtmT})P@91k8J?!`Sk-l3r)=ft&6 z^T9diOFif>q9xxdR=QhPFe!jlUD(mdq7)mXTevyJRxp`dg!A!=gdkSX%lj-~t;@H! z($X|W=({7&ypwr0Ug`eb{yl;Lx?94#xzhHE3R0uUqS$`ai59sPA5q93upMe+yWYQF z(Rxl@U+DGS2z_)U@x#}I^xU8xyOIrteT%0~uI9377>~CI=WZ`=-c~MUFPx+9+7&2$ z9Qs-z$Oe<(rbPO*X`oB}>C_-wWirWnIj&9;FW&~|=Oo@MOkYU+(Hl~+l#OlUFG$%Q zYZNK?fQDY%#7woi5}&t*-@N1%^y~8M&aJ0XHOY{;^h6p5ibJFZt0XY>L6}a8eF})* z9s96@uxHo_Km124sy33mtXUaReh=|Cg z{jfEs1RWkZCwm+-1Lh>Q95Dlg`gfzes%;|jDcJl1sV8+};PDC~-NNYvj-mG&_rQ7% zaZHxb?ZBcQG0a6!WuP#~p{V96d)-ITqJW*VwdU34r#K?`*G3_q8zzphdpO{VCi2ed z1L}=pVdA>0msTlr+y3@twU09P6um`z@O4fgoGN??OCCVwV@T!xI z>1{mWV5LAF81~?8HvtXP&U86cGGKiUwZWx6JTkvE=bLN{5Yi^|{1~nV~ejA-TIBB`5T&QJuL@?Iz0Sb=M5$ifc z)E0!;IzxCDh}yG803qt~OpkXpeMXNs9*3i#161mnaJhm}7s@Th+);?Z=m1TW%1@cfiA!%=M^ly z(L$9SO$gzKc?yLy*P$eA$SzS zRnr4XMo!C6Z>UINf&#Lx$^XwJN-q(u1~4pnUb2kZ>aLY|9rnV$OqAHd$!$vBw+4dz zIkbJkcgbu~1{m}^vfsX4Zh0PkTSckARAR`IXXVRK)JYF$_Xan~Bb^tjtCJi`4B*g8aI~+s03ln z)6y3APm7e4x+84XTBd6JckeABlFr_Az5A;2Y|@2Ryw~q2DR;T0vf&-9Q4$B%n}t8l zIj&wJ0H~R@r*dEe?+HjPi-@tPW$RwX!#@yp z|87wt^{ot53`VrzPN_@grBiS-z%~xj)P@Dy&(+j~b5vQ0WDX#I>Oq)&t)WcE+a`#p zUK4_I*X3kK7xXl63Yoz(16C~|ou+w#o57s{pI+@JJ}w5zJc#%x`&Z&RSlY@~L zeo1f`fZgc@A!-=Unk$FCeM`-;nBQyo8~p0`_jkrs76#;!;49}7{{wBlmNIlSOP4=R zp_BLdJBLvCGlt{=0vFZ-KnJSab@lWtnVW~c;M1p1-ano&_%fm){Orp+6|)Ny zg9Q_0^iaYY{`4K#2j+0m#noR6QsWy5dNOh4j`C8+K+9Tl{?F=SCWBS*g)j3NGOPT> zGIj(D$L-nV9c(o=?1FtqA0niF)q(1OZFZCtWRWwPTjASPc;t-X&)M^lnh9*}8R8<( z7jfE9RwqR=GSBj11&B+eVw>U`47`_e(23J$ z5G_m8^exS&)Iud+b?4iCcX9H*HtU3#2aWS*8_LRS=`k*}6vp-Dw#cJM%%%K9xfil{ zq<3O`@Wx^WJBL-|b!Vg}A_Dwd?MaYtg%eG{FFl3<&PkG>p^Jj|+J$V?=KjK^TA zL8nfr-2Ntk6=MDpObL}tOrNea1&oc6-N}d}6gWdpiru;&A&K6Nhth?kSj56Bs2PLJc0D0?l5G z_r@H^N?FPO@eLo8txLwf6Hc~yhXEx$B9E4vA%iQD7nwd>W6GFTaOca${VE%2O0$^Ae@sj049d6k+-Mb=NK%G#pnQ~G~e zfWq5g1bAA6( z)hBWuZxItE7~S^EXog!w!wdxr|F7w|yUIk<+#=Ki?7hDC%;N78%tnk7jeG4pwEUj@ zW~z`oTal{&=Xp*C1#+IDGQHiq>yN42Dc1k;horEsCXQ>lJeH^RDP$dO>nl zH%SSVFXa6Ch*2bs+H47)u(AF!`_dN3FlfCUjA9p!+SR_}fi}V>{`Gf@zrn>OGWzY6u=wH6S7ug)U+W!S9Q+mC zuWkJpLYTNViQ4;vu+KvZtM>=iDE+FCM5s*UTr+j3dFD;t$njPd+^Xv8d=;x+F!rw+ zq8F%++hLeu4%MPMlXX5K!=C9qRXB51WwO)euq=IYA4>(EvOrgXU>O_cL;)Bz=?v-) zZV>0(Emc?FZu(`**L~c_(2*9X97z}i6PA4&UpA^(6xRg%dKsP+a14QVk&Rr1nYc1G zD}!A#`*BuGj2etVWEcz*VTNRdxjO~>51xc|4)@+*%v%PpkI*EeDHz3pN-#Oei-*w_ zfIWE1?;W{xoi&Zz_(h3IE|^~{Wy#+SRKbW?A2f=2akF40ar2e0yviVX zH-6ZYIq^{lZIUt;u?NrhSMkf(y~fV_8}mxa%_3~dq;Cv%B8Xk5HuG{>+9y}HlQ14s z$@RUMc(!0w{VIC#XOg{;PAo^6Q&tFX!Bb@afnLtSpLdyKp2V%|GkhogGLWS7WI*+q z`R@<644Q7}=0a8C**j-DMQJ9ePZa0rVp%#Hf5vjO$`X%1UZoW-xFAqck1uCQcQ5X5 zefECmtCkb3%h_a=T}`0iAE5=?i8jRmp#(O@qj}`tsT9L(a{7I%bJ8)PaS*oAHMre97|T#-kFw65mMlk z^Sq9kNg#GY4GPHHj1gP{R_3Goq%nQA-@JxuosB5Wuvsz3C$ATG8lJBU6fS z!sN~Y`!*u_1)4P(&a^GantyQ)`Ac9<{etVO7(jFI$e%bxuI;CEXq4EeWV1^z=1H~* zsw~;T{5gsB_4N=Bw|-B`&41-t4Sp7h!ZUrRJbo!LHkJ2R2NieP)c4a`RV4+5+0z+i z8QknJ5_Om5xD!e{{N8Ddb=r_{nDL00t|`ab@r?c_I;R4tBt+7J99N9a;ctb^ySyqJ zW7ILzY{1Zxt9-LKWkv6ltgWV77Oy#@ah5oN+{T=hJ|IKqoz6Kn5vS2ijtZ>uke^O9vQ; zf_suP?Gs^21Lt}WZkEtOL;^N4!h7X^6WROk6s%|8lPjxpC9l zfdpY)jIb<%X@k^*-5rSptzP|Y9W917B{nIT>8B_|w_=;h?SAY6?FwsB=dl<@ur%Ho zA1`kgsIhv?HG_jfu*e$;qi^*bp(A5y4ivGAYPxn5YGFgI+PIJ|r8;_?4%DE<=V9uz zSkKgZ^h+wijD3DI^bk>icHNR(2g^E)>&Ny_&llRSpE4l509YpCxBbsTU8(~U<|%vr z5mk(F+IPlD0|nMO+HP9#!zbmis1*_x1|bSS%c}OujH~KCeTv%h%Di0xkxiUw5S|R; z8oLYAp4fEQ$jm;e8Q{-S8~J9#(~U?K20QGI0MK^;AryjWL{is;AT_wm8f9$O#>ukW{M~rUQ#ehAff5R2NO}q9F>#0r)MN9j~ z8)+tBzRAyJcnxGw5ZATfgLV%Ja-rBRVCc^+Eh%7i0yw9^=@?u=&XD2-V}ZfqT)#oM zqkJ*B*)Tc!D!PyG!osi}zA!My!nP1d0W09*fx$j}Es(Y*=5-VT?~Jz340K5Uu5$nJ zE?xhA1wIo1;vK>(**=90fj1olUagS0S?tkFTMxmb3^Hc#q$rO+Z>%2$k0X0cT^-5s z3j}u{)e0I+lebBBei=6>1>wSXT1vlFJPSh7XZTXw5#C|hc2H9gx-k?UIC*;b;9Z~< z>uw;*6SRj+D9HvW@2tqq6;9XhzBpX%s5!IwhhmyRP^6Cb$$d;4b7Z530&g_J<1s`0 zCGHR0z|_X63d=UUP6>+SzPL1%_PfRpr@S@MMIyFH%H!Chqk~G464a*`BB}18u!Zy$ zME~eR$vkXbZ$3RV{p7Fd8^dtaEJEq@o@p@2sR#v$9jkN$D?rM_~S(&Ki>wc!Qbbkdc@brYC~7kosqW?}k9CCl)%$m$99;9cK=*<-4(U#~7k zqog9Wkg4h)YKfL@nIdidct+dwx>GjKC+fVIK*dcp#Boo{d9qfu zAES?RHpMeu>ffU%%@Td9UBDdQO>laej8=1`lG>8GL%a4Fh5menwiG$H2H$wvW3W(` zBeTd(^$ki$=B<~05{!cn3>`x7jO}v{@&8$z55Cd0D6b(xwj;HrLm{;2R;7wLJTsTC z{}FZZl+useh<;n5nPJw9>Bpa$q8N+~y$_X}2f6Libe&bCSgIoraQNbqTMXXUkaImh z^P4U9&dxV}OxVGFxgquvT0+1U9i-B_1Tc7bYA6n z+V(D$FOLyFNjuLs{qb}@>ELnio{x4Pv)Nc>vSaX^9*f6IUrit6tmsY~-A4OG)}c`! zW~{)7>Q731Ygbq;JYF;1%|Uwm5!%-jMLRR9?lPu|WctcxUr8g9P`B_LLv#k;YR4&R z5x(hJV(r_wUvYbnnUe)+$L^)dsPNM;JYbom9k6$;jgN^bolpD z+>BaUJEqI;>y)FnERw6|R2=%aMaf&p@+6>T^fICHgbFrL#dXjqIJ5h?Zo{UZH)t1Sd5&PHKc%^}rjm1{iIG4334rRBiJ{`!?V zd5DFS%TkDX^-=&!T82B6adu%5(vou>Iiu#oJRW(e_3#K#$AIGh!H9jqRASJq6cPr` zZ1i`Hxq(~KyvSyeYc24^;(XQust6n@+f;_^$7?NX@#t)Z>h}k_pBIPit7O_dqx1RP z({+jY{l+z{PMhZ5N)p5FZ0pHi9QuEfycHEP4fkBWbI0D72APNNRZX0e@JcX0N=TF- z-EzzueGA1z2L8uMPOORqZ~l0QhGP~N_<1N_tZ=WbU~37my~t%SyiM$zYyYZyN|B4@ zSqN^QJMKSkY@5=cw8O*K#nEA0&J(j9fvPTauWoSu*5ChQy(84juB2(rM_sqLV0QU3 zSNWTbyrp7d-eOp5_B+eD+1NZbqr@*vkAm+9ST3$;bN^Yx} zWk0>``6IYh&F$`D++1E!VYq04#8(}Vmb(#*( z&9Ol>p_29l-fvvrg0ZTdQGx}a`+*TN z*i(Hy#^SaA&efr(tU#8PhX-JHqyRH$W0M9tc_?o>@+7hJzjhh@xfYXkP+NPlv&F)8 zvUpo7Xm=j;Jv;_klao?0RdckwIOiN+tMp8YOu|S<{%RI0a1T-N?tE6=O0qzqQ!I|2Si*wakS+rWJS$qrvuIq^b9_Im0a_rtJ~Yf(AxNx0iL5(7%yA4M+K&?sNhh zeo+2YSe5BytM%r?V#2N4T1ub0C;hsyv5~^U8{nZ}xB1!TMyt@6s|@2<=v>4`qqyA* zzuZM5)s9EmLW^qR{fwpURmRX}e~aa|JqoriL@=#`5aDrgaB?C-bY%(kvQ!Rx*Z^7q zk}m8VTA@yZ1z8r@4M2_o6r6nHDmNG}ww-?7w+qO_rcBg=^iL~Q8QUz)b|5`YOoS>+ zXwAJf>}J>KgM9|5l9tZ1msVgO5;LI0ZqNhmdixUW6d<1SPj|)o3F&0U{w1^$KmqNA zktPImLex-fTpW>%M%9e_0>b?O!fARb)O$$y-?b|=K#>oh@&MqZa0FCTR5Hm1KAKFj zA|sAzZ||GuBBm6c!J;Jkw%Vu^#y~Hgl zIs{epiMRL|(yc-lDCj_FeURj|a5Vrve^6}rT%XJ!04N~61{DhE9^wAC<9t z%r!uB@UL{%dflIa4x`EUvLSU|wNR_6vK-kS=Ve(=h34P9Uc*wI2@i+@fcnfchk~X` z3U8{o7okRy0A~g_C7wBPSO7+NrfQs)GX6!pmOTR*n#AL|CX_{_%oWW*CuqamMd6ge z_ne=b8{dN0-gwQMfd}_?s6rVFEkQ=ne)*{#Q2fVG1|Ezn&~wwponIY~Ch)``85tNr zq|%f4D78!b4hHh!Qc;mgE*>6FE*)mvVVLdxLu0GNyL{;cKG@x*)06#V%ToJ? zSW=$XekKbSaB$l8kAKba;$vxV?^d;c6C{BW7e+w4B1oB5@QT{y(=X#oC%4D8U+RN$ z-s`jCj_ZpT>Wz|UH}{~K^s?gb9flB?y{Y;sqq0Qv5$)scby|NS(Y5tfi$M<=zOb@3 zu46G#(aCFD6fv?pxnQ|E2$Niwye|INZOUZ|_Hr-{i?dGad){0L!x0?aa$nLSB}=PK|%w%erVF5wnhk;0MW0( z3E1=UDg+wg+lQyH??n(Xk1lqrjwNsU{+R-Z;Xl?sn1~T%%)VnWAPga7Fwpu2(|lUw zgq<-Qd~l2D8yj!JL9qrG(V^!sqAX7`t}4E~pF0YjNf$gSfe$vn)v&Nf8BejQTB@8% z#l$L{0zIh4Q4i!rLc%X%Qvvw?(GO0>MgE}!Sb1!M%a?wX_YxI*j2KptA1s~LJiuKN z3=q`{8AkW}Ggphpm4Rhd{AJNlGVlBNFvUMx;k&2{hxDpJy?oWfmPr$V{4bqF#TJ@+ zEjJJ2>+Lyub_x@f<|-?G+{^3ww>D^HS(fHe=+U}ak1-Oi2LfDMCI9rsXru=S z-7!%8%88bify9IF&D=Il8u&2TDG;Tk#9N8&5q~cdA34(CRMK+^9yH>C1L}z|1`Zme z0hEj>DeKWwmK?5(0UdE&B;$c;Dvx}WGrta;4H}*_YDH_LA)ll`JoUN^rJzynCsaN% zzKvtC1q2c*WQ^aWI7#HmoMyVK3Ch|@xnz;sD}MGd{X)XVy8lP~o!SnEj%2=6*|>|i zA!#0-j4Lmhqu>RJxs)tEC!y@t`y-wDNGTc-zS{&u( ze)rUf0{T_yi)RnM9Oe~1Dja`4eyN{X9bv*;di6(iaw$Us&djFCH1bp|=|^W2j(_G? z4#xzprCP>_JDcitEba#cVZ_XYIDsb`JKyEQ z?~a1%+EPMZetuDbLj}ywaYK$$cN*m{!`kLg(NiBDhDsTxN<9DFoNl3Z=~LQki$tr% zEr{#FxT=X#0;^m#*3$+mS35Qe_{;;3i zWuKEYYdse-PbS6RZyBNo5n)iW9)v3YBxUa`u5OLm}_OEQvB<~q?Y&0>etHr4tF zt6{2r+?P72(?`<7cpVcjpjKj&ilG+UT20)KOp%*<(yu?hIKakF=yqw_k(CaGRo$Cr zlLO%=+YtpmqLgZMG^^f$eMy?dC!U`uY`6H*LTCRG`H<$*cWQR3&-P%MlagDwmj- zZ}~GlEwHg^u1NdQ&Nvmr4k_jD&@ZG$i$6qqi-*aqjjddWviKOuo(k^*@4^=t!ZtQ) z4UMNlLbatcHg=7l{=624+ggniC}>I8W&cpc1&c408peS62x5!u%jDTpSd&IzPBXAs zi-+M0PJelSE(jOV;M8MV4-S(6bug$>fP~JI(d|O}88ia)4=tCep`5*5e#g1cpu|j) zsc|Q5$WE7@jitdNVZ{1R@B#?LSDZT_#RPP=gesP zY9NfB3HZJ1xab@U7|i)A_dK~4aHSQoDZaeEd|a&3zO@!J@#{IhZT4^H%b{oAem7FN z^E6pHhm1~`zj<||maw}Ym=f^gEM4=pEC%L6D%R2jE(s&EP^VhKT3ih#s^xCcH;b3FlAaxN^CYuNtlZBnhB!Sw1xIzCFm63Uk76RgObxqN6rWah_G0R1 z>YI-&T(py^LCJ)CiKx`gcVgdSaxfb77JrRTU9$GA9sq6DXx%-H-UNYfvt1`>N-GR| zXnQrxj7E+Ng?B%lX=y1IH@TMf4sMXHeWUvD7-Q!Cxb3CbGfAtxL*)I>S@}9{rPG_9 zdnb+QIR?xbgDWao^7)-B(!nbw>V;1j6GqUMr52F&G)j~8+de8bB(tWBaCPJ_Zr7aq zWPQxG^7BAuM6-BNK^D;)!JWDhugFX&RlHE-;vrL$UTnmcIMOUsxnAMb`}H@5=<832 z+H6=A78VK|oL|SE3;ulhly8(;s1mT)SmyrM5~VtMKi0!=;YN``b43wDls&~hTu$gwY#)}{_Gc0Is1tS6*P)joJf^H1sjj3$R5=ohhzxdVlU1*k zCxON$HzLE0?Kx}>9=A@lZ-lp2aVsf5{S*K9A$-prrsa~tpjCZRUYMcCU{3k;*)uCA zC$&1x4;2+Z^IU<<=R$j%R4wr09pIJo>~t4N-Yk4K;nZ=1tj{Tjcq3n5K?_0 zq6bPbIA4K=1hY#GgW4Vc_%t%RPZb2t)8W=EN!GPGY7O89@_qXu%| zI0{hW@l`7gbgA+DD6v$o0j++eQS%o>AU%E?cjq&ByVP$1VN#TM9V~fPt&d@I*s zt~WQ0R5SraL$$UjgF}sQ2~8LI9F_%;YH-5s?xPiihhoqI)*Z@zS3c?<3BfEiP!{L< z-!y+Uso5{#HXpoqvwl|+`D-wr8es=;`(cI(O9Xt_G#giG+ylIng`@i*U9$XV6!Cj( zG8=c3jS8&{xTTcA#A;?HjXFV!`VGjoP}6g7OHW%5T0^ia#2IimBXEEbwE$*tJYj&KZ*K5SSiW8A)w3N5!N3ZzGQea9hV1^8Q-vrD?8`|g83Y)p02uvG zoL(fnd;kBm08UPr_R;JI_tAy}_dIBZYGF9-eFL!%nV(&uRQ8dm3ao*zC=*{RaCfRT ze-o#!Z3mKjXFSa33yz*rjPwo8+^aqW3oJ+zL4a@N(YIEE!ApPpHZ;+M&l%7H5oDM} z3|Q@P|Luo95!_k`Nj#`pu5$k!`~RWD$?2!sIWlf`l^e2s@%;H}3nxSfBgFrmrX6>4 zeZD{|3=CS>*&Y8~cySDEEu2&*N;g#;%zMgG}r zSlyw!@14(Z7^}I`4PGKmVOcZsJ*{Bz2_gGljcc;}lqswt#7zcNesJllKWW9QW^tZle%)f~@J9uFE|7bePsI1zq zYttZIQX<_TEg;g}tpd_1ND3kyQU=`}Qlio&AT8Z3AOa#FCEfL{>wdoXkHg_W;HtgX zIoF)We9Y_5Mu(9zHel7PO@pU^-A|1nfBR|jr}$fe0@-Qr(po>h`XcdZYbmlKLWM0N zPJ!QmUWyr)1EU7FC4QFegMjs=`nS{%9uZPBd;H%S8aO!Y62yN6@Laz))|ZnW{Tqm4 z^j(-cgeY$^$X}q@{IFPXRy%nZ3H#F^rfT4KY-9-rIVHKY_em(S>x(XQEo2esZ&|JA zl-Zbq4hwFv9K4jGKrJVkiKj*G84BvXR9YR2`F2PeoZ7}jVjG`E?WsM!(OScc-^F_` zcO+?vlVOb*y`qBjnS4kyhLuteQ!URNsVdMhLvoPM&ItO+m7Rhu8h z+L|O8i<^6lDAy#EXH1=+SdLcpc71T(^!k5Vtd)r{@9FAelV$vMcZ$`XN6+tmjM~OA zc`iHAta_^`OUzhDa@*;V%oJTn=wV6VqcOC&-j4?%C<0-)*6&=qa0<9@#|-G2Y1{SW zs*nU);O~<&3oOzO5^S6f&xJ*v?|vJ`(icIwp+q`m(m~77)NAQo#4g0CMEW+uQh}1B z{v~F9;9WVXxmS%J_N0f++dQ@cT*f4#MYc-Yrjn9hoV(--%_Jqc+osu;CXfD#kLy3T zdu2BeOL7p>#~O2}ZQ6TFxa9J|X;NDQ<;H-WWbvBCcyii7HkNR-tPQ%PmHot!^zC_y zZ2k?mh|2YoPiCLKG~;$Fx!mhFBYb47yRz>`yMWWC?w{a1!p(3fPLwi$A1u-SE~R%s zvY-Dv{H@@+K%_q~ghfsqCp4F~90nfcCSqAH^hH%yrLu+0U}5JJbd?!u%HdiNb&{P6 z+h@I<;%;u!SRpD;^2+5&Gvgw`2rkTOAw4yra-*VmQ7f5`82-388B${3=p)S^Y4*XI z!6k@Fk^IjK?XJ~x?W6h#qvs(8WVz4ZbQRl#p&kBV#!F|^kN!NPIsCevdb5x0cj!d( zDAI+&QZ%A)pJpD^vmwI2V8l$i%PYl9?4%?YgOs22`wm{X z(gJI|#cpto^fC$1F(>6U=vth~Dnw!^YG%3Y3>g=y+>YwrJ=_UsAD#E{RP_0C z;r9;9!I!Hm@O|+6@Ng?BqGVDs#`W=Prl!}O&-&I}YX+Sp%p?vJWOb$juX}IJ=lSSI zll=U8i6>!n_Ga=YM~TAw(!UnTciGN8{}IZ)jm!NhGa7G-6n-u`ECyU;aXwsFDo z=l1WI+=RNbOlPAH3+Hijukb1QI3(<9Plmp_1;lSgKmVrtiTBky@s0@Ur*VM@E}Vc7 zTQ}$INZW_*n0Ful;m>2zdl8qv9pmEASHr;1$C9cVJGesO<1)Loe-y0vhr|E@`GCxI z$I_coPtrvcVs4q7Nq@NIAZ)^AO&*bF6N2@=*mFs^irY8QO~QV0%Syvy0W?Hj3#l)2 z@JXFs(|Nk*u@`F=Pdf4se%TH;s5;{hSV)OnAKwTTtYX}LH-#C!I;xI>hK$0dm-`Qb zbvqB+PlCgJJgsj3a8S;e{Ip&!^GHF#^K|cgljd4tPmG${5&AzxIXMp|KB14za7`M% z9aqQYqTOt<`21w3AzK(bq*ao&bMm1DS;gL@EwXCjaok7{)PjYp=#TmFaZ4S&V%Q*>bDKq`_^x(-k|YuN$*8r;Lp z9<{#Yd~XI&dfmr}6XScCnXEDK<;DR?F9bK?PnsB%nsx8h0V*~IZ|C;z@75)0C#8NyB%&x-N^#(^U>=-OY zbz4$*)5j{M_-qVktx@K@U6W5JYPbiU<9bDeL&eR`t~byG2;C1vMfn3G{ac(J9$_)p z{Q$^|2k08?s7Y?d$pA?z8s}SHNHVUTdm5~^eckAL#t-T|2G<^<3&_FQSr-75f4^%O zzSD`Wnh`|~tGNeeJ`d=T3OiF#U7WFdJazoR-=S`8WJXh=z}4JxpZs9M&uEif}I7oh^Nr+$T3LP3hULy>$+pZ{$ zw|VXh-nG-smh0y#1;kJv5MjGbB8V7}qfE+d|EORF2d%T>)lOJX6Q@Cc0^m1)q*=h- zA~W+Y1R8MFe8EjG6|`HewhAIWKp}OCt&o<}q)QA-s2&W#REy+)kiG!!5xlCL(hE#l z-&SBv1-G>ZwjxrY9b3gg!4L%p#3bA$fOaG1dpe?}3dZjcLTHMB!F$jqLcH+ss{?{7 z>;>klcL_vpOBXvW1ZJ0KU=)XS2IxO9LPOU8!rs3G@y~b0eHK!eLRS^cocfmHvgl|c zA%VPZg7~Xi1Z&)5L|Bw`vSe)ZiGq=GX=2oZPxUC!aD-1Ms-EWjs&yZU9m7HK-$T0p zxYaQE=BFkh#@m;HKdwuHi}=0Yh-0>=`F)H)AJWU$nx$hV4eP;(UFUx`5^c^})vx@` zcP*b@Jx7dVv~%&n;CaC&F+q7cN8pjw-Q$nd{;6+jLV3$y2l0!NTJyyp7QTzf{M64? z5)cw(cZaD^n!c^RL4L8d>>b%>|92GaLvxCB%o=oUZ>`v0p1dQZE)IMhWH-!4i#`$; zMBFPYMHfO`N{XcMhC80{<6|6Z#aQ15=BOCNgDNcff;qHHUpJ_#XqiXfe4-FYJ(>&j z77QHajYg+G(El#Sa>O@C#^|`Kc}jxwA)F3_OFtyZ6t~}&z1_U^EniMYg!Qwe%v}>D z!CHJg*NknWw~mzpX1I=ZR9p;#q_WP$oydHJ13Jj9t@wtPTe36xyvs^Akr+Kx<|>%< z`DEOkqkgv;qGf!0aM{>4p5Q6f2v6G-w8*HNp)!%=T4k?evJMOf_MyE)$LdsLp~f<@ z!qUUFSQc=Ql0h24O;J+`Dnqsks+OX4rTc)sQtrKNbn-Ny=h?XTYC@0VEeq2Phk}=d zNjNoKUW9Cge8r~iadA?)_eY&MFoW!aTVv@@1<*9H=06iMhz-8yE6h~OX7hRDtT&4) z^Ynvt^f7y3mi9|V%!iwwdF*9B-}5pcCKt++Qk4m-4IybZ|My*J234TQERykU41N&! zDQ};%%}u9y38pg=IdAUlq-JtN0>qpOhnlXEuDM3eWG{TfQ6A#ck7u z`{oDkZ676PRp-DYMvgryV?m7# z=4&bBzWk9*6w1aYf0%7b=3aPiAh%Db(MC@tH;gyi2iZnjo{ecVxD?w5eqAVZ9&c%3 zY8NKIY_%1n>W*4Zj%zl!2q^Bxy%GMb!Qg&A5EZl4R+0%r0+O_0qm_f`NR8T{E7S2nHtefPl~yW8oh(ZPbL%oSL# z1EI+&UZp^ZNeoIOq1=TodpNfDW7FaiFI4#m^2M&Zt8io%>Tv~yxO0?5)!+I_m=fQ= z@)hn>2s0f>5X|wta7BbFG!?sJxg(QWo80^JxJ<;#9FrVxL%Kab{4QBhN%R#evyhH@ ze~7x)B%@+DC`~>26#!`tJW~^gaCi%8r&smyjE$1F6DI>65<-2ZdHE zYcNx5w|pFf;w&fM9`&VpIFqHAZ$1y@VWHrhW!fNqbWwK(Gt=9M;B@joZnrKg&Gge5 zHh1Yf`>x}4vB$X{m9;#NIW`%GM;LO(pXkO(5;q>E#dsJ*H7zA(0#p|@L5?ECp4pq2M0kn)7Q^n z&D2sUQohR9YFOd z_lPnw3{9Fe{v8izK)_iDQuj-|eglc@Tpjk<-h42%RL}aI`zh1iHR>L}U+H#g=(yXR zz-{O+H~e*BLY(o2hKAmIB4#zid3;*cq(WbC%nZER$|7$ySx8ny-b(SLnJW|l6g+Pf z-p>LQxM1d$Bp=XVi3h|#qiV4H{! zVGL6ODmZnDDZ*Iq-TfGR4s#jgLUoZ-wz^sl$l*b&(6?C% z)7>gfae`qCj8VF*!v_|XKA?Yn1K1!Uoe0e}ILOvHNa9pKbEE}4#+^IzNuUeT#Do|sQg(oh3kZL!v7Oo8zDW6}E$*=dP zj34r`uRL&B+Im2aY~oJIW84t3*#K7Z<^=g3j5Yu}{`N9)FxuYPiSM;?p$>;$PTx?c zX%IRY!@aa)Ue)>w#gnw2wA}dp@;y)oeg}d`GBY;^2~@3OJ=|Rg_6`L?A$pcZr^Q~u zc2Udpq71wBo5JiAOf>aLv0E?uUp74RwZ9Q~syR=V#^+EQSwp%2u_L}Z4ML*1K&9x}1bjb1fW zSA%nc7byogInW~qmv02|5hClF0q44~Mciq=;0Ey;9L3)UNMK2agc0}=SrF_9pg==e zE#)vYDFylgZWN#$fBLMv!3GNI{eyeP)#+@bVg_PHsADyuLz)>z%e~o z8y*xH_qq$(_4-)Bu6Y5}f5Xal^LjMGK5MN4IH@&;EC1iKk7!S*xP~VI-v4m=0hxbs zPfE*m8#3KQX#N!W9_?lhgi=_G(hAa! zs9LvB<%n9@IC!SWIy-YX?vgemeY4i@;4&LmixI_syqQjT@ic7zB{mYn@1k2HfkhN= z)D)yDM3gu<;_=e3ztELnH$NSy)(N)U%5gbet)Fl#LT%+CsP5cC8jQ{r%09Bi>o;HB znXy7O{Xi2}sOCZcAtf&&nTKp~D!e@dWu8Tw(7^O#aPFt=4oe+O(LB5msRbUaAjv2c zK5XP>+7L6O?!c!Zj|SLyIn{Tcs-UBgXy}L0RUgqwN%y0TX}<`L(i@$l!xFw9qqP3L zZ#9P(dF{{7d?pLlDuhJ(-a6t9J4al3L`vT8Kw4#^E*-~x{k~|H(~S^mPf8RPJ=D-h zr_Otj{cwF`W8*M;*15$(eL*ks`$LYedn_($n?QHu@Ef6G3t6E==Vm`cAbtg~2dNPndch2kh;$ZsL!$Pmpk`F=`vPllwNeo#f6{>jdI@`s_n#9m@ z>SylzPn*jqXcBWa;Pd;4OEVEg`lF2Kw37jp@z=UZr%`{LCitU-DZ4;!l-X z8zj9y@x`m^vBG7S+wBj!ZlQHJ2Ad7)_v-l<^r{9Erc1W{lqMrrdl#=)NUXkON|(qp zEM`@o%L9e4h3+4@Y#EUfj@g&ld4fWsJZrP2H|*8-7Y>TPqvt{xg1uOR~r7GV~;RxJLQrg_{yy+ev5M@rnTx)(mB^>K`ON1wyGJRO~ zhHQx5)nEdPt8np4)ET!Z+0DcAihi3q%WtOCX#P14io+{17bHX~FK`A6?E{i>16&fK zNk8Q`99ddsmtQkfnr~05tJf?@4-0qwmd*InPswd1vZFGdC6H-%nZEtkvsdIo$nSt% z2jE(aU}vuKrZp*9Xj18spdMWp}o3_dN+(ZsA{(JjHJ6 zHs5*a+fq0!hiGy6nSl%Uz$j2FjMOl2vMy z@?3k8H6_=oUB7?d*>kv3eayq7o&I@$-e)1#sFaR6`^EjB-PuD0#e7|KBdDkwt4_1j z&{P@v%8QGs#UWL{LAd=OFw$-!hI_p%O7DU6a|2>4^ z+`U1)P*++a+uY7B)}$HWyqibmbdG`h$E2$ z?ma--*f`RK` z&8xn&9Pfha)MWTO;6~D9tuY|Y+Le-;$4vB4`Kz564*;T69+q$)Ne7=9ChB!*#gA^( zc-9_8@JL*xjP-~E=ro;iByK+W7#&Xi?Sy`2T%4m) zlf$K6G&L{jl*ZpFQr`7Dxleb`R?OD7a9kGml|Yly=pOHgbXk)ON8Y=qMtxjkgz6ww zk-X|*b4!=E#dl_S_HUxMXpHOeb1v&AbZhjkuA#F0jD(&d%F)k-AJ@D3rK%pFo;MLm zFm{dEI{Wn4(q_Lnn0nKx>XkA@n6J%)q`~$CKr=MU%9Kmk`}HWw!=1G16QbnV`N>kE zF@!3{Ec9Z;QT?9$tKcRnIAne?lTi^0)HA|T^JG)71pk|#-Xm7|{U|4;wP;*Igb`(C zdA&;0!1%Mvb{EIG!|TLJW{|$Q--h(>_hCz3??rna3<~#Hjs1u)(!o$k8b64Uiz~gQ zsZ6HXMS_oi>;+9HFlzj)Kj7%^R|R)}zMdQsSQbE4hCz_@bE;lzx4UTQ@>f{v16oXj zJ9!zw|0pfhVI%DjK_b)AqY!F=As1*m;5@Id_X6J}Ees~U;gOMe4Vm2Frh=KW)!%^g z+?ARLg@1meWk`aRsM(zn4ud4gk1mwYQzzP7f9}rcJ=lPKaqr$OFkIx$=<#eXfVmlN zvS3FBgEml7c~h$gt6pz@TC4rxHn?+exI`0~>{6_!lAt2b^!i*m*u!VQQ?2K5*@@fG zj=OQjpC`U2JHqQt!83>IVYx%yLwU8)st*2*5?7+Vn@8RlT)E8a?x@cf-(XA)py0UE zeOuUJED*zNKw)N_b`Vk@FkB>{ybD{4kZ6@ zv^;rKHr*KGr*RPmnlQ=t8f5Wvla8g4gt?&;hL|i2uc0W~%#9;&rGO0HoO_KwsidIA z5;1}Y1l$-&J}(b9JY+j-GcZdZI`}W8NSO@7Y9Y^|ts?Z&i$(v-`ufXd-zauUPBbBXJ6An z)z9~+xr54UF`U{-kNI`?ftuQYT7xyInGJYN0hbp6Dm~C~_8J$iqQK+=W~)<( ztL}*nD>YwlJZa%y?mO{AkX1B_6xwU2H#>c8TNZ@l^3Q+GvK-k&I_VB-JSo=O^;Qe>0_NQO%e#x9&Ww&;3ClAKa@QpRc8il~EXBliY0Z|=UQ z>C>N_%zDj>?0BF>okc1lmy)$Hks5hG4-qbSKJAf;m-`Zmz&Jf(pJ4euEX zJLOU6yzrWof%#1q&aHP}*}wmk`lY@0Za;`~yi){7}~yzmA4|MXpnlp`}G0AU*ACBf`h(e6jev z_*d(Gyuk7d5*pf`rN;tgU_?`{gYm0Tn-92m7^q43k4gOAv^Me|HfeZfw<3`fzLvsZ zF}p1q^fB_v1^1~q85U~-o{kV5wcX_2O7Fjy;)QAtY$B&o9xLU~n-!XF@lmW;o;?_^ zTD!CBt881ENJX(K=ayD4y860fCGgiGK^yaIz|5j!K5{M)QRsGM3Eu^~ANHHz%S0!* z7-4Ov4Q==0RN3(i*OWgp+Z63~jrg-tFUE{9V1=4&bHN%%T7zVj7RlxQI?R0dmux~( z!l#LCYV}4wt%XoO@}p?cdymIIMtI+~9*REi`LexrKir%ar_K1>`NNs4GPCAh4VtSJ zvN_GMFG*1QfbF0{*!gIL6@Ny_K+}LP>30WP5AnR@T$}ZYsktYCl(Y$qfN3t}fT}$l?`w zW(_RE>E`U7C}ySH0&c!9KK6cjUBXI_5|BdjvWS?{ibd$Y56<;lRfkn!tx4P&7>F>P zxKBuLT)Z89_%ZsPh($09SIWP#-5?9HoEvqFl4kWa-2rC*qv|uqb8?oWt&gS~WGtTe zF514E+3A9WlP2BR%U(7#xLc%2suywsdCHsCLT>-2?+wtJ`1=g2?gShElprUUK{mUu zTA|9Y9?Qv8JecUYGWl80o+fe%r?$2(1=nptrOf4INW9df2^M5|3!6~8APctVt_~iW z5&KMjikh?E+OOrtmLEDd$qPNTGB=M>I0$sQNeNy?&7Y&ouKzx>9Ml`sE$(9e5o zd1?HGF+V)vwbXe8E8<7@<#k8*iu(Gnv$gwcm~Sis28p9Jl$XU+S9})1|BH z_E|||E6Db?{R`xwt^Js7MWLaJrngJMTSxcxVoFT%R5?k`QR&tqXY9}DS5&k(Rxu{um?|QhK)@5W? z3jc!oy?9}&MErij_iy3Z`?o$xyx_9)GR7aG+5K~7IW@0%>9VBhdH;sP?TRY=Ddv|6 zvXt~Pm@FxMc=1tu74ONAj+SaNu-E%~MNRLhK`dayv5g}6@xsasxono$mfMv=tOInz zuQ9GK2_W++h>#cw)1?l?Koe8Ywbphvfg+qY_);Cno_LCss!F8(-dN#`2xHt}efeUB zI?+DVog@hjjLJPWQwU zzK&jZ3#G@9oCCxpV6x{4y8yZS`!|CQ2TB4RmRg1jh@~&m^YSb|O=80d4R{km>Byw0 zrny>lu}TaD?+!GI#(7u8tUzl-6ixzd0HInTx@I&qG@fN-@=-^r(Mac9Zn|%T?+rcs zx94YE__yE})|aG#wW5N{A*WZh!|u{uQr}s9+}=?f>L@9 zn$W?PX&w>q`qzmTkDvdQm&{<1#I4~xJ&w5kHLOCCs5^M)O;Sxv8&bTFq~_gt+LR9# zwz&3>u=jR&2fH$w?PO4!rpW_hbqqaDc5EG~lBvj-yy<+&&Y#%ZIFq^LT1Oqa-kUzI zM6vg%4-Kx!fjG$EX9yfPoU7cdR5d{3e5Uv4#`5zCVF{`^aZmHRLcLSBD_f!pq5@&iCX#g0Ax({i zZzQI)hz3`b?F+l{k!|B$IK@N}zJ^^rz}FH^@`6}$;g`Iwy{l|NU$p*N7cV?Qi@m-B3a$#>C^LuG;tOQ2v90|a;Q zeIxSJ5T%84g-SuY6@Tu$Q#W2KO#rpDqy*8^8OTW`k~a>V41{I=z>6dC zUF?Gi9E^K2YhE-6?jl&;E~jtKP2t)J_`Qw@wgRSDB^Z9)@!39HJc(AFUo-U33yyT3 z**YHOlFHNwmt$xHr#V4<)pkW~E&Sv#WG|0KW8D^bU!&?k${2}l z+j1!A`Cx0leoKc1iaNwoe|u#WPrHlW_dtjrMdR=%mA*Z4&GGf<`-gvo(9Ew5!q7* z0Gov0fj)#c!oA6a0EU~NB{bb>=+58|Qj#hJBaqBEf4nHVbSoSj;B>uGQupikbj$U9 z*k(a%)9>FOkQeN8mccRtN_$n6rB(cqA;QlB6m#nCTrD=T^GWp2MY{%?1(J0>GggxBGe11bpY|w23%I8&gCau9u`Ti%)eSd z6mgUD0J!UyIKn9dCzc1|;@0NoK_E3iI-=KVtXyXG#RFg~@tAyDJeoFLLy#_2n5$Bu zNkJFRLRha`s}BOMhi_65$=p1Bu1biQa3@>(`(J1L+^k!VX6}bcKGc*m_s4|5yfuOmMTtV!rq<;=#$0A>UQ((}oN)Ftvm$9a$2OPRg-_o5o}$WZ9+D%3ZZvi(fL?+XZ!^_~5h7ptNFi$=4o_Dq5R1($iZU?pW!BKN zT;~dUPsE6gqi^V&^k@mf&`L&+hx6p4og36kSOPYrLCOD~5*<}=$BocY`DGi}u)Ob; z`m0gjs$|uZcNlqSS`|9I2{PEhP;&HfBj?afCLo3rd`JI%j ziSln0RD6vCDAAW+)3vsB*8E$;!ld`>BxS#Av`)24#wHbgt~zIjMGeZiORPrESF&g2 zF~*v_{Lu|fmI)pVqGZ2@e?EOSk}z*RRZ#dCWivmSg)&JV3r8f6*+G3i|M#C;ZQ=~& z`XBP`RmIh6&@yln#HyCrycAenETr@VoQClaC^%IeagcKCJRm&8wgdf&W_1sbZ1uu%@DB8oVy7ha!2A<8vdfjh_Cbvmu{4Pz% z)iNs>V;|N^sP_L_LHBqTKz{Mi&{S?e0o!UT{Xs`}vV=b`^T!4mmRTCBW>#-iwjRzdnWX3MKtQU&Y2GjRG*-nVX+C~~OQ3bfR&Zx#mT)mT+Yq5U0{Vs)$8E^Uad9US4#hNG`O!#x8_r43Ur--$Q2VhUo;RQ1d-jL&!Y4eU z%hHG-e|JXm2V8{$q`9A%zp{-sDeJdlP-a5$4QMs<>{=QXYP^u}Y4o9{&7>=6J&``g zmtk_5XBuA*X)}|mn=4qLjZw?5_dep#Z1!z`{>l_oRL)iFXiRZ~+(-#+#M4h~e%0SAl6#DR}05&_aHD-+N+ zpifi*ev4+&+|pt7(DgMk+-?y4=M$SRb&3;acqVyNScz}FmTF3npvIpxsSO$RRFlZY zIVpODpoIMg3jib)&V>k8_QO!G2d`{>(lh6cLG7R15bKm7>n1w%LG|!>B_jH>U^JyD zW;mudF;(qunysZqR9D8NF-yEy483|-{fnfX8?#j5=BhBwR%c1?Z0+6GGR-o4rg?^j zbUi+})YEB{Ab{PZ~ugHtU zPXDS#Wr}BPYBk5RCi5(*H-3#s$!F4-Dv&50&%~wNsaGz-GO{Y3`a3>Y+pX+ zEaS~oQ!b1H81Se=mMhFGFN(iE6I_MdTW|;Cd6UG-i^PHgYvQc%1mxgx{5$EU`|DQ= zTFzTbUih6dMAJl&A*IH9iWbxXptAP)>3_Ug5#R;6{P(KGnwMh#{Elp_L#&mnD^z;?JvxU&(3l+TI|ES3;fgPBL~vx@P0=lgr!P24bNg5C!Mn*vKbGHL8Pe{DZOo$n$YZ80S!azVrqb@;O6TpL z5H!hp!`&!rC{-EIgzbHdh<$*j-U6-$FyA8aRjZ|GjIU4dmch%@r1ya@zL(<9-(SCI za`Ybyj=z%$?l#aDOjiUGPK0pnp@~E`Fx_F&lorjzU^ph3ehFhRw6DUM;ENj7AB(Dt zAPenL9qXJFN$xnA>fvcM_LUcB?cSjAGH<$%IXr-28j+Ag3_M}=^2txDmj71zKFXSL zn97MfI`a@0)KX*3taFN<5kf}iM?t3oZA}aF}tv^ z)|beMfG;}Lokid5Nmf=?w!@@HKr4X&$Q&IV{kTt+Qh0v|wjL4p6syXRFpSKrI1~G= zEuE>*RvMgem6C?n);%WWKC!aiV=rp+e)o79fYva~0l5!=lkw3Q73+cD9PfbT9;_l( z+|m{F>k^;zIADGQ3QF(F3;0#skjkJUDRYx?u*aq@(aG%|-*eik?vSLgCjTo@n8)Dw zbZ4gBh?_j#G((MLqm2%2+>ZST9)mg)@z>Hj&rd+)*s7k}?s9-eDO52-_~Z;k;3+9D5z#pM5g9`BESZE{f)8|QriTO5AUyQ|^>%MGhEjn+P5*roNIdGBngVRFuMay?0kzw;z0>Tc#@6w) zLx8B=oe?2nNyz~Ek242iaDuSInSKc;DHa|eOeXg$(CC_?_Wk48k4!smSlCJTnLWuu z_ga6j4^?1D-vICh46n`A3-6}VUrDL4)R3BhJ%gp92ZB{dwLWj)A>-3LRV&=DR^0!5 zn3?L2&Gby^6GAlj-54i-P)0wLVuRX?wEP4dNl^L3(Q?|!144j;_k_*;i^FkE zJA8Yj3tnF~_wy*IsV55&|hPCyRNf-pu`=+1?W(^tgpG)s)n?{aS8nyfXD z&-vH4UiieqrD7Qnjo_9?ma8hEV&YTRVZ-_Az)Go^Ec){gvZzbmP%2cC1KaBYYU zv63v&V^@ZH%>{Cz^J-;3sy%NcBqf$Vu-Ug=Z6+secOO)vyEMAtAFm^;daC~{caz%Z zj#jck5ETj&gH;zvRD{)I*_>eRugIKlV>Inof5kfJvAHQz1inll&9`CIMY>0HMcDkd z?EZ0xrN1vxV9e=~?Vz>wIS-lzA;ugdZ|dD|CwKz!v^ak+1f;K!1~tOYVwD(Q*@YUa z7wM<-3XCPSSDXj1q>%WL7?V^~!4|kRV~2t%FNQ*h{;u9TrWKpPe;-__?#4IJw)N!C zBzIXDv0&cLc^r;DU}F1^q|Dm=CFw`ZAkrY@IIQug(Upqb1{wkevC{6sildL}2_<39 za||7e0c_Un)SZqb%`qzt%`Z#Q6DrzpWEQcW1idbhr8A1r=!tm);aeLc;+aCq?uI~e z(QLN>Y)gVYx|ZUFFKdrn?;b4w(0!}5|Dj7tjrR_zN<_J7sOvcYmw0Yf!sGZ&kuIUz z@kuMTsO|O9S~^b%@a$#}jr=->*DB0-78c)EPhwFgLZdz(GcJK>z95 zvq9o)vb>!+nCf(%__~Pf_eoXWsJOf{G1d|LSU2k!vmduGmdp@=CXpe{@9-doeAu=t3pks zqt8VgTnzMXl#UIjjk_FvQopa6?zCL|z_g6#JfrFUW20}x+0L?3`q+Cugi=@KitmtI zXoPDu`z7&cjUmT4cdDz5w%?%l11mQ9uz^%3!rJ#)omOuYN%-C>i(7{Jnqm+ZHWN{> z@P?kMm|7eU{`mTAXQ&4!W}(YKhE! zqbiHvoE*#@mSt~w9Rx&XhCdfC{_2gc((sFb=sZe~c==qO`K2<-YlbnN*8(V`sC-C# zk0j;jCY|%YuMO;+%;lwB8@W^5-$e~!RI(-+;Q3SkBCl(uALq|LJ3hgyAHEfx$B(m3 z$X^#*$;CUZ@$r~24dA@;=LNtr5D8sFTC-)UW^%#ZKJ}%lT+htWG0JO=zeFRtq{MhC zd)vjEn3u9agkkU*RuSu6BTas)S1B5PRooKK-PcdDmasbiPVPkS8c7$VSvyHY@6K-h zleBqt5^_|;Bl1I1R^?Gt>#Nk|-HML^m7FB%v2 z|McpHb6=66IiVQAy!w;ArXDv@4ZmnxOLeenwX`BbU!mHFM$Av{({#HjcFGsEXK38b zJN*Cfi|aI>{n-#XyLIsX_W5;;rf@Ue(|cNKNinyi%jV^AnGIrPB9=M`B!0W!L?{S% z{;=aaLPJJJ>#q(o&hoGCEJ#Fqwa_5nvdI|7m|+oTw!up&8^GJ{Dhgzu{TVLZ1zR86 za01EmH#{_cZ8e{#BmOX884j`(>w&b~0r!?jf!o8M6FA))?lyZKzByU&$<`?w+GHn>zA9EBF*39z>lY9wzO)#*`X5z!>0!KNw z7rru%rCnnM%s>$Gs;KXErBLj%sRC<3dHq?tPG8XD&w%%&&(siR5@!D`!Y%VHXw3`$ zAIyFL1ZT$5`)LMi0wA-&@S&co1#V}!U*45C|0@f^rvZqo;Gsn@y`Aa?fA~VNC){Wq z9K?#o*ZI>T0ACIf0|{_S1N8WwhDH=6ewbR(#)HM^c zfl%#4sFC8@TzY`<0V*FKOv4HlD#{KVT}K9SX=S^ofBo=k0Glxc;@E$y% z=BN4eR=tUO#n;kps&3sh$>dnXyyeG-6LJ5As_vG_{JOTI>n3CJs~17n7p7?zX8f7C zn;b=-RuaMU5ZhWEzbpbYaVd1}`{k;b8-5GXK@ASPp*DBMNUGPoFtkAVSEDnLal9iA z#>rvie0QJq{F!K-V!ba1f<946AIJB@2x!C>Av`LC%XQ_yFd-SMlr!2TWcdbTWJVb? zt){dtiG~^%qvA!;xLt=w;oJu>B5M@k@pic;XjIwAK7{j5U?iC2Q4V$b+`b6cW)8gO zMUXOJiv&S(fyD#_ITLhi$hOj;a@#+K#!XoAgw?Dun04={Hr!Ore6f3Pz%D6X?m#AV zv81Y6WM@#7+}mI;HTos(lu4ldy7+4p{Xh+*V8`m|_Gp*fVRR?Q{G&uE> z`#bZE?~mAk-nzWJj1$CNQCBQ$Ydzh8VP)?UkD;SpgaF4N;4Df^#0UZiUo8us_n1cs zkuGh+eQ3}8aLn$<-GOZ)3pI!+RSQ4HXwlz5fbAy4vvK zwLWA|%*Z=_q@xg*Q{|`)Y7@7hd90@lZ zXzj`F528?@1yuw*Tt9=ye`n-#)~hWqjWsWCZ~MzQn?+Hm>r7RnsyAGumb#bRk4$01 zkGDl4W29fYkbL;<29nsN#*H=QR3nd!zTe)^#40{_HdbBg& zUlAp~612_r@vvHXgRs;&2pJd{ATZ{z%Yt=>67-$%QUKEmK#_EC?iJF;v!7H8kii0w z4-EgjU)M#k>2aU`7)%#Nkm+IRh2S+Jp1|X(>^;ewwVOX+3IwgGZ-pP?55UET6hZ{S zXtQqcwAe6!&X*dvVNi#nDT+pu|6xsmZU%;aINBA!IZmSp0&ha#ql45iY~>KSVE4g4 zb^=H+uz%IT&BznZAzF1*3t|qo&t{eV8Zx2tM1@9Mls-ibgHG0l|5gyAt2JA?C-+zO zM>!^Q=BK=*J*~V)7)uSj=M~KYTqfAQw|mu8R4w>X`v2xzzNotBsp?){5;I4lu6VQ9 z|KXsb)dTCg!ipCdB&=9JlTrF!)4j1IQ48dy(Vv!{@C-cny{k7Yk1TTa;5=mgl54&17~fawJLzPec$c$>vp`A(6V*`KaR@utavxhW*7 zg5c$MyT|4i&y%uv^;Oxl?E;a1EOxwEVMf9Eky9x`GU)I|A};q`;C&V=PVMd0zt^`# zF=(o)T7M+qx9SI`xQ$0(St`({biB>V4n1ZzM>?f0Rp>h4OR}Dqog3#$`A#ihmhz?; z>*4d>`U?uAw-vX!vXLq%yl^KN2WtweW$p^sQggC}-RtFkPv~(g6dehxAPkj=UsZk) zt(%Bmz<|w|43%@hWeMv^McM;=e3e!H-P?;Q80XGGhixa!&9o{{(3aMudL`suv=fbR z?bFdyx1r4arFDF&-Gbw06fKN~{oXDr99i9buF6RTPjF;c;(qgo+R3#>^IHX+zK?v_S-H#rg^Z{CY?hxYl*>uO1(@?XSNw4JKgweLuu)^!TJsrq2dJK7m{+()0T ziADA3!r)ktFyLD8LWlQZsz<bMVNGM&m*Tg3{rf5Qr68c7 znH8h;!13G>7ah()r2y;yHD;M^>G$u%14NAb7YN)9 z+12&#@MoAkB8Y_#Ax1wU+h&{%kHm4iyW9-Z>#3;xu_oY+g@PlKpmHG$I zYTo=sl>dUav0Pr@uh1Y8w1#9V&)y7K2%M2&ib4@oib~0Co!+Mm>k=O&N_brS@VvT4 zS>z6@%Pbw5N(|7_?4J^!6Tya|pt#jkH4cFLBk_-AF{|ulP%4Mqu0Q#M@%#h(e2~HNVkiLQtfwdye3~W}_qj<17HvaA z?DO`-Qb%4F_E|u92qs_v3IJRO)wmY#99ZasLaWK=lIw@lioDVwa1H};*dVnc805rI zII+&l6nNGQ18=Pn5@TPPHh=t~$4%ChPg|k8V1xWLu6XhT*yuObEP37JzsHO*9QB>E zlKyA193oI6xUu)9Om(=}$w zVqJp)q}-IxW5+$b?z7+5N~e>9mc!%uqDvQvwD4@He0|Q^Dvi8tb=(xpO|h~@SLDo= zB5g2JHhz=W2Oc=AgJ}B@p;9kj@-g7yzi8^i=U;P!ZW(TZ-B_k7LHNDO8 z+1?Kll8u|q9G;jvMR7L>H(vbWBvy`6`I(&5Cd=oSHamlema)2_F1hZ!oo*!DtLQTj zPY7T7nRJRtT3tK6{a@O1wOB`5!)((DCYYu|MvkVDbbP0>Cu0&CvsS2`h`8wb&Q82e zEmGa#yj_C*<2F+)esNWXa<5$$&+UN`7r`YkS?_XwTD^m*87ipt(L==nqyXk)Y+n7- zz$h*Yg#68tfkn%XY&ucGA3zjJy%JMN{KEnr!DO8Z$^i*-}c6YWMKJE?~*$z>`hzhFN5 zTIhaJndGv`wD|GEyiki z{RA)ym(+D!X7P9n#-Y<`LP^8+P40gCckWUPUV-}gTpS!ne+LNw`{&egFEm$aT%=zP z$h51Lj$1Kso;n3k3sC^SbYUT=EqtoR2AEm5dLDN}$gBe8$nSt_dkk|Ois4TQicW(uXFtkAsbMZ1$#$>q0QFSRV@m#L=DBRAMe!k4Ye+jeJ8pRZW)Wta$% z)8R)tUqejiqR*Sj?O~3*!F$b^96&fxrAZX3#}Ot+AL#fa%BZsc03EnJ0(h;ev5_=r z0;H^sjgQN2x@iFe$aJ+LFsjC3vsoq_*#Ap{22~d%$D%&7S{$&yM?p+;vAoSxD*`ac zk)IS)izw=a&OBXw&8%ko?&AsfBR;78o-$#>x=ft&)`4K!9Bmq8>w>xv2n2Y1;a>b1 zDk2?eX=!+oa(bhKBcD%CT`LwF95w(}-q_k2vLOO?kg^~NAf*wo?-rtz*iTap(E8GT z#-e5&;Sm-NS1Upqt|48>ZJ+)pTRaA0qX2Sb0Q>~9)M{_Lfwc;tJ$^UD04=A1kx@<5 zTSO7GFH|w|-xU<9Fba?$EsFw3G9plgrV1ak=L8d5&0JvU4WvzF^ond`JO8}(`h>1uHk%)0B@O-?*_$HpKyEN;m5~YN+;>_&(O-r^a;lw&-dF8T^|*XKF?bz zvUy20aR?UtQ9Q0(cC0NWPD$AI`d3;vYwPl5r)97CpHZrBKT=@OhNpN~vXbJ^sW_LF zW>VSQ9-YRh_P@-}pUpzqo26!nPJfUUKfJpCc87$EShtg@sYHzmR(L;N0)zaD;4T^ug)KH+J06QS?0f0~uQ!6V}V8aj6 zOM$Mt^GToZ&c+4}91;<|?;61qgBb(^7mkwHtd;ARQFA_ELJ1fuXG&B6VqHabTw(YE zzOVOJs`rtBzJ51wsstXU$Nv>&zxM&F*Ey5jLG$iQzxt}%TQbYs3cK6-SNIPjF8nAe zbd320uVHnsvM?K}h(;I+G+PoRyUdiTL#R)XWn&N;Wo-k`=1#>uD=>6F7D+BZM}Mbe zJ9S!W)}WKVp;c8F5crLf%CR8^p;h>7Bb}7HF}NJ(!TI<0$d^V4!6g-WSd**5P}h$n zH2{~3LwP4|2xpiG)0^E{QA41DEW1a(@$(R`ND4KNYKZ+s#9q|3@jsilZ7JBG7-zDI z4@^5*;=q`OId+=e9k))n!i(Kh;zyu#At8jjF>iC}_`(KBQD7&jV+8{@?I=wXd@%J}# z=xfb1U$_L3a3Kgm()cpxYFUm5eI5*D`N#K6cDhg$*sid}gl6y#nFAFh!FAVQ^Veh$ zM4Z4|t27?p2-morR_0y?lJcf16qSxcuN@0Pebx+dKtP4LAm9+~ik$gWVh}>+M<}4Y zNpn^!(?^c1r8}DNi^o zCAK@x@o&)Ag#%IzH^oF41;_{gwMFqVM%}!(}53x zWEpRYpX~BjGid1%r7G^=RxUm+K6OmDoYbr53!}nYo?n9#D<;{0E4L1F(&&zs5{GvD zB+6xcaCVD$ZV(L_tZ4b9NqfJG`SG8IOwLU%^^g+GTDq#iH{QkHQtIwLyZVyD3FS$+ z7S^a1Fx0>KYZ=jHhMef-?USQIOzq>lU!xf#$mdI=pd-oPnXwTfO*eg~fr=NcD5D51 z&Go*Z5Ax4Gktcl&3wkcdcfwVN)0}SgX>W^0_)aKjbzJ2Zc3w|sz)}2m&bt|6g!u!) zP|%l-g@(1O$lz4K`$1!%Ad*C}3)hI7YpoVq z?IAR!8nZV(4$~=%b0!V7mZ}ZCV;T2AYt&27^NS}@duxt#4J=Mdb4cUs$0nJvyQ$TZ z0wdN}M~xO|EjMpqLbL<{*+?1?+`xFQd`ejuO@J)RYTxroC#HzKadz((a#{`vA`n}%dzWkM zf7)Yoryhx;4w^&XE|M*MbR~*XW~=kDF!++@;?LV>jyO^P87Fe4Jm4DXUNwG=+Vvvxx%FYy<)Ss|axrjgp{mnY4WsJc!1H+BhZ!Zx0xX*j9>@ z0nZvx!{~xp%Y?N+)sG)>Abpw;Z0fa@l!GND{f^ig932?a)XYQ<=<(0vhb?fUn2*>0 z;ul%5TpbmKi-=Nwd!=ehPcYDr|GP=+=Zy#9q#Q;00onz&=05dm|9(h}(g(kQ0oY5mK!MH8P z(}gVM@fPnZHFXXl!uL@@UnW4!4VaNvSAFmd0A(iK+#V9wjBC=NnFwjlVll&_qckz+ zSu-b0_nm_&)!=VRp)H~6l-AH(;h)_+;isQ|{@l-|&DbkJqNJ+Mt2<4xfpOA5wYaWSX%*tcz|AOMXm=hDn*KuOL zr7o-p4m@0|5%0`XZ~mR7R?U;~?l%p6TDB}#noPAw9H?-tIf8U*LwoXM&%6!4msgrO zI8XrzhTfYup$=svmlFMEtE@?55cp`q%{?{coD2tX50GDYx3$*<-r@s@HC?T6=hCNG zyEI)z{5O4UL{_(^3sP^W;MG+4o`QCnpj)$poc(5&{VuCd)PGoPNs4BsrU--P_^Aa( zN-OiAv(tQv69i*a0JJvza9Vq2e2vbR!2w(-ZR^Q_ZAVpGTX`E&iUxaDSA&E7N;8o4 zeggN=J7DD9H9N}`g6jz~ZSbPlEZVPq0RThsmtMIKEv@s7xGZx#a^6 zTyNoZzWyU99D0CdBwplidsGn5-q_p>FPiT9??1A!F{LB%r0|{M^H*8hd6T4oPu>qw zGJI8@fECVghKiK@EbZo6^Lzx1-T%#o&h*XPGXd8Rr2<#MPgh-%t8>ur=XcYmuRFdB z_Qk6p#Lm5Nnvm&`3SwHg5cI`_0Y^18n4PA+_?QXlzuJ9VaR zA<-}0)PTsC?H-uBM`K+U@@7`N2%M5Xb~Ypd360O|vX}`8F9Gy^nXO85Ux+=Vy`MSy zlAqerl$wfa?f!D5|JN^Kpogev68<81G5&y(+>Ku_*UI9D;|sl=TQ^IM%#b8N&ozM) z#%>sBSu$k*{o8yjwsMW#;^BL?g9m)|Ks?X!boPUQo9e0Qd!hS^J&@oi1MA}AR5fe# z;zD3%h5&|2F!W#Ox+($6^gZ43Ewej2!EQS8;7+soZx#h)je`}A;dk|%=ukgDY6Z)_ zO^_iEDx&Y{0vONtN*|5(n@Jkc}$x2RxAS$DEN5Rve9# zykvGiIFi6Ll{rZfM(?#>KL^}MT-@D50qG3(i@Y;d-L6dr*zJcKpI7dffnZhQ$=js6 zCmhG?QB^w0>tS=VAajP)1U--j;(0rqoCsUUX>x&zAVYg))3vdd`(H9BWmYw2%l07*)O*Rc_p_JW4+7 zRz9FVIm;jQ&^*MOnoN7DxD?t|HAhH>HGK9HKi@vfwVNP?<5X7baX|YrHnNlXX8JQX z5X#O-{qnq%Ye2%^76%v_^+_F~ZbGwxaHpSk)L+}&Jl#JOybQ32YVQNZZ?T{S7-|L4>*KfL;km|VlsRxiu$;=)7Kt{*8Tg zBT2(D&-4xFzqd-N3JNe|h{uG}VnaFRZadCOjmdvzs_`S=Q2pED`7!YDqzl_ool9@_ zcB)51hJ76{+q&Et3nF9cO@{jg%?RF-TjY!}B5kyyC85y~nbQe~Fhe=UgUhD-yp$p6 zS*VsTqCY3f7;Y@z$vbCK#oE5b%5r3{$X`Cnha?(lU7|P4Gg;EnnYOiy|y~1GEbcX&l{6& zf#{|%US?~GL^=*@5oNsvdv=I1YhEA|r-cCB#7p!m$(d^Wg`9UX@Xj>E2JKJg?fDlu zD^QYB$%Nytgr=;LbQUCvVLpcas%Ct_X8EkLD+NN5Bc$(SiESM)dH1I3U%+fpyM#@D z(YqRs){#?$S*`@>s3g#4SJa|B*vVHL*OS6MXg4m_&d5sIOPY`tKBx2G7s+tYHFngT z@up7pah?ieR!KwOy!#V(MO`uVFpO2crDMdwr-w8fR>!bZUwEb1} z^LasOk#>=vb(KnDi?X$+j@=fS=>a<5|FZyIj&+`&sw(EXugK0Kd2SU&$DpZ=m4dfu zShWhdw`dhSOXFxZg}VKU`Vf1wd&brZ1X`1Uvv+xidk?R6tfYrErW3mdo-cc-3V*=O zeLqLmb&M}6tHPT#L57e^cwp!L*6jDGK5p0V7yTGFYS$$vDx^%~s+S<4mWlO@8L7bn z4Kl>~%y0HlI{p&_f;#b~6LDG;?^rs?%V%v5nyruUHl>}LISsOkbS(t`NzwUU3i()r;&NN^{+_L*immuGuG|;Qo zDbFT2-^}V(bJP%f{3>DOoG{~PD-neqT zZ-E%|0v_L7?2U2~`o7?qsf@MK+acHhRw1{8f)o;+E96tDaWVsJK0Fyah?;yZe0ask z_R5R%i~OgM0B8Dj*QZ`l?z zkQFc*I8EOKY}<*IVf{>!t|sl@7mM=T|AX>vl66dd{Mff6aCeh*BiFkA^F9gVYOeXq)P7Ww*!vH6|RzG)upaI8i zpz6vJYxzCj6r;xC$tIqma^j6$9+;h-y#a=upr-C#e}{M2dW!w7T138wjyR3j1q2v^ zTM#G#Fu}r5re43Nw->phqC$g%_!xvVcbiKP+u4Dgi% zq9G=rA)eR4!e7g@VFSzS8)I%^e(cH)sJDYjCmcnp~p>;sG#t z;nyzHb^e0pErHWEqD;fOt(;yYOJ!Kom4Q9CKap3zlI^5RrH?h}&ALVz?h zraAcWP>Q;%Hr09fboK4)5fXdCPk7*6{`n5=rn4Js-`yn5J)WAHQO?RCkXKOysi{x88Wj*` zn(>f+o7-ReR~K}D&p?PitWZ!x8iV3_az%D=@%7uX4Fi64@sBP~0r?+`z19L@4sSrz zOTd#24o8C!I34Puf2{bUR_m$E&K6jVj20Z->|L&jpyL8U!eS919?knIf-GyDrv~>v zL2J$d;W#wa_$vU@`QyFE2?`s`@NodmuPJYu(g*yTQLX^aN>3`-r(=tjJf_Q?$`7Z2 zS@EkD#G2a(OWgB_?cy@qOys+a()ry>qYo;#MDw$ST5*d_xNs@%T`Po@@D0^#i?`Ax zxk!OxQkxChqx=%;5@}HG^vwHf5;Xd=*Lu?IR4+vBdQuz&7G8sdO^8y~muwDb6P|$D zqeNEtojOMCY4<8JRi-Sw^2OtU6!*vi&q!US>+uSs90b|3vBC%ID;ps?NC*JaS@325 z1&D!{0uvEhLA3iV?*enkdtsf*IkKat2hG}kzY)k#(I}hMD_4L8YO{wLRfdDB2Kbx+ zo2z61XH9bf!H1rg%O8$Gpv%TfsT(}NY=G_rlpg&Q8WqO_^`tDK_`qMvN+EPcl^#zp z9=vHDB?^7Z^S->x!<^jQc?Mhz2?~G`0RAK)OEC#IGxmV@0AJSi`d6FWA0uxs56#@& ziNNpq;`BF>4^TfjG$^V8fkgtoy|)eOLa?#n0lg}inA+B( zvoWO`a5_>Ia*tzL-)cAWJsv_WBwQ`bRL}s8H5cUq2Rk#_#Cp2z)m|4D8bx2gt%) z3Pia5V%UbrQnm(J(&wL+wUMAnwik*5hXi<~;6)r{(JRkp81jZSqv!(u!Qy}&P zlULp>H8Nrln?%<*`LBbGX7I<=>?{%JY{Bm-d;dI^;C(^{XkH$H>Js2Q5M(0v7DF|H zb2HGB(D+}`JvAh)j}NziNb7w9-~mfdjRSsEpVNC-k*yX?qd~zA6b5EsWc<|bh-Lxl z@Y>Cm2sTnEI3s)3aKW59MF|;T^kAHf1OY~+HOgwXvjHaSN%ibld3m@3 zl;d0N5jkUE5Ci@`a8Q7d+OfT-Mw6Y$gJk|cH_&Cl&;J3pQcuw4fmhqNaV%(ZRp^Zv zU`W3LCDqCrH|GNemf(*S_W;H?;4=pu*3&9w`P+NGy%%8c4Qz>yso^l-HmRm1K>oz7 zczS;g2fqTetKdJWKLbU|Jn|{9uyg@Fkl+TT!kjcAIC{J^5)RT%!8H$PXu+Ke=z#BO z1%R39)%Eztu?kgS8U#F=fKc7V+xwFOV-OI%0_jQh&|ecCpcv}~PX}z>fLW_>@n72( zKq3JJY%kzRLF_Kg>e(6L-rgQK;lTj?DTL_=Ov-^|m+ZsAQWv;mf|Gh~6g(e@+6L>d zoVmRNwp%ar!Zg8mVezgb#%lAci*RB z24s~6EY9M=YxMPv-rsk48uicZ0V3aJki$(i`)$EQ@=t{?`-Rh^9YCgR$Rs^w_ zGr7Ml^8MASLwa!@HLq~n-@BN;8JdursOI+53z8;_qT^dRIfn2OruziL%NdfG~d4|P1$gpFO9<)7fjjo^*4Kq5V~tHxY-}qzc8EmP`1Wv zksr@qPX7L^0C_mAYcbfoSb!EX9D;(G9=#@{5P*5+ot0&9fT#CuNRv#Rqr@Osx`(wv z^^*nh$IAju=33vj2qB~-gg`o@&4v>3cg=N}7st>0TymVk_~v8QGVxe=4q%3Z`Nxaj zF>v8X9>i%$PJem1|0Q(kLb}t2q`w8`1U-Rr;x=muM1fi}xvG&*M<7@=}S#B4& zfTx_xmJb<<8G-n@U+zk}4vL_9oJG7TsZ2GyW{DY`{Sv;gmZ74j#}x4|Cse-30xZ${Jj z@l#a=sJ>Z~auc=oyVF+pWel;UOVUD*@U~tDujk#**(o>1pgivWOm{GzNPn-z$f`cl zz+U-U<`ZhnN&7K(u=icI)6Yy6u^a@&h`r2ulL(bj2j7yVd5oawm}c6XzV}^bt=a)n z=LS$F^v`CTAWehsm?@aLWEkZQqgS*^1P64Y9sRMMPP_wM>WA+&6aLwMHwVJ?dAe)L zm|G@Hp6z)>@&VfDIy0=ZB9>j@STuMLHif@*8jw|)Zx{olP;B@n1R0nT8>+~+LP4Z=BU<}rO&p0ekj zyrMa{D?2Y|l~>ND+TUjv1rUSq9iT7<734c`KaYx1UhpskV0W*lxcpBYC6zWunv@eJ zH6zN6!ReR3Kb}BRP9<-aN%aLO_P5yk#vByB@9GY4s4QbI7~+&WB9&Z|I_{5|t$R8z zQICxq=dA2)+}$C^#$r1gc?Z643fY}yf}EfH*i+SL`rheo7|lXp!2GN#B)s+vt#p)K zexLVb6Z6D_{4^N(tRLy@rR-*kFVo7ZB8+hoaUiKW^U492?^dMBF_^2s{;-FN4cOzwQNg3Rfbf=mT-Y?Jx`#$ArXy&Usm?R*-ALl zmn-yx5|(cu)XPsCEL{>g3vsn3?WX z;xtK-wUGXf$E~xWiQ@tP$TmjA?^n@%NaB9Y;ozhFHgDTmGsDjwqAyl&PXY22_tj8) zCL@fK-6%J^MqPG#{UW<^aOT`Wg+uy>9(T$m`PsNyQPiOMH-`Xh00Q)Fpe?dd#Gova zwO`arb?)x6|C*btkBA!<;vuhecw2w3$5H6;3{Nf(Z}~$4EdnkWyDR_TplEQQBaZ=J zo%o1VL4roe!D#I$kUyva+gO^FIC|V~E(NlygWZWf{XnL3^nCtrF4G70)#GJe=N+6p zYMAUNzLtO((HV*atAEUTVJrRJ&7~L7gI!QSFSl`6wilt)afi*6NUdYH!`^UN8Xm32 z8ZTB`fTjoirDLiEs8YaqmG2+#VorhfE|+;Db3_*=ly9_K637fow9$Lkj>u=Wyr{uG zqDLGMD!`iZe_rFhdv8~|!6E@|(ue#Dade77;0_ad{{7ry2q5AM{31V1%YHQV8L1xf$-9)m*Tu zk59m*&-XVkT+zmRYhZvW19D*N2B;WwI)nW?;*LEr0mPvRAsjh6ulz^_UMSeoJW&FT zjnaVN*3aw)&q`bH6VUdoII8jgn4Qa(9T~`DYNk@roS*oXT3nLQH%!FrB(>jFGE|1* zKuHTEi$Qz_b6^r-QM^;wHQM0N?g7fmyvYEE#oU_wje#nsAm>TzGyPV4w9RmD(X97| z1t*0K@=4YUR=-l_??71d>r7TDT^*f9b=rEa_eC()+3#SJcWVR3jq4{fz=gA3>+JjE zX&em*w;yAD$<8+W_%RznS&PY@m@)6Zu1Xa`)I}hz7aF}QT<{EhE-6a6i~HRT4k-Je zY))GQwNwjDD;u~DaXHaJQG#WPAL&J zp>lk{TYj;415gRDH%JFUNzqKD0==xskVSwcff^4Sv^~ylqn_fip5kM)0L`W>OM8`7 zrcY{as*%HcEJxB*wVN6YB7>VH7U zX+Q#A&UP=*ejq<<#y&?q>jOEUFM+R$#_sz1I=PB`{IZ)UR?`3|i=7SAmQBXsQUW#~ zGxQ6{a0r4f#Bo6A!*J+<)E+#;K)pi+TTf~5TCUUp(&!i~&p@3t+TO5o=t|Sj(GmBg zK=)4F_VWGr&o^LI+_pb}JlIC%TlG+bgNJSlcmObKx*Z??Ul|Vk9l+@Unp6|fEPC>o zbx5sprm{Hf+j6x_Wm<33f4Hz*BV~y$Guw63|2aQV?7(9W`cpRAJbb*@siP(t* zE#Z@PWCJRr716&@<#1adeOY$YA>~QFlaYlw{kh0K`HV?cygh6jfx?uh_?}_K3Y9mjm*1oKZ%#Vp@R)x5doQ1P zA*MC*C=#wXK7?n&0_rK_3q@p*l11$jWTcP^zIVf1NpP%)>1^jM@{mBS*s#6!w%V%1 zn0v*O)6ed@+asNUkXDT$VMDs+PR8C-P%xWcSE5(i>qdvv%gvTNrI~|IB1eUL6l0Gq zgJsXkk`x&mtYLQzFa9wcs>7_+H5aCXoQ#)l8k|Fk5M^M{EE;Pr%q&PshsTlo zFSIiJmtpVG2@k>@MLd`zG}?=Y7^21Tr6DaYhS{NUh{J7!nmy^wAMo|()oIo!J~}z8 zki>G{UMBO9p&z8lO<-4&v>uQkm|<$-rUwP546CltUuKqy8>)Aw>cnqvxt}*O)qfUd zbJ#?Y9Uo`({jG`UG2uwx+>3IqNQTI%TvCmOm3l3?S>5}ixq8&P5$^moe9`N+pFY8hX+DT$kWjMh!E0d{#;X{W8ICKQS`o-)_g^raFEu z^=Iv|=DARE7$lP4eC<_imsLuc>taI80V@@tQuiBBX$Nz-frAFzf zNsuffKcO3|3wbeRNj+!2gFffa;8yXs^+Yv3TIM;HNA>%HwW%qVw0@|s&45Z-;&nSJ z4Yl<@jZo9#1V!U#naJ#ETT7$D2UME0NeED?X!RTJODh>pO|#IOm#}63==+Hw5v7+e zpee7no2qhVsCmm?yPxWjjQyKG9)rzvke*A?Df2(N9guI9K1|m`p&d#Rmihv}UKt@ZQ=tb?q8JBHBH~ix8_YFUpo70q z^#vQ@o9=M#nR{QDo~RCDP|AeAMMj7jnRyN7Ze+aZK`sgX-;wLeZYLI4#a!3j)D$;q z!uxN}Np41il51S;&xlBaBdpOrNQwP{=jr!aoW@R)<}snlQZ`V1*{e z4|Kz6@Oh#9g3BwDe-AtOVQ6S+x2@(2-6yuxKb)LQU0f8~^gj9q<@I3HeU=r8ZR!&e zlUj{B3C5QwdSTYt4afX&;0S6;ia~A4moHg<`@9dFdV_QDGfeZtG`m=LxOZ4lhR79} zlBzPJ$u;hjEQd{QmHo!U-tg}xLpjE&o1WkcKItbHt276>Mq+2^!ZozcV`toIU zzSas<20wdWkd4jA=wrA)jj#YvI&lb;fUE0wluyyvuS$}iX7j*hf-Xblod_j}!X|vO z3eYGqcqc#(#!eeMJFqq*5+Fqal0QMhs3BLmmgR0xqJQ1rUjq*&At3>~)QE)!kKy^J z0vvn?Odo(nn6tZAr2j`qzsvjqPe!z}zyGJ~`xThv{goM|xX&m3UgTE#kRRwP%CaU1 z(&R$T@ime9Ws%1I3$g`F&X@jpmqsgcLNs6r(K}rfcYO9A|33+zAj>@TId|IC|8AS^ z;DvkFJ9T27$Lq-6IL#4gfnD;bf3)Fpd93y9S8pyE@>^`QQHb;uBa^9QW)jn}Z;I2n zU0y%$H=lUfjdIgoHbf)@4d|*19=`AQq^8OJ(H6ksGwytK2jf=bT8)^y;LP7;Ez z!ZGOPd*s<+a^RDCwDq}?E?b=;MMS1$s`J%1^f}wE^Ap?%Q&H-Tzd3lE= zev3WuJ}vV9TlBo#zpSctrHEI0?)>p14S1%?4u6`rZx=x}3YfOn=_?slYBtH`O={R0 z#Rhwqqx8E}H#SBH|M4WSv)lWJ@PwR$sTl8=nlfojzcVGt#xZX933y0=Cp|g>&E^oY z+PIpFmlyICez%St%A_@P-X5E!zdu6Wj5RAOSF^%IGW#XaNaX7M>^emPhYjFx!T1pz zA?yGCVFJ432}#MD1U=bg1y|gpwSY$XuZew+SLH@eS?|W5bUk=CyS938q-ORW@fuhN z{t^|3VKj&dkz+kAfIwN$_A8-0Hixf9qNyTk%{c=2T-fWL-EEh-ht8W+$RyY%CU-3a zWYT;*9_)51?6dhwF{1U(B@j**my+^A?wwimI0`A|OWUmQ9UHa9bHNndwGOF}k2tV`gJQ2@X7AbD(rhN=OUf5Ouo9%-)6% z3M7(5y#VaIQ0exm*BCU22AoYtPh`B9*pLJff)KO$%-%WNR=sB}ep&eyc|r0g58)-n zQMfhGGRmaAnLyJZiZ`Kd7HX;yFnl)kVMv|d5unhXK!ZEa#0o*7Q(?H{Xq2&)CFCX$ z;EU<6brCj1PNWb*2T?P0h|RHNADV&XXj>@o(m=iTr3R-HnEqV>ih+zU9hvfB73Tr6 za{K2J4*c@ykS;g^V6=Z@4=pBeLf^R8zpIXr&kF<S7JwLi-XI_V|@rh0CrXI*j7Rv-ce!&<&CKsMQ8j-;KDI5Y`{@{3L#G2n``0S=0% zYX)tIcT@owiC+4-wJcLCZ)pC>u*qv}a^E9v5l0RHQ$`dLG%kUZ4>vcaVJ6%|X}~3s zLgvf-`>WRnDc?W+WXit%wwen|D95I{K}lJ`v`rZ0sI+@v1Hr#{ z-LEYv_%~iuVPz>N$%$e&&fo6=3v+Rn&`R(gL`7jp#@#@*)|8YYfoG=4GVmC30QTwP z{&%E+SvF8tXo@qi2KWsKsz+Iez56C=*DTNI8F7PK`Z%LLMJnT^RW`eN>tD=?ukyE< zEBodC*r_-Q1KRt7>LCs-#P0~JVD#^~5hD!uQmF74eeiX6Pf2-Du~6do{rZhCg{Uoy z@2#aaHn*J*q2q3n6Z)3OyY6?wF&Q&ICN6c#dTaVE(^Y8U~jj(8xb79Pxk^h(HMYWiNpp2)j0Lb!K}Z|BIefBfMc&&0HPJ(vgiWj z6F}U62n17mv?;HdlYsJM?bw!wl*jztuT!H+)bZ0s|2TOD4o*&9S_KPbCAG@#L#HFb zWFk`5!QVuUXDQ_C31KxP2{gnMlPStCS0K>jlk{HNi~^Y&T!UU7GP0_!uvaC^j?34!RraaBP^}LliK&TyCh@{|l563V0q=ozed3NUARF5vCtMxj|5t zR2_)yOD8mj@-xJgQ7F2jT`A5+V|zGVURq|c`-s%9<2X+p^ADzgi~tsO6<)TZ2_s_H z1FbM3$@JIlZaU8q7an)Y#tLA|bKY+XbJlsImQpZ`YhrSxbIxOKT2#k+(m8;H(XCk( zbcUo5^v44ev)K|oxCWh=%I$t`mADIY_kH52B4QN>-x+%^_PcIh#V`wL8FR!2p^wUJ z$x0cL)Y>!Va>V8%msp_*ot-oR=JJ$S)7%uhZxZBMzQRQ!#_w|(EDz#kP?Q|x-r2u+ zE1WNIX88A?yX*_nb^hpIsG1IFBioix)ei+SvMJUC&*HzIgspSHK1DwnzJ*T*5g5A?|ukR6JoKTp$!ErD92BNN! zHGOTaji-5?%O^VrtL8f zk`P~OqJw%Vp%C9tHjC8Ms^&DQfbuxQKBuA%BU^ztZ0?`&OlhZ!!&4_voW5o&TxnXf>LFQJqWGy1 z0JDzy=r)`0e;rdF@mpymnP(1NNKEBzQ5N0}y=h_mMU*5lNimspLzBG}0cV>+c16rJ z3_{^F>N?M#EnK9BJ!dNBOn*Upru?UBTp@DCl~FQtXbvYfjX3|j#($7CK*PQ9t1)GW zNsh`Ek8n6ApN&6A9;U4|?brk{r4DC(lf;VyH z@*?n8X6Je)n9N<_>@_c)_a}4@F}2EuuiK0WxwbODVa=QC+pC;LfpB4ftS&FRgO-?* z`pepU5`n=N9A0Yl-*7h8lJ7^5#+ynS^SIo*-CODqoSy`U&-PrFKJthAIB|8lvxs4rBMiL&5TC7v~wB|ZdZnceZ53sBaJyw_>E7jE{jg$ZVu^k5(D%eZk;K#a6 z*ft#PtT8;#(A(Y->H!zwpI4emi;*F{v%F2GZVO#esP(97qWAKFho*BurXR>55nt}LW9Y8`rI&%NMV&(mLTuX?1eWbMCK ze$yB2>9{+U%GKmDow3_UJ*35pVt9UzmnP|p$(tUl@n@xfW^o-5qoS8R7>G?T`>+_}8D z%YV@-U7#rga$1|31i*6GcLf-Yy=eQ>X)Qi;N`{m49~5}3WlLU>RyTr(Den)5kj+@vDD$VZjJ}3oRgcJ=>-_Ht-@9Xl)OiE%lmJdr8MH2q0y*&L(_wV0tdHe1~2`Fw?j-gT`$P?PJ5h$ z4#p+*0=Ks&i{CG1Dltt`cuW*uPTEY9HCJZ)P52Q#yhQfKZYqh5$gm1tnI*wPk&6?^&e*kHsE<}M4WE;iu#Ia^)ipU?y0Q78e%*EHVd)f72sCc54;0$=oXEl2g~pfmN4% z@@Y)?wXHQpZ%^yXj+K|S^FKkZOE8#feZ<)po;L049ohKY2|-k3P2aRD++ePXa z=n0f*=kJo!oc#t=E}wLunxM0F{$gb+qN&C3!%jOJ=->bs^OQWa<^b@Q$N*YJ3^y*=x{5B6Q^F{*8D<>OdxD+UAy)C{P^%Vgkho@VQUI51?HH zx=}8Ipw$7X8!!O`lr-SD8?&L>ULd%N0yIBM#)%kh@0&2$n1CYu6?+Q&9sxlSOu7MN z-2d?4UmUC9muIpl1m?I-47Be7vQe#v322$q!o~gf%K(J=mzZc$^F}XRyX@)x1Ti_d zkQdh=aR*-Y$G!#7Thq@evB`q?46QUXOStpI^F{yI)*p>O-i==^cHFJzAC>@;E|U)!If-m&suK-fci4{6(dv zgSLodsW4YLP=IMQfQA4V{ZuwPdwBF&WR7nGLIPZgBS4W02&VnaEo$&65L|=^0nE%( ziQNd4_D_*gPYO_S#u%z(H3f+f@$`(xms>J+Sx1DBlmq3yDxTO#XNTXOwD+D?>b zQUL>m5k$o}diH+>=`ik>>4V#lhihi5`FS#41jxdeF>X9`#!Y^NGgA_W^%{&@T&7jL zbmR#(gQ;Om(a!JK`G;dt6pU8V-{EwJndB}#NXxi?FJunUH0L)ko;o$~B+gfLuuqQZ zoW6GS(utSqd$XlZfXyFRvlr{B-U7lYe+})! z4w0rGfWWjM(Vybt@l%byXf_z}E!dKH-TbiVG*5-l?l`E?;(qiQ0rcRN8<;q zvwCyuvQl;7m)xW@D!qI(nznk`goC(^jc0XYDnSFZFni`7L+xSR)|hafk916L*#y&x zNA^4&g>UHwjLDtJa>ffDaJm}d=dy_T)-1Go6H)JDse)}j^jcmRbHAvq!*yiHo;C{d z3cf}ReC|Q!%o_OQ`I(pBz(wt6I+!n<~p%Y zCwKPsYjfzfZcf#XY*Pu&7L`Cp?ll?}*;p^novowrTOXdvZ@gX}wj^~;^JM{hN+Kkd zN?YU-S9@;hVEjt#_KavEemjjMIfgz+;pdj1xc;FpGUmfYaEU%u628rN|Cck|Kt3T+ z%_cQUdPEzvD@mJ|`jB^!E!qS~Nn5GEA&OSO=R!2k>jq=t3-;FU;hK(&c`meB^;NBj zy;;jt92_Hg(+6wot)G+%B8{w|a|jTO?izRFd}9%OVJ7LAJh%emHz6Gz66ec5D2|5} zoizr@!@9uvuXlD6mV{>#3A2COc2#-fJj;Nw<|?Tu@gO60DMv3&Pu6v_C4R6pZszj= zn|`YII*Ri>z885YlcU`sS~))!|E%P;;%`kW?+9E#(Fu|CFiS zmxZCWAC}f2)B54yi3R;1O;;Ti)fTU57`j_px=R`aX{1}a5s(H!y1QFSQW^%SOM`T` zfFPYB-Ssx_t>?P`$arVXoV^d{+rO{2i)rSy)9cy{P>h~Z#8`0xk3U58n?+Q=OK5%- z+RnN@Che4JQ#dCmS@8u@!!2X>I!d_gm4&PGg|NFwWlHU{1!d>W2?KGww_HD~y%3J5 zF`@VTS~nc$Uo7X73qke-~g*N{UPk= z(S0=FRp5vMp4MNr6p`;OEemc_%5HG0fN_@%|5uPs_F}jyok9m% z26PFar{pD#O&}`+g)%uJBx~Wl)GysWAc2Pth>F!bK_mM)0H8FuktRiDmZY3=Wg#)E zDY77ev!3nXj+*?=?zl)OmZN{5{Q?tKk6H3uS!^A2o*1m#je(XDB8)oQwZ4ETw2 z-Gj6j796N+fsVyT?lSt|4MsV>(&uQZT#zmSXmpuESeMR^M$t>?FfZ1=i)5fz{iqud zGzNl&01FSQ!%!pwAriW&F$ZBJRx5913e|G4HK^uFIB*9MX#6ldnA0!+V!GNKo9T>ra@1KeJhG1dF$-hp#K7Y!8Ul= zE%y9%|NRF({-}G6F00EQkf;gNuxd36&Mq!NAZ?LZHg3}dpiC{2_qy?SjxLuUm-*S* z*-i8aflUsyya3H|2sW641GWRGcY%29H-1t6LRHo>R3Y4X2+^KhH@Eco>A z_zCkRq$J3tCB}v~3Jg7gZg$4lQ zO9n>kNQ*cK{M$o&|U$VWMmZezj*2X!#wItoHm4MB(KxA3<5(Gxtc zFutE|thRpC?u6LOYJ^b^*l?I9+ganE@d`SaDfdSztZ58P@55TW~);9iZF<$hrGv zVh(ofIuJ}y`kcVhB%%PL`6!l3u{s0@PC&*8*b^c$*4!jOc?XyVkOAYA^H?u_&-2nq z3%-Vch{#VMau%F`*cXFzpJ<@#2Os7C^w;a4qUeP@1j;3_&`mg`l=9wUsS0(`V<6;( zZTHBhdU^%uDTEo*gV@OgNQmddI1!EHr9^wek8kZUpclQ@tV&3Gi0_UL)KLzzP#0N0 z_seiQ#9Z)Q@S&xg4rnsZ{KJM1U{(F^%qwt8NtT!jEr2@Y$%S(vq(+bUwJyOs#@=j> zkpF66Q*R~TT5Ub4cY5G4$5VYm^{e+q99wK8=tAm$goiI-=W|H)AyKk=@%ttU7sAk> zJsq@$7O?a@PiLX`3|nl?Pn$NS#lfb7F4Zz+neDysx7^yRIczMn%5QV`e%!%H-ke}$ zunv-)c#b}7zkUtZfNnDKP|G0BGAKNZr(X_b<@69!} zEtfHA7gk^F6)`5tZPk!ovg>!^U`m=wP9$2<9SFUNAR6ZhKMo^?+6pQ=b=f{6QOc4D ztEDRY`dN_+8iy5*Ca$jbtlyk=uk9MIZ7L~h+UsABNlW>g7S0}ryo`*|)cT4io+En; ztWOw)afo@D$9j$s&Cyy7&W&^h71s6?sp}R36d?T4Zob6 z99rfF8Gx5_uNZ&Wek6#);aA#$KN}12dC`UGA`WBoSXiuT!HrB>h`QuOaS%syjW+U) zdJjz>28MFNz1EByLxXw(vp?R@q~h=O5@OzF)yajtl}p6=+LkJX;U9-@GFHx}i{;IY zx*e2A6~FpmZ7%hHwqr(fF=h+?kK*6l-c7#$MxW`yf*kBnI$d*7UTT#pr8C=g(SKnf zNWu;GMqU`qcvf&sxNntWM-ZLSi^WnX(J$){t#SygPzyVYPJa%zu8AReE1e6e zLusVBrE-)|5ozQ}!iIEnV*07%ZRt#u!s4gc%Y8*-Cv0nO}RN8d0P4ab&^I_e(S@dw7Wy(b7JFz&vNRVC3S)9<;#pg zF}bhm8ULVgmEID%896^YnF}VEG6rZuM9{Bb*KbWH<8PlU&}E*J;bINn{Dr(n=&)(M zd!PylmHR2fN*H{6??isBlXt=FM zYiqJHP0Zj`gaKJg&0)3+Aq^#ZI0*ze;CEX`K>6N;@dLA=cKwzjfGH${dBL_1{om?` z-sg$cua|O32A&<_Jl7F}gT52PRfHZ|?w*MUR(}XztIa0l)5S~_P#nlf8!1;jRe4%ZpZMm)9V*Sp_{@P5|S^6zABtUis@neTW!J&8AcGA`Aw7x9DkwYSDEdU?wT-LQ*9Yf)AUdb$8^l9?eBhkaU! zMH%J(mVUY*V!^(vE@p!Bt?Rp*U2|`%RCg+@sF93}j5YAwI(|AJYIfd4`ug?oo!ZaB zaI6+E11T-FCN?iyAbZN3vIPA;>gf{d;YG@6@6GD&skzxKlWB} zg;jpoi-G-kNjg@?#XqkDC~NwcWH{{#E})175>EhU+iv^6X6L?gb#_)Jmo2jG2aX-D zixV!{bnq7$3))w-82q|}U%ZX-2Y>Xl}$z`LbqBI0xnF9+rU8 ze1^zhbS8tz&^kt>6=V6;{+GGZTHZ@jzCyVkYq15Y_=K}taX*vh;I{Y9I9unoULC_O zR<65Uzeru{M`HM__B_d}>cxU{x2FAs1V8)DbEIXsB>Ih)OotlnVi|bpq4&A&#v88q zDbQ?VC&4W4x_{X!m{L?E53(+YA#`3v)qN*a3nPfYsA<^(us0AvPV;I7MAW{GoWEB{tqE2=?faM>^owy9#;T*{ybeZ5$xe9`-H?QSXf!nmqzjybE6C!{`vw&rXbuG zly+jkGf3nBg5Poqbp%&|FN7|CeW5FOE{RU9D=TG;7=Td`Fx=Y!u^e$FIB+8y0@|Dg zgSoU+feDsX!wLlR#as6e580=ur|P-g!qr5Cgw0;(^x!Z6K3&J-k>h4IaFmtK{sWLr zNl7WCOBW9h4_Kf8kS3v|ECuPGz?hbL#=8CeVD;R>+dJ#@)VV4iTND2&j2mV|u=KWS zwPN_kr7exU7R|&VPe52O`mt%1rM-O&0D6g*geGM9|DjO)B;=k3p?D={#Ai=OHsYr! z?hp}1rJm+UO;|{hpRVz|J|c>|Et4((9Y__rMB|s<6Sb>?-a}kdU^>gMnC$N-t-##;gvkGt=wZk4 ziQfMv+<(ycY1`NZlrB2NV+XLnNSi9RwY8Bic2sHGeaE=IzUF&AYfK7ZN0;ugm_KxH zFq{sX?nLBdG!Nyx)pAfrp=2M^*_CTQqBaVuVRF zH3sgFa-PB-)u=)E&jgdq_SU8yQuBkHV}70D_|-pzRzZ>`IGA}IRyBc7bb}1yxOc>V zRG6aJ2wHo4>pQFfGY61~6xk}&EEG=JaEgkKf#lUWnbl7JJP@%1P7PqHBCrd*#3o<9 zeD&+B$zKI(cW?>?#~~|QTlu&7c|K<8Vzm#mEgT(Hjv~3j zfPOBdMY^dhy>gv4MiGrWk>oL82Zdi@TKLlr~a1gr$EeT6yBGmUV zs*Dov;mT`^;GnhI*QpXJP*q}~D@npSH4|uJjAf677G}C`zz`fibXc2?M_0 z0;e4P0d2X&$uF%l+C`fXS5nsGNo7gt*G5vpH&*00NEfU8!)Z4aH3`CQv88He2;ZE? zD72u1g-vs>fF*Tmrvl;N*BH^77E$qd4-|QPc*C>fyOlx95%*waz`{c#8|LjrRqua6 zBy3|!IAW8;lu9KG3xFhn8g#WjTlC)r?&BH)Ta<%dtue z^NJ&?%%MZdvyRkd9%MZ$R8aUeo9HJoaoHK&j{>d1WLil}NFZoWU}jwPW49;m-)@|F zo5f>D42iZFg1YGIZ+pquQzZ2YPzDJ`v5xCix;78~nULwbNf4AxS>_{>f9AIQ5M3K1 zy)_k=n2`QNez@X0PZ$8DaxGZi?x1}R7xa_4D2i%cd!GE~(ibB%Lm&|kg~lm0EKLP# z_F>9H1N#_bn|k-}*llJLX@#XOF=J~#?fOdE4H5iDw<*p)C_DZ>46mQw4dfbiQ|ty> zD8trb5(#vSXsL34gVqejVNvqA%q?9D?vE6AFjcad3YfA47$yfBTPo99UZx)I;`qf3 zxjhsX!3zZmVEE~U$h!$r4Q<=&kP>Q08W1{ExU&2lVmX&9#XM%U<{JqTqZgvOC5C&{ zoI4RLcw}%SGi^)iVRqKrCcWkIsVx6Z+bE5!1jAoaJ0Nt7dKBiHDTj4hzUHjGRuIluEFr(~GU!{G1M&u9ZEXgxqaBQS?S(Eqk6iNlde@)b zPmtXz@Pwrv+3;a)3M3icE%fp#7z{5XM_;lKAT{S~Ro%VH(W*AeLtNfmFNFW+*VZ>a zBjqg$_dASs?2bYcFJSP2S}INGV?%^MBgp0ALu*hB;Wv3S^q44ze-Q8?&fDn7_ zGqc17>SZPE9KNpp@x*ts>7K+baQ!%B!3A0a@6>WKXPm9R%oxxyT*Q45`6ssi`99;q zMdJD)Y5W#(-=r)5Sgtlhzc<{+jY$;OTVP3oC_ENjjXaR6NIt3$-@)WzBpFFAmiqlG zJ@H;?rVqva-P-Y+6XXD9@4( zejxu(sdhAp9k0`Psh#3P&jcCcHg%6FP4az)3yfd>@-#=!)8<=s3K2pD6pCaq+^a%$ z@rtcJ@1J%V`W^GcwnoOhJI^=WW_k3ON>Q|I6ag+&)VCuz!B1U>!fWayqZhd5u_WFr ziu$`uws47WkM7U=G&}MJ~bWMD!PW33ap1ZTY^@@nVFfS z-gD6CproS0A{7TC1yTo^-4D~aD@A?pG^MJCnj)xNL4-3J8rm=vf1nQP8%l%u3tNfa z7PVI5SJXQ?{7ukI4gd)7$0Np|>;W-w41j=2MQy#0KyeJB(t*G0UrLt+b%KPhSvj|; zsOV26Lhf?;9Cx8tP}aibBj(;o6Hd_Ynh25#Ui#6&EK^Tk-wZsC0a>5t=zI79ASC8O zmG2BapVf=|@Fl)&z1MBtVl!owz;PzWlU9Rh;zGA0Kt2Sn$$Ppub3{i&BO^?~z8a(U zaw@c`zVc6+uPthmy-_Vw{K9G0XiODQ-BpI+C$|E%*mcjRTvy#1_Q8Ucn5z+ zi+;GkAB^z;>5M+t_np&fu1$FNhl;{ugFYJ~WhkqH=}HhXlMm=YvIg}i&$r^w3;;0< zYZErwk`Khh$FuZ)<79@wl%g6rSEI}kULnhC99V&#p2bDIlG0Me+a%Wt)==O&0upMQ zEK_5wWnjUNlPTmv7{>jI6BZ8oy+3k*xBx)`0Y+H3!%Lx98L7& zyM@>Bu+718c>yMoWmxT?hVZ4%5}=`m*E-b(Q$8vHfA{Cq9u>y|k+aq_!e^3$f*<~a zC`{afg7TgJ+gJ(EpY9(doMqgr$Kv8*YNy4isl+%bEfT~#{8!2|Zj2%Ia)a7TmVk%Y z1Qq4HVTv7==mf2#+~PsUp3dZ;ER^7Z@xRyn@?A!Sf2s1%k?R&>V$ylPG%7FtO?OjCTo|$qAE!hrmQwyK4YY7D9bXGR@lu1iQ+i% za$70|k;2rXh0clkFe`@TVB!w(*C@#}Yi|*g?NBnyxG_;}omZ__iZ{}$o*6}Mbo%qJ z+unX8+R$3jVzzV2?jx2=;<~Ps?FlgoYF890$Nc;Y@kqDsrB&*fe9F5gF3$D*!? zB)U|21RZE65==A)vK6BpCjU!xA-pfI-t3v$Cz@*KnXRAMqM|EHoh((8#t0SU_2beG zkPTfz@hRLuahLu)@~zKJ!(Q>uG{Gc zPQ$oQXL9(mEDQPZt@E`MG+`Utr{J1PmysIf$9{Ae+ABL)ZO-Pvi~04?{Q^{}t_1Q# zs5NTQY172w`B_IgWN;L5k)@bZQc=l^Yl1^4+(Y4?AzgU@ziH2qRJT^c*qUIGEB<8MEVjo?|8b9BS{&n8tHI>%S@8PH>YmWjimvuBb94Jud^Q_PPXxtBsCEWV&5+eJ< zU)9Uyag)Mn+BZ)qce_MNjHbx5!Z1M?(QOrBQwX}CN)s&o>bGe4u&$y;Xf6r%CS9|nt4Vy%H%j*`E^FfuZPB@xvqi7+pDhIEf2o-V- zw><~t(h~0+90q#M?xVQ<(0SE0%+A>aDwysIS69o~`XzT>mG!9WXwG0^2%)+#-WCLrLLyMDjw%3eSY=0WJ1*3kC5Ntj; zC3lQ&$tq)5mHX)<5qEw{xQP51S0=BkPqKOW=1nuy2T>~chyhuo?K$PK9q+%K6kfiB zKA~Io9Wri|Z4=Z@IlMsw$s`NjepB1x{;>}_J~ktareD59w^AP0J>JB42-7Aha@j=K zLQmEqCllvt2>rU;>87ls$+kWv~6Mpudc3d_j+GZh>q@M!w(T#xPxeEF$zLr zw|VSOh9cr20R)|FRCR5bO6!L#!Cl$&zFb#XCb>p2WM>b&DKaL@(YJ5s#x-+YjV5n< z)Bg_cz6Za|3Jc9aF9b63y@-!nJaEuYeKOu4*;7hvJRNq7;H-`uvZ6BVs)HF_&p`4B zfR9=1?z_*}BggaP#Ypc&Np_9hA(=Q%6a?)7zm~jznylf3>DyPK_jXy)VMy`LnN%*W z{oTsA`X{*fR&q9W&-g-6O#B-`&KH=^9KEk0iKiLm0(?IchfcNp?3GVOgCGHswSt-x z6V$;iVdGlpk93>=R*PbLuhJ5r4Fj7(*xi8k1>|W4&P$m-~Kk$*X5Y7VB5X zeZ={Z`E()vOsEY^gHpyrw;m<^oXqWcitVNWS~EgF7jNyTi7reNsyvcgS9b7e<>yeL zuLipfcM5kz|K?jfR|&bJBhQEiE5#)`7q<6K5(f3h$9)h;?9g3Z&o8`v4=zcOWtT-h z-@xuxX~a}awTymW_{e*J;r%Ek@Vxd6?zQGWX}N|*gw5w|=eY~UGM8-o0~3lP`sX}v zuF|^8`wV8c9)ArPh~`OI*uu?bs&9ifJoIR##_oJ6IyDg-!W@#J!akly}KJ1-N zWZ~GKx*k`=hMP-`F#lAHUra3(B4bmH0*@W50FRt1^D!8{PxHw zDR=FR?@9kW{_{*deVwvk?C;B1`J3ZE6y39i1tY-o-V{rUR99BM^bO<3)#LSxmQkC{c z>nneZfA6aM4PREx4Xa7~AtaH%&(FD_tal7wnH`q>%cLZs{k>Bv93x&B6!%_-o*Jh< zD0LLVk~u;Ys>%_3MNP!&txfki1eMTnbkaGPI!a{3?k1A<`RpA&5m1=^_Xla=r`lH8 z!MSS{Mwi9*d?FGfA+*@<{0?im6y`Ej+%)1CTg0m8nCh{hjh0aU43XZH{`{M4GPzP3 z{<E%1@Wmh z?&5@h(c0lgBjm>nRom>TN2!MzBUBy zd2pjqzNk<_VOA4{x}lGr(fkc+MdsfZ@&fGSva2UZM#^1*@A8){;sZ$xC`hY_N&F^W z!&`zB^)>O(BkjO9%GClL6R&)WBah+cKbEcz=~&G^1QHhT8BjtpOYf=cu0ELLDM;SoW2SNxKLJV zclc>HiL6`f_qG7}AzSE4CQ&N>4qzoqu#(4=Q;2peDF3FgBTanHO(kn$H)^!Fun`^r1Tgw(xzjpAs z7E^l9P9sW{QcfW9k#|THJ2kp{?xE>ueUC?&vaXS<_i`akSI@|7(y_L6W#?(7^zRY* z^r!3E#<1P)sD#>|s~x*t&Da(u>e+`$Q+@q$sSQFkEBZV0RTGmov!J$~iPE>WcV>Xd zpbe*u+v15JN~N z`RKvT;Rr{EqT7bTkn2z0#Yy!uzE@gcXji_j1Y5Z+xCFK7oEtLPnHAPqV_*X(u{84I z+UZGFKFw;D%$;zDNbiF&gFJ4W3Z|f#w@m3WED_#-`K{0IKq%S*m7N4Mf~3+Es$~Mv zMd)|_&9F&P-547^KKPfZ|0=pAXFigpoK9ucGA{BILeDT@%Rlg-h&D)Gt6L!-Q|PE( zP)9m;O0SpZwD@U8Ot|!m^HBbua9&zynoRpY`SYZd=DcYop0tC_2XB#~=c%FQ)CMoP zJS=%H7!jn#&5S~sm~I~IyL6Ty>q`SiGwaN}Y*W^coZrcybs0Y}>qu02AY+lFGZkn` zMw!LdJh}glq4)Oj(S@$R)lk_uAIX(=L^kzM1?=j$o;FLqJ(I|Ng8ACT9LLgyc!K_G zz=?9>i>iONIQ61J-YBCRr3i}|Ta9v|H!d7;uY07^t1f*-{14BPp1t?1AuFFvodcUz z?+A8wtp!B?Y!}8qXAXd_h-og;2EjXD*;ZfWQdjw;q9?D!2$zA+)%2TzIULRhSWFzt zO~Wt~Y6HgA{!bt3boPCwkex0k{woP9j^n~1K1)wTj_?~DQ#l8x%478kS#XpN0NoC- zrKRa&v&D9623s@Cr;l-srdqc@%*FFMI?wcp9@^42Q`_VU^sBCnyI4*EDGW}hfT#e? z&Ac%)XJ_0XvQocF+pIcbGXoszEoUK8+EG&0W@bU%CS9p4Iw0`Zpv6VHw>ESgvzzAz zsDp566S;DOxJI~FeXkAKIXJ+0!i1C9<_SE8Uk=IrX~1N=Awd6L12`)bsULtG3MBlf z5^|WDm(6_yT$hWp^V=jkFeJ(vqX#1?K)nDJA?TJJCIt`JjO=U+AD?U>&jRBLS65dc zR|0R4LSPN(IFRxP_(p(2!2eqn&pMKVxVO|`H_QnIu*UIm-Z8PH3~nW)ta#C0y=Ea3 zm|M+0C7q-LGH|%09;l#dX9JL}P)4S}0UZ!~0Iob>cHXykj)0*R2$bAC23oP3)$5Ld zU}UV>eF|q8u;u*Ny*4w zf`RJlxbl^x(0~JD`N*tlu6YJb1*HD!_uTP{idNa8u{mgUN{19F9 z*0F_MN%5semGrKD(LSk!>1D{{vmvkp;u*k%Mtpsc`>}D}4 z;Mq?MdZ4#8vg0_+n`;bPk?^U7w~f|d&Bt4)`2|d!g~Y{mN(#K&#~mN~9cx=!hA5v; zDQ9eW74WzO2Z%L>?Eur;AWbi{E)DaA{0ExHGb^N=f7sO5jw58#}yPLh#1>|9K zr(l18i8ctN{TTn^H+KOIx2-Ey4h|T*u$19ejOrx=keN7d1-+APy~H2mUP3s#)MGI{*0-0gUxPk}abh`R9A^Gk2c^uAhRk zg;SH9QDDvmW=I-~-`|Pno4A2^{+X-9Cw6Zdn!oujScwT3>h@Vho7pUjSX0(@EB&A8 zS*ILGghS=oN4R%(cEDF0{`=bAz-0`Kx}Yji)$+cIt%e2$llyMqC7*poKOnAms?=we|0vh4VL<#=A@=o<|}mA?XqezIkz5exO#KOiibLe%@GwfMc> z3$YLS&tBdKkhsL=K%6i9-$Uj8^-YUTnk69fL2ShB1Q@J>v0wP#A(q>|H1S*iXYv15l)Il&woR!KLsCmD z zE&34BgfH775McQ>FzVX*;&<7`5~>Hf>k|sR^g0!9=q9Uf05c5NI-J?MlXOluBH4!) zzu`(l+Xk_o#)SV=MlL_BYc*iuagkA+Ew{=hJGZ04WjUn(eU zlodR{8%sCzhY;)BAcWcXpV>k*VN*GUC7!^3j=*K#ZT8Lr!uKL<+mt`!!EaG(6B_wa zu2?iuxjzsrpbicT(`P@W%~>MiXi6FquEp&J3=Qk>RF`i5zZM`J26awh=D8ZZgHfk4 zafzk8Cv-O?ZWSAYDm_f1WGz{3JiTJI;cq^r9-PJso`HE6svHAC2x7jZY50^MOK0yf zj)VlnQx68oRU69Krt%$ax+CxvHnO~t4kF{5$~lD(#Hh%sh(1NzII01uq@(e>z$9oq z&GS|tmAUeJXIMRYqc0B{b`16ZJetJfOkH9^b$EYXn6I|EoG<{p~p zShRrfSjmSiXALPN5k*lW<{!URtV{adDg-^g zeL7Q^yJNp>IVq`j%Psqnyo8Ptm%0ox6$)W`@VmM`?nk{Z%be0kDkos)!P|MmG`z>` z&SoA4i%5@bj+PK!KJ-CeVx-0J?41?+ptl%iD2xD`tN=R!Ri2a2nN_u$jC6Q(V>#gr zQG-qV$Ek4G^U(J!JH{omal`0@jqZ~Ze^s-#Po<`rU_Rl8w;xFkvK4k;u+93 za%%c(WWifV`|f&72amz;2&8{ohr)l+Qq@!LN}q*P+ROc1&h8 z7ocJN!#Zc?$)lgUkmou1oRmuANN7qTGJ2#c{v-AlK*CfvyK7WVs!DKog(f*~dh?iT} zN_;M~-c_vQo!uD?YD_*Dzfa~zq-mZKA|i(4cjkJnV3)+AkRe)%W7es@cu0{ zL|!LQ%LLU11`;=*`X!*uarZyblS?&<8(wQ6J|2pUTsjCqO7mXPGxZwd$`b;@=Xo>d zu8+PRKEt;|BvqR{?Bh#r%de*WqQ>mwqED$Q?9?!Vtp}Sj%~^RyGe~vH>Jz(geU;@F z2b^KDVIA!D`vnJwLMA-+J|CZK`d>qPEnCOr@3YUZNOr4u^h-;#^M3gFaeT;b9A8{n zw)XeT8+RrXBDv_c%FV0&lrIw!YgX_*EOzsuxC%XjiVXQp+JZBDaHXMee%w0wUom>I z(Ov%4v^~LZT-`eZ;RJ`b|LrVn|3tcppcZB4UcW**7;Y1uI zC~Y2}dK+)lq+(BYtG@sPyQX6%<5y1ncs-LyblsOe^1Ji)=5I)y;F$^c2imBO2Wg{V zSBP3Rm!OulgG1!PC!@k;yZT3quca#S#1}lAX2E?3(^4>@JW)OYk0Btme<{xa$Zg@ooBA`&dkrASkxL2z0pS2JBqt{WyjGb~5+aW_ zLTxEOqbcP)fxb{ zY6$GR1E4|xJknp6@X8mWg5U0NVE$7KZCE~1x2Xs47yy}FMT&Dr*bf90$tOPF{)OTmcs5K#fQPHA zlT!efOdt_%7#}*r!r>**-WPlCUElw7HbAXlihBeo1_PPdd)++XjY0sEc}xkPuyDn$ zg07h0gx~;B<~^nT$dd@q&wNq3U5WyZu5^Yv&b*|g1TdgJr_shQa=91ob!J8b{P2RJ zfCD#IOF|Z4@So0=R6;}6bMpaj41f`YbXfTSNbO)4iNQ+HgZ1O2r{1Ak0n#W$4NxBf zuug(gEH1x#j|dzp4DN}IR{Xnbp`19l1wc8@Do22;u!R92Pn9XWT|*Y!k0K8FXF^Ve zR5mrq|A3C~@Np{(OdJtyV&mgMGqHjFeARljS6{S_peZ+v(mQJrYqMQd+ z$69MgLqibTEM}8!kS(#B4M!)Og9)|-YFp9+1`<42c(A1ec6-f5!GsRP?z}j|r$03< zE-it`2)it>GDWrr4F3dMiwr;(y&~W(A07-Q((kVUV|wk^sZu%v6aYML-jrU_tIx@j z;K8tMf}<1DsJTu2>vv}O(nYrV&|pd0({(dlV-r3sv$@BR0 zMUjDwMZwrw5VCsY(TdtAEF!W6D*(gH*+CUs!3c%*-8BY5;>Yw&oK?=ct38d05 zZX@~;XwpBBmpXHN-SEmdaL7+^`}vmgIas;0qN^5;DlNF~%y;;#xT`QK*{B*Vz_jO` zx)=v?LZrFzTU%HvRtSt891ZHf%(OE#&P0eD)dM?MH6sdBI!@OYo((*TdPj+P zmaLLgBt^|^nad@IG|XSJ#tpF(BxV%WyVO9!3ZueSP0@gm)2A}EMqjbl{g)!4EQTSf z6W3Dke%6#E;FqR2I%2{gKGyPqCML;{WE%9hyuB2568q1H-i7TrJP2}H+4;gyW6JyN z8ZSoP^zhzE8l2g_go%c~TXUkR<*A4k@$Ec;$#2@?XFs&OQn=})qP#2l&YiS<>$2@5 z_vE(D>||@Fr(ooy@k3?EOZA7^Iy!EChNlcO%B()30K`Oz7^)OXT>O1@BW3+ z!6eq1Bjd#+qFoXkda{DYTR}zkMw7QH9FQ)YzH=j0zn1E|83f^16bL0IP&i_l$$sp= zrL$6u8~LgaY0_o+ej{CNG-Sny!_#J#upyiY;lasIq(ObqjpX33bA*}!9Acf)kI`XY z)$-9;gfw9^WTIL5(Pe0p( zHQhdkioaUx(pnkAldnX$RW5bKQ&|j6&}Eu;nZ1(i;O>P@_?p8FBFgSgAH(F$@u-OeJ9pT%8sh7O@>{P+Z*IAu zs;8gnjUQq}i z9C$YA$@gHXy_VA}au0s8LA_*Iw))|JaI@!vBx1Tw28)V$?>@Id0w}PpYp~@5@*Fw! z+(j;9ij?z6LW+NUZaI^t-D0^lrQ=B;?ds7y$WSm%i?C&#`D_w_mAWg(c@epnMH=~m z-tyG|X&hmgIl8rp5b>8tE?=JvIgJ>27mZ%DE{kqmYIAcZCG^-ol++SQr}6`HWISz8 zi|*RmRxN*j0LXMN(%dvLRZk($K_7Sct}(5qM!tl+U&t}pPzmQh4SFcVd@Q7o1!MK$ zuhyq_zu2A6Kj#Y>9@f6Z|MFcb{DYVtw+_pViKWfVnyz*aL5l9Je``iQU-Glg{F7;R z(;u(k2_LKAQNe$HE_qnupZnMS!W7ME`s?`n_485bSmq4H)($@#7#3nT^wfC^jHUl~iFT%yYdln+=qiK;FQSp@YWpOzLBdCUHc`SIV`-i+F3F8GgzAJi zAx8)+x`sbW_!EoTPlke5o#2k8KPhSIZdQDa6IU_B{)}Bv)eW=X%4R*YIm?F2q z29@7Cdo3cx5ROyNV!uzV>?wzkDg$|aUA3QN z8bzID(=Dt1lW>x~gnxpQ#}ZBZ-!Je}eZfPx5jo)r`b6vYA<4J7V-LvD&h9bMTsJkW_(l$ z1J6@XMC99wNAs*ng#1ikQ(QmUG!EghR}0g`razLUP4#{DM5m$O!y|Mwfj+Y-ydVzYqq0FtNxMgX4vd=e^FVZ?Nik?7xqIvox@%owe<>=_ z9|1MrVFxn0i;`tQxm`TJQ51i@45@&R{TTE*)g+fNc^8t}uRN2Co4%PJ*RgnQ|WqMUW?qWjRinkxnXeMg?=v#hEQG z6gJTDP^R#k1M{62A7Al!Vj zjAIjQ{RK1p`tt`F^+YL&F3Spq zv&CimWwZ)_Wdlaigqp+a==w*$&e<9%?Vs36j4{&RDBiz+4^lPD9B2dNVW&|t%&e@C z7~#Xb+jC3i?D-=%b^qYv;P8J_TX*U8K_$~JommIr)c{xMSIuLiWfrkjDyee-oJLMb z$-~DdokRy7uC7N*eC};Ry8!XM<}}5Zewmoq^V>G)1Gf)A7Y7f3BL!Y(bCLVC?(Vmc zh+jt@z&HTPC+!~5x@3DA6|w*cDzKZvR57#9r~&W~DHzOwSe*?4D-a0-RCq>Tj$V8e znc3Nz{old#4Dl3b{edF?7Gy0ckq-dj8W=6=nHj=UV(N9ZgIxu}0H+Qw!4y|BtWWiY z+Qr1evgQAZVxl%)!%c*`SzOB#M@lP+BZ^~^EAU5JN3v|G4eUX#;Z^uy0m7h&Vn_Jb zhQ|P+6yf8j7X6m$?<+UN&9@nZ5q$GT2bDw+z*iIf{Z2R!G!phgMl)anSe$$rDs64i z0r2r+HU(EWCdCEIbP5;dJLdspSwD&Hce8Ua*!LkAwLoK-p+s?K;j{ARj}HBiepShN zc7;w2H^6e{`$x-706h9!)#qu2X=Y-{35)>PTW#Dq{^#lF545qdAKXDNZ2I#}{PQ3f z*l~BFngGvol0aN$W+u~^3h*`q!>=hAINGt**Vh9gdjA2a5CQh(><6a#iNAjYN?vyt{8-XkOnOC0RejQscJ!{`mQOZc6$UHY{#|@{s}yC13ggYlSm|bD zbi7e{v2nK2cX`LfZgVfPmCe5AjqG5-mJ(pjcp~>|PK}t9XCXHGv5#X^=<(*arQmYJ z%yG{cDfDxQJ5JC#W1#Y6Qk2+ET>4rk%wHdZ4CwBg@8xZ*rcY`$TRY5TXy09FL+y$;v^M!ohNiUv#j105v^AXc(qHr1yKA0v=30oP<<9 z!xmzcNN(!n4Tpzv zxBlYHuQZ_=nZm&TrXH*+xbd#+*TNvF5*@OsVMcJ>wrPx2ITy1g!%zVkIjr z9R+kd`Uh%nnq7i$nHA?P{ou4Igk{rz=icQP#w{neinG<($opd5-o2)e_j>*lYcS;^GT0XLa;P*H3j zE^`r?)XTW1^RY0*s&2E zQlg$8Lr2jVJvd*dTU?a?eH%NJSYppZLrGvoPK#9YpfAkmv=HRUfj>OsQby8;Ozps} zpj{N(poVbw;lGa{#wNLcJ>pVSnLJHcfF>0WY^6T<1P`@k{FWiugbNs@EuS!`*&1LVb(tnDLE_BpVddg^r)2&;d5Xa@pfJ7= z&CNbG@B_^@Y8*j6Vzzm6R|b2(2Ukfvax5`Pfr5EobjFa9Nuh=C1lO9B)%~q)SS-25 z490wo@@Y%c8(U?IZ1TL*wI}`$SRb;-kypNACdFNR2l5e{QKc6#Bp--pgiW-F032sX`Zu~ByNIhJ#V z-Q(iO@>~#2pM9P0*7-Q@V#bYa?Wc)|&NwfM1;edl&Nu}11`iUHC7>w5e1rTa5>PJ_ zasgzIK-uQcWE)bP=>n|(5Qi%?YJ67LedSiIt+}Kb|B9eDHlz&_W6|><9isQQI6+`* z&YzMI?aX3lxia;3>~k;yca;E}JEyL-bN|i=reJR!A^jT|`tHtc{6=RC;(^KjW(LM zw^)%scUI2buT~ZPTe~jLJ{*;^Y~Onu#qxX=Cd%Ok)=92ijTf%=_H0fESLpUBr+=3) zgkEFX<}&DR5}!w@uF0;@te!K;9`86iY6vff-?A@Xt-p#OTzb?wYh)>2W)l?>nhz%s zUjUrL)6wdK5NI`fgr3AO>7_BzWYoP4)qqz8lJH_;I`(#dKR-h~D_V3YYv`06RMxP= z18f_PC+iUubB7*Fzka<;EhTAreZ)=~XD4L3X?h&NgD+pcJUecSb-zL2|7txGla=379CoI1g}}?J=!N_ac=`ZjR4ET~ z2w#Da$%;90lgL6icOL*tV49(XWAV}|JOOU-Su;(X1RlvVxw&bPbH2U;p7}skFtM^? zh&+O;I5Kv*nefgx1d$sgg6y^Iev!{A^D$a%IrO*-Lv1K32HI@(84V;YyJr2Y@K9D? zAXoyjc9JuDp!Z$|rp<7$qFMRjdWb=prlzJotAa=f;7FVXdVOFG@h_<254?h948iO_ zkQ+7SV7zRs>-OJfF z;}zW$V*ZBAPhdL%=@O9VVGhDx0LBD}L(PSkC*q>W+YApMyuC9gCsn%cejRfGP1@lF z*d$$je8xZq-K4c1ixl6hlCL+G!f57ob<_N$E*Mxk8kxzc~ z2g2^>M+6d@QDp;*<;_h-bMq^(@Zbl6iQYdp7PSz&2s_&g4zFPMAf8-AQg>(ogMy5V zDLEU$wtUF@v@Uj!2zDNCkSb!EmG-Ybln#%e2|O3a^z%=!)^mK8fIAeUhdAHo?#YIzilLK$Iplrk~LM>)t zovpvF}EvIOLxia@Mv zlf45u#wRBy>j71MdGG^x6`$#B_78hX_uow(@WEQX4ubqG&;SNB|9IxxeeEmkbMcW@ z0f+(skNyP7fu)A$+0Oym%nootJ-g1yzHb9=83elgXBExAAI(4cX;*v74zgDGcmAW% z!Ev~M{Q$}r*Y506*EM=R6h)imW0Qf3njHYy4Pfo$%!|^jnP)16uDe;WH8eIByNd}4 zjRTLQe9OGf**Kl;MnAgGcSh36{XecLfoA&&qmn5R$P~Fs-QRC3Q6qzrW7gm6ogklY zN}&I?)q*eMPk+-RZ8e;fBGDC*7g>@qed-(`6gBv5oqT zawS&C+A3&~4hkOQAPhvD=Rpn(vq~^Uieo;KlOg=2W{`Hl^7P(PWDai1xkUBeIr~S1 ztIYQUt`sW7#8K+v5;_Mu_gXPj5vGcGmYkbXk=vqj)SSVyaZJV@FM~2sJ}iv0^q|#d)wua2s(HoE|I;?{yeUk=u)1Wi(tp9g7;fV*$_D?y zCq@8+9$lALnD=5*aXm%SVd>|hcsQ}=%qtEa1;I;cr_OwPP)-Fpm^64N|O^f*7uM7O|7#G z|D@A|`mUrl%&=AFYj#&tt`gks3ClsrY*%7EJlrKTJF+Q3`>n%{R|E%NX*3`hkCVOu zCfh2=>Q3K9Ezi0#g}S!NyFK&D{USDR9rRSc7M;`3YH|OPsGp~po*r|Ld_7z0QuO^> z#8KH*>mpH?#|`sYQ6w4ikjkr#HJfw*Xt zwZ!x7@e|mx!6Y-zsU&NJP1ejw=mU=N0=~Ha0T=xB3kyy*8ty3}p~i`FmRwY188+)* zRBLZ6$n-E+vFO=$)DV;oSJ&&-87HlpcJVgX&b2N|{~9^+#Uwk`s9yG@**lnq^egqd z_O%6%E^CQf@S+O()Qpueei^^Z-6xJ?#gvF@NC|_jI^|{4VJ*%|TTWeJW9}$9Ct&8D zI`}B%{hI7I*@4T$iFZTBN|{xGso{?B2=zqt)pAlb3tu27&D7|n09@7{pT>@wYLomw zIdA8GsrUAZ{9mq@^Abf;2w^^(0H0)(e~y5ZY$zS|kosHkWcV4_N8{l3m zrL2FHC+_D!sDbLi%5#?Fo0p2w$@S)Z@ajfHC!#Lmw|ZAL`frGu&r!9}&nlSVwb<4p zLxk{>Vk>`yo9T(!#lEF23jJt);X}r@N{OVR6MgTR-syfU=bu02UWb2R^4nhZ-;`|k zQwVQ|9E)x3B|~jj&42MvZBw!@Bj(b`w#QH=i)`9E&LfIT;=L%d9%}Wlh&A})$RQvw zB}XB)o*Yln*ga3R_x)qlV1|C4d{n5=RRKk2@zzxx97aOAc=&c%BhSHz93g^zWN%8$Y2DCr|LpH70BR~Z`}ix z%>wC(wEhpUZAJIHTYTJnIa#P<=B0=NNj#HsS7-;cRVAhC)cZp?@YB@92Dj5)V+`q{RM_sZyuLG5*XvL)6Zm?|lSNxKOqXaMO;GhD9 zt|4v#k}Zal4l65^7#~Q|te(wz;}a7x4R5sEZOqIhf?RMOm30e&*bRu8HUXWoy}hl$ zsKnTafUJb+HB&Wkd17x`v1?IQCt@Nyaj z(c^U0|2U{nfx)an?)Qo^0+0IgrM%_y^5Hw*Ng(qBXY$)OydfeWClrSKz(_G+_6t4rNv-Z7L4{7(pt?Ph$;C7su4Y_khKP za)4_N6l{#*dW&eqj2nL@pUsw7!<^u8;G@923yO#G!2fYL!RE2BpsnEf%-tFt(|PA) zWtjt;1BiQm27th&27eDdAKH08}JV1^vM zsoTF4e7riBMm1j^dXGQ!5_?bQm*W?_q=p{{Og$3n?0audb6JU;g_I&_89(;94v^9HvgM$L6Dn)Xp1}FfJ1a@@w^kzAa z&(1XNY)0A{-mhEh4ef|Md4n6lS2;Bo=*WXCrkzgyXHl7d(={KDpB`61NGHk~Q=c?J zjINAVFF=@}Nn>B|o#@|-`dC+US?Hcrvs%M<=&h%qN!pe%Ietu3K1;^;9=Xa>05M}XD&jSkl+5EYf?3VQ;UJ|E_AwlbE*UMJL7F#%X_=L)RfK~! zg2CSLz3{_S)D<>^hqgmy)mJh5{JCQ)-bN>bK(j$%s_MEJ{BG{Kl0M-ycrzu}2gQEg zDd}?AW()7~jf8Jz`9G?I5u%b&IL|Z4^8_qFB+_V=1X;ueT%NP zuY76BC?aAlJX5jAtM578SQ%!-{#O|9l05E}mVFg_ZPV+;M=K$n3FH{*7c9+@PgB0u z7zF3t51s@Qm~K-At9VqQ4(>Tq&={I<|6D8nLy5ungg@Jqr%`t(*O7QhGb?r{-nlbB z7+e@ikAo^i__w=XL}BrUvo|;W&R;yeeMQrqa&|tge5L5GPdzV!#)BAF|BX{&f;LS7 z4I7z>3FEb-TV$cqM9(C*X=aR7L9rYfS=FAY3g4G&^N!%V-gAT}LrcS|tyf=Q7yd~D zEiI~&=8C^X?(+L8t}ipDzB^R$Up$spRRqMsrs!IEs9SK?s8Kvhoc{7;2>&g~-z?$B z*|&%*O{IVT;gP$_B$vwFAzl@T&3a7=*pe4`@Zrk_c!i3 z?#(`GN)4>z)OG!#Vulh}r+x6h-=E+jiDJQZuRTUy!<_!6fKc2hhmuJ{JRk_HG~-F_ z-}mc%J{8*4a3AM-i&@sBvRn&%CrPNcf1{oA)AeWq3~tqFe*#m*z)NvD7hUjJ?&kb}Sht^Oc$G_RjC`Lc{7S><&HiqF>kuA#PIxX3@-%0%7R zZ?y8UvPpJ`yp1FaKC;~EKVDu+F}-IF(XcQfkCdx_<44?7z!7SmUNn>%MBW1(`j{DG zXqc2BrZE1nNcd6I39iRg)6D+xf@#`iD^sRAtH8L{tjst_Rgvg|RW(kILtr}sA>uJ4 z?)=0RN%6jCxi0O~ns_9M;?5^+bT$yV_i)CXC;DrkvAUdpk-|b4QpI%lmWi1&PUDO$ zKcR^5#Q-?*^)K~QAVuV%zEkfaru*4V)&y8Xy8^Q^GtHuzh|3{>@rxs@W74X8!;`H7 zJaL>o#Y^_V1PO1gt*0!Nz12ZLEBL`Zh9$L_dd3Uv-@o4k?4n=ZoPjc5+eB7w?jR`a zCZeT3zO_P{w8jO9ML^*5^c@7Kld;z-Fe;2~b3OA<;4Pk?4Dbmc_KIKpBx(n=>RG0L z|FKR#K8yIft~-x8g|H#kI@E;uLqy-+HJb=ndP7nV%|C7%&l9 zNl|8iC9M7~!QQT!B!rz2D})rv86`dhSf>qurf6CrQ^MSV0Ab_;hR$qAK=JIybGc<8 z;_>kI^z(}Wdj*)U((UEVvTcU4pf{z>FmEKnQiCR~iAP1R9O+)N;HPmdVSPp7i!Gq_ zdTzf}zyW9A|DTR)xn@YU~@t7+jm`IQ17 zup45Jn_@t5=j`V8tiGz@1!-cZM;*sp9C3jS>~pr1EvtdBw>SwGjTe=3JTh&Dj|05T zOZGq^uF|9e79#Mfci)bMFuO_Cm!CER;GCLt6Cw#-$C_P7qb+QV;(B`CVEX4tpoBRH zkDw)cbK&Ugie`HU*0}cF>I?VM5Tp+l=f8`2@zSQEj*=x`+xaMUnju8pi}OwE;{0h} zt6|K-SALeMM&FV~ToQuVH}b`jx=pzajEbnA3I=V)UYl`A7s%m348gGeaz>akY-H_gL&EaOZGuo)4<8&|`W_BN8U-9wE8OrDU8WT8Sb}3LO|=1Eahisd+i0ZqRc%Up}amcu*AO!uL{{ z$+LEROLYk)mr2!4Dcep4&Jupt=abIk*V^T?;_gqe9zuTXFF$gwrH|9CduVidbE$+~ z_3X@#-Lb;){|p+9k{A($|h9RToI#P?c*gu+MY29gG@`5_A6~DGYoHU(L z%R;zdSbu8>LRrS~B!yw&N+jeFQ$QcWY4PLgC)$wZh{GZuuaqOVc-z%5bwslO8k$SC z&|1eU4&Jxo?XZ8;^Em@IBMT?IS{j5gO;3ftkRtA(a&J&K*|OPny^Q<^mHdN?pn?A{ zp)gsY(?}3|uX%TQgz}CcEV-*HIL_s7mkE_`yjC}nax_uQAAj@2e3O#0{YLzD@iVTk z?{)c#Md?s}Rs}n_J(MJ{J!+0M#@N_+5lWy@BjE8gDHhy|M0!q_xo;d_dtm%->0LJ1 z?-+ASWR=NZh+LI*xBTa)%DA)9)^-aIu;2T9rfI*+KC#Dsu{BTsou^wFhE3sn9E9RP zLjxjow{U_(Y^T{YXJX_9=!E%4Yy={hMc5Of9?g{ci0sATZ2mz$Gw1zUQMu1~RNto) zc6Zd?ZTXKtwp%fX$zR0oF!FDT39MrM4dWyjvfOq1QwMBV6>*>`wh)aqPQfU{(XJe+Rm=H=2#iDeTE$HH!Rr|753V-U6q>#&`8_ z^qe)Rm=lYw8>}h49aXwP=Qg~~>_3PbJQXME`tq_op5nI}b@HqQ+rq(T_BLY(4V(d~ z=bz95C%{|wc#)6n1l@B5RzhkZL=uIlVKk8Iz%4d49~8#n-JRcQJ)FsUa0P1&DX5ns z*zp#$pnPR??cdmtxqo3;y0QMy_ZKV~xz(FfhYUA+0l)ia%?JtFD7xv@s>`%dA?ad_HnZ$_(HK*8sv=nlu78^|yF?h1+)uM|c6JWPI;`TY83rnEY5-8uLWd zT&-vx6&k&flOi|5>1TLEbPDCrBl}!=`dxLgA6`F?2o=KTMi|bo3Y*OCn2<)NYM^E5 zEINQ={G`R~cLe@AG^9c|+%-fbx5NH*EC7}K%~NTZFzoWnyxw~Rtf2LD(fNRnPRcb1 zS9b;uy04cD2G2FKr_Tp6(!dIH22vQfVDX_6vQE8=B*bF3U~)eDxfFgL&vBG_iB!Z**j&LJoo)B`lH_e@HVQSS&` zt%I@2Y`)vyK&mwL1@7}Kb)}n;HvoU^-QD7dGUj-!IwV+=KxmjDdwg6R|1YhbDtAW) zAjm!wemhg{hO5{vXZ!d14lS7KIt#R%04=$E5*%PBa}Z(96*6tAL50?H;{-shQpT-- zr*N|`40R$32_golNwsS2)9misZ0yG5g{;iEkuuQJP*Vw@8a0p^KMbI>NG>|w8gt6K zhW2(rvuOoPun&3GfW7hy6QARX=@kQtjAs=b40E_GC5Ly-{9c`5N!*AF?N#$ev$27jX$`Kww}v6t zBUou1f!CiIAfhvlUqF|`b1gNyNw61-^OHYn0XhfL@$?70;|VV92IHIKO$&F=xNT?;DM;WFwx zX&DsHo9%vpeYStNw(B1=IKrLnf0qYnc|di3Zw#}USPeE{!}RHX9qz5JNw;p!GuHDR z(mKIuF3Vufu?H7jbI$R|&KQ4qEbND(&4~`73$e`b`n&DTlSkokQ!dZi$PHTArk(

    xieCZ|`~N32!opr3ZJm+mJ$OEhnRkhGfwUWk(VhaYi2)>wT@3h?ZJ! z#``)qThSVYrSi7BNFUgzZ_<7Bgdm-Fv5hCryr0_QWB;zn{1XP|tSFnuT@9rTo z)l*Pwwm$b!FyJNY#?UpvD#aLwGI?}9zUEDsT~i>LG$r)?dZt3=V1wI_0loV5h9cij zQ!L0hp+Bl2+SE>(1D5o?q0IKl10hf(L!!Nevo%JzmTKDFqJ=SN&lWfK3mx^^(#PoQ zyf9eumpmGZEe;J>MZp>T!!F^$RR%6%BSL{>84ir*2ZeTP9|qS}%)e%2 z{n!wId4HBqN2!VtvJ&KkWN5*)bxYJn+)wn5MQ-Gbv%wGVD(sj0p{~>Bfw(YS2D(GJ zZe{Sbc4r!G9;LBRP+VN=mchBrZ?-&|m6 zJnC%xjH$^MYQNhn^4mD@P|eAKtUjy)FH$wZ3sM5hQ#J#apsZ11i>#n8$@G#&WlTOf zX}Ju)M1i=p3Fl$1DOh9lX%1!VQHS}BTA9hx`+4TE($5{WS`uwqvYGkd2}+FM>#pdZ zo#y9*LtBC9RE9h^0JXw>e~=U$o5C873@gJ>tMY-q;f}eXV%}d-Sgyy}Tm`Kv3hQbK z)>_0MN9g!4fu0u|wvyDTSE^t5MJBRAt8bsc)37~q_zUGPrY!%^oW$L4?zSn!A(FKR zPAv)74j3V<_KA_c_uh8G+=*Wt9@{SirN(=t+T|dKX19Vj{Kj7!3g6-F`}M|r=Vd${VIW=V)@Ae4gL5tMj))ZR}1Aa z&dPVqarOpbr{J$RVMGHjf4*JqX4YZW)$0tb{K4zwZ9#179r$+ni}S%1tnde}zFszt zT__4&${fjD3C!b1X^aV^d&^fy8AZ*qrCH`y?ifEzjE9rKWnLAuxD3J&}{YcU<3f z3T4%Fim_zHcQR0eOfoV)ol5l`w9P|dx<9YW+-e27|J(gJFp++T7U&I8s?&v=39=X> z>4T181a0BX(3sRPnU0fxy;w5H-+QeVzZ%{JjX7ZXgr>bS1>ZJi<{oGGb|jfpw(aaS zD{00!=1feQE6QnxUslSu6q8eWv7C#Z7l&4RL?bxKl$<2CHHjqX4m>GzSU$6D4!ft7 zHXIxUAw3W0Ke5BiCOiW=LbCDS+y zZm?y({OF%O<@6DWW-Wdco_sMgi~%*h^xnT_*EAKF&4JmY z5x?zX);%#Jqzu1$VZY879lW~Y1^7Q$Dw_4Jdf?kOCmLACk~!&N>ahxS-ba+*E* z-WYQxR7$~o#Xga2&`dmF5iIl6Y!C0JIun*_GyJdH^R`*4ycs|A}IVn0!tQKH(<8BX$59sx-7Rq_50r}_G#Ct%5U%$3~-{`j+lD+zK(g zl048tgTR!?q5^}0H6CNxMfD?~sq|vB30p1VjOu{uyBG?WmRq>}qPlYjdP4 zm;*sg9ipl0*8xx0&O1|N_q%dpl4(|;ECwxSv;nPu-6_~iY0R3Rw1EY%f>sL*FidkF zQuxLQxAofFXs;`2UnjMFLx!;aFz+PAi1d=nSB2U;#K3y|1AD<{z{`-Ip+yf<4KYTts~w)0K<$4}0XH$`_QyL8q@kxM(s^*+KYQ%GfGQ_0 zJ|0v9jZqE*EfvtLv#~4@=pL+8CuRSBj=TcA&vU0y*Lm*o+H-IOCm&w~2=GTkfCadY z(BjgP1o)tOf+YnX*dqbYIyf{BJ6T4-Z1yuihP$iJC}vf8`IYC^?afZo=k|>_HOz zO9&-RzJA?J(AikGi(i`0;ABEu+~>{htZy7+d%a~h1?Cs}JDhFr65UY7?kkPl3Xi*JTl zgq~mg-D=xtEbyd8z*cJ;H05rtMF@KP`a7+bGAyvb_aq zqmyHLHRQb}+>iK_X=+&YvNwZVCIg|9u>nWq%;R;ryJs&xp1wf;>Ja~EsFiH z=TYLAFkA3z5n0qGqKN9ekCl1?0`%8Z+fweY)wAVLF}vcV+1RlE>1xA}SJh%(oLXVE zZ=irhu*ZWHf#LNZrq7{KO*_ewS|kwGnA-U{57myRWc?+DzzDJF!|Ya%q5BTmIswaM zVjd*AqjZ;&maiFsdvlCeOj8rFx?AftLn(KyNabI77b**U?ITbwGsxo)I@nei+(Lee zvcE8zIo>5EJHvG|T*Q)J-dG+U=oB+cPYtSn?Y+<{Eg<_@+S@ei?WU63{?vKB#U`pL z??2msDuyY$C($pl%fHw31)Dl>b}Lb@G};HgkqeXm{StLm4jl=8(9t}OH)I;WYwIj; zF&;G7^VfjFaamAiP^)EZAC_b*^%vBQknvtKeD$}LDU)0zC~WDYPjZxNmS5ETOh1Ta z|Ggw`_#gdG%TF_+qc_{yaW8kRT)I!>zxCV_)M#h-J_&oeBCoAXZhPOb!>O0!i22Xx z7o$&kYyreXR9OV45w)p!=%uiH-rg8hn}T2gb>Vq52NFK5f1j7e7s$>`^F{KPzC z4YT34_4bs}N7A9J{YCHvf8YOtuR~s=D)+qWi~ zEbbHRQ&GbmNeP-);^z1osNb}Lmv{yn6rHHJcTGQv5DAA2lILWPJAUR=PEHU-Wwa~C z?3KK2hxIn5SMPmek*@`bvz>V-mip-sFG&y;9u|G4ES1{x1X@i7ITj&fe^1FdPp{N{V?2bHnL`__;-mJm*XBrQ-l0cz@?3Mgm@a*JY%vVYRw zH@&r^Q*7C@z!B)W-MXE6s!>z66PCSe2<5iVtU4o*PsVGUMA2rSD(2Ra<0apmEgt3< zCZT=-)u)4K%-jfT(+CY(|NC(RHBU%o9hV&I5|$Cd?jwzW6B7EB{&2^h?C*csH{E^4 z8J65k0JOCe`mljeI7KF7L&_^$J0rShfyqg4sZzREVk2;E0cFdt7ybk~kpq9E*|I>P zS_lP1nFCJU2VnR0z|Imq25vin92b~YBtSbHuuQ-3&Wd5?dQda&_~i)apNy-Vzts}E zGCbSon^lHZS8#H3Y5|H>03icN3CeLU)$9q}(px_NO+M3@-tUzuNPGt==Zz&+naok&4`7((T+3}A^xb)YfoSf_h zV((g6S-}Gp@5W6G=i>5m_AUg}eV}TifG)e|XsG9Iy60UaDv!zum9u}_JI=Z>5_ANn z8~Y$XCkkCBvcc4JCBz_~B$P3MEfC1lxedG~4#Vfh6wx_`>Q_UXoI3&F zRv%1DdmVXI;K>3|2iOJrfqVn#jbW-^A%#jc0Ez~vfcilnCAC26_%_mFaq|%9#sNZ! z#2o=3s5%91ZGdg91DO!CTIN?;fr4J1)^9itBLjo}g#`lG0LEAicE%^rr72Nasu8(K z_dt^^<(~dq4B#iZxw$rTuYW#ngo10SHdZeUj9frfwLY56074BW5*WH&lFk@>sog<* zydxhnskDa?)1Y`Jh!-Qmq!1mTc$lSF2j!2?huto9oGeIVRGIMilYOcNV0A1#lehx5 zT?EW)i<>|uIfAAJ`L^qvBNihT1Z=eePbotTuk)n0sjQ?8+Eu+NKcr8qcLB@{h>=B3 zW6++vSUylb6!Vv$MO78fSt}Tnq(q&`Ktur-)WTfanm5v}YzzEa&tVM40T1r?535fi z-Q|oH71sb=1CSM3T05u%2NEjo0QU|fpnt(CwwUcKULa}KM+b`Wx`iOmfSY~_b2Bq2 zfX%>Sego1%Cn?8#uaDNB0lw#``DX?blDp!O><2=*XAeDSbh=C8pCOq)f2?VBmX6f2 z-^TQUq@qwqV5(dP*%-??2b%M3_8?vzowU_nDbb z1ryj;p+j(4eho%am1y`)JPAk&%tR6f6%{j~O3%(m{U)Sm>!VKbiqP1IO@_VMT!vlbBotTNu%GeIgOp8W|)+c+_;E#by4nhp0P}aET8!9 z`g3C66nW0}wQs|V)Ty2BG$v7(2Xc+8wqYp(ZE0(c1d3Dlt1689w{rX<&p%4YHUl*mhK$q#>HRXe5 zYYqKXsekCrx26VygBfGnhvt(v8%@%QH+mRqoVxIRj%w7>60Qx>A_8`fijk3aSp%#; zp>#*FE}v1xXtzdM;GNs%K4gg$j375rQkP)41j_Y_5 zcL)*X#Wfk?v{En-n6a7^^cd~1ee2XE$XV~1)a7tQHXpPo&Fdvt=vHtC-I>k(VtVk% z)rM|CspjD6$iE$}ikU3@B;s$1EdqfCJl{BEC74hd4}TpJCoButHP@0O{3IcA5LO#< zh;6R(&(?*l)SQjD!osvm=z)0@V>k4=60KpZVy@Lb!Da}jJ96xOy~zk% zT1Dd=T>6BG4gITl=m&@85<1tafaeKvm~aG?o`k)GY@J}ck~;qhP9D#zw+uWGjoiRKFANJ z$jUB-Q$*dRnDq3jflGOp!kTq zLCzxS9SUPPlN-h->)t{IUO&<_dj(#g5?=~s6I+-D}cl+TVdf0k1*tSt&}*ubjc5?qm0Stq+fE zE%|Yrf8Q+%hsnV7P|oJzM?KsQ8s}||4ChSPoPEJf>?1~rDBk%(suu?89*{Z!=3^ws=%ft6#Q-SSE4O-u?jy`jLYYdsHknOo(^ z&p!_O!lGcKZL6L4=IEYpJ2{BJohPW*zyQcY5ObgbR;Sk~HNe_|1cR{4Pz&XG?socK zbASy7IEB$7q^x(SIiU5-vm5u(eZUAt#KHR#l#zki4p<0}rB|`DpLR(SR?5`#K9QaY z55IW-6?N$qP973x5ws+;6Rbb8qiR;A5 zS}UFz@hszKB`#n^Z!`iZjTh)=J2@L?->iN5SL=LxW(B-n zHQaE*2X2BHp!ONu?!z{CczA#%3DjYa=WKO?l5ns_ffKF8j1Nv}lYaH5IPB;tpiGV7 zOgu_D0-F{Hb0o3=9qR(C;9T{uCoHYW6TXN=0C-o&%;b5F0|DT%K7qu_O|Zb=BHTWc z9R#$$iacXvY2uRq+JI7aFX3mwOjcRWbMPR-s5&uBQ0&KxJ7DShwVH@JBRnl27HE+K zDm$!RWb6oZ+^Ec_KtS9e6Q>xg;Zd9uhUhLjCFn2f7~Z3ayO>V?)CM z&{XrI1uWsQ>n1gL_2msm%`Aa(zzeuYP@Xf!~&cPnI ztzG$j3a)xg{4lr*bJ9B5O2V7gfM>FW9EghCV}6n$V|;kNcFFnop~s01!A&70>6@oS zzLjCb9ST{&H#D*4@@!wB@fu2@>Z;PvnP?zTENu@s;h13f9BN|vImzwD@Py| zmdlmsmrm`ESs)7nHQ*p6^dCB9Lo*;zpUa|&<$u3x<{*jHB?S6$C!mW0WG+xQ$rcBR z-6o3(yrsWG34eOf2^d84lo|RAL5rFmJSXy}G=e~a@(H7Tu}%qzK2fKqnv4Crm6?r% zr~N&2$fM$RMqnzAeaIahnp8!xzKQG6_(!iYYC`*z+bsXL*lk!|0`BNUc|M`=!>bn$ zevh$>>^ZRPO+(9GK|dN;y?Ymk*nIci#TxqJ2YBbvq{mqP{mivv*Cv+lOW%;AHxAdR zH_)VQNIDd1pF+r-ZYJ?qQ)K}$W|W#-mWD5*-|rXXOK*4j-I!`iW{44W5c#yXD^SZa zzgR4cima89ka%=AfaYKpv?ytVV9S>uU!X-m94m)K~6Ig*VSG$Hf=vr%+A78_fxG|q2R_@Aj(9{g>p2hzXgN166Qu4BGm7GbLv|7lT$(hrPTGDUk!*}Aa*y3?X>XTvYcDPwOr)|iakQZIdLk$S_+ z6Qme?FiA`GBRjZv!h}Ja+gy6{T2|Tmbb8da{m!nTTH}b(F#kry*@)~CwwV?7eTVdN z;a8E(1IuJ;53cT!3W!aut(&S48FwG=DZxU=2(1V#`;5y9);3#<{jud6yzlPRj32wY z@yk2?6@{v#I_M5F%#Gao3OCJ{l(lzT+2&-+%*|(KKwxwD>RqQ8KaHkIwbPWc2f65b zr$3=T-{{D>T9IyQ@2>=XcQGXpheu$_;qDQ&b_%7xa)%wF=U{|>65qt5%b}LRR78i0 zg!U34pvd!RC8_e4aMMfW33)|v`;eoRvZf#?S`~2TZ|oj$O71NVNi~{KNBrzDR1ZN6vD~cM#nn|S zDY-A#YnYvDCdc&VX7FI8Tz$<%mod&VwRTxxEEUf6Tm{(3;nfJ@$sNp(Z?VH4NFDbS zp}f5%e@zSt23>%>Fq*yp{G<|hs)f)*xxil%r4`=9T&oEF`??d+OBWD*1Ij8;ffGv? z)YQr-waM2s4*}F4#4J*uj0Mn@*hT^O%}RGbex^H;rKBYA;Q&+x{5*#W1I0~(6><6H zv)@?YJk;&>WzskFe1y^YYlaEKlV_A0SQozRK@ME8X?=lE|3uD1iPS75eft= zAU;?Q?Je-dtQyP;a1r$iEoyCI7;RvC2V{ivro<5jyHR^6z-_F{l7lvA>!!Vghk&ui4Ks)& z+DE!(gAq&o;|54WwpyTupwW&spaFad4F|Fk{1wgzEM27J*oIUoVz!f>;2rHgbuMNx&8WYCZ8i3 zNK50Cef{}Kxmtd)~!#cC=`xiX{3RM z(z|@V_xEq|<$3K&_?{&lmvqIT4V8JfU}9XPD?_HiwGp7-V$rDqR(&Gie*$|8_<-Vi z)Xmy}eq=15BLW()=hL&l&kReh@E#KrbJp<-jgY+a;qmdN*weXKeODJoDXEu>tu1n@ zVwm1<;N^R!Og&dW@WJ>V9vyK-?}LS87{0U!eoRtYw-!x9#D6^-%R*X z%@8KT@rDYQ9V9MKE*k9(Out^yAmw^ZYf%k#sUQs1!%9nO#48yoF00m^u;kNW3|7S= zh=|?^6RNZ^TVf|wdcss34}-;|KEeGg?2NvLlt6zUYf@S2;E>w~=Ix|iRlclJ`9<)X zx9*TxK5gI+A#Vyy6*Q*yYOH%z@#&S~U<(FP3tpiOLog4?hULg*ir411@VBDhb9~gJ z%Xp%G*MuqAJCv1K^jYF{kiT`eHK9$hb*cB*@Q5U9%$t0jOU2%xkn*Z)I^2bwUNzVr z>7MqEyWpQPWq=9B7_+Dx??`=;ZFfegNM*)IV-@DYUi#TIV`br5hB2wzsO0j%p+U%s zpogpZ%f^L$1E< zDXxY1uO;HEMWjS@-}^n>ph>i#Q|YRgX&bu!<58DoR!uh$ZH??dp@Hv`Dn0Rj|HC*Y-{aBO*zMrkP z`|yVChH_ctAk_!f@8&mho`c{5l`gzP#sATC7En=r-`gL$8wu%3Yw6fA4=Sm&=6{ckW#7+2`4x=h?ihJf9(hiVXYd?r0xf zx;|Qiw?ZCerC4rm302sSBEeKXUF&}9bMi<547b@f%8@GGC+a_*kQny4FP=e#CutpM zLsEC@%X&F|!>ufrN$r2IxechmwPNIBz-Q?-V$jP#p9hlgukcQ!04Ppv`Ms<@W0vzL zI0d=Vw2-+BFplhvod`b#5%k#onHQqA_8HSdYFNK1G>W*f#^;e2gC<(e+8lS`o-Ln8 z_a(%YcqF@Pg9KZaA7Tv267RhsaHo=<78t$7VS^W!)e{WAa!AWLR>7>xHq7(l;}H-& zGWE8>A)bHUJe3LhJbm5g1pidn2h1>#^c~P#w8>Y9i}~I=IzluP3t4e0{Y5Ke-y1Mp z+K}7iD`Sl`g2Du`ew-&Z&Ral8c)&WIZt}ry+9&nE!SC{8WS|TcZ^VFkfeA-bUdN~NsIj4)$RhS$*gJ!!v^h31qwlgV=j+MsE;K(>) z8wCJmC}>ZF_m|A?uV2i+m&t|sP6q*9>DB&Q(g<}-ee4SKNkFPf;rW)mGROCl4vg01MPMKx#>WgYOskOB$)c(G1`fpzk2x%VsFgstCzM?GzFBd%sAE z9TTHSQjCa*TZoX|DOxT1%EMWQJx_I+SgcVI%2O{W)k4mBQyU0SM!M&f$Sb^!5*(t@f0lRg zkfQRbBhJvv1p>0uaRsi+i`GKIeqR=6aFZKsx-;w|yFSk8gVClitN0>T47bPM;xs^` z6uROEQPt)od=+*km0Oz%4wU~t7JwYB8J;|9!BL-; z@Y<;L6BeivKpTi8ZV;^T;D`IYAf+x>)Yq%z_4g=ZPM&6Un;5^&H~?eY@&iF267ath z7=JgwOV%_t!hBA{)&*8=BflGqPYEEH`kJ&3Xg+(rEYa^jI1b^bpv4#ddo?+avH(17~ZO$f@*dxNra8$H>A^2*=&2bNeNz^dIgOR3yI;(EAg$-k4XakZegfG9KwVkW zS@2jv%{P&4TNv8?xrJYi|8z5bZMxo;?x@!P3!Oj^6$&TLHiaH<(V+GCJd&FEyG-u+ z-D4eo1X^$HiCC^i<{9~WmLY4}IGXWUgp`Qw5LFvS(qGYNm}Y%U0~i$p$`;g{QicRX zZV~LUN8U8788uG>TSG1cBtvKE0Tmv$O1dY{W*etjs*>{%vv4ug`dGB@%ZFX$@Y4

    lkw3)9xU0!HTrpWcF59Gg*+%c)km4&JZiliRye2$25e(NMg*jJI_IdN<|CyU;_V~8a1QMqwG$^- z`-oD;5AJS}dosrA=vACAUYi^1W=$xUP!#qB3kMpg3J{|~N2F@4Tb9=XOqrmkUDSkR zbI1?yIgv+!OuYrz7%w!}^=&c!)G4;MiVIsOdA%;Si%8^TfnrsdOuvr2lBS8xn=53X zDLGmofyW+gSlH-Q)^=Wxan3hk?8wZ|yA5YDLZ7cU!R&>b%_^?I|T@h7#l&95~&Is{c|gRvu)j`J`+X@+?r zjqg(H4llR9OqRdiUFh+7_cgp&@y;edP4V}>Uu>=7U*_GEQ0?3t#n<0>2Th5NXM=XZ-GF_rfJ2&<3Gm97M zYxh<*~UbC#o18kKe3`^9ORaK@j$ys8Ib zdh;2P3Bg9jy76nXvmM@he-{dyv@EVq!M~c0HiGgFP4^?D_=C;%G`Fdly8|`Jy_@Gf zi0D?=mDNKgmf3z^4~#bZo#WpInJs_6paFaY&Z);aV&P|Rq0g65E1`b3YvR=AF5SLM zd9Ox?)3`nCuzmf13)!Kx2udNZ5l#)(?4ioWLAMa65d0nBcYCyg2E?5SACVXY9+g_L z9mC!_MY4?`r-w)@FzUVuEM}9zKsbQ+KsF}sLL>ZMZpKjf?>t<&p_d;swPR@cS)Hs1 z2GXeWPfGDL_-~jt3ed{8pLcG*EWn+RcX7K4N$Zb5qNSe3;brgJ`<7&kwVAtkXZS4? z3zDCixlZQpkhUjDntjvjw=IO%joB=Oi^Y~9iCKG7dnz#K?vA??(BbojhyLko0aI|T zPE|;z+;(a&xwcIxtfhqr8~e)X_~`9FFH*&lH(s=%e`zyS(vJU{EvOKiUN)UOQcC1| zD({Om7u?iwN@(?@vn&)5iX+Oy2ii1&RR^|Rb%a2I_?d>JcIf36Rw!sTtnWO5UJ%NS zEF&Z10ix}6NGjd>`riD?dpNLalU1tP;&|T?ty~%ebNQTZ4q|@E7np#5u14Jzf(e$Q zZs0c-5J6<2;Sx`^Xa*s^fMfjJXbA~G{6)C=Lm!lGe*+0n#a|1hVm#oRYhg-3v0H+Z zoz$38I~7ZXuTIu`Bd&)20pi1yJdsVLUtpUz@h0XdfhRMykF1`W zPoKWbV88q5)rh34eZ9{tzdJ}-_Z>!N4rXW6%#YHI@kK?C{@ARGr%5CVK7 zv0y^)DR=D==t%(s4;WAYmVQDIu>m%<0o?!1pMb^ef;cx!*xnqXGXT;;0P+I(+5g%y zn^aHfEA_yG^vO^zS_6)PEDfQS1LiH#f5p!avR{JG^o0E%v-dgH_F@n}PJ0du(IfOT z8e0EuaoG*|_7RBt^31k&cBgJ=JB1DK#;-oX2$22Rg_}?A?in-*;$_!~esfFx}( z*l9i&9t2&HdddU^9Z0k99e=0796|Aq47XFzpA#-u@{GSJbpG6+D(tE}V#`Ic1`A(4 zDFt)eVNf$H$OaTx(cHGxFXGuoc`SVrKbg3>Jp*b0=18$|w24j-SeWt3c7gt)aZy$_ z3f$iHuT2$R1Hj{9lEThMN@eT#yW%*B|#)Aq4kdd;j-G+3mg z?!K+FH6XC_8lGs>Rm0$)ZPTxQ*!w=j)63O#cH-Eu!^jjLFkv3FgFL_&5l@eH1j7ER z{U7$P=bAb~Ub`RtM^pRVZ&JCm-re800I@S<)E68l4yCa1&MXkbKw=-%5T8JN|7?2{ zrdj~x1)P*tZzFwuQ}^$X^c+Qa;&O6Sb7`+EdbBG$>pXMn(NNcnfA5(4k8`rJUknrggj-`!>wYc1n;tTiIYM?66=4`IUeWo-Z7jKAHPiyxa)!GQ#Dsf7x1)DAXVI59umJxVxxQOlHhHbwwb-21&n0wa>ng za9QWNq0xu~``#?&SK(RBh{PglDrF(x?c6$ z;5QReyybl&;= zTz!bsE#LO51)NI0Xh~VsWc@d!C-Y|pq4J){ovKz6?TNcZ6`E?aKKvgM3ik8JBU69K z_q)jBf*1kpTQ_NSGCRW?1|u{c2-+_N{IJkS^TXhRXr?>*fI951QcYwVjV~_^!YW=e zad6<;sHzH-d(7|?BH;$95z;&t3#rhRmP&|dwxD{ey;mlZFyFj_+G2W=R#6!56zPF6 z$dlJ!|4sL|k!9`S>25{%dlOo(4!45C%Y%eD1c8>PBR8!Enf_!OEFDTd;*rBf__jM~ zl)d7Hn@fpz)|>brT#bcjh`5WP!f6)@G$2%1kc}^SjVV zu@^K;ns993C>G=z8)Kc2h@|zpRd>4gjhZsH$9QA62YU9h2g8%bN|CgAZ9-Tt>L&&t z@aYz2hp-9XsK5Ei&Oq2%Mp$6)+?h{O;F5GIE0TOMFa6Z3R`JUzvh1*dW#=A4Tr(lh z)T}$K>T~HmD{G#68^d!*1wxATe)>?dTGc(1(EcsQ5<_mxY!^#Q_&$+VrJEbIeE{P= zx8(001x?py+Tt4%#G4bnp4UC_KUqx`$XP=YUjFGV_{yf7BGLbmeu{}s<{42v$>$(S zw!I-^uE07kf6iIDnwbYhN%+D|w597YCj zQe!~25)q~7LSGUi3JEq_1BZciZDaZQ91U9Y1fSLHLFu6qp1HJd6y2I;@^eEsYiiV zv!&1x@q7`KYf5iw(zOw46Oj-e)Qa>@>)}YXWUZ+h*%+w;gQr;3^qzyDPMr`ZMMB9? zKffDwqox&%jFjlt+I%GE7RJgD1)Cxi$Srgvq2zgr{4*9ZW4;mYiGi8{TBSAQZ>DX8 z&?2koEK%n68sqr_`L{2S^%;j;){Ku4D?gE*yL?U0A~U{QWJdPgAKXNqK~=k&)tcWB zc&rE*@_$cF{jpZzV%w6TaBZ(XFe`{vC%~(>Kz+Q{{~EJ(vT1rBE8Yq;i?02?;5~RQ zT8RP26)~~LK{X-%Jo9zn9(Bx+`F#YaY~F?IMSW{1Te0QmejWoTgH}0s^0jiK>hn{; z!ou3cAgUB&;3tURx!$cf=K;h4Z11KjzYaRqupE!Xsy~@>C3!Qc7NjtW69ig-8Ic)! zP$S<9EwEt+Y#?aR=dT_Yf<3BwxuhrEPWncm2pq+bl3Bvdhfkk~0A<*Atzb_#y3NyC z#1;ysQ36W^z+^48_b$8u8gT#9Cl_R|dNP;|J*QGi)d)A_7X2I9#C^9~d?P zF6t-mQaGJ%Tv{LiB1#~o(fwD1di_;kwx<~;Y%b$X29Xt5EYY&P+Oer2xRJ+TjF$#! z6-$adqJI2$opMbhR7wuW2~{ zTsXce6mkQ6&*I{u?0m#e*#X9j90-j(GxC}oLkD0;zDf1rx&q7xf^7{1=s@8~(jj<( zZ}rpG!GIwF-vhvQkc&vn(q9JIHqT`qUV)I;C1DwT# zrCGYGKsk^v#s_^8@R?y35vW=VfT0%@ZlJ~B_6NW!uq+hdnE{UivJUVF1E(-3h=N#W z`7EFg)0FH$;Q=9hq_aTK0x$)Mwd6%=m!GDJe6hOb)qBDsY@gq%4XfaUovT%9mwuBe z5+f|Dq+Tf$KZ=R+)YH?;Fy44)WCTOHK@t?g#Qud)Y1m$hYlh+{)=8JP`?Jw0eVH!Z zx)yLXjzM%;QXGNn$kH3=HsB%!I*_h`fn=k;RJmpkm^A2ie_Q<|l&pT;3g%^h69L(8 zTmv8q#wkyR8D^>n6fFQ-fDfJ$Fd|@NXh#6s=m{{7Ig%zR;|j!+^vnMKp{)H?3!E;H z6f}qNWw7r3&%drf!2pw2C!sSy?6D+OoF#;XGs?)WmMbYGB5pfp+%W>B2=xBaGcwj) zLG265B_t4zv;PEh-{tCqaiXPq>EM&bnjE@kJTuU`8_pK1SH;EnvU zSdN;4lr1gXi543|OBqSE!JUO_Ep+dg<$Go_oB5ckw5|E0zUZ)`G@E(LFx{s*;Zhq< zW5vx7&{jRisGn0F>y{k#LsU&*lMGA<*=8s0m3@?B+mx(JI87Z1*HvW7rSHq2Ul*lt z(E1mREyOrOLz)CqJBmrtOK2%{gwuxCnED%KAgb9_v!0)5P`3l#yT+uO-0QJv7dy&?MQwh=nry5I+5rub2aF{P8m6nK z;&3l^@`G}3Zd@{j@on9-?|TGUc(F$9-GGL`!#)yp;FUNeM43J;A%b_r@u0FK_ks0- zu*-nEjET8Ue0eTVTLIotR^lc6wQO=$fmM+0{WJI6xVMYVNUeXQ-^cbhe2KU#i@p(r zLq=#My@&i9BvxS&N@@6vJ^P(>w}2$7M;tvHYTIjQjLwzdW`%;xYa}6C>vQ)jCUHh!fKiN$rnYEzI z;z{*B&Wl`)46bjIC~lFv68~MDUjLl4ej#)G^vvy$)xrZqr21#fVFAsdAmUp^JLJwQ zv8Vj&vubl{OP-HeOt`b%o&q>lNQ;~GBXF{x$zP?`0j_goZgJv=wdUG&AWt%vWF#g! z=|_@+0Ju!mKN5hq6;=QBHc}(m^(fzHt|c&xhSDI49xnNtD*vE|ZT>T^UsKH$;b<~*CoUV=#eC|)*3j2NveiL__g05ezDr*ds=p_jZ6dqM5J6s9+0zQlwiMp-m zSsH+^GU^Qf8KnTAxMp{EkfSBiJvW6$_DaL{^9WoDoEK&pUNYs|Za5`PKINCHk3rmag)=wDBk`-Dq6MLW z-_U<9=YI$gEUu}*AKMkQp}VbMvpJjervwE8wu%E$bLL)p%aV z{^1D8-O(|=t7+}hHSL~kMv2SMHjfvH?U>8_fopk|>w0rsmOO+%6g04okS_St=X zJ?MWgv)tkPIx=jm3U9&G&W=4Yk6)>nE-C#?uvku-+Esh=%(>Gj23NJ(4u9j&0MmTohD&^?Y*1)B#*!y)>XWMSzC0+j)DF0c9p# zkpWQK-RtW#scC848H!van9WD@WR|HGY_GsbRlpa6{u=o6pN?|s5e*E>N9QrpL8KD^ zyasp;Kr;p`L(!7apm5e*752VB0c>*XTpa{*$Zpmxu(KD{X{;cH+;JY>l z<6yR+2PMd}^1R`SLhjHE#9}=Q_>SD{>^0yA0=f@?dpve?+#NRuV!}hFNP>X92^5IP z3{{nt-6TOkyllHWYHfD?i;s}QUuT{i}-lBrh@-Wd7$Z1Y@moSHQ?m6x|ibm4$ zfQiY;(}!b!DzLkN5m$ipojPg`=ls#veWM0?xZq>N7QAg)i=InW zb4iuY=CL(CD%6!T39{#bwdJ&zboIdzmy;C6vYD)y;)NtbFOS0mOel@%aVSdjBCX1W zOEw*@GOj!471zu^k7+Nl|*xobz{!x@1)}Yy`w-?K&lu%qQHh6U;+vAp6lV?jH zTFSi2yP#-q%_x*kF)LRt-0&tZc>MefFQCn1nE2n#x?ipP0hhxw3zf z|GxR)f7lI|de4`9;b{g<2)vW(%x!-~**q}W`^IV5M)aMY3=Ousc8>w09dh4fvJ=X} zWYA85hg8l?PXlC$Ihco;U}oz#@iv@a3V!gMNmuOsViWs{OWL{(Sz{qs}+t*MR-|SDEXF4N9k3+muMW`S?=mZOM*B?pVKgRFn;7{p@fmVg%7C= zhADSVE#g=@+=Isnd&X{xrN0O?75Z&}@IZ%9gRq})Aa8}c+g0dvm${_>$5YvdNYm$4 zrH@RJX#P4auJ_&IYdm*}>;Z~puC>duuKC+M7>>xJmY5LiG@?3u3$K3%J@5OSGez4V ziEgf7n1qH zOTT2u$ny3J4?WAJ%atI0&RY$S^|V_$1@PclMe+~or}NLY9*1Vo&l&=SD``iUTN1TY zhrbNffALP$T6WWxdU1tfX!TO_jODB?@}rT|i|YKu+1G+BkJ+Vyb$pvHsU<`Bui_L! z(3H@GH$4^QUJcB{L5Y&h{)lPcXC1!N&bFZ9Z09XR-o5Bv>^7ISI!UMNia9qYWf&4# zMG6%}pffizdQG8yZ9^KGn}GIdk2TR3JKM6tvj}4|X`_~-q1(SBrs(}rIfVb2QT5lo z#;i?K3aQu~QzCQ?>+E-HvhNOF5TT$s9(CG$tkLa**pVB zoCrB(c8_8JUjPcL)f7vR1h$2SZlTG;)tf2b*n|OPVv~}WMIS;xH3fcs1@0^Dqq@Ir z*Y58L^L)>6n?x6Tk7l_`3K5yUK)zHd3I)s%brGtX>Apn%ff&0Osp$6HT1jjPW$%Io zS2^DO|5yNy_eO)>ofizhy}S`pZV^?Qj@Ro|9L(I^$4c1kKAS{hmdKhYg{J4Q>8E(w z+l;hR7kAx0G$L5;Pu*UU!R?W&?yByQclC)R9XQ^bFt&7bAWp!K2#M=`WOvq}cIq^h zfD3_N>xI;h&2!>C?RpCIs97z|PzOlCvsx_cGZCtOL@Y*D9fr%N>iyCR^@FDmgHjr+ zXRq5%4O$DI7_uM*fK@8WpbZASpB^8W#=v$P@nlMW z6D(QaISGQ@)7FS)m|5OQ7k693NldH2Zj>O%>8ySULGj8^E@dMCuQMvs#s0+~9$Wn# z{#3%53bYaA(@tOvlN1Bi1-8x@%O!e7CMl|_X9F+qPMdlb6&2McK&5^;0_Tc@LtHnh zg?QY-YcT!@E6WF-Ph3$8qFZ(MAX?GLYbjT*2-H06VHXoBl0$5nKDX zTcLm#AlMFkf&9JF#s2}+pu1HI68XLC1ju1VE06nYr#?rS3ni}*1~J0p*-{l!aT)P+ zFp!&i(#2JXA{E6HW&i39hRlE>2#_nVDw;#1Qrk>0?E@$XK;cIQ(^g=v<%4&K)P(#eANp)tg6H^8e$O$|K_c@3VrP!~QW)2RHSBpy-k;b~_yhYBw<7BM7+0(|0*k za)nJ?;w@@ew>`lqg^PP|9fM#;Lqm%$qMwt1$8DGcd&DVyGdsJOU*CnrJ`1r$!hR}&NxP9491e0tU2GK8fd`dvp66+U(@<+?V)D}NW0Vw9%Q`22kLNoz z`-xv?b4y5W&v&8c_8-hBieJ2B^|5~QHhI{N{yHpK+5Blr+KmuFsZYd`xT_hfs3P2* zE+d`!YvgZ6Xe3cqv`O#u_N1OX`;Ed$^a%>PG7};$_8QTP;pi877E^v|Q%^#M!(6{5 zNz{&K`KxymO~gLZNvTvM!__X(@6U`%vW1Osdb6g|8C7eB|E{G?RzLmbzN~72b6jqk zLGSWT4Yxzn`C>4QxZ9vO`K>-;U2R)!u&SYMEz{9>oa6hZ1k~Gq8}}hLtY@ULLwP)- zDOPWd2)SB?RBkle94TwP)W&)a7;wk7`@at~X=^SPV4IV+aI)w*Y8&Y@k7$FO$g6BN zrlwqZ)?D-&{0zfdsnY&WU$}yUcK#n9@orKi+o_djYSOO zIM|Em)=622Q@_3K1dGfyf<3OBpDEYVVw3;$Shu)>?i1kR;#SU7Pc;ZFui+Xd2Z-WR?br$LQF|2TT3N zHLDK%==paew9#-K96dVamkfL_=Yxl04^;CLB9vHVRE%1qvfq{7C@moR9d<-d_%2P^ z>LQ@0>qcpG!s)4X;o~cQPUtC!#nVsUK;13t5~mBeFs?(?G9OY6_|?!rgk56{mDE!- z=Bh>Rjp!y3&xFshk9_sJIr!^52l%}tm5~Vpc^tqc>m45SK*L}*!_AxxGEC`+tc+&k z-tlSo_B==8MHGHf*C2n?u)vrHY4BEd%H2v0-@s`^hz7zpBJ7SeQOfG>SGcF!`^ANdw zTXl8&>bn!p#8?()@)=ar&iE&8Y-QY1KC~Y(B*XF7P-Bs5Nz@GXOzuJ+LQ*IpmC`j*78Dt;iepha4bTe~A?76$0 zoh3#r9QSxO`R(2v+gd-DdX$fdXwUi^k?Om$wSN_HkHfeFlM3sdUjuK}W|pGE@6Mg7 z+W!nzL3|1CPO&(#Wz@3Z=H-nWmXnLf|)?R(!CJapf!~D(q zda11RUUo6dYC;LVguX{Tw3uh~w!nRa8pU*;c@!t7d>J264H;AYc6-;AW0Yw{A>Xv6 z&0Jf3fccy`z>9DY=uSXL0Grl?5@yh^7`+E=yPBq^!LC#=fm5==6qdu$8-_!w>Iu3G z+=p=36(_KWe&9*>KY!)l%fp#53WB7E*3pEMEJ$InPZ$oB^q9NF6{xvkA^Wy_F_8Cl z*&sR|EXCZwLb~8%01U#$T;lbMTla~A;*~EEB*BltAaTUKOhpFFqXcO0Xd0)Pl@-j4 z4FCBwHro1;uT!WzO(XJ6^APWPr1JJdw05;I-0*A`u@|>Hxva)g=*q?wlHCp5Gc(q|Jbda<}flNqh2G&@FVnX15($jfoa|(w0AS23Aym`p_ zcLS1mPfrJ_diAY79fR5hHjCf^%--r3C*pBuaa({z%j|psC@P5=Fu6dA2|@S_{@>)k zu8}}h0aHdvU_PwJKXH$!{ues_&;ByWhhf7Lq`Kk4{RppA5Q+>sliP`v>nP)}#!NVq zxYD;lZXW(ujw36=9PnLTEG?sG#H%ei}>RY!%ME`ph9N@@m**o}j0vAK506XONp&>ZMc*_i*69N$EOYEK08e63;$zU97}ZH* zDQeL_(18#Y@xD|KQ7jzG)o-x>J#xnQftb)@fRdAANf~iW6i*%H4H2Avzc_(L&BoB%MGTTtyMx!zr1Q!!O=+5o?d-@`e7384x zkhd7O#%WPgaH>SllZa|5;@ND=^lKL};HcNWL0V~CwgHu>Vmn?z_3afAoHJZ@>$Mabh3~}O;f~yw9lMdg zihudyRR^0-=&j*B41^9F@zDS>K@3 z=u00-q&+@}vKB9^SE`$`F9#$qhvt^~Kjm%&cRk4M=U2CkhCj+$VNJW!G2YDx`y8v{KhM~uHO7IEU=(7OX?bc}tPDhJKSxr~F1v?}xjx}n_a-zS;_7zkqZAo`qu6(o zPtNo%sgQ1fJI#iJ4rDn}iT7KmrsT9h;AQz-`8(3q*u5(GDD}wp0;`@e9uoPjcntMl zPFgiasN&W?s*y@9P3wN3`&xm{tHo8#ztgH~BBegGI_KkH;7{-|X2d!g%`Ao6sIkSp z5!Xy`PHI)pD7A5Qt!bnuolyTZftWU{>gV!Dtmyr(()I5HASAPR3nOr&%e+r9rE3t~ zj;%R_Aqc{D=gSIwW6m)+=*?BxPIT%T*Zy71X=f%spb^DLPAozMH70XFC{AN8(pS{^ z65M=V_$1E(cI2!OVU5hx*-woE4sCQ9nXd+hO|VdXsl6!0vhiA&@VUjXOnzj$-~S9b z4|W!myrpm88<0p~fM4r28;K$P20~5YZv=@{OBr(rd!80TiU!4p<)q8e4Q@M96>PYU zTApn_*$}_pC(Ye(=$T)rtFB{pPd+nAobYEV0#Vqw@&1AoJZ2QEyyE8_2 zL#~3~t5UmcK+p9K$vEbghgm(93JL2~ULh4ep*^w&?WnfPm$!S+1z)`0{rlu0oiJ}L zNcwdK@`Gc~?V~C+^35>X{O+RYKW_Q+ct>4b!U0o9{+`QAY<>>T{HCRW+0tj^6qwvO zi_f2Y&Wbmfr+0VgJH(l{cX0FkdGZR+U0ez6$Khi?+naE|t)G6A`_oC3#Kivzk-dSgQnqxy4%l*F0$p((Ms^3B5)TB1?)mH$l1 zEm%T8fF_U*Kqnn2)3CcK$Vj)W2YIe-r$U?o-NsOm7$M;p2=rX->rbu>#Tu{{0Zjt=XZ){)g>aIDibfbj+HSNf@ZoI>@a1f6 zAp#ZIGk4N92D3Blh=L* zqivYRft@pH9%Me`V=WaOU3l5z!=aYEYMis>!F4=v0=wy7#p>ly5@l4^w}lEf*_KTS!S?J25uHT<^RQ;+%Ux<7Uh2en}0Qd z$RzWyjiNU7$G?IZ`}C5q-N45hQoR}{{` zgaXtMa>k5rNp3PFuOnJw%oDcMGD#0zg=|Mu;jzsHf%^!+Mc1AgaEd$)hV+BL-U;Jv zAOGe(GMlb{0R)TTmgmI9>l|h9u=EUh9>WxhT0}}JDqaQUMK!8a%)lQUiCS^Gp#TX1 zhY#K#^eu=&XqswjAZD1Ld`thZ2PW|Ce+1+90>~`5Oj}nhIhWl(qtTLMoq2%a$oB^4|(_J27cun-XhuzL@ldkzb&^M=`Ve|`j56KMA&DCa7d z+6vWyRQ_Sj846f#Pd0t)`Ig}bn&6Bcj0^$)9ocM){~cVN2M3toD}*_iFp+JmlA%l6 zkF5ah88+wPm1gJQ0F?DPc4Lz(IFM<9PGC2iot@3-Q1Oa4&z#A>O)s_KoC)Ilt(L=7 zd;*e_&43OCc(2*NYhWy*#cU-=>(jRZ>2ob z-3MkY@bIz^>Se-C2S{k}YL5k{mtGDumge;`ODfLg!dAfSa#G0Xfg4yXwwtp{nBz!4 zWSaW=QVfs)PggHVugSYgBG8?Sql17h5*G3gVEutPp}^@7rlNIe2NyEeK6iByI=lWSqkQICK33>yDQhhZ^P`>QP+s z>G7J6*<+b0KhUy}qN|5}@-g$qT9kbj5?8ZbxB^HO%|Bk^IJq>_{=(NTAiXa$8Y@c_+u_1W5ij=qCSPALcQ+6-1keF zQu4to-iIiN6aK-@F-=SAA7vSeLK{Rv@R+2lLT7)X@7BE%+f4QVG_>tu$7kZ zaR?;K8!Y+?>F;345$X(8tK^MYMYiR;9z!LQwYf;Yq-OB z@bDj{2e!wf(KDR0>?s{h*NB$`^)wb4PL98)*gQKy-X15ep4F6V5-`X(CaZ9ub}fBf z=Fj?hcPG|F&CZj+sJP~gQf)OD($Wt>{Nj+TFQLu(_O-C1Br`fr?H5k|&zhPV-HVQI zP7#gy92qWnwvJ|O-sh#}ai3ku+SH1BGv0{-&Gn3ZJIxViN}`C`yV)5#QDAN? z&Ji>fyzKcehvAZuf0`EZ$AHssStlaRzqAQkm*l^tYjUBom}nOih;l}#7GliQM}EdvJ)pww*cDb6CjQr`e%t-lwe3%T z-6P?4V}W-#uZ`AR{b$9`Ue+$M5x(v5*JE*py2LCXdg1=q|DV5s=J)F4R{vwlM;MxR z`{qIT;c3bDSq?r5uDk8&%Eq0o=`;MocrWn`?V~}&kUClPAgQl4s3Dl>=*Va#0{uL( zwE+Yby{3>L7bZ;AZakJt)E0`~-nw|2fKW0<3>&p_YuB`_W>-%HkPG(q>+FCdU(dtc zmE+x|FZlru*M+$hI&<>)`a+?#ePypt>a+3?Kp8>#WeJRH6E;VFQvUYwCiuFq6wUZ{ zxx=$6*vp{KkVoT(!QoHm%MlAtlW0+b z0o_SuqV$1IpNXc{r}gkT^cu9pqCn-QkeC?k=i}%gZ2okZG0xHBk8XEP#{{l;1Z@YW z>YzS`QPzts}kKF$C=--{m4`yOE{t2QNd8;7~@a_)LZ@j=gu!Q}?W?mOwqE?@N z6yQv4Ni2*BG7910QMZ882juNXD$XRlGcYipwYJdk*!t~rt^{V}fhaEt=KfRJB=_@d zb7chb-cbOwz6HD|Fx})w2~UDPO$?ag(v<|NsQ|$dvO~SpH_R{VPsJwHN*O=V@F)Qs zwND%uJ`49G=xB7zNH0~2x>$IUu7(s>kxl*ySUEr`unk)e1f^pYZ4>CA*a7(A7jn#2 ze$iv433T;dU?IBx)%oy?X_W^Hopn;4*<6okn{o0S6;ra}ohA-_7SAM)az+Q@tX!AO z;yqJJ#LSDDm^mSMB)n@Gqg~HfFye;P7_XRdRDHr_aoIp`hshpZ4Wxw7jq)H9gMq#+ zC7Qz@Dl?GwJ*z-$+28)v+sf6RdaFqi`Zuvlf5u;}_Lb)OMbgWu5=xn?CoBUo9?%6% z5r}9aKm!1}1ti@<5q_kM3iy(7c@v_8_L$`GL1`B~XqNiqY3o(T0Zb-Y3A6fUo}Q$j zw*pq(F;wY44&}RLmBU5kjb?g-<7V5fLm)xrvr+ZrKZ_d!9yK|^7FiUv+oJt4!x0_{ zTe&)w_-LQozon4C*cZr*i4LZo^s`xsq$fZHA*cF_MIB9-j3WdL+2Bnl2F-aQ6pxfk zXJzMEi%&qs0UT1x?cT(Y=0|2_)A74q|3@pItJc;2`Hst%_xqiXHkyw-Hd`QG%Sr5CI!t^z5^Q1_4Q^PsQgam z-Z_AeEOV;BIKGoQDz{#aWj!HY$Fv#$5GS4{o{j<9SIDMmgWRO06*xTG@=zmFhE`xY z6TR6Y0AYCG;)IP@?8fmsL9moZ%r=Oh(2!pTLQYUO1fVj)9NdlhxOA5Qd6vONMv#7V3{O-6pqwC^i*UsEh5$yHWD$GV-*4-ta*B?jN6my`; zV6dN-B>qeD3_;bo)Zq~;wrNr0+{`Ff@c&ldYP-?0t>muTPu6!tzA*AfDBE|rCvUdy zwB&mEMVw&PPIU+0*?qOc(%B~azTgERKViSbe%trhd&$<}Z%j?Ck-w~^l|$IhHw<;F zF-$@pgow1fWR_+4jPIkQPZhg)(Ice%Ww?vQSwnSEh2*l zIRgjSRXJKKj;F$;IxinISg+rDQfIa*3+MM{6tg?r2J?jRm5azjP^$#>xwL6IJl!Vx zYwo|F3C(}By2YR4CaFsxD^?q8vuA#OHJEsGIT@Zg=0N^&Mn=|Hc86U!90|2^z+ZVz zj-Ps~D-|9Utx2M$BGZ>rYg193lSED4Y#sxCvWTqTp-??#CVt&V0V5?c(WrLAuslFk zO}@57$mw=|pxQvyZ{`<$BMZ9Hqp5JIGw#Wl{`5B@E7SqfZ}l zleq)lwy#OY%Z7CQL+KTg@gxX(&R-L$XLXxc$?M?~uSzsPzdRUSkAT6NUTm2@oSu_3 z7ZP}*sIwjLp`TP!p^?nP^;h1XpvHktB{^ZE)Oy=S>Z zuCPKl<$<+^=ySUn-aS$S5^6-4{V$d0`M%cYU}4LU(FH&lY^xgg;e zt}>Ir=jdBpLu>i3G$7{7=_R>i24(2<`ZV0g<;ePn==>bjru%zZe617*M^tOwy?4#- zPn5_(wY;QO&yvFmTI!|KnZ3A(8mL-B)Wq!aT?4f1Lo3HAfBWqUrFun?#N0Kz+;P~i zdIh(yz)A0->u=kOTA~Z!M!_Y&*D*t`?faQQHCTaE!E9^?_lJ281D))h;j)hn!n{Kj zt(**aFEr7IE#_G4?3-3T8r>YKw=ML3+RV4MK7NNrKSi2$EOqUmT%Tqahr$o|8n@;G`~a)WDc?7%x(+|*Yc@88QpypW<6v@72RQFGcmnh*anU$#g z+r^o49XDrDhP%QnoID(qg+*pZkLK_tQzXzhKfFZUwL-|oF=yLuq`D~Hn`4;~?09ee zP@HRa+LTwVQ3>^GjMZ-pFhxH&%roWr^qAUIt|V7u_xJWZ&8v8sGP!{e@x_mOo2!vn zsOP^*%G&20pNIus)*pQdfOJq>(l|GCD?yOq+W~-Q-J1Zh1X90gC-Be2Ch0a6k;O=J zYH|RVgVKc(1A(or?HG|9Gmylk{lNCmWs?jOSwK{D07P2=)f*PEus>gI2Ewz-QhC*Lc^sf_yBq(5aVCp{#BXV35tn@}wz;6Fcc=vlEhmr=kyE(LH_<2^rCKt#u z8v@{fK-eqbBnB*uball6?FgC~tt--i86X8)Znh|hBf z1SH@UB;8LXcYy`h@A4rSCI;}0i(c6QxN2YPG4#?lY>n8Mlt=-4sy#H+`)GMMa5Az2#o~`31VcdP6&Q>H4y^&>zW^ELv-HyMgT;aVBdy1 z3CDi}XcOR^V3g6DbPi{#LcdEN(K)7KWZ;c<0v(DF%*JzADN(D(A*sW1Yo80WHQ@C> zM1+}Pplx`ih7aZ*u$(~miNRLFefll+`M9BWm3EO}xr!Rh{x!KN6aTBUvZo}u9Wet7 zp-4n^DVa`)r9nw82Y_C|dN9!7JZGz7`N}#ceG_xtjqV=_n1h&}?`!Khl;5SNrNLyP z=b?bF0mX-Az&QrADDCTj(fY4;0}v)ag9N|^puuo1vHlk8!N-`m47;6fJ46V9^9e~v zAX_QzSY+yk0(ynp+6i)hL2Qi0yFF&pe1zT`dZE#Ca&Uu<8^3l2iw4qsd0(!9kqKyn zK@6+j5x}TGLNZvK@u{o{OL|vWCBoQ&75F?pG_XnK?Z8yKfT?Q@tgfl)K}zwL$u;x- zG*IVMGPqET=b1ZLsW1PLnt-iS{v)jtp7@heMpF9rfb~b}Hx?OA=5CjYiPH%+yr;^t zQw_{rieh8Zoh4rN>bK5Ws5=5V<&|$!Ue=}#De9l=bwJ^#$V)k7B2TRN+1QD>q3_;i z(aTNam)Bf{?MpPiqTPFeZjloCMdeAKoP^@M|MlzPLsiV|5}G`0EB={D^5GGJ7XM*; zu^B@>zwI-z8qo*${+;64(vTA6`t=)rR1AM%8%~C!=)Rcy%x5tqfMR5k6Gu8{ptPma!F-u ze+W<;uQpHcwQugz&N9m|qA!sRzTihIB;B@ZEisBu&$F$VLO}hf+FVvi zgOMtwq1$?CB2M4kCB2fAFHnV-O7+PBe_m~znn-sU_mZ=rRi3ephb}j=^v2EH58o;( zd+fEHG<~x0SBpUo`h`_Kar9Wm4V^!K>>!U`)I<8?@WDg$e`iAHEQ!aWM!)hRSg&3E z4qZr-T+=LZ`e?vGF7K!Eyp^|1GR&5Yu&e~t^LDcK(dnRDgIJ@0xs+Kkc-IZ8p~#i1 ztctG@m^Qz0Fg{J>$3KKWhc9NBpN24zLL`59o~AUwuhH7HL3+(Fr~l?OEr{i)6a&LM zz-P-dpD5?b&CZSc>KW7l86VNUE}ESwz(K0p!p?9tzvn=250RV-gmAwi*TjcX3a=~6 zAK4`$Z(CURa9pDA#Z@>F;u+>+8a; z^Xa5S4lEPgGnK)YV!3SY*4y$&Qv~MaZIS>z2Kqq!&M?F%0S2Ys>| zJu~N}^B$T$6a-1uLw#Q%jOTtH#>dX!rLLqOQ&NOJB8np?o=0}(wYB&$CKsRbwuMtb zh%oXRH&_IVzb3?Cl?R%seqx@o6&OL}RcMUgn3Lswe>jKop6)2!-RO7MHs^9z)Wf09 z6eiJrAp4^IhLx>0JU>uPq9YdJe^n?Z_`!S_K))$bfD~OPhmL50i;=W}LXbln3a1+W zDjrILflEwZ`_&IENCwV$FM&JgQ**}q&`LBmcRq(z{eCim_P>q1cH-R$@ACaV__k23 z8wbXo%E2)r+99F|;eHWah?Af-_u&a`A_*c_(Bfhb>L=B-L2Vz?((kH^Z3(o6Pp|gi zCcXrngg~3|kJz_^4g;A*F-fW%UlnPN4ApJ@y(d4jvF=pgd>k@}So(slX@izt?RI)J z&#`$s@xt6YI5OdQV=^~VP&fxlc=Q_Y$8bx&)br%50thc48NcN1_!ld(nL=d|u)X|44Gg^UD;chFDB`cwm zew>||@yi?J8zcIB7t;&$G=l)M1rnOzCPc;=8USSjUa$7Va(lOuwl}ro=AluUy9V6#{c>^pQxs z3`wcyz4(yIGka5SWp>iPsnY>MJ0k{96io7%-^4#Y=&PSwBx$eca|EQiCUVZ<@U}Ol z%_l*w9iO4}Jdtlb_^lk|82#M;m+8)8J| z{e!QW89Z!*shNi*Yknv+-p&F-2npM`DY3hQbcM|(_{Xup8%|h2H^2~jWF8S7nR#`( zJnHC#9^8dX@E`A|p2)@TH?U4QpUyaYKJrlMC7!W+{_+C+vI4YcqhJTKGa`B3jFQ zF0)!P!c#Bk{gxT8HBso9vkHXsh;qWBi99EwsABt!TNb8Xo9QfFUxq?1Dd(U}%R%$} zLG|N+w^|Bev*kHH8jc$dHK}8_h|OZq27XJAz6k0z;)-mdmzElieVLUhJKhz(O8H28 zsgAxrzDB62&CPtRHiyrWdVao!f4vQJBe2ruG? z{=$s68Bi`Hu5e$6*bsL7SU9#jxMAju{##p5M&lrL^G97@Y9_cB8*s)a5dA5!v};?X zd4*0XV_sG-O}fIl0S^Suz2t;clk#{4GRP-WJ;*n+obx=yDxAOUO6u=((}F6@CFkJ` z-GBF1|AJQuX%mG`2&;Zj4k>?yRO@4GRA?q)K4Sa5T~T z+}3^Up3#Kq_Wqfo8rR=SV?58O?&tWB_d|>)D1xsU-4^WAVPxV+>k-ENzxi1 z%(%xlwx2&Ny9y{H&C!p@T6(d$&Cg2GQtImDrx5an>h>%`JThKLxc(c_e z>sd1K@*b1EGZk%!rS4NpqMf{aw{B!@lij~4o_yYIE`{r3CQ%EigLEOFx2MRNr zd-`eML(7w|GF*?((bLU*;85U0%@diUKB-xf#nH$L@Yhx8e2*x#y+hwlopMjIbn|&k z-MpUg{L#V@$+OtmB9gWk>JB%u!#eTX(2WEttyR3pt@>%E@P2HjchZ;tR$kIekH8Fh3$2E^%sq z8AdHh?2lUhV0A)kw48+7uNCl>l@cy zTh=svF&+I%xJj2^LqD?bovIh!i%R1V#^Gy(-UPU1Xl+r@ib6!PNO-fdIK4FSn{&%G zaTC$wHKOl-B6@i5y_DA~p$Jbg!g=CnEuz8aW2fCV!hFc5j_ph%~?a=vM4SlnFBnMR)-4r|iR`=~WDbG-S-1aGlYjVdU{13NZ+Ol7CA_E1O?)=>3{VOo}TH!=D^emcvxLMJ(KV0ZUDeO;2hL+`LVr|%%lPcOR#UA0C@BM z==hNX9AQC(As~@Y7OnCDwh4OgxTK=Zqmp860bdJC%&KQIyG#d+C!bO##Rp;!z#N0~ zDKD88D}iP5+js9`7KT>+uM8@ys+@BMDJ94G>$@3T6Wjoq$ve&uZuCW6$VeLSE`YN% zU2_g#k-?!cbw7Pivz{{PH~9H%lWb694h(kJKN1241Hg#|5WRN8F~p`I#=5l|Za#C2 z&9vU{qkD{Q$k+e*G%crS80r2~P7W?hpE)PxsJ?7kvNvqBZF)PtEIrN-q=Tsn4BrH{ zbed=O_H5{1g0%oAOxXJYn!b7Grnf_>&vgK3ERe3IR6hnNWS&s$F7YWGv)Rr71&6%M z?*D9=0H^Jh;Hdx_%_|{c9dO_q1Lq;#?s5Z`z`+zPkHHJNyGIZ=0f=(CW?Iu9Z-KvZ zFXWGYnwgndsKuAJRXlV#=E2F%A5jgUAJx3SR#jI6l>_Y<4+#32w9sSgNv22r{N|tL zBvYzXTJpk3*Ea#vNaM;LYYg3E-Q_=mVnS4~ zzJ8pGD=F%gFF_i2aU@u*f+kDRRuI@p?@UJGod@DfZk`p=n}&Y0C=uE6o@7%GO6J^y z2a5ns>EP>lMT!NU|p?Y~O2aW3} zerY9@_3|ek>@h81JoeysN#`^|!se|=J(p~68fTLqH|KN#p&}yHxcdZ6WItu9w51vr zr2!HEie>ASKWi+vxg!6M9KXJpQE@)sR$?w`Wdk690t;nmxl-N^Jvt57OMc+84ayh= zXwRVXYl~fgTU-Xsi1HmlqKKEk9SagZNaVolZ%xpkLJSgrm=Pah%J&OtSqsSSYm)!C z4q~~$J>uAX!#Mu{@Du>RfFTN&e=4x*1rIra@j2lC0U#mWusC>k+(R{?0+|o&Sm78O z73e;FmWOB1<@4_a@1oAE&?V#OdjjGS=s@aAMCUXL} zFM@Dkoi9BYYpOL>#-3)e2fCSVj`f^3xhv`unatw`2JT@zy9zD_) ztJzig_u_qX!))fWrEa;UYA4x-J7tNPI({v5$u;#}HUQ^&y7BGVxKZ>aHSyG=7ABGIr0E>{ zsPcAvhFTo)$e%t8GvQndmh(#UjZDFP9{9za`(1S*M2#%-UG=0j=P?Uu$ZD#f|YvUt+*qx;qn$2v?P`($kWHx)ECFh`|%I99S!wr55m5c1< zLdb~T%MaFfJxfT})n*r9;zdX`yxf(JX~MbX4m+iRFWW9`%u6mo&reTh6f{y7v$$m2 zNtSRrL%DhO3ci<2rW#!A~-^?g-9sAzBw(LNH>?c(jsK^ieCZMC(tv86VwT zJz7JKR?_FxUfu0AS8JX7#Vw)DcDbZI1QzbJa!3W*FN1px3$cb1tR%%G!#Dv=O)q>* zhv5(=ZmS_)AF%;dLbw|!7e^RYLAxB2nq!I&gU{>R^q+|)H|f2vY%#jg zAdyCcZ7;A}9E5-Z3B(8kjoPUfZIC%97BpEAJIOC;*+1MspQz;V+6Mb$x(Bb+znlRs zY=*yakV-DqzQ6SFeAe;i47<>hbpy}_FCEThS%CiscPM_*Y3kb>0)rcJ-RDhRH z>)%5NpQ?f*e{L21>_-KZ(2Up@(+oL-5T1S)|DQ}jL(cE%pZsY)=*00z*MF_3HXGh0 z)V2r=xfL3Jn1z4ISJ3%M;>|Xj==uQs2-^opMyXiwv--|n^_mb{#|x*2IIZGTmOK&v z*nIyBNWu}3;32%_o^IqQxegoC`P<8}jc;rMPu{tArI7c`JdlYNN!L&bOC$UlthgnY z*7Uh?I_j>m7Z9G_3NEZdX;Dg7EdBK>nRcW3g438wcB6Ccd%+1|gUn)5JtXpj{NKCD zQW>-|Ult`h8iH&nv+24AqMqC!=Xg*oOV6^ z>gr`F=EUS%6ZN@3iIbJ8C2mE!ky-QyzxIK|TL_b9%MI8LGixmxoV@eQL?}1c*NqwN zfcPFb5*vI$G!y9JI7K>sd=x`ZVH*Puv2+=pXz*_)|Fud@zV0#{0sqH42h*kpEurWr zZ0yc_hUAnB@({Ijbx~}cgX8lV9dF2B7F}kv`D(H6=2J&g2D`f{|->~0pd{Q&+uj#08<5mE$}tF5TUnV3TVV8CX`?T zM*s!@(E@PxWoN&JCWGmTpFpol8x{@)I_C30BQrM=OwT_P2CMV{o&Yhi?RM_rb)d`y z=Enh?M107H!d?Iv0GFzuG89j3b^qV3Vh{LEfX9PGC-ZeZupv)zfPNGev74~9x;axm zQjlo@WNkpax8d~lpVHSIJ|&Z?EstD9Mp!bZ8ovIO`s4QKA$ZVOZlJfznFOV3peh(# z67UwXaTtK5Q?$F(=d)N3kW7F$g-7#m;EF&FJ+dvXL4K9{x;c-@ihP08^e6zl&)G9k zlj(z-2*FNm$CEP6`XR(3#vJzg!7vJ}jBMyU%1|UlU|9K%23fmXy#lKVGdI9!m4(&S zVes5NYdeUpRWHEeff)lhHh}AL*u^Ba59lNt=R`bIMe)9asR$0x8z5F8X>{JZQXMq! zF{2$E9B|2{?!6J7&M$7Tpn4ujqci6{oFSLL-0uF|N7*vkBJX*sLJASkjwb#3qec8n zP9<5a(4(jwC;9juPF_Hg8RiuH7Yh4KB1ChKx3czg`{P7qZZ#1*gfc_w{QLyt3U z1c}v5uREqNgT$5D-!zpz(1wf$i{tLhNid8X31q17WZnVE;5x|vf`yy{q2H?SvFQCD zCUKC|6T~2o#6b)1x&=p+C>d@jcB^rN72?egPTc}#Osc0&z9IR} zFL|2+zIoAR4nh`j`kkZPo>DsZU0%6k?F6C(M+`lh*94yz21`Bj_BpQqHgR4F9du{! zgx?PlS{wQ}TN%2iu4?fT^+`4B(Z4QH@?yaKKrEc{;rHj4tD3o^RwrykYBG=footg9 zb3DCh;xX6hO^tfb?<x*69Sz3!U`V*brP^Uc;j;fZ*^@ZEODCgv7B zT2hjQe56VC6*rlu8aD%nI0n?aaLiPVEk4lUEuFxH6hKB6vCnW@INTu|7?tX^=FKvC z2+2$cc&@i=P(Mr(!mUPLbq$63Wn}9EYAzx#478wnV@BOw-JM7UHR>Q$NOQQa*t>Zq zsRw3EWJ5XaPlpQqlnc&fvBA0VBoSr)aUpet-y8dqsV^MrjO}IY-wN(wU7wAyYLaHz zXx}W`^pbAbdG|ILvizX8kQt6Co0{KfC<^zp($-1j8irI%Lm1#JICGEADXttQ^P)bb zT!xQraq8;E&k6d45YpO%Yo^OKbEc2oLzL(3%0B1W%(wlEt7hFsy8->rxWu1eQCY~S zdiLlA20u3 z3$R|c`^)_pI{3S{6u&Dz7V-wlMw}f?U~OyqjCa{F?uDFPUqNw3?l>(?8aJ_}5HJ2` zZsu5Cf6MDt>eB*sQ`UwG>{InTW==vvQti81O>u_BIDW@(E7xr+ZyQ@Oq@)jMP4C_N z*ncY%juGp&r1hG9lT^D&i3oqSP=@}4g_}stF!JM^uiE^EgeHDKu>ZH@oO#STj!yyB zvAHCyhJQGIC1zjwpZtVmk9&Ul+x*9IXLf@Vsk`W=sL8aNdHbug#M45=v7beB`8X5> zBk@=JO}I81+GJ%(-M6c2gt_+BJ)dTH&CEgLoOteu;RP1PvfctT<1n03Vv`UWv{*Pt zQkPiNlw9f-i7W^@I)Q#id&vGV8|aVTTsIDi^t?Pd380FMB&74YEX3#fm3iiRYxq)@ z;n1yIa^s?0t2U$87+OTWpU#6c;X#mI&40S;cvai{qt~2oZ~z&(^?Xr-{18hmmcW=t z_sb_unmzTqK|H~SgJDK$F7>y9mkrX^#d^V$>I9D64dATN7UnYm0yCxjE_cnAZ_T3` z#Ecmsl_5R)?#`c z1-ca}{eISEQ><{#b?ozUy*T}uiJ{2$WYnJ>BeAD{L+3%6-Vf=kY78vBj6u$%?oMyl zodN-wsKG}{(mv+ycExjWpvXlb#2XWxwpDs8wf?078Okho+a1f+daI)<*BH@+2S@_Y zS=NLIu?gEa!Qa`T%jgf$W#3V;?v`8BaOf&Q;CrGqFvd?_Q;wPr=w3zJVDPPqy_(-G z9&f$>aaA4PP0)kk{ZRk1|Zy2?m0BV38;tDLoks(nL~|2Yr=RzuxD40W$YES#p6U z;1-Yp5l~JmPJ+@cOI_GOa=j72YoTlFJ<~P6KY=*opQH@6H~)nTQTNz9y$&zkGG78- zwBJi>kNg3T=lQ&e#=^O0#$d;9l2lk&I4jAKr|va|{M=h4clBHkVG5W* z55Nhq8n2%=FwWuM{=73VBEqz9U|s<`WYRqVSAek15)rH`IcLf9B~Wt#YncVI{Fz-? z=HYrfRxE@sr2yqO&Te{9&yP>%M z`&t|rP)0x|!v0%@{5{R)DbOg=;3O}x3osSHiiirUOr__}{=_$Ie)!V5wY9aAg;iRg zMA_+g!vm}01xpXKgMfzzFAd1|fpiW`VITvlA%GGylGj?53{d5ppzZCv8~823g`KOK z)d9N37W7fn-5ro?iuVLGzjbYG(eGLuKqLXcD%K}+Uji(n4_GSzDwd)SiysI19mJZy zKm|*)3Mi1>%x_DCM$F7WN#}0w1gNqJ?i~MgCA{#P3=qtkQauik{f#~ z>EAy`N={u16&yo!)>2?n&Mq391HdPTkXq^~Z=mv{O2r>R@1^T}IBGdTrYn7{EQ zS?)XikTXi&^)?h9O5SX3>o&HMHz{>mTMps9JJZ^T%e*(9Y~Zm|Fnm6q4FAD)b+`lF z6vC_};ry2M*K#DY>&QIqlaavRd58iSei^mrgj`m!FXDg7q62RZjwWgoXrE7hS`WP@*Bc1MI zKERncwuSOh#W`HZtf9>LC38~Vi{YQyb6llCw8n8w@#BSTR2tvlgH7JU>o_x44b`MI zxrF>#QYQ04z_uSqRK$_vO<`B(wy=`2ANTku#OeGqja3FZ@&`>cpG|tmD23#M-y?0$ z5L@lfv~wPDh37{WYiN2|aRdF5I43i2NB){hjlpAIxrQOE4_&Q8-wVg8m{z-+=r_1a zIlr^*T=q6ja9(FLWqtl3q-Q5|R6alJa|;R^fu#05CgW7sI$UY7k=)h!b%ic}EMrgz zf*NWNN#=tl;WuUuvOfHjvvodFoho=csPYrHYYt*;J+*{1h!Zw?z>6Ua&O^wEedP$J z$T(p>nbCdG%WKs?osC0a$)!Pej}bf`vKFhSL?K}z8!dv?Ttn?kpETu36poTn=h73m zme;1uCzB+swWmGy8o~QQfoVEb{wDktqh=Lz);Eu$Fdy68aa>#X&$5k;$v>?oO8=qg1 zezTdXxBSHC|B_huWq2PxVni(nXjC=QZ1w4i$v$?gb1wg|agBmS1xW8rcoBcW!F3ES zJRT-YY}NedKfbZgq2}nl5g^15KRs^swl)0G>S2Z`ux2P@B{VR31WRin@)RR8b0quP zXcpmtz=}DC7wi)}zwcoLCAwg^`P$9CRCW=38*Zr(-+J0Pr<6+0>r<$1l}CuV&MaA;?QlP|>6i*TGvyGw0l)Hh?`?bgm-c$r^z5;fD_^?)f7s5-UW0M^6+~<+{@>~y*eJWn#k<4qh}NuW zlGv!z-xz<&8UCTRn?B&@HNM`ktWv?Wy3AIjCAD0zz+)E&T z{Qjc1ZapAT=14Oz__EX*s(!oAE!j)gas6lSB?dA2U#bW7g&<48 zSZ^*G60zYV_&FQ6E~63hM>?WM;|E<>8W`pkOa(#RmPQ z=ozJ>#zih|ar7UKnNpUL|;aNYjZxM~RK6$C@hn zNwpV@YxRq4VDS4eM9T{?1iaBEtYid8LYr*oYg=1k9!C(o7!dIbqivJEK!2fIOD7NH zmEJ|z@sk-l0O{hmrR-FqlIk)7AzgY0fQ3Llkqju4vCh&pGz9Fz5a|Bo)E_(gy&h z0gn2`DF>G6w}1V_5~OKQKlPavzpTfDhE!OWN#2x*RnF`>^_0dxo7qjtKmO+Zp&xZy%LTP+6l7f^A?;y@uB3+{1XLLVgM4cqpThFH7>I4Vi7BJ0u0kjO{P=GrK zKrKR3e=OaA#t=k?{dSJ{jS(7W-CYmdsblpEj79X79shwuC^LLXV_U?rR>Vk4sJr3A zV<5j3d|1HO4W}qr$qDc(zz8~z4t*j}MDv~R8Tg7}X<%gZx=nu=glN_QzT|2xkP2j~ z+Gq710_)_}@!ALgm^?f@R9RC`&hwwh0erJ)N7$y132ZV8D=S0bDi^27(c=Q4CG5iv zF89(kxJTy2=M^gL6pN~GK1Ao~u83kvBW12uWi5>8MUA_`e_D=IIg)Hq)O8E%$C zpW=dU8U4x7TI&ZJ_BhKTAWvK!Y50uC7az2U!qrI3rxZC=2z3+#tySXbM$I|1JvWEA zuI}#LK6szjT*Ez$CiIO(QGa-OBF(cc}(ScWyuNS;b!6Z3e2bx zh9lz3Ili7ZJuN1M{Lo&Ln#|sTlwMc%B$PjiYQ2yDG@c-qC%0p(A&lFQ`Rp|`i_3U0 z$c{h4{MW;JQTJMeeOqPh(aUB^zvye3znePx+i(^;Ir(zE9?Pd+np1|uClKk?NlD`v zG522+V?@-lp)L_JK`+HdAJgYCyXfyOHP3Pb4qb)x41Y~*>HSst_b4CXK}l1fnDQOzea~7XwrPA40>p6;${{5WvZy}K zyaI(G`=!>mF)y6-@?F}3%{#I%mMBfdiW3mAIVMH27W zJ%8v+(Iy3L3W5wHNj5?={zPfoVDJYtZj3m?6onwJ&^T#lDxWS@;gv$PJ_nIg_Ft7- zgLU${ETBsF2xKUMm8gf>2d$S1mB6)PSRsUvVj#&eCVzLQAmTJMuMOYBP3XmT?0Mh^ z8vS5UE)O0IdG8%cFxdG$zUX}U31+f7FbfO}NSX7H!0JGVzyl*uv9Ys*&6+zDude*N zzf0X)j`Ym%U9f+Rnt$wrb=0O=aLXmwCF{C?tO*dlFzz9%X#XeR7$iF_+NCW8a!^LiT? zW`H^dX{9Vyxx!bq7tuBGO*b&TTEJ4R0EDpg1ol^W```=ggpoyunO(jxY_Ma(F?ItV z#=-G1uUs`yTO18=kVIP~LKqqrV;5)2R(8(4|LcDPvmtQS6dKkH)UyH9q}gbI3z|(S z@x6;>i-pjY2nVbIXgb0}*$BBSl;9pDm#>DiYJd$7AVp(c5Oc{BU{OOcM5ln?a9WeK zP+yV*0u3;BfPEU?7dILKP&O#^x@?57d*+fhEXaiTfU;@r*mZ#mdyxwRT#s=}UVsoG znS+!q;)uR#*I;Vb^gZZ{59~EdhqROlyrDnC(TQ5Sy3QwGdj0#Ua|%lUgK1oW@n`%2 zC@%h>;;+MhTspj5*7X1;k7iNQ*ASxKVkk;ED8K?o;M*Vm&dje*_JSqT*<{ipfOwo0^u>v$Ge{GidJC6C3l2^XsdY#og?$v;-hA=P$1BVIR z37qwoi#H~Uf(2#5$n{xzPb}z}Pk&WRA7MhBJy9YEeY9D6}T|qfjb5^i2}J7$nZ~8C;^`l6JjL8POsoayWxXS zz~HUy;0h+Y`EB$gTCRa+n9udG0UY^;G`;cd%zb3d-z0Ts>$dIZzC)YZdrAC;@BYzl zxzk*a*pTmqD9<`mC)g0L+W*c-y-2lskdvBEEy6nv=lqa-oKGB`({n{5Gb-tpWuhFUhk6)e_nF<{^xi*GJn6Xw@cIc z$vM>-N~Ti|#OoaE^OUDd&EOrn;t2L1R{L9KKze1NK~sjZfzvT6C?oL9*e^3TQ)il9 zD8ZAL?}4fl&8A9C?5hX61}JMm?~sAd>G|&p2(kG()r>B_G?91pTv*U?w|W)R1af~A zHAD_=g5CdXhIDa<-ddLCHhEy|*@#Y4H)LdmJ_z2i2Rr_1bwltdXQny$gc#h^Z*@z5 zxpY2-Ic-i;Q@^-+HJ_QY-O-MJB9L2R%bApqmEV5P^bmg87O}H0Gabm9rOIj>Iqito zM@-La`ii>NgGmZY?uA2uu<+RVq1vrLN;Tifc-v3{Q!nmNY4Pe6;o=T2p-nnU>I+S! z1%~RgH*32yjgghU$C&)_IgL=SC z+qQ`55QHJU7S8imc&{FLe70zRt`3Q}hX<7<3E~5`I~<|3>-CA=hlXVZuhQX^60_f9 zd8}U&;AXk?;hx;8nWDpoPm5@Csd#eWWlrI4%Pom}*yX3j>W+|;#aHDa8yKqlaWrHe z-%d9_IEm3^na^j5HDn2kDTp!pp1Wf+;LAE0l?rD30h~tvvz=#Sk0Nh&i4a0Ip&~KZ z`ZayxqYumv-iqWVp`{4dS!*M*;V4vr9C>nq#F{U5TGrB&nb)PgsCJ3!tOfGJ1nU(0 z_F0{r#SC|!754Gun&G{(PM=Qtx^)J0g0$d+2FQZ0gzz`8zX2Q<2I3d39S_uRi#L0o z6VCG1W$LDFT@I=D*V(^E3fb(K*LF7u{X|wvK{huI4O^n(?W>=+YQ-=LFj~J%Z{DwX z2jw1+=++$^zGc_%c(ecpzB{k8zbKn}P~P%aHgxp${AWb$v0s)l<~(SKEdLh25Se-( zRnlI2VgG)@Z19Z2xD(z43p+nnHFm_gF6(twnk+5nT zO=sd$1UtA3Svp@6?F9H=x2i#mRT^u}eeYn{SdpXb2Lj!2%ccMn4ClowZbun94^C z;=AJd{hdRG{-`CAyy>r=7qeGqBRqvk2Cq*O0?8qr{%`3)u~?8qkBwvyAwi`S zHHT?sv?;-x5_O=v@Y+h%aRM<|eouF6BLF;L8-v!#;H)dT(`ApEgQ%?}g%aA8&(I?X zY|QcK@Tc`PT%d4R(6X=7H4oAf&IKM>X`aj+vqL)S82hF1uqNO@IrS3Ri8x|2z*eOP zyKB)eYe{MeEwDX`3kBNH-XK+xoL<-+45 z(&oI(dHHga&+VM={fxYe!WwSo%wOxX)rDu*I}fBx5x8e)~wH^??N3F;TG=5#~)G~eLX*5B0@%zYT3w|EqpETf-#bpUTDKpMA}LEgqIwOE6o@a za|{?lOPqC3z0%4gt}T_9GJIX1m%k-slkAXqb~yiU0< zS#hiS3M1pC&L+mZ+4_LO?X#dS{<8ESQRp$MT<)`xDI<@F=PZ(`EJj@hs)0bKc=+ho zlS#xn(P?DG_Ie4nUJUDRh1|R&=;;qi?|llaL_0k5JSpD%_R8LAwm*N#++t+troE>C zm)RyE6P~G_X{7qrgnIBk#h~2XQ7U&1i&+J;O*PPnnN&uS#c3i=#ob(J3F z2`0sC(0svRfM6dp>N7s%{8j^xd^g4J3)m^37JgFp`s=pZjpY{WpzdC z{;bG*f2TlvM7x{YhxiQIZ}#RN@hbkXQo6~6*(trHkXP&{8cR($Q$vlQ!5qSp{UrfthSz8+}%ZFl133Cta zh0}8cutbdRNnO}pQ8(C+bA`+@xRHcrFmSy`i_Md3T+5_hjWv_c@M7o)ddq`pKxHE0 zVA`@ewE8Lh==;0KL=LhA2?#r~?yqGD_ckPSOiD2yqAmxj{-{^U!fqoEc-XZ$B*kvV z8JL9WZ*&cwn;oh{$+G2VvDOBXJ@35kjiZKx<1(sE?EmpNth9!@F-C`m0?FBkxJ-}0 z@HmvdG{~s{6?Fxh3u7Xea|sii)Ie`_cy>#5k?PmqH$9Q>ZmXb+SGC{SjlSVcW=NKo6FOFBWovqSCJBsNN+6GE3!0rTco&hcaB#OO!O5o^AHdCjIQEJV@JivuP zj~gxby$_t}An7!b89tyU7El5JWO-XPN8V})xECM=<-(wY-~u=V?0qHbsNf$Cd_G)I zC5(KsCJj}LI*l@<)|9{;9Sgz%>{KmiAgRVJl7Req%ZX7TBo9hSGU3piUS{}-1y=7& zp);eR2WNv^>6@&*kYg~cShM4!0UCp;ok)v8;mJgv9v52@LATe<;5B1%COkW+^&B+i z28Z`%QPWkjgpqN}Z9z<`e1s_4!4pvQ{==aK9QVoo-fK~OasKWK-qTD1HndGYz7JJh z!Sb_k^j1X1#Vqhg{(EDsPOMckxN5P)51b=t;ZT6_V+?>&TGL^6mmB$*V$GVt{?AbR zD3fTn01#aX_y%cO9LO914S?1M@FrYlY4%Gwo-7O<48`3rQVI|pBJ0QW~ z6o5p{$u>=BOU*mWjp|+M{^56Xij43h&a`mKvtm=vHEURXNwLY30o7O6(=%1Tu-6lf zsDfx!;hg-OchEDvaO{r5N>+%AZLPntkPsX z(9V{~1*lQx5{gK3Yb#)a)R^&4{{En|%;^AJ9xPkUl79(c3a|_=fHVMUEjr9B1EUxL zMFbqo>yHn2*D$B^{mR+{MYT~+JQ%e64sDGFT6!Mr0rs)b90%Y#5DM;)3`pA{AgyV& z`_q5vdUJrC9IIIUycxv>=N|sslc7_t+|JDv`>oO?zoT{J>xdbQVBJE+yD%F< z{Li=?K5QuAYBe%it-m#Aw!ZgsF(#zlT?B?@EvBvVFOXH6x_uz0qcU--Paz5bq zN^^<)Y&bb1Mfv zZ6&`F5*14U1vIO*l6WxokHieU8#G9cB8yQ^XHe|*X8nc!i_?B?E2AbYh9Xxj*+Uju z2?_gHe$=3$kR6*fI&WV6>D82$dJ2RF>0%=1KF24fjKa0uh;L*zUH5CFMal(Fn)`3# zG6E1J+u`076!1jOS!$~Jpgnz}-xK*r|w z53A?rznu<*hIx=0|Bt4tjEb^r*F!f*cQ-E$(hbrjprFzXf^wkFd-PP`ekKv6s}rN(Z|haM%Cx16 zy13=W9#M*pgh;9+jghf=BxhZSA3{GX#wXIMwWS}QQv@`Rjwx~$h^5?|Eje?P$kQ(U z9HTH+reemebaYjXOn3qdw?ztG4?IsGPi9|DS;5V~M7YC7(M}(_7z%5Gm_K=WOGHC! z*jHSZX+cFTu7<+wmRKZ)L_*xDtl(jploZYxZ_*zpow9>oC`Byp@rbSlirVL#CF#rm z``qk($ga%eKW!g!Zn=Dc%(d;gcDJkKVwA1>DP2jy+xJz^^^Fyt%Y@=pzB9%v*k?IB z?py37#u#Fs6&iE1=#1ZHWVr03bqU?d5NVaQ-vpeHF-W};6+)P;fIvtf3_JsDb+GHl zvL4p8qt1&uwi#cG`IWF(lQzmYj8NQ&5Q17_-0(Sk-e}o9-cNrYzwO98dmfJxPb;~R zbk%ZC`jEKC3toKKZ~jcQsEoL%j0wvS(!ne%jg+)q`U%-mDwJ(!=uE8~-rw|K^zZ0m zD#84;Qu)!WNqP2r4=c{a4^-T7@hL{~EQvoe!pnd*Ld4@AJRr>>s_?lP3_!{-X2U}g zNmUpD&s@r04-E)L_kC#cMN^q2vf)i1hczT{Y(j2krD(0>`E3h$f2g-amSU;8xc04J zVFLQ)2T=45_PGK+#_ZIMgg7&9zke(P2p*&_)BV8Np2<%Qx27 z<3U1#-^}tRDAGeitTSlH!Bhcq5FMUk+oWM907=8uYz_<%8j66qnZL3^f6bC|4y>3* z|LS$w^A~M^jm;?_LSo$Th(6W<-w?@E9u|F%nEo1rNkXnO6*LR}QQK=s*Z11JGmZUjB{Fk^6- z<#PvQYb7gRLOW9sdCUZ(0%i04v!9MEZox{cC*pqQx2g4D1$n$$HRMcz!-nnQ3OM-B zrq76~jK#>$DFr5?K#RqQJJnvW&!NmV{vbGL1C7Tyq{kLalU~__Nw_%2|Qfd#1Y?TBjL76|cd{(8d>_7dUHk72W# zWR|;ndeJOx3w!o(1Qb?466DHU)=KStzJUOAupoh+h|1O38NQDb=rf_|@nAw8a`>J3 z!-xp%;zS0)(A3xgCM7_BTuBZAyEatI4Z3Wgnr9&21$}&2Vz++8_~5Vsp%GMZbn>87 zhyyx^zxm!5`%2a51SR0`fBDmWSk)D!t?z-Lp$PaoK=hc)j+xg%-A6{#lQ+e;@LNy5<~5;e0l+z6ouE_Sl9WkGbNxd9 zhuv{Ft|$m2E2+#eifn<$N5=~^@pTbd$i&VO4_UFV^q8o0`a}=X?#;h<-Ttj+hY0KA zpSM%Gk&Wu!NwCI#7I=$_gFUI)h__(YLwa`e2iEMHMx1Zva*mq{;y=1MomUmk#2U$1 zG{P7EX<-M!NNRMxSxbxK%(J1^>H3Lqm3%rf?3wge6ki?(fx(HcCDy6;-SHP4&lapl z)KiLW|I2f<%y{b{k=Ct5?=BrD(N zql;1=V9qh^9_`3A$GzQe+a>(&lnzcXWeMV;DkSy}#+v^s|x#WBSeX4ou& z-E8M5ti0dANNBTFqo?5c_b|A<-BN>vWm+^nU`T@@SHay-VQ3+{NG0oHj%)n7y z3Cox{Wm*Dm$s7(8xjIq96f9mR-t0_e&%2A2_d@7I4yhwHlz2P06{b;Ik|q@C#B@9< zrL5MH>S@Ketw>nIvW0ZjDcp#_4kJW@@ZT`nI@N2}4RDtnPkVMQ{1v7pV&maC)M zOu;M_CpbwW!@e}r`FYP1(!G3xV&R!cKqUBB8Aw>*z|oc*ge-<0G3zImjUN8Cuo zI$cihdNv;$r`!&MD{e#l{DDWOj`-_9iZTPVwAf}@lGPmW*%*Fp6TiPSeXuxpCj*)- z0KJ3o`<@&uuti`=R4>(vk*AZO%xFww<0ZuyD*{`#1oh!vn4y);J=fNhkD7EE%oRVX zjI2NGIk#ChEVF;gFULnlwv0lQCaH$8WQODZEcu@9k^^RQ^}w+Bk;qP@HMIELWY`hW za@)^=Kms<6iRwg)8VLhk=tD#lyz+n15wX%NNl=I-T~S~O!u?uCFiV!*h{pWmF#fFN zWLyfLN`E-)=k3>9wV$V)$>n|sVMg5;Mv}2=&!25`Jn`v2ZIly@hx~qCL#T)ibZtXg zx17o#avt&vk`XDQj#o4G81ElY5@gjXuFj+;x#FrYLTS*TC{H9~Ffp8>G~&+M7?|MO zaKO!#+Gme_{^O>fGjBDnobey% z95ehS`u#um<42E27lH;3w6TF-Et#Y^x`7;AEaT%4LzYrKI5T^aYhm9&S zfzK&LF?~&Cj>20Qg6Mon#W_!|lPw|UKlzXIh-V#D#U#g|OI)^`OGXUom-T-FC2kJt zr$$1#jcQK+y_iH?j1()({v~^%{YFcU%p5zp9jmx)H0g|vh{-_PT>~N9w2-jm%5sDI z_si#U;nU88n>i%wuunBCcpgv6amQ27RDXi_(dn*mxYUpv$O+}?z~i3yl|;yP-li=g zYY>02m6VEsdJr*ivzo)V-!XCEMQwr&IuJ;nnfv196zZ_%X|b%|UF^Dp1`c)h&gpb7f^E80c8> zI8|`L1HLabn^BhSioSH=&>;8Fc zChO-efDN}3g7?= z;Ure7x+gYAUw8$y!^qTNm26fG%MG8=Iu74((F-QBkv1(a8wX&Mxdp8ue1oRrp=={E zRkyK>jX|0EGfIZUUCwpYPW;c}gV>Z{Cf{F(knA^6-AZXiJq~0bPu0-Eg0Wj(W=x@f zqM%5@1Jd66E&Fnt>{YPec;Ie_sX@=^El1C+H>mdTEd^N~g1p4)P zPAtXNU!9d3rPkgzkoBK16r$JL9&8RLF{xPFIagjs|00|;=ZOlOnB&qwzy_N!|q1(!m6 zIEr<2Lx>@_QO@uUHT+@J480$TKdu56hkm;RD?uNCRB{i6lxMe|{{ij@(0b?vquY+( z28{o3Xm$uj^+BwR^Yia%K1B~01G}>NeM?ECUypx*|U4wmm3lCR%_fiF3iY`8C38@P(JO+0TJyR;G`n#x_txO zTs^g{L?Ql)g#o8NH*Gd<0G9i-0VKl_soA3zO2hAA;Q5HxJ7n(1aQ#r{H6+a}V27C~ zzUzwK^!^j}LoS-UL$Tq^>d`0g%vL`|sO(4xnh|>advvhUra$arTLnQnGqt!SRNNX; zc+x9530E8b?LY2EL3{^K?{C9+d6L?U3ICNTJK6SiVgLSo#O_M%tHm4;x~uM@M^7zhl(*;u9dogm8-;`cgO^_GjT!@>vUDQ!d=t&H3y zJfb}lZPZy>{k_epjVY}#-RhlgGV9`hclAcw+m%L~5dKTf?$iChs=H$z$i3DE&QAwU zj50a|2sXjK|N9&+_z>mLqV}235^2d6D{v`-X+i9Tq@kC(Q%pe}X^6-IVkOF!`W-0p z(N|#vvB604fm%n=^>}4n(R3_R5-e2zmBQZQd5^B;mk}hgUnV%`RVmRQ+-)e(*W6`_ zzx?!YMKBxYepE4XfmuDir$3bRZo1$RnVcv(@Z%lwuF^<;MwHxBBgWG`(*_U43Yd2;O^FjZ)04X470W}CM!3CzaznxJ} zT)DtN#liMJ@~Y0luX>87A5e0er|_bd5k<`;P_qZnsZ@EezA<<;#hyV-G+t4mO#!_| z5f2(sTS3tHq!6kTab1WNONui0)R>!-!uGk&C@edBSZaiy2}QNCVlc{hmQ((|c)4!A zZ``218T|KygFKmDvnJZn1V|7ZGs58qRD8p|Ny1;#xEi6fWKA#eY2qB`5iwDDGsUf< z1|j0f(Q>^)QMdM+w2Cozp3hmW1kR4)PmZaM3ptO?Rwm1wkDU=)GE|ZL)Oim@R-RwA z(0~O25$MuRR(<`zMpr^H3~V7FP{+NB{+r-GL8SXV)P0fB9tNdOW?^=a{76crEkmjl=2RF+ z^mda-{P~X5vU8>XS1Pw~svkso1p&^2oQ^M!a~^&xn0cd#T)FYyl2k5*{Xk+I78Rll z*@U-Y^j}w(KD0y>B-$uh9sKJ`UZvam?NGbXetW}ZE8c84EDG=wa?5I5mJ}Pe%~7gd z!K)8;zJ!EnqIi^IgNAEsC!qS_=Zu+h1@Q?;0rmCRl&iiWxgF$x#^^k6uv&M}H_uuc; z)jr?nmuCY@5~@N3WVG`j7?nw>g*thLi`&eqN}BZcXt%!}LDpsnRo>_PX9FD1h>8QK z6{*5WKBr$-gXbF8eq-Kraah$>j-b5sMdU=n`rpknx7|)R{Sg_58&QouoTV#Moh!ZY zIu91d%X}BgdwS1#=Wl4=m5zP-q zX9ASENHzbt>Z|x>aM*Qug&k=BdftsFriKu4k?$*$w3_EFWacb`S>bxA;%p}+N1M)t z;a*{BfJ5og?M%V|G2_?1+;>I1jnghg-ya9M4nd9#;#tv{V#(3kstEBa#hOrZsP4n% z!;?fHJwYYYjUG@b!dL>~LRU3%o71Q%ckCA$tBZRxMv4(r9N=tu0X7w(Ox130f)Nn0 z0!96q@PHl^1a$%KCsMJnmvprMU;OAc$P@vufciK9eE<_t?1(AY_JV);u(rVQ|5^Zh zclY6wZjDkrpzH-uM$oIVOW;j5BtisIC&w0DNVW7BBLJL$1OjZ)f!^28DlJCCF(Uyi zT_*E*jti;d=HUPTKBj9y2_G=lRRbU0U!jb20I(W;oKQtA={DZ3C2xQc(b$HR2YIBd zJ5;Z@+Bu%Sz3-d`!wlXVszXFFulq1hTO$%%KBdKiFj||kUiiKo>OJC12QwH|rYdj{ zQ6(xGaS~C*kL0X;0fQpod22)&a8S&D<$B>feBeue1JtO%G6dqn1W@X+qcj!6Ou11Y z=3>V$G*nFqTN5))s@qS%M4uwiH6}JznQ}sc z+b^86?tyx#Jj_4knS95EKqtcBV1&o<)klm#Dd6nw%84WGmCE(gVi`DrFk`@~WcGW> zMhN|iekC9HGjntsc6*MOEk@j08-GEad-s=q4UQ(r^@i{Z8K;i8L)cU1V(M<00p!}=ny-6Ww}=2~21$pV3Q z+69~EM5)T=QHy{Gv!@hFRgRh5bpT;MmGY%s6@BoU28g4%g>@L> z{fn#s^0dRHi0ltKY1~C7TqzOD;xl6+<9&b-9-I)svYwr^oz`}~Rss7y=m9q6Ugs;| z9)8<}?sp*zsnca268dS%EpiH&wv=&mk-?!&2f!ijwMKPxbV#)6{?B)2HuV9VYnoUI zmc(8_|9<(~9+v%lS$q`W2n>x-sk`#5X>tNkjJciskp$9f{;oR}FxsupX&Vd(pSA}A zONV0%Ix{^;;{(-!XKOuhz^?E36`*y%ng#6y02dI*y94tm_`J<_Q19KgBRFrspa#7O z!7#nTp*?9o`q<*-`DWoYQOE(y`<36gKU)jkD*T)t-Q2S0KYH)yt0-NG+Gm|Jrwn?v z`jAKo?qr0_ysKg^4D))4_7oL8#@MP~SWNa@%p9FqEdTDb#yB%OqEPbU;duX$=zAk# z-~0_nW@|sfrZdAmHj|^ZdLn>y{-ELRknvaXM?09Wbf2&+UiZ#_pxfaHu6kqp8}X16 zB7sI1rT$D4)Tdy!F4X@>E9FAetbndl%v*_jkL??n-5d0CTTgRT;{L4>u|K^5wgVec z?x&9^CAX!JsVn#g)C$cIIHn4rPL={~)%|Rzzf#BqZiSSU7yQAw!DaI%8ej_r^S5O< zo=SP34m(j{(8ZzjE8oFkO!B87Wb16*8e~G$A}c;JIrmET*Ot8@c)bX*R`4Vavjy!| zQtpt5m|mhky@Vo}LEoF|`%gM-8wFU!Hk48+c=qvV9!d3YlkRvZbS4md*gH-1 z>xfv^U)ZB-C_L70wz&Q&%RYuY_^E4)Ru$!hsNz-G{rkaRB5ZvO!>!;;NOenf^C7n- z_H3E-}vM9KJSjx+GMh=RkA5}Ini9{$3dTOG~};WZ|X*VkpK9(C|COhMa0ZEZDuUjvbdfLQR=r3gm# zMid1(31pBkimKfu`3Uh++=XCUe}2vwZPHHrERUsJEQySy(eMcp<-Fo_uA?H$@!AbN z0F6p()^WLEb+FGVvAcgy_e(Mu8Kobw*!-z9wYMrR3kQy8;C554;5#<61T>1g6}cWbm?oQBx@Uc0GN+kn<`d$105#aQcJhDIr5ePMzUI1(f=#3-ip z85O}gJrd@kVZRh%N6JEOVGRf2XYy%k2WdR>0=bmO>T#$XtI04xi_4^Iwn>5~65Fv@ zNGW?+Q>{+h2gw?oP(D)H+`_l|pZaG8X!J#%A(7cp4$i-Oeg+FS+tUX-uhUR;Jiyqn zMg4V;(3$DaT+r_`>I(MUbP-5H_{L1fkfMr|qKa5uj4MAx>*kx4cd<~qL;Aw18-Cp|*5Hm*^oU__Z2af9HI&n5y#l8U73A0Uxeyg`U&opu)r?9P+V-U0CUmMPbU`Fy8y zhh;xzhk8zsO2wG|n!S2HJ5GmuIgnebzhMsYGn+=L?z;668Qa>)ey9^`Pz^BJUpsQn zD@tVy&4^Ck(Z-9;35(}fDY$7!b>5Xts;9OcB~6EsgETTg#-D~|Xlt!*dF%zXv(#F} zCaMyXWA_$4+&5l~=pWnt9%L0tJ&)REx}9xu7YOzm0S;g>jIXRks7a)PNQ6OOV1l&U zneE5!Bf3pbLI6QtU~}M04ya7sb3-D!CjZT2m&Oc(JUZI|mwQL4(R@mpt>5urW9r{@ z?WEv-bX#I*yx(DfQxjLT|7`%B!Yxn!ix~OFB$n^HZQU>I?{2K=id#-KQZ+11YIWHs zTf~JGxZqup11BeNnCW?lV8qZA@J10^obpwUvq3Bwa0q)DnElQjcZK~m4IjdAwUx*9 z9Yzkh2Lf+=&I}Aryd*#)JZxSEUGPh&rqF6KW6*eDe@t=I@RthF6yc$2RxKE%F~D*4 zR#LyC%0Z1&hv6PKk7tgXbN+?d%c}x3PZEm6_A9cUXbW&$6xbz-ih@YjpLt3A71F-j zzq?SvHLL}FD^U`3TX_lpWUb!nz{eGGt1I=gX|Ag+W>RZZH$cK!W;`s zqhHQvY1lzP93xW`Im_jgfe~zoWi4W<@Ta9*D+4Hz7R_%B1pwVG=#?i#+$_m!brBU2 zLEm~3F@ysSA=>;6tqYmB$z8Z>X$kJvtBfs^^!%><_V5s3WUjU)ee$6UlcDJ*D)_!+ zK5YJuw7C9j2gRYTS(4_3yaX3)1$K;bWavM+Cj~IP?x8?-NzblSPHq4b3Sw-)2yzwX3Sy379W02>|x7QSep= z_z{=`FflPx-bLtI#9_WxG0_9+r!T%mR*qfro;9}V#PP$3$U%xywthcL6@S}uK}5Xo z@c`o`0c6V^`q_18E`Rd>;n3=~=$iBOjF|RrlKQ`~(!h1qthmkxxIHM?ec;5`{n3aI z`|<5E)q8e`6MM!SAKdLp#z@jg=ey)=Ba|V9dj>;SkW~k)_rPlgRLo$aPlpEkgYrqG^05Z41*6(C?91RIW?6u;2~ZT4i~ad)o(7c_{D z1{&-!0=Ww;$Mr`r(t^RR)*Cyf0g%b+OkS7_4-w&&q%cWp+ENfs#DOumk=~2?vxU<3 zNaEkCSNtvswyFpMYoS^V-Q zS}RWMw0CfSeIklp1W9cBFEO@HyFps84OK#Mout`w$MB)4h0_SL%f=I9?_|(?bHIC? zvaiGrqF!vqn-VhmNPCALv9AmhI%R^;1hE~M9xF0*!VB=Qg^G2*f(r@3czj!WV*9O> zk-X*tuIf+u94Wx=1zCjpcZ_RxoBoXS<4Z)f&%e0Z>mw>*jmt*i)K!o`h0$w%1&=5u ze?!b)1y2|2EDiGqp8pEr(aVy8KQ)Bvo9xQBv{R=ieMMY~@I;0jt0**M985BmR)a1y za;f-NQE)vcJIJq$+hV^_1q~sEB9wo7utoT@0XO;>$r?#K8j$|UNB8+bxF8=d29-@$ zLdsB1wHt|eO3J#r33J}dJ)WukmW4V8sj6m0(;d5+jT|NS?vygkp5Nt>s@lj|$XdY;88EO)yT_Ts-lD&~mWU;mb@8PYGHZNeEQmrgB z{fq9m^PiKJD1(NIkQeaj$$VAO+?@0*3p7-S-E<`gT-wno0^#d29DHeWt%Pibj25D{ zt~F+zW0aJb$pxffzqcum_;Ce~N2HG84c0<#Bly~N*HTB7WsQy@MB@%NuVzydDo2&X zuIDLjI3k?sZ18ntBdnvc)xLDV)LkD)-!~Sgb(}fx9L%_7EBcwj#$oSGn$cc3(;y2K zIU2;Vh03MfWznK4gERy(Mht`urA<>UUD1D;f(tiL711yU zHwkb5V(Aar^U9Xi`n_!XJ~`=nZR2~LhKl#z_}r?M%qtRoA}8aII$QC*M-o}}`R-Wy zO}`6nh?qK&tGfMt|J)}uof6Bv8`9>NiLdU@N61_zFbhq}TRixdGyQ=`H|O({Cq|rP zKoM%lokn9+WVpv=IwSbFWB16f^HG0r()ZcvaZ}s}X?CCJQ!>Z;>f`f5E-8f_u6Oo-47$-(|);ID??11o|^x@FBzZK z|5UZ0-9BX*d%P`joa#e9WSb26-KWS(aB*$KSX~i)a&q!`hdPnk3sykl{0H%?XQjfg zU*_Hn9r`|&1|`h!V~u;yz#2-!wqi}W7Hgf{PRw!<6ZOI|6m{15a!YOAGRDhFsQs!G zi*oP7r8Hi`=x2xYQ<;*@zJ)!WhyU>&cfUR)@k)f`m{!@=kPn8+R^p?*!F})NrfiI` z6HTdb-eOTKiD;NRFT@%hoWQ?aveFnyh0^~*DfrxKilLY72 zlfCs*7tTBt=e07(<{XqnF z$=pl>R&x+?563uFg7zofJXJwxZoysRlnM#ShNSu zE<|DGZ8DuB*8Q7@v6Di@LJdjaxONu8@Kcl@zAmvzRYnY!qMjmrWf{Bl0%)qmA3!z? zFdkKij5J^FPjGy|F#x}+0}?+2BtC6!$F6N)&;(UOn19_jF+j&3mUM(&@D&uwTym$oN+3ZfSLO$nJT^4jPR()(Lf@L!+xpwZ0P{ zK`r#){U@Z`R?M$EM@+egbO_A<6$rhP3P&l>{ahmZR8B5+JXFP zf*T1^uQ%aUV2Baa8h5)Eh(+_DL_!MiAkOsh--B}wisbqEGRQqoBcH1}LZAa0*uuKs zthmK0Ge9|YWNLuXMu2Xp^{WK~C>sKthv0{svs*#HB0%JT_w~FOh^ubrn>qp7L}t&g zq-+QrdhQqF{53T-AmJfW{61g2x9j<^YolR7KhTH>s<|8TeU$st?g7mi>ILaa&~2a% zUpN4)pbRF+12VYnC4|;T0freAA40>5fIT0`$3Si*IHn?5Uc17pK&&+Y?E3(R269dRx(zV|zgZKDfFmT$Gwmt;6^_}1r=0s{Q-D-RoYLC-2FVRDW=ga=1 zr2oQLLaw1p@(Q{9?y2+fW$|krgJ9Ir#LX^t%jt&?4*{_1R1nxTM2!^{4cB5bl3DWf z&wN_FBaF&Cf6er$9spApmHa1I@Rv|0ipN`(B1lYv=PF_;~Y;LyQDSPV; z8nmK^D`4eI>0S9T(G!VdDL}nZbX#cK%abo}g=Ao5P_CJK;H1i`Y!2a zWgwTg%pHG2JLWR|g1j18VU*7jVrl+nkG5Gr(;~5vQXM|M1NUo0ytG};2AV02M;%r0 z)ScGLT%OC>Gd?*kTz7H8Iw$VM+jpxP2kh!Ub2{;f;0jJBUQaE&ql!{@7ITUzU&`u2 z+`U1ValuXsrh;e?tBerk2Z|Xm#nhg$3KQjtxUw3R^4US&2KNux#V4)uG)H0om?YZS z9mc09d4Gk)&aP9*XFq9Hghdyxk36o-K)>WtNCAU~n}T#O!_MlG)yK}#A*9|#YRElc zX&x|AKRSk-GKRI=Y<|0@$(78ko;uHFP3URKZ!-zcnAfV%wR*L<7D8$N0 zuuWTyPGpCRnI1f5mOg=08Nfn7J7a<55+qk_{q6V)RJ$NIZa^b;(>k&0#Ajf=hkD|7 z&$ZqW!6?0Aomt3yN>$^D(M~pEzTxXr*xnZ?afCXE#%(IJg44?T+1+ZGI6BcTIsR6iQE2&=Yo--mQR2ukghi z+k;xpV`4q0LFu!4{_4SO9C?%)rhu5Wy6C~VZ~K!kcb99}^%`NsAG~GZ*PX355jCVH zn+GljkwR@qlM36lTi+21=u7xjOZcrb_*6k)UvuSX+iB22te|x?+d-2G;wu;c;@+V_d=%1m(u`;fq`|rQc{WjqmEy~=nG!#lP%5-4^ z8^FC5L(pIy$rzo@O>`N9{y}HV>FMfStzbIZq0`tnp*)?4+8d;=p*D8Mbsa8J)Z#mf zv*h~A!|@8+G3?H5qC&Q-%j)Hl`Ev}(Du&B7XJj&KSJPsKTz{CxIE+Z!KxChGrSAGx z!Nhatu9*>7)2ZRJy|0Of=13apdEJ#d+{*j*qBi5?-LquC3UJ#e{wRI_1S9^iI0O}) z4-p>*4wl*atOT0$2!{l2!ml|v9p9$A*WM4s`d0A1w7|ghc+GhcqH$=zpB{NuJX<8& z1>>wr6z!8+5za`pa(Rj>JQb*b^5TvZi!YrrxpaG1^v#^lyVP3`nQ_W|6TKR-Qau;- z&L2-_M2>k#N*X}T-kIXF5x4EgKQp=%r+X*G+<6Dsh|wklt*dD2?-h!aIF226xwal? z64QZ5tB7}UF!AK%(6!+_jA3J8)dd1oqHv@%#Y z{1DZduGxnicun44(tUSx9GKa+sQUl{rkQ*+^TGu?^wr?FSV#XE+-9h!xVHUJn@Cxs z*VH0sdKFe$oF-GMiH^#OlgP9=_hCD~^S^3hWmv;sJRG&*dpz;1r1AGmqFS9}?s@x} ziJiu(+?$a;NE1i!MceQE{l^3bH*3Cp`dOKvq=YNt;^|2Ot5MRb4w+Oel&V_DpR=xM zZ54v)*Q)S9ZN?8DsBhCiaQ+TE7SfmNx?Ifg`X`$isNRZ|2UOo{OL-XOZnz#YGP0n5 zWqzDR`hbB2zIK4C5IW)tQAEF%KLN!Ku5IIB=?3#guK&*MEl`8@{r#KO_yB};VV*3B ziXZK^Ni-6hO5L;)$p3VFO$M*8uje+Ff*%V+!h(Qge2yy~&}H449X6lr2*VV#22O*g z)UH63>tQJYpNOKHU0kuv5Z-Hv(ti=x4XA4-^Tn<2jkLN7O?gQi09t0dEb{dlojM57 z9k};_U(x0HT}OJl3}}rqcXHCa30qqXIB)|!$)T?TG)iT}vMoU8*=RDy1#qiTS=OP# z7wcqAz{UCVV*;WT6n%r?3Rwr#DtMJV@FQ$Rz*YbONYv(D%_wU;h{e_;eAR3laUHsO zu9GZ%OV{)<2K7dgWpY|Ld*SO&4(YXu{~0b)-}jz7@?A67~2e14sETE1{#z zffr;$bvsR;YZY?YK5Drpj&4KKv7rM~*Yi~swp2C9QF0fVH~SZE@CYKbWP~z{zzB69 z+Y-|OrZe9Qe&4_ZjkX+Dy=4AXuXs=#8ez&k;`==LLOkRE_z7cxF+%4uS!Br{?`g9q z>p;;oAbUY-6{u-5TIPdxcs8r7GaUTC769~Bw6(Q?7rBImM>%}X(EzguNP1@>6|wBy z@~Teg1lrOf$U2&*Q3`0=D}|oBI}bokQ+i*Lx75%#$eM62&S9aVp3r36(|d+e??pRWnmen+oD&I&C#YHAM{#U`LnT71MX?f@ zdv;;gf=gWkL_B4EZ=K4+Km;}{BFjc(|5NS+p8ny550VqeFL}!x!U35berz;dvQniX zW(7Z5yO}d0HC@t&750!;qrC77u=mVvJ~6J6_O6ltXhXk|{yFfr+v|0QD>!5AYLj|j z>h+yhdET&tFp93qz&izJ~E%uk+4EU~_>?D@D11`=7`t zl(ND$^fjF5&b~RDH$QDNE!ce?E{75lMQ~=WddxHqOCa`pt>5&O z;EuLuqHh_S}KPt)x}pb3QCG)#1~G@PU7t>*GS}OT0K+j zT*>463*6g>hlC&z0TI+tMiXPoJug*Q6gQI3B3-eKIx!Q4FE&>$6eTXxne86vbEnd! zDsz)W5}}9657j-ni`?3Bp6SL7Y;v(G?Flw~Y;wu4Y9y$4qnFYFqGg~N03fxyh$^U! zUp>`i+G_Fg2<+>F1Kl>w_e-Be+%IE>qA7tSV#M4D_>Wnag^z59+Fk0NbJW^asS{PO zvz5B@24=7M8sZtQtkd0AyCU1zEiu&Go9(kT+f>Ek^WAHdJ-L*u8G;k*h+AnhI>XyG zxf9?>juFRY!yQ%%6Hnsw)Oh||aQ`ckGp*FeiPk3&(;vqd=APy?SR`^oGC#)EH!XH$ zp{FWqd%r^6G2wUb5bEyR?Or<8hxUc7m%k*xc+8W^??lc#_|t zP;N8OGZX*}>}!3btT=UULm!lG?Sq+H;%b}Z z7ZenwOI8CxJBI}`%&ge?3#2orE%l!;SJ=0lxP*?g#I~4O!+Q+neWz~z&ISeBmUavi zCE4P}$LWYnUyCcan*)>q`b|K>B zMlG+7M}Z;P)S(65HQU^z+bUnRN%(BYI=!yquhWk&txT^sBa3bnsdUQk?GLQ4fwttF(m zI&E2y>VW4i4Re)e-1B0n+`x>RbumNtKUTrT#8RV218~Cnd9a#(Sk~e z!TUIG2VPSE9X9vU6KFOpT0V{g0mdybNt}VCg1Z=IO6yKkKw#<% z@?8H%I4P8_#Dyr-1^8K+HUQO9704NA#MLM=*Ag+y#kJmIc6~h>q-?5ba11JYb zY<>Q*d<^{iAX{Uslm)=-aEzC+J zEG~Y?68BXt)#|NfEt|70`BCCpdL)A^*`hlyLGg~l$;k6k{$iH8)3GZgffK)e|i91S~T+1>k^WL9-z-PJomU{C$NFEg1I6CmTRS z;L||CEofU-+2PwrwR3mf7wtPum;5D%rscWKr~{<%0UB_%%FyKchy8f31m^_wFhr&XkUjs>K9p1W5ZtFe6tsSX%_>se2?(jBKu4m1aV2H#nD za`z(5p>E;u93Yf{jvSw!jzv@j+1}#tYe?d^FaQ7(hyp2EyFlZQObt|3V3f{ikvD8T z(=tv%aA)KPX_UX0mrcCAGiCE7!6|Vd1M5rvwEWF>R(Sx!Y5N5xpvdFnam_6(tiV|g z&L@Gx`?PSeJDHlDy>LP!mydny`f2wroTGE?>*_<+N&Lxb*CasjiU@Ih!7X|y*4JnY zay`H(x(;5a0L5#-8w|Z?DMZ};4qJh05e&>=3>_OAvp<|?19vhwg}XcB=_E{^AnXyG z2VfW2KA0>2)8(5DEkAv@IlXv(IIRQUHQlZgI@}7c-eFSuK5_x@6}%mwwO@8tA4!4P za}?mXfO0kjcV<52(>JMHXlgu&a@Yo&gpWUfE_8GL$0x6UBaCB{lktUI?=&YM9lw?9QSk(pQCIAdnI;cNPqhw97v)egkZIP+E- z;urT7k&C{!?=L;LYf?TRSp5}aJg9?Fk5A9Z4bms-a^v~)F8g(hufyK~-jxU?E^MK+ z9l^X;&6BxKLCJvGBY4Qz_|N<&6-smGB~f@j*zRG5`$QQ<7N6zfJ`zy8x+0`@Bx z+qmxU)c47=bg(qDBPEg2nz?6E1qoEan=Q0>p507@Ma9%-WpPtYTnG} zi|{AIWanpChQ)XI6E2BUVD}e>Ps6M_6rJ@D^&(Mxkg}X0qNLc>4m;CxW-&~$FzAgS zL*SMW&+kotY5$t!^S6E!nPRw&E#KAhniYojow|@@v%=`>BbgL>=E&7RwM6j&83xV@ z+OwPQ++VEHLhP`T&LqevnkTMkex208E^Fxd)6+K=Lg@J#>0_ULN4r8_N;fWuvf(Sw z^n5;0C43g_s+ewM=rto_%X2baTB`NvX87i&xcbA{T_Nm%si;Gf^MeUBLrooy$Y*qP zgmWLwx2Ybu@a$g;J54SX2M4XcjVq)G5wBvrzC^4OsxROnVpS|3U)>LX>d7tkqyA|} zPct=h1lCU^k`Ped!aw68Dy-$nqSuR4{X>4Aqo}RYoXbgXp{b{O0g|bLrYmmn(f6Gz zw>q0CoRt4adx+Ux4p)!_>Zpa;<-M?8XD?Fd-L(9^=NI+{F?R4xzu>Hn7j6eknll8$ zFU*YvQ&9bvlZBizLifF43_Tylgd}An+lJrYoGC^pB~zIshtmTwg%uKq0O7@8;z^xA zUr7J%f!Wu{pu%bc9;jyb)T;oCj?K?C0(oV6g)Td!va! zRG+;-&g}lop$COr?IPKoR}{e8_O0~l6bfdU!L6ntRX&$-#*I5KPIS8Ikgm%vmm4#L z695d)fT93+1dw>Qo&E*e;CR3b)OL1GaQI%`9Gy~f5~0f%&jM*L3l9$~8@mQ89&x1H zR;}QmvGOVjRd~Q{Fkav+*HEyu&j?W}K|=f+&lGlml`Ik)8HWob1}Lzy@4Koo zCnh($9;0TeVl6ZfV^U}Sj2|UPE&r{n( zYUMBjhZ5Bx_Fv)z$j>dw&fp}%eC%`}$)W!Dyj2xVfcoax3h1n@IX`rXQzegbgAvC4 z=ooEalLA>28T3;WEFT|;Mk@<#Qr2J1xRQmMa)ZT~0rZ-*vUlj)l`SOi-tH^2c3@hryd1{daf$t=~b;S;#vIOYWE2&hRdp7Rx9Z z1#hYL*XGI_Ok0#w!zm?JW%wF77-pZ<^R~9<(;H@PP8VvrRGW;JV6wn}E!Y%AKY593b7Kh@Dw0zRUE6Nm2D`MfHnzVO}Pj zsm4@vSf2$h$#4*agG`5)VDZNdF$_yr5LOJ9 zI^V}3-!Y(unzMcfC;JO6e98UPSxC3VF&HdURQCKf4j|JDV2Otll zHr1K%fFv7?dR+Ycge)cqOb0g)U?>@{2UA#m)X(6L^_cl)xvCa0BpC&M9}Y~Dtx3V- z0?5TM9$~R`@@(ENs_>-`G}>Y$Ip}FOWy;VP!Hfr(}2; znVF*|VA7B-95u1BLaYh{)teL=Pt@S>fbkthzyPrkz&v*`fFuUc%dJ7FR^JjT?Gad6 z+TscBf4WMj1MqM`F$akLPMuBzuLo6BP}|7RP#ne-a|qNCOiJ@-Px8N;j?R*hT4elh zY8#B=$MiKTKDco>%{5=Ymg$WFybtpae12f&hN0M?Ehrbpq91>h8n)w6UPAXx?cj6E zrd2n+D2>I+Yys!@8M83UfFYHFwrJX_!Jq`1-k@@(k0y91|EfP90ho=B-USW=<{IO0 zMZ+meOUqaALxC+5;IziZ0e~p0MnGH!&#g#OmGKwEliMTJ{!W9J;+r8;dXsH+`y}GW zwKwq}TNH~zC-M7~SrliQRA6qMGV+fH+hwlt^_EWK8`e}DIEUf%wIj@PoS`VN(IbHz z4LXzKtE*-!YQ;zQC=wkNzAR`LxM?LImNH?4mQK&maP@bMbz@-Kpe4*_%;|$LH`=^Z zbFhPu5eNQCL)P>`%a$L=)Rds*nPC4f;msRfT~%aXRTUMF22vdKy83!wNaa98!2>Ky z5#j6R)_K-?CTcKc>EwjS*(ypgX!hayv-=VY`elAN2EaQDStal>^bDpe{sUMkR1lBZ z@B+m>e!T#)TUN;D`VM7@z@cX?eK4xFPh2K74(I?57;GJ|zu^zSPvqe2449_x{vtBG z*ZOBrYy_XAI!7LH@ex215nS>)#M_D-%N z>S(|*ucoviPS35y%dgSpns*|aqhfPYU3L2($yfx|_C?s`x-yP*L7EG)Qd-RUj0~0O zTW-JG=AnFX+xtY4^u?kFK411*{5k$3r5V=ScO2*%^?%`F#Kd@)FGT(;&tR5I%WD_0 z&QtN8n-XL0+PGuCe!b#?&fJ<$+^b$?b>Bx7(~Zm6zT23OQ-+kzrx^bc(m|G2igeHp zFVUQkdzr`Eu#qb-eiw(R{R89Hla%DeOxv`=z48Ybbi>(^iqFft&_f;*6g+%IV1%@A zl6j#V`Z9ns^i~N==}{5pBO+m83C95+CGs()g&$U(omb2E?!98@bVDDz_ce{+ZjA`W z13L6h&zAiyp}TBqm~7@Dr|MQnU3d~133ss;1S%C##X4`f2DGP)(Hu5H@hk}2<|B^U zrH#&|GtfDN?Vj^U$&|4T_gI3@bVJjFf?7~2^V8kV<|RV~0+c0%7)xgF(5n2DX{G&b zV@D;{sr0n&Q}4=R2EKx!+DBFlyqqBX=a%T!3HhUM zdzziMcpV>dQ^}E?6HLEN4{;@k<4z<(C!Ba=nm{2>@+$$`A!FnI7iAooKZc!JWpZ;~ zT+=1L>Ayr8HPY)cC9rIV_6%{~^)pnhh_@V+lJAPo;hdP*B}Ub0vhpfQ5gX5NQn0CG zEx&j;sTca{SkwWDe&1zrwHGNEdqlZ#AZk^ZS|fAcAFW5TWcrEv8Rmt4_~_MVsW6m; z&Bmj#$wlskuc>0MhuOLfNYIlr3%H34ycjcvzFJ2JNZL{3W|bEj_bJrdUWea)5yZ zmo($~_x9Q7vxQ6cRrQ$M^(MhFQ?>_5n~!3DTh0e;lk}M7r52;l-|l)p@2;6`JSQnO zL$_}38&X1MUHd^f;d{Mixpjg{F--9?+h4>_ZFQsFR4^oBhigLUjli8ZkflQNrPYDt4UmjM-MT=sb87B^%05R z?w0@caLwvjvnvtp_uk(7>_*K6Q=9N+5tM6ML0fteps{SkJ}W;d1J;`s-i>emu=7TO zt95;GKQW4cX8+FtQHwUseZF9xg=EL4YdjlzH?0bBZsie{F9FOb@@N3UBvVQ5e@UQb zTm)*r?P`JcsumReXs#y}{?>7(x6ToOhXzPagp>uqc#r=6UQ?{MTx#1!i)%_l{-wV2 z2+1qcaZ`ZxCgV?AwNh1abCS+s0{efa3yS}ElDE5a_ z=u5Pg?e7_m^V8Fh*0|bO--9PTk~aA{H;=~RpX0>wUhFxe5o?B;tFs{7k>W{u$K zxROJKAa}DFt|6}W?)IyyXg`|cUq40s4@0I+Pj{Ua^V+yFK8)_GxXFY{DWo(B@ipY+ z=1yiebGSJ(L}VbT=03JtMzT4Dn79szD040{x_YjuQ(xS{p z@-TbYZZWPQrrKbJ`6mT>M(k&^9y2a{mTAC4M5yh(%9u zmWC`uoXcdffFfJ znHj)B>(?S?YOJ86VU5nI_THdW))4d5PZT3OwB%N6wK&AtYEIPuR7rel)8oq}|NT-k zzwNV23cTXkD&_|_iv%|zFk=GP_GY^gu+>*89--DcCAo07Mmi`fN2{u;p1jXPF<@~? zKxrzs@7XW45Tvr>f5?ZdPD{MXc(>WBa3DAs#uIV)xxpa~HTLG3O7~>DSaq_IAa4hp4iNV$wg)yym_Z@v;WHam-x5S{39F7@Je{=8bfSeZ z0mizH&mYuor=03tsSsUypMQVYT_DbQl0FDMh$sCtliow$zkdcKGP52wb=s7eJr>kIALP!vG(~HowE0yEwcPHoRq; zEFyl#SbeVWvo-F(<5jyYy-0_;8gOp@=gmx*-2dqeY>9KvDm=8nLJdm%q7-;9;W=ac z18rXlB&=*&r{sdZKxQTa^#=WFYSF~ z84I2Z02XszJF3+3@O($?zYPt5F~Jsrz>rNiO*}nQLFX2GdoF(a7}$6ohTXlrnx>}8 z-#>^GKWkTVQ73qk*UdQMQ}asJb}hM73~s`?K9Ijvqd5b`fRJU+`SfY5r5-Rb&;zIh zQa~sK1{nKeA^h+ao{=wH8ngM!F&Xbx!FgKhn@OyrK4H}LA7wqBa=z6rK3?e-U@>?ktzh)+&5wi#m z&PU{=!5w0%M*`G796TCK#3%}Z`S^PP`86sz&o}qG2*U3(=BYG-rEJMX9!i@y$y|1( z`P$w64XUSLEnDgnzu|%{1ZG}QJSIPeHUWAz+`&6rVmMhpf=?n_1)myViCBsdHQW(( zMj~abE*0THpD5Xj?zir=m1Q3qmc3s8@NuyWEk;$ZH@ESZU|@&0zJ&YCARguOOOfH$ z(dphnQC__~v%{c`$msd#jepA?BLn`#oc#C_UL<8oq4wW@%wzp~FZ|}$KKY3N-&Rc+ zx&OK8?2L!MuTXaG;V*K5$1^p)fk89;UC+j2oVFrQ(ugSg-noqOmKem^ipy;;AiecX z@9jNGY0UoWXF4f|EN9ncJ`hM`M~7au>X;J6zs#pAuQKnAEnyubSe&=*?5A6|PXA1o zQAxq>Ny*yJ+fPNuX*$KL$aF5B957?rKN}isa#>;{r!lx1F8z+#*BxxefBa4_kk~}U zaHv3v@2c0=Ytd-v*lj7XbidMOgaUCo$BhYSPb_f;IH1$VVdv2Zl|tbct;S&EAL zSET957=R(VkQR4WN-vU=&GI!%MmZ`GWr4<#N3S>f01oO!@o1^cg<_53Xuh86=llO( z3(z6k?!<87`J-MY#Ii!E(DU7(EXL{`ilKMNc@zO9?YmTN`o$eHyBmI*;?8Q@i@~BEBz1y4*QG=f1OvmK2CG%}Ma{B5eEj8=EVSiAaa6A`^ z6BD}{I(TIT@(a>FPVW)NVivp@nF~s+3hv=X_1Au$8x&_+V$GK4NViftPfC? z)_7jq5@r%val12&eI+%B(i;f-s?;R4PRF!ua`hsW4tq<2%(K9rej=#IE=LkKr9uGj zf@$?o9n8rctJ`~|%}EO=2QxnW+2)Rpso*1mgYnw4pPb#u;Bl(L(eL$qE^7a%DxEYP zM2UltkPyrTiAs#;q_@k)Fm=73`Ya@c;7HHvhV}NTnc%+}qCf38mjMcH*_H8G9%?o6}Iu?eo-7GL$=Y3u_l2 z@Ai$T$h&u*^x)kd-d+&t4`aNt3SHv=@X>jHZD!BS))%#OCF!rQMa;o2rSprtY=*aS zE8n=nUGsfd9HuG~zxEaWNF0mn-t2nxfZeEZz(u4;d*NX&B@fx8P!+zs_441{ zQ=coJ^wNYkLPB2T`0XSlY4?vV9}#fUsCGy9I1=7Dh>&H^e=m|;I{7(T@A=_5N==PB zG}DgT@G=v-IXD>nnLZhu{aUNS$no5=Svu#VRr>k4mU<=%*Py9uM@a^v=M)ZnMfP-t zyQ)d@y$w(r>h4}M9XpB;I)7rD|LPgrr<%vG%Rj)N0<@ny&`PI?L33XWg z*=B75d}0oMzI0w`yaRXB@ulc@|2^zlY;&i=UORmGe6suzKjWKW`Td~Xme}S$gS++G ztyQPD5wh3*%oQK~qCPdBO-qhg-kvkRk_rdaPHsa3BPQl!-fYL<<#pP9BsGpq9QEY{ zF8-DOrmO>I$P$7c(npB>O;qS*B0fwRls&z}Z_BT`dG_o^=mFmX|HAF$Ww9TJz+?90 zZIYnH1&5#@XPFJx?fRCHz_(>0Su0tYd(ODgO8o*D$%gQ$1Da=h*bm+A#Xa<0rcbFT zYRng=#=c2o*h6 zCS9pumM(jIXDR)C0dmG7#fdM;!*rCFvY9`J+|=1|lz(KI;c&}t7H$op8Tgj&pghz< zx_durbJxw)^+h<|`-AMV{<6`^W~Rl&@+iMvG)qaO59*!)X&IZcU9yIyEFoGGYnq~v z16p2ZHr;UVev}@`Xrubn=z3uYUU47q(>Eyh3Vr#+l_Q^?GywVy-LX)Hd0ndJH!o8L z!0W^Z4d5Wd2cV`9Zd4dJfUEpD>_CL`t8i-zlH=$M3n#i^prIptXV<4dT$#Gv*nE9D z1FjDcnqABcZf)ku%8HsXspCT&Ci|P+#wrzQWGirn zdNi<}RshszFg1yk0nIh3tU7=!!t{}E<}Y74Ne^&eNRe6POG86TcXyr%j3Iur#!=0Y ziq9GaR!2g~wmUj)7x(wtZiARqc$)Qg0h)TCnYDFhlTU=ckyYh$AGbKkM%;Efq(TR) z#(ui)0ZKMYdS(TO7HvJmzRoze4O{02mW1ly5SPu;Wzp)@#1-z04GExKXDPU6#oAfw zSOr`BoCBW)ls5iJZ@Xextjz~a8ic&_%4h}xs;$rL8sQ9a%>E?*b$ivj>mRQ9%kdm zvyZQwM;BiZeoyhYezKT@ACMJvE3z{*${_FL#v^()G1&8Mo66hxKZNiU$^+QjNt7Py!61jKlA0(;g8|H z;mdO`zH-Yi53+YSEIQUpUGhXTal=c7BZw2yT)(0#TW3DCM?Uz_$f*;9WE+wma20F$ zd)hIs{_EdY$({MuiuZrseo>BmNB9P92Gc{gF8+Q3-Gr@*am$Z1d8`m~o4*QdR1s9B zOQGK$q38%>F^l|&?1rq*CoN>ui$_ClN1>0nk-U`5@y8OBy*}6wQgkM8OzU>l5#=bH zZfQvCU2RRilTIKHNq3*geJwCO6IuJ#%H>H~b!JYtczL_nv{IO=+d3+DO18ulX1u&q z8TX*K>8AcYTSbRW`X{6_cS0VG)rndOF^kqy`|P1~BI{tWnfjj6Au0Ma>i%n&P)s-d zlBxt0sH~ir@kK{8S(ePSC+|dNZh1&MO_8rCgYW~HhQJ)nhgf7H7P>zLl3X~-ytE2M zi}8~1L)VE}Gj3MG!{~44Ounxv#Kg?j3Syiu>Lyr3Jj zZyUq;tDvh}g_3|hBKnasq~E~&XhfqY{sWzlk|pCe-O%o4%w{*W6VjA-9r}@GT++t= zO3q?1p&}XId7V0BPUPHE2fZ|ARu-X1Gp4#}ydn5KqYUPCTW+=9&L&lXn7`?TBJ~AcF?FBVtEwz9pBc`a&Ab zcklV*ZcK%fC75svDNuk+vy zTk3#_k4t|3?bZ6FBguTJzcjt| zB+ZIcP_*Ln<#yDUOT#q<%jHetGzPM!hjQPe-|-ZQ{~g__B~Q4>p`!V(zG>Kd{*t=K zEOfU(mYxr#Qn`L%dE?jehE2l9kB)h;3U2(c6hWdR`lXH6eD}`yF!7kXagI{2eDMm_ z;L`CIxgiyz8ud82JFtQh$D(UbX%n7C4^ooq>KV%XGQ7v^GcRai@1NfDO3|W*p}ko5 zQ)ad@t>N?fnT~s6JOP6*?azL$i|8afw;kP?Q;8b&8S3bu1KASsYgu-~Rz%?_VuXUl zQl)-yBQCJJY!3apX-Wq|yWrjLUv+~GJ_BeLAO=?5G9fb*j3gk&f#sYVSc1+@sc+$L zQs$|v`^wffHJSdL2=BTGUg=|Mh5sjLGpO$`s(m}|P~pFM&hzC*8~L|AjsI)QHx4 z#5{OgM%Dk(Kd0?igul|1|5Gc{Wi$KD4}U2y|8^U+y4Bpgq(_qZul&{&b{IEMKY@9mw6v6t)OOKPsdD(Brd>ZqCd{r@p?*g8Kk1$o*I~hw zVXOZ2Be?VsQfyfK`E0<4@e0=c2RaP~Yn$Vxz`i-m{0wOVhVMV!BBN>u_lG0{KU7K) zlMu5zFPxq_&d4b|=guse+P1Z#>^XiP&?o#xx>$Xba?dVY9Mt__1~}JdzX15)1h*39 zTk4=?)^G`iK9gul84=DvOP*d3&Nm&FRM4(5d1aJ2GU?015CkZ$PSabqn-l6|vclO~WX$wX1=CM!sF2Yi<~IXUn;yn@gv2;XGhc9ysDHZ8;W z-j?nqADIJ{A~||=Nzt=1-%rPVZh^b{B<3?=`5}^rSW!wAdFl9O#IFJXRz4VhVFBEO z?o!LFt|O?eI#in@$%dTiMP2oy0l89{Nrb3vHE{j=gX@>Vxj);>^b^I{)9Z%f@Twr!Q!$ zL8t~7FuX^N(A4w=!yk|(sI&$)@qZ415+@#@^dO@xB`H9x+Ay+0B%?s_{yNklK#A^{ zgQ=Bq<(A~h1Hc}G+EgJQLt%uW+HNmb#hM-;{ojLxzUhyZZaw7&>%wmeLs{mWbeg;k zb#)71Vs6)fHy6fE7zRMxR|jwtUx(Lkr}~EATQN{qad^Z7;sVctC`40BjwKk!qipsI zOMAhJAc7rCQ$n}W*wGDTyFZ@xTWsY(uxi_GstB4Br#w&g7&lyCEb(ip8dozBVt~B` z;@50RJ3;pb(_>=nB#8A5>nm=nChewMV|(7SW8SY{5rjY%kTXD{3t-rALIROHlSYyJ zps%CO5kA2mwOP@SG`zA^{Bd;#daC-RN(P=L_iqIKQbKL^#^l2={OS@4iD>XtK(hzE zOh9dCWM@k&^#7l;Af$dDF*iXa1kj;Cc-s~fInKayhIQea2`5C!?E?rH*wWMl5poa| zhd`VFA%oih;5LND4H5Nmw0C>mwyt`6tXey`rpY1;0>6`BP_YFa#2Rn-fo1p%5npz@ zWqi$wkfY7cf`BFu$a0wNj-}QhloG(OaW;EMOnVm6ZhXpH&?K5QXNp ziUX=bAisrk8B-M?-UMXdkzNV@P~!-Ms7l+yRGk-C<$y2kYrC$$O}qU^bNdjC5TN!< zfWr-9pFBmG)$GePvjmBO^la;XT1@gg0DosBd+P1NcN7oVJp4|wv#u9}8185UEh*F* zLD@=20Ya#X2lu$~H+XzGnmPUW1viR+4}PCy`j?ZFB)1|=VBjTpHR_k;bzjdTH^4$c zY~+oN!Ues@Lkc@Lx{Ir;&4m$slK*(#Ti*R3sM>!nWUGqJT6%TkIYnx*vGVG!lJit= zJu~j6b=r1A?C$8l$ydnDKV)qqg;8gVwemJX!d&PArE+!uoiqEX+`QlN<8JA%HRSlK zS&)UH$>fsi9X`1Bo)ZK)_6!Ib+ zizub)IdJ%n#Cjg~#U$n9u=zfJ@$K1W@%^vS@xM~A_C+Yt?>%?x%zfP|KKH)+*oLuF zc^1Es;8u8cGvm6Yp_Kkw73=RKr2TJ5zY2L+PWCR4i83fhHUCwhQ6gjf(!e4Zs+e1% z2&{C9?A+*~r^Ha;kT%BGcQXu^WJl6PABxxtRNV45L^t`2rMmF&cn>XtK;UIN&MH^tItX8)i_???che%!^lvIN1+IaJT^3J zY-Lr>A0EPt^ey-tQme!Tk!Z2@LNdRH4ElO<598ck*@k^HxFy;|CBb%J_4zraHuce% zqsmp8jP2ug*WbocC${qS5i-6%zS&{bf9h2``3oGZL@34`_yJdDOdmx4XV3Cn?qNd5 z_36$G+(<{it@EL0#P@Q?8-}NV)87wn27|AwkNxM3Bx?0nz+6s@Bm4Rl%CJ@Vi1=*| z2!s(Ko|Mkb2xB>P&o082lko3PvZ|n>;D4z_d$$b_`7KGkZgy5Ai<_qA5_C2 zkQq8!Z~9dSF_&;Q@=!k&@w>`syEeX!g==s=@Jti}8Nh6ZxD2UiXh!#cSFoAB9k%}M zxH~rJ6+O};pW;BpRp2{T>^f%li;Bwz@43l;t<9Z2G%zK17f7C(rCEqcJJk+;Vq<=+ zFl0p%V|lMzkxRyiHW_ug@a_sx`h0)L%_;WEG$97g4(Dl;G-a${A@wn(ImR$o=e-Z# ztKRxmx6A8)HB4VutrHRzS-!nIc!uZt^}0peWOkdIf`Giq{9c-3&D@`jKhefF*BoDc zcW{gY4ur(7Hxn9sw@Fri)6?^taEf);+Qs#u>N}=4dDHA~EKyHNlX|0lO*>OT_1RsP zi^~=3dXb>LowCH#>mt(rCUga_T$=!H1lFV&k?>XvclRg<_H}=uuW_F+x|hSenx3<9 znFX0<20i~&BZQAp&1%Xv#u^)UFacfR{_y3wtP9)H~f=>aY~x#Ib*;*<{mOXu>9%mj>Z zKli^%Ki&0m`v2JSH}PhpUIYebv4yoV+8m9Z$&jDtw2GZ5+|aqrFBR(?I=*#AW6X|Z zOF)sb~he-`GPQ?jkY; z3=kN6ut(rCeub;LTvMU+0eUNQ??+He`Q4?!!=US}V;WChF!>)4XQZnU8ch&9w`tg4jMELMMxT9YE9hj#n!{eZob6FaeY)FFeH?Tk^tzTf(YiIND3#k&STIxTup>23-i4@Iug*E}fKWY3!-=8L(Fp4u`Ah`i zJAO;`>`LJWco+~j9ZTGc<~9=faa^Vwg*B(5Lk^wS#I`@ zZUZ{+ind?HXU)xLCp?$icC{6A%&0`Ps+R5*&68vmTfRC(mym6NARfUT3BLj4RMjn~S?uWs?4_6c&_@f^MMb1@6_XWK zJR(9uk_!D`3ib5;X~zfJklzkT!&c}2RuUjZ1;HGGh6@%d-}PK?K_Q_f;CcZ(gI5H? zy6vK}Z5gQWi$9w_BA_b(+a;`8Ac+I$4Agqyx`hXlA8?2b<1F|@Am|n`Ucy#=6?MB$ zlK~zNH74MBc?&fEJA=|I5F$pwD7d>j=2Qe|M9ANw=C$-#!_Wpdd)XSnf zfVq{8o&69J+CX>*h!*^v5k7-q?uxCysaH2K3~a-?s2z2>Sm8^-xS>Yx+hR?Q^7~C9 zoU(M}ayU>KW4C;Mo*l{DI{fXxh>c7p$j9f!<$qClHtfHEChtWpZ@tA~y~x;2E*^!N z_k{jxJ%`iUDNyx#r`fv1PJr*P?<&>xwd`Lbj(?&SKdon6c-h^}jZurf$N1Zg8Q0jS zz4c`0@?6?Rx0Sn>=aj(V?>unLGp(VPVjb%FeY3D+QxN~E;G)9zlw0{@xp4m5vzSxn zaCGIB=R}&t4$@fJgf;0H_s9$G4Ck%f(tBd%wh|+w5~fM~GvQXU;x<-gM!oz|XXizd z=Pc`}*{Rc!^k!X7m6xVxszCogRx|>!PGwb$DEl75t}U1 z`qL++nE#^Jx_-#`A>CaHV=yqFBh-~&@@c1H^{sxy4J+@K&EVyP%%$1Ng}NgzQaR>sDZ^&|QLas1l{mfjmV3J({*e7Lk^2)|Hg zmuh>PQ=|5vmMoP)D>#o;$@1w94-OWC$YPQeOEO2Pc?h}&zw5k4ucD$ybLM9hXO!76 z-H}gE#Bs{U_a!C7YSOIax^aEjkzSUaQXRW@Vy2Yy2`4ugmHjj3yo0HS*REMbps#)u zz!3+~)Kx1w^4Q%*wZc>Ao1LFaO68hUs;0RW>>jj5hZ7`?l6-#dGQYsCM1vo@_TY7ph;!18T6?hJIA zYOl&5@9qr(<$|c~M!_m?iLc|EE|3eoY1?J3UcpHb4?=(yNV8c1eFX>{nEtrJRq?}) zU-VP_3UUzakYIs=r3PZEYp1c{;s~(qnyeR;Oe|;%|?}bn9e;XNzZ?N5yx?gzc8=4D_R-bZ5AFo47W9hlE>1cO#>* z^LM>dbl%{k61w`kl5fUk6}W;EiyQk_WMRD{y=`qbSJl_$jCHwz_?1GQcftaYyNk;{ zyVK}j^p&Z_{k~madi%CENjJ?D2-xfg+|q@Q-hDYD&hV1#t^6OGoYP-(RqCQ-TojL@ zXKdxnqPKBY%BfQuO-f7b?KmJ4Z+9 zKsx0kBFB;{Gr$!tnXgMPSuQx(IV+n+BA}aLTm3zrgZi7%^+q#RlMbYKtCwlw-Q@6 zxz<;YaeLj4o~X;-^~3zP<{ZkA^4wXG-feGtWVr3gp{K&`r2M%m({u?MA?hZa!oYqk zO`m9`=~$QN?Yg*3nEnl6_+ueDusOj`Zk=B z)M{5dy9Xvk=(4G>r1pBE)vl1_{v@-G6QA-7@2^nv=-&DhE%aLhFKumltWp~!Uu}P0 znLrF|>9rYaW?d)^%r^z07O$DVrNF)nwR*haab|Td{u*$w4&Y}qGyXDlb$tt$C;8A} ze!lPP|E~o&zlxybW3ack54gQtKn#U%t&(5tii~ga0@DH{6wU1c&5?KTnKxV`@dG+Y zagdh*oE+eX0GxqX#?>$#h{xo?Rlu@f&j(o#z_*$#J;0Ly{*iUR5=xjML<{o03Oo34 zz81G*0(b~NAk1H0bM>I_{`oTvqmem1Z=iSz5}}}rAj{AOymcIHSNHZM8>H zf`dOq)kjC204%acE=zBTs@Qo17$e~oVW#2vfecNPt^olb=I($0{vEzwO#i2DW+LXj z)L=}8&K%(Xz@iGzOOoO>vaPdo0#H46wOLkOFztfgCxQ?#YB1On!KkHY03Q;-q9EJ` z7$!i4!21R=BoGUXtix>%$8{C3dZ7Nv-XX{qtfv%X2Va8TLR=Kp%O@d9YUg-0@p}2 zKJp#S_w~{eEcBZ{et`x1*TqJKhgc5>%iqZqPYlC=3E5h+!{VCN~#ls zf=+u8Xt+*r7{WUN=@Z}xRaZBQV_xk>s3K@+nhr%Wl`0zLO}`Hh(^15~krWR>Yw|c@ z=p{pZ%zS*x#+1(Iwog(TO`%AEjYOK0tQ+2(&LvLJTKxR^6Jfy}nEK2HA4~WL;58G7 zQE4#(IVcXKKxNRG1xfz!kYIZ3$l2cB zh9?CpaYglGPXRZ~SqFYYPXVes52+JaIc>ljQ?3Y6HVqT~V29DlK&vxs_PGni@2Lv1 zwVrO53W3kzhlHvNmQ?jEx1!yzkfa9Nvy!rM`K6+8E(Wb6_m)n-;d@iEito?p?}EJo zMmQGIWVBoO{GnHa;}rsN!EVFia{{&%oC>>IeHQ8>YVXZ4283@DN6LXe8$hzxenQT* z`XB%RN$j)gDUAXKTDoQkCM<+MIay`GiO4esESQ$+PNi6Yt?hGW?H81Eoc5e#?VNb< zHJ{9b6$7cf=%-UXXgoE4g9;Q~8@wHhRx?|+5e&-Z?ySz+8&_zIG2%;9rFKrI5r93AjItTJqhBoMzM1S+c! z5RgzPCWT#s!1(rJDm8luQ0A+Dec~9Qs~oNW-cvLK){giDebf%O)I$_Acu+kgG|OH|V=v z%Im0pq{qIhM^^n&_|uZo;ZqilzemHlV#Q)lX9Dl!5hf0YD2W6aghrpUHPG{=aa7$q zh^KU4{wqpOwAGEKX7%~pliO=xGNfqEppT59FEHyVn(3J|+QZ+2VZDMo&pq+!AKvG7 z!LULLkwE%XkG*EXI{h1G-<6@~Gcx|*m}=sFB;i;s1F6Xn$_mxcy;GhHv|hH3BJRYV zjt0@q>QF{B-?;m^kL@#BJqG?`L1$mIQeUkMm9&d#n`&yhRrCL8=&w;;>Wl+g}7FU zl`O?|d|_o;M_C-hCtgR1L!HGKm?%OupQopK`S3^2bM%1MvQZf}bK~CS;W4+h3B|Flmk(v~1Um6SVM7E~(9F%iiAgUHAMg z#4N){ZrSw|Z|tPlFhcmMlvP~V)Rrk#^iA*Ik0^KKy{4n`gPf`+EMJjuEQQDjf3?t? z?&d%W^FTKr&|+-w_-fg7GJ!1MKc|8ozvmMB+b|y;YuyNTeKKpeo9A-fkzJbX?XKmv zO(>CtL*E2zS`K~*bvHyle<6BLMNODY?#!pe@a6X0{aJ=@C&hu(k|wnGIR{_R)|_pA z%COWMGpxc7yo+XqJ&w`k!KwUfDNfo#p%!m`CvC@V@{X}?l6i?an_%DQpH>v?T;YO7 z@--x+AkU5SKMNdHcMCY~YpkLjx(Fg#lKBN_pm}F$SYV+WB&=L~soK=kTPGNT)?0eXEc~`MW|Cvh%l(2ScX4S=It~M4$P{VEYw9%79EB5^Ka4Q&%Tv?|z>frj zk;8*%&Rfj8>Bq~ow|zd>gad?tf&`=R4=292O2ve+Jti)1;9y0~5A>o0D>M8H6S&`3 zZZYIk_{LW#~;OC_RsxLM(;%{@{`15VU;h zpuv!T;yrx-u-w(hNu1T6-DCgAR<*d!!-awBj=7zkLPLgs7B<~Pk(+R?T-QwnY6wnv ziiU?yA}`mTwNd#`5Cg?G%uWnf?o01pUCkPb1^gpK==7ty{%z^By$1C)LYOO)@&2mdbIH}1 z=|ktt?Gu%ee6#JvZ#< zo5jt=KHR;K1p7f)>~(z=Nl|I82~!&A>i@`9@T z4MCJNXtdzo1=1P1jLKck&dv;{=&;uT`KsO7*uZ)#FVnzn8CQPDLX5*M%MysBS$!EQ z(T;AFq*bW}V+(Y162N0d;#@OI(d^kUP~b2hx}Rr6GVw-!Def@xF#Y10@Uy)rZ!a%{ zbCq?qti6S{Y7EtrYhVLk92^gb5P58Uq?y3@_Qa}m{DrMT>G;OkCHNt`x}peDUz6vS zmTKs57x}$!>M3eQ&k0hB$}G=!;?HJL8vOhTCJwmUfmjBkua0;@Y4RdZk!E&;`+IuMq=8yqxsOnWoPA+L{ZP4*v6bKuz7aEbGK&o2@fC;?FU)&AfBu{?s$L%2pWXN@jUyqB^k>Sx( z#4iIB2vH}9gl2Gf!vqYTU9czIV8n5u-$P`he8CJ5>$<)?>kxWYIEt8^ppRjnwe64< z3k?Nf%tu6RLkckB|Jc*uzK(eSn-of>7fvXRixvgR`xHl(10X zWCQ}?3t7Q;kp9((U-C2`eSiADFk)!tg7P)kAH@HKizAuiEnM$@PPN^v5x$-?`eZwy|JKDEbdYK z<0C5X>Eaz%qHp;JZ*|v{>+SRRv~~24IcL}7P%VQxl(iYh4~>>FdP82diR<(!=JHk}nixuLK(Q?*p8PPI0 zi*V9xC0vA<`yJ5POeGszh>_~i*sPpMouXx!O(ap2?j-%u>iAOcJ7A)YYN6lQOF&Zf zWVbchgb}52|M+5Qm{X^)?l^JczM-p`RD+fU4&i_1CG&>0M-I`E6CcpfHg=V_#@&`x z*Xm79iyC_zUvU%VV75QO?flgK3jMn>D6Fa?tj6tbe$Wi~U zJlk(Ky!7-b4$8Y`(%nWuE-aL2165@G2SEzY9CTQ9G+%jfJ-u7hEz3}#+Nvh{ANocP z?Qt2;69wAh%9t1Lw*>0u9Cw4lmrJMEOU@?I-Yt{w+UHdgenEXo!Vi zSbDw}HHFMYv3iSgCu32$6AwXZi(&>2V@--#2KwNbq4Bgt=BledHa^+-WIydhqwHW- ztfC_7WEl-=!wPX-rP5p~M0|>(VzC!mP7Xz!N~az-Tz6*7ua`TXUUzc}b}kXJ4R*rf zfk-buopD}aH9p6I1sS$#u>4;ySuEWA5D0-iT8$~%gp+nJ9_At}+IumboOrPNoxD4Q z9_{~NM^rD50KMKHH$4dCfnT1Ux0^j+SiOM^@4kfk_6(|#IyPL`GKZ~jp*lv49jPnP z=`NVcpqB=iy@U=E+INBDGHp{)rmR;q)Kq3?{dcI>-4s5&nwPQPVvHI0{I!P1S;cuq)wAXlMXB&K^!6s{T+6>T;bQx`bGJzt1Q9g7 zLX{!sq`{_7&h0E%fCC32Q@TEIntUS6zrH|n-01NK{NJXt+8j3jmDZTgJ zkJ^M$s^_$ST4x2J)AVqO$J0Gu?e|ZqCWY)si;kHlLsykkXOI{ceKxSr@FJv5J*mtS zX{djV>_pO;4!Sk`?;O|AAcu8-v4_;S8!`vrNPL_+eIp=BqkDQC-)>L$sQLNkd36Zh zRo;|}f26tCg(k)RHgV=PQm*!D^ug#jJ3C7j-7BOszy`BHc`pDrK*^pID1VBc@|?G&CD)@RRI8x;WAxVG z)2l91*y>M0;NA!a@!>K;O@v^&0MewM5LzdTmjhs5RxIDULHc-&RFb`jR;I!%(v<1U zEX}e!9cuvBk4sNqzZ3N9APfi70IQNjMcLce@i$u4Q@Lf-&I1~5w>DXfNPVxeryTQ) zgHY8^?0{KpNPkq!Q#}avLWozYa?dIrw`E}1u`XhfQv*Cs(@wU?4Gn43Mzi7IXnJBI z#cy+bFuut9`P;Z5PCQVBfi42Dt#J3MlsRlR3CP&;$G+Gti%0h) z*+?|@@f&CgIZI1Qh}ml3@`eO4^qj;C!gZ<=+X}zsCmKmhH$Wz8O@Aw%9U0ibt%9rF zhW9mu#!Ao@5RZ6haXfg0TA;av#8k`e7oCxnB?VD@j`l{CQ`-Z@OK`vdojK}MFKO)l zv8sxt%)!)D@&U--HECq*lmJu#5TsULx%_DJJQbSL9r#^O|LP$MKdJ5%YF9E_GS3x1 zZYY057!$We{Tn2sa5hzp0Imj`83=kIg=JDiUFn__6CaQIF8yS)E?cBiedVFMudiNc zo`!}7^f6S-TXT~m);rBwIIdtMgn?;se_w5~y1bkjARB)PhW7?&>RI3JGp){;aH=_m z&eo~F#Cj!#W90`yD{vlmE`7p{EZSDnOFC~*R%T2lyAx#|NJm~w_g220SJ^WN3O8$h zcZ0j&)n4%JzHPY^3r;e~YN92> zW8ssr+xEz9yBcikhOM@@H*%{9@}Z%l6+)J`I6yoHy2dzQZ@$jP06xi_F~X}1TdbB> zP+-G?Xs7+WbtHgh@{b_Ow`i8vsL=x(HX`r6dD-fzF7RTtPBqK@z5uZVfI~l2SF@fKr&%sR0wGL+&$u&Xn20;UVhRca z&}SyfKjIV@Pk;bCQX?N^a5?l&Oc2ip-v+{LuB58k^_eY4)L)x9dH3(%vdbPoTp^JJ zidYY7s{`>7orW->!NY;R6j1o>H?>_hAqwW1h{J5NGV=5LKpr-=IlN0jM&uF`iJ$kYCJtM@fJ#{~ONF|>fqDPxr}K3h%QiUc!?+^hZ?c@daK(7@ zNA(7+y7>?X7#hc`<5F?R%94XNv(j-%;oM$84&Wn+EMIWac8Px2aD7I0)LQA!cy2>^ z&3P8a<0&R55r@gu`V8}14tj8OPt1Oi;Ey`%s{X2@{Hpox*;^ae)S2GL!jH?7xO6D4 z87UciOdJek6X*Ma-}oN+Nqq=7tND*R%Vm~1a6~Y}BuWJCmafAQ^R{1Gv8B{v*pK|D z8}#Y0&sKZi@B1oC^l9hVTDFrb9UHat{oW#_sXg>SQl!MmHA&w75}dmqrfvShZRhBe z+&nP4(wS^qkkPV%=}nL#k;#zAq82}eaxZa;?2&e% z2qVeC*3D7e7`k`Zh?dl$5-!I4XS~F){=O%hsr6~w(6wpO0M7$?ib40iEPPk4r$oJ) zIROK%4&p~2wm;pMP&sQJO-5aK)0k7GRPttgydagFD1;%FTvHtKxb$*4(aJs zX(cMXPZZTaFL|twRlXiuuOk>%BEF|sQe;|rBY9enMk*==zEAopAFRa2N zWs%V;`O=k_Oce8%?~+5w&X28|O{)c~ov#V?n_LBWF00`z8vg2?n={9_Hmsd3gSnwM z*G!gCKT!v~-p!F82WdEKkJuHF(2F$C8oacadDm(=+pB2Eyn^$reCP#7xM3gLq_KqH zWuLn#+Zg-5q&MnYW+YFfS=eyeACXq2DSeFSi=b$8F=!t6rv1BG>b-zj%{kaZW01ruK5+%mW%p&Mp}$H>E<`%0%de#cN@uhx8%B^>vFKyX&KE z01^ZrIw?>rv}08SJWiht?8Y5F>}DNti=jEkJK~x49EnIW?!UGfIx2-_8lK_jZ0WAF zWv?l}TT<{34=b>cK^cSew~5CCI7YUvM6AK+WSssdyb-!}Av?~DvC7nqhQubX`TRRd z(MTCTwGbN<$>T%^DBQyPMnK()97?~LmRj}hnP`9!9Z4W_OBYV)BM3NXCF2JkeZ)<_0E%ojx$!{he@qnf9lcl$GGcT$80Y>~2A#XP#ddSe z1>@tUN$iV29oG7_)OU4ka^@guX8Y!V2An+MCZhrQGTp|wO?vO01>&bg&y0}NXMxO3 zvD8BaH(RoY|G5ZbVKBuLnqF?;{kr5JQp2)5j3QM!dmT9z zF^XpD-%9zYiDDI5P*|eT{#~`(L-pc^>Z0s$;b*~74<*v?WV7M44DC7OIT}_iCJq8? zE_4i(F$!(pf0RZjzwk|~g`+8G%LgsZW)^}jaT@hveoS+W)X*~-QU4HEIuvit=$~_a zM7B3RNRmf*;@C$@(B(mRYRuJcDbO-EM=E~0NDi&xsNi-N7fRGQUGBEi#=>d;SYAP` z)qU33!p#1jE z$ts-9rGWDav>TyGN?ctZw0&r>OyFxj`wD3 zsu4jmuaVA2bPR=wR$|V*KqSt)Y$81^-QnJE4G%gkca8;QMY@PNtT`SQH%(b_Yu7^2 zp_KHT{kTh=fm#R5h8@K?3>D~u1*R<@m0{P5K-JdZs&m`3h8p9w-M*E57gaKCx3LGtWp%5qngvEh%_4gysLV0NsUoB+`eJIj z`3|QZ|Dp_+Wv8{xPoI~~t1cK>hrS!F%~jOM5F$8$8nZuKdk&Nv*m;*UKFou?|G6hF zQ^ez2YwJ(+H#gx$v(yzD&7AwQ#b0UYs`2wE3;wT#esKGkQgnRPnS@B`{Q(enaLw5p z5~r$NtM%bB!{8rgn%WIOH1khpjo zoFZ<;;_RK)pt}J|glHFdC#cFSFuUkIhP1*O7%Xx~DCK_OFm<%hgKE01CfVOtittLGu2wJ)|zuF)+*@`)(h{ z59vZ5J$Muxz|N3cTKVG#dRvl)9QcyuL>W-VtiCki?6XeY!n{950JVUr8yOkV?B1`s z{G1|)`NU~e+zfY^Xh*gE978j%2vd#v4`o@SjKrs2Osdl$K8A;x)@lN~1Q;KD8lo1&arlQ%3d{>lWI@w{_=r0t=w zccuyTdZ6C<)R;q|TEKr&pmxTh5Kl06Bz84p~$#2apE+AqETY9vl+^CqsYvDjqj@B(kbF4Nb>D-)lr zH0xF<-;e1}uSwXP)RGEx7a{{<*6hxZBBlfZI*ukWzRz{2d4($U^>k-L(j*r{2D%;_ zXt7^Y3*2PRx{u*k^88?t5qm{YT`u-G1^WY;>7yWv8TUfBL+esmn~NIy0e2m;?A4#x zM6rtqV}b9pU&WMpc$P&n*K&U*oGu3b>>p*dd@8(olzYrY<5?^g*HCazIl6oC)3lE2 zY%Ye{lUjC`={d)nDMd6(pVa<{wd22e9dy^JH7>q}&aVeEz44_}O?rOh2%n99Dg}%A zed7tq|6;7>s6zcPqE~s7|K8U5h)G1${o+<>Q1(XAXCqu~0wOwdwKL7DDwd)&eKMS~ zdpTXil1sH2@>8ASqujXj0R!=!h?nL)st?PYXz%cI>E|j-TYS9B`aqvIxdiQblA^4f zlpzHJCyC?=dS}p7{=LZ6ofM*&!TXVozZ&n`Okj05R}wUJVmuGUB;n0yHmetsW9$MN zL5h~b>~&h&a*1axH#`JDet~IwrLc|E&5RO_0A5W@C81k^0;3fj`0CQ;O$F{QV@fvV`uGKv5AilJ+RR7&|(M=51P;> z1yh2|Y5=rBKFFZN3nqzfhvjqAg6)fEzpy+T#Rsd>^QMJt)2Yevh6$&YoqNSKVb5;8 zFWlsU^Oat;E1~8p`;KXd*&Y9?1G)fzrU*a(0%g3|1d{(sgAFPJkG>EYCtH^O!FeY1 zBl}Jtl6zKfQNV<4~m?VxOe@NRzh-8DR_kB&mzTTJzCe(llL)Q9=TL?1fL`(Rw# zG+w!X6RwcDH3caFvVm}7j0o%Y!8!V+fAHKusbMz(g6{GPCxo=Ms|)kuOv{%%^3~1Z zpE@<}O9ZzZ@R$B@ca`bi87Al)q4>B=6&of$P_&t4uz8y-iiskODLtcUZ-@-?j$dev z!Sw~>7|Y5iCq7tM6JeGVUr*lWdD9Tf`6-Kk+fbA}7TS1%m2X?w2D}?EFiB7oMs4S@}9%LWk-8v|^ zgF2}Sh%3)ZXu#!j4g?Z2&f z!pAIg&g9o-bn)jj$ISt){rMN~hqy?B78A6Vd4hm4;98!3E9d>kheJB_x2a~#;rHeK z>I&<2#-!7^=ra9h2Q9nWOs0P$`eT`Raj|EF59sP~&zwafUwm^}YZ2A~jZ>}$N|zMY z`q_K6Y^mXi|F_{)Hd&_A(e_1qRx}J>L23e2nw4YKh6anZU@Bgcj<&XX11PdS1hC;? ztsZ*9UIm&I09-g&fu>=abN1AJ&l-|}7y?1f&k1LL5d($y&n7Le;fJWIs-j*CC?z11 z{DdUG-g4;EFKGaJPP-C$irB%t1oyVS?KnJ`aOj}ik=h+7G$>vG&3fj&ZM6IhbsBcY z(B`a^mMz!nuOM=)OyTTba)h6b;zmV9=`f@^AbA!xJmq0%I?BL_S(P(aM*JS$5HQ-@ zAOG3X+h4;ixq9zzgFkVt15}DFXl+`iA3Q20=Vnd_>c=$-SQ z!X+Wo`lEv6Ro?%Iq{;N8cW>WiM-&}Ng}sFFHP{-z`u6wtL!Z)ZfUmv*e;$pBX^>}M z^es8!>5g_oG$cD>V{!3uf#B*T@!`b&{yu;KIhHu+V3OfZlz}n;;9+11Q#c$fe%oty zzeo^W{@f-5ElFw>q#9fU!=g*t-)=8;qRyM`-9=X&R=(eBw>XD z?rUsdPOg?PR-k69YqbAj?bZZL0eAmc7f0&1Tl;dP`VCw3_VsbNRLW)hg9%qsE^Hl& z96%*W(5%i8jtqbVv|LY|%4x(y8bTK}-_xbU-Slm5Y`-8iNF=elj#p*@Jc1&CR-GX( z7$tLq)R9qD=Y8p+{?B;sDW_6>u#_sW#Ep-SH=rVS7%yhAc?mFJ3Dx3=2PMYnYfAV+ zNu=Oe1v(YM7F=g3fY(M1CNF*OoknbJZEZP}gJcPlce4TC`@M@4>d8Jh3K~~9}6fVeY9N@`1qDTFsUHZnuAFwBbv)bEN7X=&gyTZ4bE)#t5^`3qN7JD3ZXk^$icjv^r8V`B8OrLbAuU|!tWQx8Jl%^ zV{U5BWhzK*^&jsnNYwE;c!D0rXbKVJ@u)=n8^$_Nvy1Mh`|!iZ0=ysLfM5R$1}?I>?lo* z#;^3&b@9YHuTkSSh_L#R{-W;ww(0 z7Nf=Ecv?Mi7N1<@k9C%>hE3M~J8kh3B-LXPc!%Bh1LKGn^W&-{Q$hOb`u%-2#?6#= zVQ2Rqv~L@i8NN@|{KI~ftW&q*tEOigDvcLe2v=#BHV6ma6=FgRm(mGQISzG~B893v zb6=Yy-IwB>&f=4E%Tjh3wV!?OQK4Br#*$_0x=Sqjqe%mE8 zr0~c7y~}x+JLsxSInvwaFGS(IoJP!^pw4-NH-(0& zj#|o|1rda)jQ02(H$qiT(lqErA+f1h!xUqd7NYXsEl)m>l*@7kS*VY5&HlBZ?U0!8 zr;Z>Yer)85&Gtf(x;&Iu8LOLO$Rdea$_Vj^I3&v(%O5R-DdeMM_Gsg-18H__uxDA6 z^c5npKcoGPNFcuTdPA`fCI*4OJtD#JrslrWEEWlYgTPD5_^xwH!Dv!~!|x^WEfe^{ z{}uAwrc=&(&ZjQ4k?oGWa~p#KpDSMRL8-3(8ymX?R*6#tj0uquOu+mR^zq$SIrt^^ z%=*EBrw>jeGbhG$RPc1VDK%%LJzI!j)fETQ`c^uwkuP7c>oL+xo_NP>1=n%HinAv} zR-|dbCKU(SG&?0(_M&|*3rU&%of^E1p9gUu5yF0V9#eo;g&;)c4mqy#Fa0zMRaE(N zV4%#KsfmW39!>*~Q}deLHrm%j_tRBPEiABWZPk3-x39Lo``0oUHsK;shbfdvv&(d+~2PYi$}#EYv{G-?MM zDW|~*fZDB?SW+q3tEX9@kQ=H)^gy8bIn&h z;mLL%IDl77K0kk=6B+*)_DDG4e;)it%?WKs%jm2Cr@)b|zw-pn==MU-P8B}kwGPwr zv{5fFFUP=+Q(GJ9SsMkDAROlSCZY)l-p7ADl4zA)w+GHi4qF6_f3_WC3uG*$alrSG zHSxv-bN z<0(^b_ScmJFPN8~KbvBkvl}GI?Pq7d95bJk!;lV^3K;wVCIxa6+Bfgr2zZtUwA=9T zFw|EGy}c3z$N{hpHqub|cLv3w5Ig@31v!!Ec=5X0+K4K7pk}x$d=GvoZw7uUfUa}Y z2u$(r4W@!-WfJeZmu=Z68 z94J!p$X#4!)HUkLoW1K9u5>yBgj|f$lGN!Fmw3Ls_#`;9Di1%q?Ck7(|9TzX`O?Ef z_K_P{fl^=|fDdD|f`ts1I>aAzd+^Yx=A+mmKqzooVRQ!9W6746D!h@G0P=d-PB>G0 z!8I~B-x>~Wo&a>qv0s0M(e`ta2?$ji-8(oCfb$Lt6}gKRl^fQ1>#(Q6=Ze`4!jIXW zWPX$`$`CBNsFQGl=k4ijp%q}~o_c&aru3|rK2}1HSQVGyrApwLJ*XAI`8snOh&7nQ zk-mSt1J41QQ1XvIK{&XEnLD`&!F(pLFCBW)LuLwi!UQ?HH8AYKwo3yX=BT8} z9kNC!iqHt2nx1Y&X=mW=!)`WbZFo+DQf&YVRAxbaEMTVqmJszZ{7;ewW+9mB)SPcs zqd;-4QsOg4`>P9&+&on07EJg}Jv?qg!ZIi~Q4>zM)ljGsO1~DWXD*8zW38yMPnBTMJFWx&UPiYKKUuP-eP0^BKa(Jb-!4%zNz zedZ)jky$IV)nlbheQdMnU?}L ztt{G3#JOgk)%f%UJ8_Bi8f|Ub=Z*>+O7!#i{*@57dX(u*q~~yW<*`nJ@S;?8;W=G;%d zD4YB4rzbZMqps8N*S2FJxG^UsxlxZd1uVUdN%UG-kx%hY2L)o8%h&m|n;t}Qjd(QO zyjL+SxB1(uUL#nZ%V}a+ctMb}am0+Xk=%3g_z%CJ&fEQ{mFVEj8B%=9Lj{C1ef!46 zfT`f`A<4)$oMJs*8IPihvftC95&Gfh_u%9V66Y|Uue<9IxxW3TvA!j-nEBFQIrn8X z&%k~CF*iwH6S?k6;Y+6Dmd?1yuf+SMZkJlb`u@CedU?EK_nmBxH-?J}O*+!{r{t>_ z+Db)-1GSFjCo$PA1bJI*Dn6S!1lh%0(_psq$fxxZCoRQ}_IpMjxn|o<5QDXVz_7PTYG_7t1 z^-*g$(2 zVQNx7cSJs)w6*goZ7T6`Nv1^8-@n{|eqgKtHp=hS)!_>ZGGLk}z;d*WSiVRpWGT-S zZA390C%b~Gc&yY!@+HcryWSPUQu&il|B^zz_dBrT!CGr9a9=-KsBb@WSWY3AhnnE? zM7+y2=*u@<@q1rkczJoDrtY=e?cbp_)%EyDojYOVBIe+SdLzUwfE!{Iy8wjm?g#%! z!6gd>$c9IfU|1_TMfly3&E55tqbc9j2oHmq3nF!igYpLEdXAFo$~QCFv65_TEBSGq zLTAl_DVrj{^v{KprNpcKt#2F|T&$3XIo9)coDA#n2XaZ~803`}bL;t!pQk0VAy|~H zgPcXemdZF^yts?>E-`#uFc4ynrN_kmsI~+}2L|(P*95pFJ-$9^vlBX)$VqzhNK`bf zl7|AXYD5X%BMXB(cltr-zB(JSjrvyXI}LkgM35vQdTBW?WsOQawLzIz2l*VL8ap8Ck6rzJPAG%Z_R&7==Bf_BX=V};`G&LIf z=s8LaD8qmU6<#o?i-1OruYRP_4>+QWa>iZ=$zJ;Js{k@F=0EA5U@g{(8RWNpK1iI+~qy-wO`#!0Fkvu4trk)dp z%79J_^BN4HUqnzCG7IV%cS&3GW`y90Na=Rh2 zMNBHgEl>{X_;NM)5$

    1Vy-tT1!vx)D~~?(GlJAFqix#n=86?d=B#n&6p?P=G$bU z3NNUcoSbY1o(qoAfHLF5h0%L-xr9&PszTH_<$sSIo*Mqp{phGw1=0_2T;4k_d)BtN z9M!~fBL%s?+NF1(WUK84W>n$!jg9{lx3{*6y6k?1Y~hXm-~=>@Ao6?k;6ZS6vkd%U zbOjWXi5kW~Cmw@BtV$0>uYs{Tfapnpet7KB)J4hUWg1vfv+Eit_MfyAXtU9zH+^O&T2MFce=iE_fyl zBWy&nRSHT?3Yt40bYVOT_@1D-p`!lM27JIeqi}2aL;B0?y5Y45pi0Vr?qKoJ1JNHq zPIs_0>>L*V?@gdkC(0SIK30t3_jLshPTb=TU>k;r3E<=*zKI1T^npbU3sbm-FOKZ41?w)Bcot9{vEnDQ7-GPi1PWEvXJf@uW8$Jo8`Xv6JcYHqXTRH znO5An0hf$dB1{5AiUW13|EC4OUtL$G?HEjCziun{XcoEqlsuJP#pM3jV1G=J1s}2a zTp_u5qN7UG`by?U+xkPzX21NIz3A}nHc3*xIsvSNQ^U!bn!vyDmtapP{hVjKTT8TVMM6#_+WW8a2{J+CjkNc{g)^7eyxGC!9pW-$%xy1P7BQ&f)(p?M6|=EeDy2WErb+S!Hr`Ldh`c$}dKaDU z<7U{dNbrWvk(o(#zNpIvWwN)I&=1vsW@?i46w;J*h zzdy*2Waw^TfcM?mSIHW&JtldZJ`H}Y%DmkHX*qO_CaR|n=nF;#o^q?qckg3ArqUqn z{joTRbd=V*{jo?JGUFt2E?@)bUgej_>Ue{LrMg11Of|V)!%P9hpsZV zpo;oT$V-4GOZVH{uCYpdNz zLDH^`xEv)@*_k5A62oW|l;@X_JZ?b8LlE86e&Sc=S7PP=kdWG^0olB~Wx8>34uh%LbKPSjjSljR+I?`JK(b$*gD%(3rGeEFindCZLW1h8Jvxe3}DEo||* zRv;@q{L*`)NpNTUg=rdpjQ0JiWdPKM(>zN}v=q9O#{cGxg4T!ZSgSG9qGfr@zr}-= zvvFz?t?-MG;9zZ>*KVkJO=r+Bf{_rf;Zr-}vYH6J6Wt#H(_m-j#2@x%pn!^I49!LQ&8UhG`B74|_FiBjhr~7lI z0ep=#Q?oPiwT%d(H`FlQWb)6!CT93FZ41p?=rLjU0vi#KGyy~c&OpC_mwFYU90egX3;86RF0=~Lz+SHlh`OGlCS3!6@V_>IU|34B|~7k%Vj?W zW(@F68BeT&pHtCZ@S0e`YEqu?Z`bTWHpmarE&LdOWi^2B=g6+a^E9xr!8cir$UkKCf z0DZ3RCWs!^TLqBX6?{9v3OGZ+R4|XVr(C+%8awh8Qqg6XxPqviEEMe5!BT<1cFqz1 zsJFMZy^Z1bT84tC;Qi`HWtQiYKrYELkx24V2N_cXi$@~;Nuz*?A^Mv?Y>60{{{f%^ z^alQ|(K_c`ae9%w^?%&joiK^P$I2B^KFz7nL?2-5uQ4X`8?zM9v(bqj1~9+q82Xh_ z-e#(wO?*)|W>#;l9+&OtC;`b<2N4?XkgN_-C;&!CquceZ>;z~~d7a+-#4!zQ1r%*2 ze51>_;$k8q8ZkFVF~t7*ZQS^Bo$Gv7)pyYSs5t!TS|VGn#G z&BPMVjyb!30ArdUa!bl{G39I+o>stFFqVZcK#l-zvY2+EDgmRyb{bMTfMfNyN^##? z#DzBlqhEB;LxX+|s7bg0M&{<2on{(kFEwUUq00Iyht{yY^UjW!dKQIo;1lQ8|Ap+U@_fN0tN3~aP&ODqP^D#XV{hqE3pLPv4gmFeAZ)n&!W#pgq%3tDK#{;db}gOU zs6UatSdh579nknG0HqJfE?8A86Tz)9I?HJuXYO%{pmjZ&h}3c)Csk{RljKx0%eZ{~ zch;w99j)^ja%v};pRb1{ZM{#T{v;zsP>^ae^L=D!$Ho1>^_-%Qe56`%&skQ&4Sg${ zKM1ONbew8uMGsdop_iGdt&ykjt){0~UH@7S$#C6d%gbCKFt2JFM9&-{66<}=q9&v$ zkb}M;Y3Qi0N{7!ieYGkwt!mffnO0lWtrrn#eOii`_7JY?Y0GY5DMR+Zpl^E`6UFdA z?CQ#Scm+KpXlDXz>^VYXGr|@ zZTq##dr<)sl3@sBB6pKAkv$qUdI@L43ruok6|ZihWRU=_YmW9M_(-y>>i&JXiEil!H!Ld)-E|JSbLigjQ)U2so>?Y-4b zs83EVafW6MJC*BXvw>%u!2k~7OPZr?EFzZ z&Z+aC(ph#ni(+pRdx-=0490PHt^>7rCqlb(`z@6}V*Y>Fe$plqR{h!z_MN>w9hkO` zqkDts@#2Ha+akZNJr_0;H7hmq^jk}CV@ z^c@OS80qwclyZ)`t(DN55|l9QYA2%aj-}6> z3X?h1Gj(M=x0H{&$Nn+#Mv~4O+4VZS(lEWt5TpARNKfj432~ER@&UrL zhyZcjbIS(ov)jG)#odE_GAUoXOV>3E6Ldt~Qd)y`MC3!gov#Jmx$|jNR5Po4R@}Br zT;E1c*9t~uvp@gzKx=kn6?&Z~r)sKN^T*1ytJldR=tOx!*O#de&gq;V{o5Q+`J?=; zZR$c`)R9n@AyiaRm;f6iK6|G|v`R0-;B5madQ)j%ZfsTzzE+r}NIItKp!{}lhOJkB zl(f!hQ{t-hvx3m`i`DtypZ|zr5_vE;wp`S4)D20IG!iky!t;Ctgc<8Fqg9UzWJE$9 z=nwkBf9dv)>`RgLD2rmk}Pw!lA9W2HC_kMg#>T||q$%kMg zZ}Vw!k%I~MsaLM$AYwDM^$iInX5baVJGbA@BHg9CQFt?zI+bl9n&54wNquTp-7O<( zd(A90y5ek#*3a@)WS&NNxVT3X6Ol6>GL*S9#&uCg$LBFmtXb5S-0uDPufV*p+ag#^ z30;|m^I3hAnGL5JnN(i>L}ZJ3W(%tWlzqZpk+G6at^O)8d*V$LntN0ngge0hgyT6F z>e@?0C#=rv?B;7A?jUL*$+7eC6GWvd_!ZI zP+rLSl3ZQwPx{v&$`^M!w{IjT6a>y6($6E_{4#kwQax*b50s z(C1xE-^!wQma}fWhR8e5+P+$^WB0k>8*P3r=w|UEWW2*b3K_pA8%zBE8T=63V&3q{ z^$eYXJeC(mX`o{VH9(cuF*o>aa0gO1UuYmA$%^AWc&S0S*DF@V!*t^`K&j=`1o?6N zeJhg0A0z=ekT(m2s6eX9!Y?OZ-@m*hN9R6$nG*elFDv{8BIltG07YsLC=i-7d>H=+ zqArp@_E2H*zXV{QlURyBYc+TmU^%45&XoJCI0|RKJpHQrnBDwOwF3N>8?GPnxaJ*8 zrfq3o@EF_2$&#QQxr)%kh3LH%N)K_?CU4(nf-M%~W2uy8xmT~ixB|Pm_P3}wNFRg+ z2#qz&%>UQW<8cc@%2PqJfFw1#cD`95v=362GN{Tc)KmfpvaHe9ySwd-&^p@P%~Rh4wN{pTsbC5H z{`04)oJC>{;p`=h?TA5>=0VgM%D0H#?GSzbWuj0rUG!1NrP%V_3yHZ~wHjeMy+ zbG$1W4c7^pyX2tA40`aq#ruH-gle?+`v%4Gxf*jY5^jsMDIQyxcALr7DA?Kf+5ZD> z8fq1YQ+uii3?<-GSR3w(iP=c{sx7UvE1Gk$sJv&3+9OmaCJ7_B7+eKhrT1ap)_KAeWF3;90tFCg|{$M|JjoeEW4$I#7$Y!9Al&xVwm>k49)Iw+Y;<@}NS9Hbj3 zra2$=fhwyhO}-d48Ze8JwnmF;=|{GUGQO~C z@niY4oh1yU6m@?HK9&YQfJyRW<-UKNm+e+pzWOMZr?czRM-S#j{R%bp~p z$9U)??m*Xf-SDVCo_;U>pvQGqVM-25&3k?dd?&>vDNkU_tdxxCXyO%${TtvXiD_K_ zpiS=Mg_wAhxH(Je9YabI9g$4tPpug76R8~@d=1@1E5E41Z25(He zlWMm`Hc04_M}B9BA`j>RktwK1i6tT!qo_}B2Nm?V$g~vzX-?Pv#J!l*fezEXk~D1c zpcO9w=gpcsw`yPOLH}>nQ$Mt;KvGX0WHKLOG<1r@(I@m`KxQ@OJw+}_Y2^#%h-Z(` zin6sWl^t9?a1E`!mq^%xn_632hZ!=61_IIC4t+wzG6zerJsT8=-!tW$AS?Z4o+PN- zHbA&9rMh9-+*EktP4x9-*Cm9q(R>CuZo+CR;HoP2ycDjzDw-&cEF7tQMR{|#CKvm$ z;LAXLA}@98hSu)q2HqaAOH1s(YJJ2n7m0|sT!hCl#gN`NoSBguRlXz9VVkY{#yAsq zot~+@i!vWysNQH}_+=c;@0&FQSi3MN4JLoDl5N|(oMw+C$PhF3RO zYe=}*xjhTb359%mLFalKx=?!!dnvDzb$?+-I?Z3u1;}{ltwyFhD#$z<{FlJt+Nj+MSoh@FgkF;Av8R zr9?vlS?=*d$D+~v7JYY`aLRUJM**)1syq^l!eMQM9mG!1X^lAxv6>+T1k(1MurC6A z7~)~(<@LxZyL`}cVEvH54|I_j)Ci>wCsDKgn?#|I{}7jGTVXB9{<$BdN!#bk6>m=P z`3GRGF#39QQEDirX7U4;hk|ad20NO;s%tft-wwDJ(3pkPosrB!UHhn@%+3$6@@LDS zExyB1m#_N(_4Wd%q!4XX)&&w|V^v)P14x^v5v(Z1sVtthB}YmH5OUz4i=s?x$vYV< zAi`;Zo%B6_V)xB*?srnqK;dK>`4oY;!L6sj>-EF~)Be^H;C(4}^YL8(1Nmy1%Ll8& z?}eaOXs}?@b{}Z8lRCSG;BuVq429w`{!iVII{;=ks7ez21$r2TN}5tMc8K{ObOUo9 z29~g>=puYi&_Q?bV}=daiPvQjeZjeEW_EV{eqZj;8$0d$Wa<{aIuNEKBHTHEeHS!q zAVEX}Uo8X6SsY1nUH93U2&DDWKC}hW)#gt`uks6y1o!L9OlVZA_Oz2E8aY(BKeTRe990hCnrzBouN=?VPOFU>yV~1yxiLQZSkc6HB7=F%ouh_ zM|XEigw@`VPVrb|x3pE_E#NBd+v5K;18M{3h89f4jOPD)#sT(3(`HEShu2`*_=(iU zHdMUU2`BAA!CoPhZ+`1HEl8b4xz=`lB}n*1+(lYvkk@ zOpW6D0WHd{YObuTcq}Jd_>thSFSN|ho7|d#_XEFaT*yDQ$Mf*f!CmJB#&ajNHE$P} z(RhBPoU0uDKaOVyRvA7=I{Porq;4AK7Ek~AGmpXpT9JeTUXir+zVri=l(G5mc1y8(Ujw z8jY-;hEC2{&?f%;^{cD@?UfV!Sk%xB)_x0PV}H0U_^)6dy|bKZ$1+Y2!Eq-Kua{>~ zrT}2dRI1&fi~;HsmLSXzrHzFV+TTiR+cI6a!%$*4Pzbu8?96GsB0Vj*D3`q(4@!{lTu_Z_vg;ywsH^S5(e(*v#d>ca(}C9Gklrgaw){5 zGxYJzbk3o9SE8!SU5zKuHOZCZls|Oi&ils&3!M2GLRQBjSR%p&Wz)ac-zY6TR1^Glx1J@b zukT@tPU)D)gP=F2iox=WUH9#q>+7<2#6lZfcJ#4lo}U=}o=dX#&)%69V%Ti^&w{x` zSqH)2#D^X_?vv|B^LZCz-f3N-f;;_7oCDK)LXr}HtIn^(@7>?L6q>kyfP05BR^QH{ z{MqNap=A~}SyNB4-@l0PN~Oa;W71nvFjgIgmww3>P;vJ6bC<4Q_GhGik;$|}s8qyw z5^+I#W%*8mCYW}n+4w?B&w?=YBzwp6-w^x7`gxXDKGP1o(P*Lzk`3eUIOY_;hm1H) zeRgub3+VIcn3{c5z8?@#p7^dif^ksW*rq7Op}|>eRk?lBWJrin%zeIw_53^M^jf7D zHA2lDpVLGAMemwKqG6(XocEdsf;KwRg@5F%+%0&e7j!-))ldsO)NXX{wLf z`)uJ@85O$XUa89M;I2wE)*D(sO;;4x?zHD_%Pj)`$w;F!VCe5&sKV5HXxFq@^KYtK zr+>Mr#K2i>UzBrF6IXVfWRV(4?p0eH)Pm5kxfGv>rPp#5y2;agI1nQ&`*L;Cr@ADp z)3Y4wTP=p=LWuod=w7F|(jQm9sAX>wp-!39QyL*5Au*#H<7jSbPepgw=o8q8x)$Z{ z)-XkXoBl!^t=;p?@7w2OGJw zK%31b^-BwHllex6#w{KeXq#An)j6|sef95p;rH~T8uvqU1NYOrXU(M0ws3_B)eAE} zrhR)3l#@qq^!+RqRVsel!t?g@o~?IXYoDv%5j}Qmewj-D z3&vWfG@89EOFvS-$R{LK`pUMu++BCb^4{eNv-d8F|Mu+L1HB5#?T-Ah;6X$;{g*q( zE`r9cqE>B0=UTx@(B|=VwE^jJfF#oSKv-mDp9{=Aw&8bGlTA$ z2?yntho<9|%(od}?Lw97Q6JlCl-O2ucXcVUV5F>gfQEo3vW*B6pH?>}Cyg<{nDvZ3Rxa+{( z;bhG6Gq!;&zcRKocl0%6nSdlB&mo&Vu2qk_9j1cz`iW2`)Lj0#OwcOaTB(!OX#CTg z<-47kh}fV)*@I<|3^YZL3=2t_z5fvJ?_4*%X1R4na$f#ciQ#eP-b+cR-Lacd4$PJ- zYLaAR6^O?z25-uR$6N>%NO%QWfbn>uXw7>tE%;KWe&*p8gH3hJuk$#GQ*tOrJLSPT zx!oUjmH6=^2$B}Tc3k)X1S!kGFNPA_m+pOZ&SW~aA+^sKPuTp+%QatDIJSOMY`oke zU#obGP$^NPt5m*#*kN_;*H+SISoM=9rjU$3p1geyvUJT%zk)}(@!!>|ShrRo(Lh<^ zmIo&VUfwj`x0Lb7(tGR`B{*R(pBI)noTt7rh;vPS6*?^9ta*<~W0DHIpx{D&&bfAs7U|MrfU-mB>NllksFx- zQrvo1_S;z`9r^BQ8wVOmxGh4HXa3fUJx*?(T)J9={!*SQ9tVJo3tP|Ew2EXlq}|=z z#{6;+)jQBmD z%;TB2j5y~t(c)(~GsikFU-H}f2aj4qizbR$0lVNxWuZ;QBovjmR`y@a5x?yKE)C5X zh#qh-pqz}`HTy&$&0YaGfFu>Wgia8YL?>T0eLj#_d={0Odb<3uz7yt0`0>!kdmD-e zP%)>Cpfsp8h=%g>6yIggH|ar*CX`bkbEW0#r>FJl+5w!QlxJ~}mQ~vd!gT_Sw4hKD zzmq`5i-w5X(AX{x5njs>mJhk8sbH48+LgF!H=Uiy-wWlr?!UgAp^gkWVz5#)%i=wK zCChz{)_ycRrp~epxU*qTj-V3 zP2&xF*E;gM-4P-VgMC`R#B#f1l0zSlKbd>0DV(LB^H5OZxa@NM{e-BoFqup4e=~y~ zzZiL+TKH43=KMdJzA~z+t!C=G%F(%m7AgtUkVNH-GF z-6<&@-@TuAd_Qy?&j9w?YcJ-!=at2=%%bcoxw55%B&}^6Ml6&_7U)W5vUzXvTba0m z78qn#8rA(N-#1r_%n+chiEN}1-u$ETQu|=UgB^-jXyMV)0_ah3edEo%1MBUKSy{vPWzYd>B5H#yo?C zXZ(6RL;cN2AKyRGOXBE8_o+JgLWQpD_GvSG{p8s_hD*GlCtp@9Y-9-h(%B;vf8jmEZRIdi8@pWe@LgdN+$ zYZT0e*eEHJ|79J4JWVjyxX{% z(cf#Go%o(J!@47Tr<0SDA!M6x;e=sqX_*K;7qB2&eS14G_hw|XZI1ap-4<%t(*tf# zU0LzGoX4c)Y*&;h-Px~C{ErnWI^XVJQN4+}BgT*C??fg-F^{`%kl9RrSD4X@n1DrP zL3p9wYJ9a^GWX~F=h@Bjs&B1x12mq~o;!AXG_Ci_pR^-mBXlrnX_pqC`z1mFXUZ3?ABEO)Ya8@U6}-2 z|HS)dKev8SgX=bpe1l2Ex$xv@3`w(Vi!f3LTNck3?am!>cvF*;)+2LspJ(TCe$K+* z7C(M=5Bz=b=m)-tuuWBi`toG&I=EU^7P2~-$NxGVjdbqV;&0My{k~s*>>eRkM0de1 zm_W52TT2>wS1pbuDQC%1ehsa4(GNHoSaRR(RDrXA zOTJ^9GzridISQNqwlS(dJ4bt?G@08VC&|;RV;_1zS=3imjWLfu+o{E7Zc`(gCj+I& z&2t0K&jt#qn`_1tmd?#ANSdlIG>e?4CH@6w4N++YElYDInmSthx97R{#Ea=or;2%% zcQ5)7X+~BhPFd&rZ>p_^J|(fD;NDA@J}!H=RIy)l)nT&L2EDvloe$g-L)stRxIwY= z>J!ddRR$Dnpz5KC3nawG`tDeM5TXCMW)0-rc`}I+FvI|L6Q@oT+Ky(W+!!Sma#`l_ zQ)2CnIxA31Ja3rM$xcQxZxEG7uih=9Lwy&*xa3D*RSV^V(8&mePBNdRU~JJXg|mAX zn5UrX!w8^seNOpOExx~VZU6LB9)6j$h2H5mNQ3~4Al6{`76LS^XSjhJiYN;XR6#I= zKmjqddr$z9^vg&pX9x-br#JMDSr+agzf@>Mk7CR!1~?>Vh|GCit4I^aNcxarAwj+9 zNx=xnS=CvHAkYBRC*WCllBaI$>pMT{zwr&qiz-Zee*_vHV1{@ z{M=jy@`WZFaSlH6BMNu~75%ZXwYR5yn~0KfFDnHJ9o>us z&EN5W*%4~Nm$B`HsZzY4hOkxr1q%@X{1`6Ly{pOwSW_dktWd2HZLVWhXKcKvP-=8eh>(Haovb~2@X`W2}fv610n>( zG06CnZ`c8x`3^2IkkSGKkX-|~SBeAZfsE%H_n0pT=1+0yUTFV0$6lE8{89{r4KWy?>IKTj;w zs~%Lgo#I#kT;RHVkbxsTOF!f*l{mEx9`=!dgnnwFVp{xW!qyFyanbL3X?S zL?286mJ_LMYmoAEc}Xw(?%OoXw~&EiF$J8uCQ3uH+q7P(mWZ(Mf~DjoIaHJ1US-}^ zZF+*$FAgS>6Tmo!usBf!7=TlLeTCU_uWtWYmnxNLN+VKeos ziz0p-?KX!-gvq2|uXMe)vy*f)O~V){AuLW3st2pA4&+HeAsTo^pL38{^HX%#6_zt* zh&Xq&0mL*pH)jErTQZ-GW?p5Ax_&~G00R-lONIlTNlPC{Um?kikHC`;&ONa~@D2yT z=YhbBK>cGpb+Fo-cz!Kw*b7Bf z@D3pQ3qkt9rJWr_`u5FVdiqAnFOE}!!nYGWc=663D3Ocw@dv`JpCV^WW*5< ze0s>2G5b#asH)j8eK`Q@1<`ZLp- z&%A%r%?xE#&ICjZm!)_GHvKC;oSZGy(Uf}XxG$o;`#{*^xHZsV*{A=T@1)lw_rS_o z5@S4U{QZD!=;Yx_^^`Z7rq^;f zE4)b9#BNU%KcdAa6aR4CaERi!)ms#}oUyo#k#H_aRBg{p6YSD9@9$u!`O;@?yhio- zjkaTWjiW|>ovkjjWOMbeFnUyPw6qZ>KMRWRfX4(IUH#@We+jd?q&^!UH{5q6#6;pU zAZSm*Lq8*S<5tytMJ;)+D?e&>K;}-bzgxC@#EKZz=dkUk)OfrooUVQU=*-MDq$lP# zkvjjZ>HEF=?5RTiqm?M18HG?)-|Rsrf$=BQJyyQtyF;Ii`OjCEiXk5 zFiY}LgilOwCq+g|OXWCDLzNx zJU5c+rjBkk7EWn@E*nSj;ovitPU~SbyHX_P$*19z=f2H<$4G+G870p531__gqY1fP zP}T-(>m1zuzgOKCz0~u%Ik$V`-Pqkxk3mcHy)bf^#f!l*BihHHxt$hcXYbzzjZO6& zhTOs#%VA*_CXrP5?*SxD{8ei8($??)RdGD*=cYjSI{UTmb<_R0R>+ejzLmBe=~Y}^ zW|;H|NyhoN2TH6|LMYVRemOahBO>rrgh=s?@16xFDXNVvw2F9W?J%d@7mt@Di#{)^ zy-4K>!fo?rLi@#1X<+{M+8Eh$n2T(AkCp;?Mfi-d|L*{RH9>vVYufsCT>+j!B_eiL zNc{9kVTD}SE-^;S#jMQVo|4x$x4Rzkr;dyktH=e=Y~!D7()w>pEp%qh6deADTRy%t z`#r32zQ~=3|O!0nyH6zjkKQO4IgQyoON6fWj0zW)$!FtcxFMP}d`)ys> zYd@A2yaWrE3LON34q(cEq@0kaLrYd3#Qh=oRp7%ew^Zf@)X8Jg@{hm!uotAC%;9ZvkW!X*s+!E^|tzy6*V9|~)eC)XX z$5s&6>WLqNpK*1xQ|KI>S$hR}6PnfifAr@BYrKO;I136=Ron6G@?q}rAxX>5ZzOevF1GXN_tFBa2YInggAX*BAeI-p19w84mN2CScN^P^1pM8S#GKA7c&y2h!S2 z`s3#O6g-lWh>aNp8y#bCJ3ykd#-2)tdCwY>;N!3jd}sjYF#6QbVZJ`?hO1Yk85Z%u zTJ>;x*KKlon(u=6WmN4$JPg$O*)n8NYAPzGDRYU;_5JGPV#?MIoZK|BF8oC^W zSKx-3dV9|v!)z?m79XDJ=5g-Oq9C%m(#sVY)w$|=dCoG4OQlX)cIQbpDsV@^5 z;us3oA!YD2ASHplU7IIQEs?8d*Nyd`r;Cf3U;PIeo4Jfej&AlyJmK7R^N z$ywtdSf{X@f%HUhGw_OVKodY(f>*z}X*8bpJn9!ZpB(f-q>h8qM!(4?9UMx3=YBr@ z`D#5@O@e3F4zM9$C!r1um+l?(jzV1`x!c!8hpw9&2?VInnhYP)v~PfRNC@OMpt)dK)F1 z^yIhO54#J2PDhaFEUru5iU2dW1VC2sfBKHGUXb$uh^Q|Jf%`$e1j;I~{3E8S3NR%ZSyg37s|>imOw}8yBxY*gm%o=s!z0fSsI=BO6YISFwfif_+4Q;EjGAvn zNuRT09dn`Z^0R~~&9R?YgDRhdD@xOozlK%b-x9F??*L;=xa*CW@|72vd=G|-cUX{j z_QvSEW^zZFaO1<}9E*Al87S@FzP>pJFQig!C)&Dm9U zjA!tMuVqD3EtbXEpa0hr^=_E+$=0woQ7kt9qAm`d();(%it<(h#q*nKoSw?QVaBb} zMx!{QLK(bBckXwk{{9_jmR_X8HLpDNzIHbXdw?i!nN-ktKyY;5_`)3mE6perFH9t< z&U3s=DuFptSs|5MGUPvf^Jsj@R)dmC+=PXwzp_nEXGB8Mt=#72yK zS=k=~P2IoLH`5Q2;&kqZruV7l24Ll-PYf#Bmv*99ei=oJwT$~-a@P}+_b|J2%C0_I zqz7wK_@1GFo_~pLzI2!4%WQS(_o^$b#>`ua*Lf68)|T=`I}U3p;(`;-shaxFDJv$s z(tGh$>l^;Hz;^@^#U++3v+jpDhmYccj!=5S(&dM zZce;@zNC&LGmFWnY&AIMP5r~%DQ+l*HE89jh-#cmjH_}_sb-%j2^!Di)D?W{(`1w- zhAAXBsym&;f}9FJbe@JDSE+|!N$KX&P%3+`c5Iwx;&vxz;PE&TmUMwhq2Bb3qGuN#Ii-{wAN#FRtFWIK}%h|aKV zV_5h+(VF)-gA@HvPF8)L(y~aDGclttqM7CKETiG`zEXbozpMXMuNCjSJw4mcQ9Ix9 zNbScBA0|L~C0?E29x85)H_2o$&WMRrih1St>T9pVs3kuYH`N8sos>m7BW}@L$rwP z4d|H<2vE(aaDs5;!5n+HRod!htCh+-veMM)WzU9==C89D89grzV{D%erLA;xoi#Z- zQZY|8;p;e=XHv(w-+T$vsQjB~+eaQgbK}=mUxrLg(Ep*uJ%JXD=+GU6hj7Z-`CDVX zXG?&VLoid)o^I#o_qwUR&rIh$)^U8S$TU6Z+OcTI@umg)pGC;^wE^ta?LGyOk|@-e z8xd`n(G6cGyjK%n${V7S-(uoEX^J@C7M|Q=2U#qme~lpX^_PCS)7*N8h@VfpSk&3# zee}-7wGg|X9g^5lA0MWl{1aB$;y>A-6>&?64c?ssNIeo@i>gVc#9rv2FV$k_lLXDn z)rPzzFH$+s>XiF!a5^KX?|Yv_zq>ODm;YD2_z%>y@>Af(se|Z}BA+J}-NxNL8L&Gz zKTYl!zIuhwj$qW?w+2BeMCgH71x?22Wz{6w0(73D$UFmfZV5Dv$@Nx(sUVb~bJ?z` ztFzKKLVhrh5Tqah67tccq6_v#Vb?9qmWS!KNz+o?bjU8q;D3d9CP#=}p+l1kNgaS= zEy$Cy%eMd3PyWux%)BE*YEZUKA&#|S>*zS-M+HHB0n5U0uuSr@?1rrbYp))mZ4ta6 zr2BxIPbd{Rk+Gt8h@Ip?{7g@mNp%Q43M=hyRP5LkQrga$EGXS^3gz@Wq^(GyvRWyx z<>JBvr5fw=4>&!_bfm+!ZNAl+@PCp_R!d!w>F|9Gy%cTc?!#)0!M(VTQ3( z{iSgH9Kb9LZQ%AYtwVSw>+0$GgeVK{N_2N4i+1rvp|46#$7ntpl(Zkno*~*;9_CrWBX-5d7>DlrSg~=J62x-i;eN#V(XtWIt*MFYQEnocG{#diCc6+S$ z9Sr5SE16e>h@bstzOjG)_R<$2Ef!7314Kl(v;$;N(9Z)I=SREtzL)>?muB?PMomzT zI&|b3eJS*l5#G~{(1M14of)3u%|xgpVyMkrN`DcYWoZFU&>~)Pgj1a8VcSi z#hp6K_!(_6`%MsexjjVldu$Ik<+pBuu=xeq%O`uAlkAhG+f(EoYC(f#?4CTc9$Gq! z+mlgvLIrT0O^MFuxqT`y?y-_pWjE0d<=# ziL{Hvq5RnmfiHhsq(lmqP_z7j_&l88RSxJxtN%SW-!b7aq5tI5$;qt|K0T+VK-T## zFZJ((H-RB;u{(se1ct+1K1UC0O4c9l%ZzEKRp=bFp&O(}rzGby{YvRRA0f<9PJ8-u z;siBYZxgk|DGBv;BjIY#jMCty`u8aQ6@}_(vO)^9Xxu#8DO+7Dh13^4EhR-tX{T*7 z?2M5o`Yb%SX)oNz|GyTXC+uD2R=+TljzIcH0YOZ<`zC*}b9css8Sqorqdh)J8>_!P zY^c3aYVg-*{=1CQt!LyeELb!l8Y*Rqm6aH}{BB6DkTl~Fh+yheucn{VM8vkf5YcC* zrG~$PNUy^q#WK9>I;mda4fe{*b4sKY^qI-UwYa7;p9&c=C^lG{U)6q{Z1N>kJf_!@ zvl9?u`j z;SG$@AHO#q|0KP!JMrEMxEuc~c*#M*k?7fpfH|!V@~Au>uHkcPwoj;C|LBDb%XMRPCa7MFBw8{Ss^@r&E9_4PxKJMk)eb~H zs^0Xx?y~bjI@1lRWllYeFqNn-7Ygp2Ok1ijUhQPo@&6O&`@wC zA^Td{$B&HTudwO$R-z%1F1t(C@3qIpg?4Dz)WSoHAFh+!ungyR|M4?lu%M#xKca{b z7Tc+4@`dAT)*Q!hO7HT@$1IF2FPX$2#{40tonO;7Doh(Pqi=-FI%v*OsoqM}{C#F8 z{O%n2`WNzLxxuDr&waw4GQDMmJWU_cW+PTZ>9-9c*80Wi8o?CS4qG|K|FNbtH9r-&|Pb6ZvFw( z1Sk%00RKDRgl{y1ebG1w`!pQ3KVsQ}mc;K@;Pb9Gs8B-B07^|`265xADJY9Q^@fqB z6@<&M^8t@_Il=polk;$6DCbGzu7oK-++aFMvZ+y$$Slz3tO7b>_>V57+t2EW6Wi$& z?~Gde%ePY!YBpatPtu7Ckmy(UavSwt(F~u1z|purcWxJG$r3YxxDmVDsbV3ncQF8# z0zObsf=8wBBxGs|wt@AQF{qC&DI|+aDqcg>> zZngLpa#r6n8g7uk61&-d#1c#BmXq0FWJ8=VisHxWd-3+lbmrCZ3WGf9u&yv?P(=do zq4=V-M&{;8!LZ?RY;~mOaR|;tL6OY1CN}Z#hMk%OQv(vXGo&`R$?n znXM;M9j|PAL3GGaXhs=x&_L{HT3|uIZb!6sIj}$S&tRY+ohvU1gZXu`ol?Pj1+Ovc z^r^}r(Rj;8CgNjdyVaVac2%$GywiS$W-Y(7O>`{`K6p4tHrJU}-lGM0#Qe7;eq+E#L} zf?f9FC7W4WOf}PgP7Fx&I-Z&lk<_J)a?*-YaxypJ8uNFITPf8YE)pid_l6!roQ1H7MRGru!&RCf;pvq8a6c0X8Dn3LlP3Sb<`Z3G&&rGJQT_Y7Et(gl z<$cm(K5|X1^^qBOEu;z6jCNFeVm6MH8$WB=?>F7p-`-I}_c_j?Jt&yJ9w0m0DrR6d zc&VK5@LKgEm!EEET@5q#-8V&L!;xh6*!LSi-%&SZy^EJwrW| ziik43Pv^qsKBJUV9gIXK+lfRbCvQak$syDS^O)#Z3^Q#%B`1sDiRGO0{%$rIiUdUv zvdYIk$2JksD}0xC@$@u!Li=@!(LY8PNaQyq7IDxBgM8EL& z-2C!dsjI}LS3nSc5L#pCaE${^mK@7f;j^K4#Qlkn#qa&2HO?f(6G}m%&Et@KHLl0&!gyAxZy9)= zS7ux?yxtOI?9({EQ1G~Ix5$qEDViMXrSs&Ff%bcw>Gz9I{+`3^4^BLvj{cyai^I4t zUUxl^fA0Vd8O?ui)Fu3AUF~RQOUD7P?%N3ut@m+ofWhw^hNUgusJCfYf9;wmuBAOn z*=P4yfO^9PS;A<`SOyd6e|l_k#R-j$j-fzdNl9B(9~ynLo;& zepi>igDgMG=|M$tpqbG#uB*DTc26cMzW?TM8X#A&i>?7Q0FneUf}}d`KG=QBA(@f8 zYzArB1Wc=EDNL{=gRc?Jx8*Wa2k%fM5(d50@pBvM!V?Y3IYh=H-7x-Xt!_5fEX!uQGR2>3S;|Bjc;Zo|87xSkp{x&m%7 zFEHj$Cue7INlUZcSQqcBmev?I7i$%N+*KfJ3v`8)KMKFNx-?420nPvyD31}VBPsAA z;nPp7muqLcKFSnn@|M^Upo-e*=^Gl}k;$4g;^vn626GbG1Z=9x9)OWMeYf2*n2F+i z_>g=de&daeO;4RjVEIGO49gxTm`p&`1eXXxj^%naTSowGK$HN=&*VPL*bF<$ev6Tf zH?ZvirrtUSF1^juOUUYVaBwj4^8x*Z-vAtz!+IYZv&PmFC*}@kVr>jyw11k`n$CyN z#t$;cpyUV`27+MHc6jf!NRv%!;_VAIVvuueqN1g}PJU)+e!eq{M1DU;A+YZK5LQ)#eyGX9W)uHMqkThS_*f_BLwMn&V z5}|Mrj%bBc;Gx($&rw|s(C}`kUBtr8Ao*-=%SMFFlBfLY!=lomHE>frC-=~PY2QA) z4k#B;n*NrjRh-;Uf$XE$5HkojY%0Hv^&s>wG=EhP7X1K#3hZVu3pCtZY(sIglY>Ju zw2HYy^dw{|!*GH)&O^Lh*|vI-CZJoEK0Y+_ry_6vrdhv5f&{x|fZSkKg@FmOu3?lq zDz*0xg~R4Fgf*>Ce678>msz7$3Rt`KQ0Hi^I0HGMM@fqZ2XK5A#B@J5)2s zoLcynYfawgy4oA`VG!rm7t~VQ6*Wi_*ky7s{PfD(05fhfNnZ+ zs3eGMJ1WQ6W~mAK%*Ie4m?Hb|P4x?R0 zY6&}zjMa?K?Prhvq&lvqbTriydCVpH%B^;r@8-+ozOJmY8U2y=M*Z-ww~E}M=Pl13 ztVb|BTVQ9$V{l0Mq>YbrU&im#jJAy=(!BgRvIkK!i`2P97)*@dF=#gVp?EE@rJ?wr z5=+~0P0}geH12!GH=L_)(UjFmvMgotB3}*#vTN;{uX7dSPIl+-DqD`$U|HJ9JwPew ziD^uz2`O}Ccvvx9!XNAYscl$f)3ZqU-t~5ppslRzNp2}FeV)c(NA^zB14+gF@Ezu* zBmN}Y5|yWvm3XMHzP-QytHepN)h*}sn1Z?ZBX=J&U*eKrX{&6B`7 z@0Mr&ra!KY@7m3ce@h+6;V?B-__Y4}D3yTIME@uTxah2F7C|^F0Xl?x|F>X+MEWfP$K;^_Tb}Os_D|a2p@S) z23e@14>DF~c+#=Z4{}iWO9fPSb9B)~qaFda7!D6G9&xvs}*Y4kp;goAr3>-M{7f#BxPO}KVDPCgzcxsN72s6=)Gcktas#Z zbO%`+!^yu-;PjHCY-)a-R!05kO4S+zPDS_YaC`HKu5mR4pLqK(^Je6wna25e;yjwN zTjg2RNYB{ou?9wr<891mAFU-RRxgQARfyY(IGtCL+KsWtss3$PEetDD<2uiN_Rs$K z7+03K5QTW#UPSaODz40LU38W^&v0erDs7Nl4K?JS-{}eKtD)cc8pzl~6+0r2M2|X(Q%*juWmM8y-$w=Ia%Dc{)Yq zfc%4h{U^KkJB^7t!|a*E4)7b&CF66={(KY9R1KJiu#drRb3+~; zuCse92cf-Zk3P8%sp$76;ma@fHK@oRdFAcv-x+siB_h@+MLA!JDlN6UFi=?tk}BGd zf4XL6)^@vEcsj4&B4X5~Oyb9vJ;zd6E-d@=d6v+GrT5SNWqIoN(Ge|Q_6;LZ`y=aSSk!I@c!yvwe5CS-T8CTV$A0B6!=@r-C+Y{h z;5wL^V!%XcJP5ZZ>mW)MFP(h@3Y!k?G^Y6&L&~myaF*s-`L?T6^2g@B{>3lh-~ADk zGTvAd9SIyr$qxmM9TUu1d!VJv=UEV+ezsN`aOHy50O}4oPZzW3_8N2N&!AT(;gT} z`hi1FLt@1)RFaC`b(@a6JzxJHGXL?PJ@mf=cRn?hty?+_nGo?x7&ws9=4g-z$7Gn2 zK%CMMo?1>E@_JIM*qp2n;1e+U<^t01m%d@^;W0I#_xTwa>LCz1Fc&ybb#5pky|iA4 zj4OWi)!D&;dnm&0$6Y@i0yF^R9gf!epO8_WjsKtD2l+5hIs^2a;L{{~+XS&*z#EOw z3a0k=oj@@x;*!8w4QUs<#G&nh*THs^!?uE(E}|f10a?0oGF2z|eEndPfpBLKQbMwA z`L#)fl|BvzRJ~{c5CZ!q<>g0*B_VkKAYT|ln3(iAEo+Bd|erKG*e*s2+c3L{N>yLaHG=(2ZVdxSA!8 z*EN&#N1akSXdIo>*>T=4RgOARefhJcod%m31inF19r-0B5`dW0jfGP*wf}*qrzgU+ zl07{)w+7P(47~dg+suS)#7+{5kU~S}D58QL@-C50B>|d%e?t>{AEc27{PIIcGlhiY zE3~1#9!%?P2zeujR*Z$VT|{BXID~SmedzlN0!r@Ykn1+ar)jV?2p<_yvEaC#Q?rIp zM}X`YjA010Xl)IOXYY)=T7R1cKFaCx#18RRVecIjKc#|)iodxJ25vBVyM3tvW=Df9 z9y+QyB5A~zMvD;QVTaA(`?2FN=|EHo;*QyBeI18_cps>k%LUi)$+SHo8ZwBBEnw^b zFt7PD2s2DTLkeh%#MS=eo4ZYl@_$SeH;MW)!M@CX`b93PaoIKF?%6vuRsLca9Nk^>vHoVA1q=&k;-51an-!gvgt1hDjfd1rqjVGGQj-MJ9*NcS$@dw3mGY3Tfu%t%(|jwIH!{-Cv7k-N?5c3=3FQ#xjWN)i)yA9iY&)ZyvD^b0nO zjwc6gWvQS{vK6&ApZJ>CkgXT?8Q0WMm7kFl zYt3CF9@z=ea65JF+(1{kBufrK%oyKRE4$t>N~wgO`LcfOozvt+!WyR?!*NfGPOO3y z^}p#_wrHt)DAm~AUnETKDNhTN_(fxiBE=f69*z2f*qiI?uOZQ^0fX06^2>7d`0tSh zZIM2l8X#XjDbZD$(lA5C!($1L@H2@){_sgJQr*~4bWAFPL-a3RWAo#Ks#=zv8@fls z+9R=qxUEb|!t|r0ad8F@RBLdWvgLpLncCFx9g$1vG0^U;@Tu{ZzMwZpu8X%dyWgAe zou^P*o=~07P}lmk{C&$@|`muBcwMiSLR6GNWu$f z`PTt>({<#`FTB)rTxtK^=h+UPcrh`5N1Eu>g&J`<>Jv^!#x-0QVJ&OwET%9#hg;v1 zxgEur<;J6{cTeVYlH*;?UyK>d{+T7HM|ML+qkBe27bC~#WEImbe3Z?TDxjC@t*bYE z=UV8Jp(!= zqh*r0nCfYpaVX+RE9NFuR`u1rPh;<1s)|i+^*?-QV|#eaa~m9*8yOT}=GP{@ghX>s zXdhiLhUlhB8h-=Do8Iw58*x-E8u=gt>e(~ZCQCto45Q`Y{NB3{(P&WcQ;7tvIg;hN z_`7H_sJONIo*9&syE*!ACiC7YC871L{uTb{a%b=Ru_sAwyo}MEyp!{hKpkt^+1I0w z@?Q`7{@pi-_z)Co{(YrW-{Li)zWWVTyi!7rM=B+)T}6%iljSbUh-!{drmyFPg5gL3 zw2zg4zv~)1+qlZ;A`}Tv!)dt9X2O%ex4Z6rG0++P&X9P>x#j*vqu^EJXD>{Y+ez%m zS51R(#`$nb^B?=R=6Zf%|H}>jNC%8z{Ge^*3GJ5Qo5Qy+IBc)JX;S*DjdF{KV725q zdP(Ixm&f#_`Q<7usecd^$o2mEl@!%M(q3j$vB^oVT1zl_{?UuwPD9o6Cr8wo@6%F} zcd8PA>`&&iJcAVPQh!odaW&c6;eZsaC(E7%-GmiC@+Mq2`>|!o=^4L^dDO`CD=k4L$BZ*2qbX& z8XR@Cimk_zR10!Q$N$Leg9sp9Rh|z60DLg66#5H-g90|j2M-=VUMV0OaC~OSB0y)L zprmYd_4epve^~~FUwx1m2R{)Oa+?m;c8gq>FFmE&<5ZnPbip8fha5K{p@K;lSYn-= zcu{=7y_@3k$B_!os35U~ts62pFc3XL8&TPiASIfXw(eff`RQ)S$YxfOD+GfO5)#7u z0Kgh15AB5Zvom4fvZ1h=JnI27v!j8KI%#}DrR={Sa9a)zDln?+%8I2;dx|_VNLdq2 zlB{cV-(`>@heLydvx`fvKh4(7n{T0UF%a;+hYSxzZ0Pgg-U2TVIk$-;j#M5$U!najjBwA8|M?2Y02`?U6gm}UWl+`TwHmXn zWy6`5Egq39W>H0MeG3}@AG2e%g-D`bR6kLxtj^mCf`O)9l7%1vWm_84qS{U`=qU&~ z!@|R%nBwXGY|eawf^t7**Urw8z%2vh3#dINVc0IFc$PC-^i{-^olJwAp_ zjV|07(e#K~Li11%Uce^+LK%KKkefc^n_#8nZv6x}1!ytB&;&RMKrBGr!ySh>FO1+K zkICBpwzj~rXr)$H1L~WXlmE81zBF>ic3XKq7lq5xr7hdGp?r3&HkrR&e<9lG2;U5^ zu*KUyIOvRcI=qy?FoSW6tUJ$kRa9xeFCBu7RAOrhp>Ny&7_8Tvd~lB8!6Ih@f64sq z%_+ppVA9t)tzv^@0>Mg!l5!owM!ntW;o{N;5>1#L!C?W_Nc|88LhH5fk4HH5=9_B< zTWee-g@*eg$D z;7f!4c=%a_R&m~`=g$m_aLqGaA|;lZt`ct{i^RmlJwg@9yT9MppBdUTLD&ZZq45GDZw-26 zt`=!;==T~gIcx0@F>iogG@Z3`y#rQ}l?WR$+#Dh8ALPg|sv@#U;42V67lPmva)y2z zH2`DOuj~dr^&GuRKtUk{90Wn^RR!eX+Nj##8(oQ~$vE0wL;=awC>Xq63FKnvZTr1UVpqZxWrL8% zA#s`Hz?85|KeI4+K;9d;ZOE?A6{8in+3}yWp|LObu|U|ukasJ#OyPNnnO0y(-!1Or zw_V!0(Fu_^I5l%Qc+7_PbNVxkPLyG7EzpF51# zkRGOrEiV<*U4v&oPDeagZ6c||ikqeOPXGEMOjfJw0YgmZr$sx{EA9-`C(j;i%1ZMM zJtCAsRva)`H{BB6`H>^1RdvPiyA);I${|jw>gnc%-h&*CQMKgFC&`s&+NX4OYN)q3 zQBlkSg>CkPPsf?XNZ6Xad_t--;-Y!A8O-Rap2Q_{jK&7f+3T<%rEP6v3+IpU^(<`i z_kWPj`P$ZjUc>#>xJnv_^7iNR3dcKr#!r&FtAA=Qx}(gVDO-M~W_P3d<0ciB%z>tJ zZiKFPiuD4k{{iWaUV`x;0}kqTfS|WwVb9t+`GubJadOY7ahG~f?VXoFjr=W!HmL{I zb6(Wh>w-jCYRGG1=FSVKk}kejJ8ejm>PdX!ww5opdB z7*5QcsM8{+P4ZpepY)YSGBXP0+rRrlzDGi0PGM(#Ouy!RFp5nxiTNg3)@c7-Zqx^& zW)N*9tI_4IO3q_RDX0(U1j|lVCRGnB7w{?v6UlO559j--2%hyC$94|;ir6}76P2@= z@O@N44i#g?K0A#t)?jECW_=)=!WxY?F{rK_Yw@0lkfA*{-ejhd{F{a{W-1mMvGwy` zrYMT&p~_M9kNruO`C0j-VzNJ|B;q{erHUnS9WFv%b%LTx)`Y=6o^N9Pe~0jB=Vw;7 zIv?%){eCR!m)L$!=PGKFQ~hFb;VSZ73y+xQx6vtq4AJO&9PH@BGQ3&Zl}V|z>pS1w zGkiSK<&J_MefwMGcu6lGgsM*}^PnyFM6CTNz82l2@eTiS3_^^?abN}65Jmj+CHB)d4q!;jKw78;& zFC(Yd2JuC`%V@4tzi^lEI^!`3%~R(*|Y!Y^?Xb42>@Q(nuz?Pm1@T*Nhj? zf2g@}hZ;b4@B}a}kPja5XD#xZOrMy3W&-76tsTC9VI0eTkcp!D4im`Pz_Yr&4F}BQ zYZ#7@Ja`N%WdB`ygA^^nyaG}@!S(uTM#$fcO0U(SzFzJeHB-^ooRypXI-tnv4!eQ-a<~w9F&>{L;V9FqRN?Py zhzi*Ks@?tE@WL=PJw5M#o?~cXAF}f}KQ#Yock;pGr|Q@7kwx(zvz$O=!AJ)3j>vWQ z=<@m+T@_T>Kmr&dW-Y+z0oGxdJpi&tbOgj9r~^2d6KTYv98c7$z$qsS=;lt;&YKtiIfhTOTGwlrdec;twsn| zzB)CycCgJ^eai*3^-1t1UDT!Ba!?{fqe z16pOBLH7w$CNvUID8nRCgD-Gxq;8-Vb4F(L{t@v$C#!+8vciU74#YJvwdSUvzKh~;3IE< zEPU9ZpBHJK75H8-BO=BCcmW0mVe}>wComD98$UmZ3HZBGV>q6TbRhZ;Q_CBG8Hq&%Yv2!izAK zg8~Rdtq7M&&d>r(5h?D_*aX}OJm}E!09OIVSLS%7gJs&=B^L4sO&&?ZjFy#i!X@DW&PW= z60IQWEF;R`qZt@PXfHs@n$sDBgmibB%v~bGvZZaq0VDGMW5!ixeT~qGaCiO0-9Yq` zGqZ4=z1SyT%rAw7?=O1xbiPx=>%BXFw*r;HL`88meB8DzWI-FnuWyE=)x$k5!mQ<^ zvKUW`y_kB;T?wVxtz-rN`z^HXIICP=wy{KmCjvzGzPA3ycqfWP;VGS+KdE0=uHB*z zinYJxxiXoV2u%V?tcY>pQ$qcZ+y2`DLsv|X zqdqa`)D~qB5^qS!*_ciEEcliheSB%8Y{K9|CS;r}8XdjH%`aI$`6M`*mxAq_#`SrF zZ~HcV>q)}F5sxSL<;kSqctS0*bX7#r{=>KN6%o9ZTsG;cNSh7^e@aq(YaIQ# zn=KWVUmgr5e^y;pkdH=FstQDA_)khMXPdj>YbU`^2Rf-Q<*D?&F*+wmmqc5ts7AqC z+UxX~+oe~rL%h#pnabXx6Uq2@zjtD5jz)>L<~B#_Aor-n?qNWsW)DulvXxR|?8}?y zY!r8wPT8Vi=fGnQ=#IKGFjm|85S+wwxwfy)2#`x$sByNy?K_XR7u$iq>y>yTl?g zU%fLlYtXnDb0eK9Il05TPb5v5Wa>p^L?RI?A3?e9O^~w1ClRb1)G*p42x;A4n~v|P zJ@N0p$>gdhyX)T2UNNFid6XD=UQci#VgAQ{rVy~Rr5X5?)lw99u2rUS`{CYIhiSJ&%JhXkz`I{l&$p;cGpRvc7 zw3;NI8j%VsMNd4mNhWIPVn3X>V~vd=5?~ck;>3#GE@s-Us2h&lDQ{3eD?x`s=N%Op_0cCFO~O*| zjNfcxOh;Nu9j-0&v<|H3l3dE3TVo-YJ- z-bJ_Yh(nx)w2Ir|cxxfqW5!Eil>;2Y$o4icWXjXA)e6a)m21C&zYvr0_rwHQva(zd4fwJSg6sjzRx){~@#3#OX90OXRp+lG zF#uTjqn;`i={Ra4A}K(0*e{kaxDJ7!&=^eu$N{^TotQ!?CoSWG@9dC}>=BW@cSQEydyleZ zmF#3?XJ>D+v-w^3`}6z0|Kc6DbDwkW^SWNw^?W{_1yf8J1@a2P*3$r5vnDB-MVL8v zrt9c;id*2_5bXKUfWctuugr(Bryl>T0+?+)J$1QjD4}t)7uzl61feOn>z`-IFz1`4 zb0^2NVB)f9KHxU7s-7GbtAgbVS~|{!6V)1jO7x&l;wY%pJQs=d7W(-_#X%^I#j263 zp_$!p#&=JW)6(D!zg1Nc$?S4^Z9UhZs~lvImX;=k<+sFtH&l9dZWL`A&Wf7+>^nF! z)8gghxmv6-{bszkva8ySDvQM35Iv8JhB5_^gjC$`M3#oFsV^R1i6+8B0YtLePo5$w z&2!^!j}jj73KVZ^PNpU&vecPs!+Ht9dbOx4)iP&xrUM199|=c9Mk2@}iM@h&W3n35 zRjdlAf#CGDw~vv}mk`M`hm$ZJj1#NHmIxD`DRXG(0FZ>zFto}#6*j(rjBkMC)@F#k zbJ7}0PEM8+7~XKq6HUq1kN*XN1UPQ_{G%^+&7>!GmK4uvg_V3tFF#aK#|Pm{pwhk` z&(~l9k%$w&Hup>kPTj=T@ewI){%CE%C8AYiZ?DF^TU^PIuDo@f(^E3R2OYkprKLtZ zfUtmN1%$$;;Ff|2@^BmA&O&T6V%@#o^0_KU6c6?dieGeAVAY4lf^}UF6|DPkeT7{2 z{)3%D^^@Vg$&4r#Ktu}Nmy}X9WF1U+1iPn05ePqwgvjkXgN9>2^btNT@x#l2sb}u$ zuM6TGBXFiLG6A0nU_4ww_JN%F+!lsbFxi0*hv>!RKs|spprVAC4pd$Mmi2lUaY&&|E%?Io=PwI{nNWU|=v$=7J;xKSWgz;yh-3d*6ViC=| zf2|drOH&o_R@#bCa_o_FxOUL<`ML%7RFaO&piXR$_LrOESEsrf^#oMJ?LI$DqbcaS zaaR&XSAR4GA8Twpn0$WMGbzr@gk7y7d+dTpid+;YkCwiWPFsZTHNgwjzEzcs7Q)rv z%&X|o$w2GN_G69yL?+17_^^9TRuLnUEu4VJen0iY$93^76>93z)Vy}PuwIUdpHc$C zZF5rUigyJ}RA`fa-e4m?8hXIC@=|Kh`}r!var|eDqh8+~>C@gfB1GD!TiDcMtBdSh zC4xU4k7)My10Kl9f7mgq3qa&}uj(WG4;~9-Ih}GnqO56zJd6niPr_gcGlJ&BS{0Y)56w|is8lB6dG?1z#&k&3DLX|Z zPN*KLJ3Hvdqu$z)1n=&O6=?U&sE#-Op`v}Gq3w_I*d4irpNCR(?qL#lndDp`tMDCM zcAoq5f{I8gmny!MnfWAbXY7i`Qe1^U=bA;+ zl{W+iB(kwisg=yCwS`Z}24410%I|y{6k(8?HGgnx;-Pxmj~^&_81-@sM%o4qWjAXL z^KM6&UMYH+Ykd%XBwaLtPka>#ELvVcU&JSjFhAfq7sHL7Zzg(i5sj!9Oa{; zQLQHFf+PcxEzXfsCwzt2+$e_m^Gq^%P=7?3*#2DP!dS+aQ>)LjE#)cY;o(O8`L8<^ zSpZu*qM{S^U=o#)h40ZL^|&79lv%!)<#UUxfKK9!jC6mM2s|y$Loa_0Tlce20 z^2&7g1e|(SpY|}hvRz)q?&Ut{%(;?2S{Pl+Fn*uJ{tKrskGM{FVCnSqbkt(!?_Y1t zPKJ1SPF~)8WE)EY(G5W?{Wpk|aQyf1B>yxv+>)xuD9IQ*L_;4@;{WvsY8kE|@ACGXNalrkTGCdqZ;F zEUSHxIR;zjNFk3eetw4|l{~OUFZN{5Pg(-&Hp7c-<5rghy9=Jq+MSQ-4^_jNK_o~j zSU_5_=%uhjO-V@`FxV%$|F-Yn^AqT$#|*3yw3$EbT|10Ew0xRIQ_G`}BR_4zs3G|A z0<$yfLH_8@^YU>}hDaWN9^Zl$2dO{GWXeS_9m8`k17$@ZLh|cuf$Bpk3GSkUhxoBo zk6!$%7fy8#QJA4lb_YU-q`atN4$3;nIssvq*L2r7t)$C;RdBhoCU)u2sL>|Bjb{Yh6r}8;BIFsc2E$Ui0w|C6T7>ZuK^XS@_`>( zGY~ig@DByKq^G5g`fBsm0-yyUu7H*cR2Yy{%mMQQ(8oxe&W|WEw!>Els1^t{Z?5NV zzG9s6rYb>Q;`Fc%Nuow~dM^2f=~L=GvE=k# z|JWn-1CN1%oTba6gSDIKklN4b!wMJ4ee6{asTn;&oK%iy#O+2=d9NJom8^r_rgj^I zFYBDH?2pGwUL>l8XUjA{lhb@?8)O-0%cM7w&B#30uH7?CbOn?r=cQ*xM7L##?Qe7nl!5Qk6j>7JuBLEjNzmQrt_TF@9iPPkzeCU6*q{9QOjj5s2a(oP{SV zX4rFWG#%0^`#LjkbU}o$#=NDi;Hr5;{k9JSQN&v$D^+Gw;m9XkIHT$V&lpoLHOy;1 z2+S?oyom}yX~#C~%;@@%99Jf1^jcWOe?_R%jOjK_)d3UTQM*}@qUil*ydYMy@8uPr z*OMLw;1F#R)DlhM#w%@RkiD8XFqxOl6DzXQ+IguXFS=X~{7%Sm9Ol3;=C3$Cc9iS=7cNmo55Vn1O`!z zc)Mr6sc5F$-k3zqO8y9q(fQIgqZ=*Jnlt^@ekPG0HS}Fq&d9%Y51PmKMGs0zgov$7fk`pm8OxSX>KTzw?^Wc)cSG-#Ihv)#TJimR#FjfeLq{UjmKt5lWLZq_J6zdg zdA=ILG=$U~5yO&(Lue!|HmGjZ^hhg8H;{2&|e~5D@ zLNs#WQESq|mA#0W=O*FKt4QzP~d)P!F8=lJL zZ^6&@d!m5;qVzwDKZ+R?o=7^8CEsA5 zNj{OIrKds8LXpf;hcW}QP9yCEwmPF2HG=}!A@&Dolxp&FV0q3FW@)g%FM@}Yg!yXkBTJYz z5b{B8vZsAX`xhqZNGX%pgINsKj~9n6ztA1SOTbP%4Neru9@OOfDNO(5`pScDZ&*=@ zoBO)=e6rdc_V6&o-t+(+3Rn?fy|4p10c;czP5D~YVhz}Xf;VByJMR~06yDAUnrcsd zpWfjEG0oYT8?@1(-wg^t#I6`FAoxpZW4q_wsDS@5c&;f{uTxr}{S}a_;M^4C`Ez;s z%}fa~P#NEX#y%2UdzyIpO7L$0MCyf3)AL*wjhY@o;GnaS8>A+P8=*H{x$s#&0;Mtx z3Jb~>>UKr_Pv75Zcx!wKM`3$pCVmL(21gMScTWv15ikoFbAX2e%EkX;TM9G1Q$(*u5CerRk{)o~ z!hi#mKZs`{#L{VgO6gWPGxh~Bg8HYi|HzpLUIxss#A@K8>3Qt%2J9sdSxuXPAQ>(m z%j9$7SO2F4h{pke5(rwLj(}SOLC$~{N!27PC|$w#12=@@=`7en;FHZtGpx zoTNca->&z`S4e!x0PzbKAKwpzsRa(^_%uPe(5V?FDG{gtm<}!;(EnaAis4A6mCd9+ zR(9ANPn&-{r+Xuh5+kkEru^-sF6!sEou%fY+q2mtu|qywLQLV(JslT5pHLXm$b|=@ zJooO7cQ7FtYX!&NGE1Xwd~lFxd%GaSU%Denjkky%WpIBN*T;A#cY0&UN6%y~G~-a& zC0#FycQflcIX1XpXuUhY(A1|u9e3YMV8e4}g6=rx$L)PIsu%BLaSRxZ$(wK$47Y^} z%48IMKdG}!{wxpEBb%tg*f3z7zh9f9^<9Xp%G+(&+;d+DZv#V-t1NV_-ZjFXg5MSO z(8ZSmchCJ!m8kEv*o}J=a@Fo>mpke=y*bg}_veo(zxkaz?WKwDZJoNIhng}jC7UtD z(iZipI^;z%T5{L_9GQ<$zm(o)J|~$~68!P;t?WeohRP`I?4Tig_$fuZ=9rhHJNC_p zsgkV+kmmK2EqpnSzGKArk<$vtC&o>E*EKa4_h>8$f6cB%>T(?9im>dW>UOo-d9J>` zS`(~~@ZS=2EwkWW$m9`YVZ?v#7o~W`sFW76AR90wKkUuZYW*hBGORaX>BEA(F&*8r zv?Q<3O3Du~5?J?>m1MkQZfgc=(wYuS)5^&{KC!UXUS@|%i|`+>MUB2AfiTK29h%(6 z439wwR*~YT4y5PBM&ZNHCvL*+Nxjs_eT!)Elc^$K=tt-bJoDmq^TfgX7|S-|#9;5G zHMjS&Xw7u?V<01aDkr+d$j6H@!`E*zXmiz1C zqaACfZm=i zTQB&eKo@^5`SV@5Y_lkq$mm^US5|a6iY`+Q()EW_WlQt881=1(Nl$IppL$Vj7~Bf2 zNvB(q5SKvLYB5s6`9-VUWqdo*R7msv&OL_S7QzawK2%-K9~v9l}ii-3%d<@=)}jL z5Bs6J*WAi8ig8m8TX;+!QQk=Q!6dGE*dn#zjQLmDxRy>b`a;#0hJH+HUGuG9BFE>x zdgHm{yG!m~LIbVGqt#)ba?6h}QO{9>T3hy!jl~&Kfb={5{U0v`SILR!4=!cmi-`5H zkBi;h#!y~H^<0r1%dCoxn*3W`wZn8ECGu*22A{_5K>dK|8Szpn8`6j%>YF-D*y-A7 z&E={FBscKn+hqn%#VgN0Y9bo`kY|3${wcu0Wz(yzJ@!u7Hhn->he@ymEx1pY_bS8- zSET!tJkLIzCVz|z2-|1+{yFIcSD&5w>+X;88)1#>LIx4>z)0q2g=%se=tE~SvU8Uf z2>=22WEMIFI1vJEi~tg*yNVn*O_8ulV0oXmQy={Ox?2S{J9sdIT4JWz=O+3DIrvx= zmyhN1tHKf5bY+-X&>5b6e^Y6lig=W-*xdZH5w#;{d^KSH*ixdquUx0pQgzHi%5S$1 z)3f?ch!XoRDiUu~lE10AMw^d_JHvRMJRzyfhK=df1@yuNr)yznIz}rovcUs7R&qs? z-{#P2Ac1^0pVJ_pj}$6Q zsQ5RJ&wuVUG?zAWI%Shq^bMv*KH5J}R94QIVn;X(o0~;P`4Ah`{?IK$_>bXG_Zw^O zb`z|Pd=C#j)yU-+-S0a^%2z}F7fe9B`r$l*7BP5Z?a&QTX#5W+4SV+Q|Gt#(gJQ87 z><^Gq8~7Jd?;(P}e9jVml8ZtaW;?ddpRF7o#o7grOCn!UnYP2}1jvKx970Y9Kz2m* z7bMpiKuQ?ESZ!hX09jp0>pawoE^}Tl3k}c3#}e|@f(0>g|oXccv~wE>1JqVA7- zX!B`k^ZZhzs2QLtLD=`-p@4h^_*`%fLBjz;&y2PGAzA7L{yXpyCci9gF$#IU0}-sI z78b#X`TRFf0ft3Jsuyb@jsji=Dm7@hBlar@zbO1Gu(}Z;Xo!Tg0DMG<8IY>L>*;H% z?YZ@8ZV_7bh|Dqs%7mEsbgbOF6VTZpNraL&1ArCRJ9F3J&@h7X_hp%GtJ7=HP(qj) zEu!l9{)X}pMQCf*xccSptIY(ei<~ONz48y9tRE^md-tdLNW9DsL);U zq7~1(1)2%2p!5N2(<&$;;L3XItR6{yr#tYuroQ=VcE>C3)-5K^ScwlG7laM<9tB1u z8$ML5(7MY{{KtiEEm6C6qO#*6hU1O68{K$U%iI0bMVh(=kJw(%wqhcNY{tm+pcbD> zQA1|ej@H;z&r?PMn~xn1;#1h;GTWx71+k&G78c8=_@X2T416(IPN&;_KltA6Ov8Vs zdsn1*+wj>7-oV0_0nq`jaqigD2LazxU4l+{<7TcfM3F8Sw|SF2@hkeBYjL(_ zj1%?ac@s_PJmrt~m&LslFDrPa+VrIkXlf+eYmc~%2g4+^&eNWt=)O_jc9RpjCDhxd zfc-7*Ln?87ZS(FFN*BgB2D|mb6pFDy?Y$TM7qmvg$d}y>2itds>K22#ozMf9Nl4zKmNLaa< z6nA}cZ+NHUq)uheN~EVEkAp4v+#jFAY`GYTMQxYVyXza%BuRK#M5af;Bzr6IJr0H{ zYC&;S{H0L*HoV8hPj%Kk9uovkjA6z6~F)Kpsj`~>Ux5!$+K zLc;a@aILz`DMu`s4rjp!(@4~km>>6=v_7@4^l-dLmHiR6_c!l%6!u!6j`-G-isvuP zHs&7hPvXDemlM64H&Bo>@wVpOV}%Q5ajY7Rv!aIbJ+EKpAJn^q;2n}`=#JlJ%=Y5& zN1=1eSgZc&mhH1A^ko0_OU{?r3U7Yg?X9wQoc#o-GHEZu?Im##mD%MVnqmAG@h zvL#s4?@b!sm8{j#cp1h~wsq=kh)o}tbAV|$N7N?a=lB7s_kip`cf7p{&6y?tc=3Y# zm4AlS^uK|xBC7I}m1~WHeFZu+;RD)Q2_Mp{#B;P))Qj)79juWGkB`){MK^l0)D))> zRj_7@rtwbp0)AU~EK{xWI;YWfCY{+C-xRZK$?~c`qPGRRh0PD|M7$3exVXJjO z7Fp4+1#?0x;imK3R>L)^c`!{!p;6Pxw44~}j~6E!QDj40=S>>pw+KAUa6I$_j$4lW zS{*tjw4!fTd@l6e==Q38&PcA?eNL~hSX9Id>ygu`>8&{Y=<0I& zH(9>l^QgR{f@5Ir=1O$$d`om~INyBzxN)Y*BM~;aFv+wN#(SleH(X4!ODcE?jeGmYMgU!$cP1$1qEmmDjtF7ex(ao+RN4jg`2sEf6k_Lic! zk-Ylyh5K^t=5p=G-RpYV=fbDKZV3bAX_0da4q^JgPrIagl*g)xvixdU(5n8WW^z_p zjiy}{IShH<$&@9_{P|LHwEBa4!g1!km{mfbafWL~J92^_Uw&Mqy3Y_$wH-ta=g%ch z@F^;p3*3yNsJzzAn*6hHMUx%B#(I2Yu7Gbsm)f960e>@$zuL3{odCEQW)m@K@`EXCWyyI7~K4)YD!2*Cltgn4ZvxP5OD)l+P;AT8=HLY zWlXn8l$vD$S*K%6?+P56yBb&zKuG5(C(va_N=+?W`4;p8(79mM$ylSOyLXr*TDi1& zZeFboXam@v!a@Uma4?%%@hL!&liGhCOIp@Dp(SvtQy8=**jUP)9H#tfdWZ4vr*BZF zBr67jLkGIp(1daRTDnoNWU+eac77!?X{E`%4YC6uqN!ABEhC_bP9m@`CFd~=bO39m z`+M0+ij_k*u;jqDmmrW19qlPUzX5dBgWm8;ev{zgSq3SDf2-J<05^AT`vIUemA-tQ zQadJj!HBL*fzF_w%{10xR7H>s1O_@WuFl4LcmtLpDOfMEIC`s~Z4VhIr9P%EEJ7B7 z>A$ldE&co4LVT^z5H?{1-z!R5B5gT;MX)C-E3>DSu|%zmz%gLu7V;Y2o8?!HjXIsj z)=WL$`|+bdbHOb+w&eui53_9beR8>JcPdn(AXk9VNp-gM zyLVgy0^JA;@At!WNU*M(1W=mOYtSIW^#UsrV9;b5bRk>X9=tCI*B5wK+knXmiX<4% zKpU?cB%-9a7zj!Rg2%E5lyWGD-)erNzB%o>9HPD=fG&g3@u)iD!3_*B__#hw=-d zD1}lHPHjR$!US+xfmw>sZ~*k|ddcT95;6AzzcE6DQl{I`22>H=tt}w6|9AKb>`fgi z-Umeg?I`A3Q4ul_kmdr6)aNK5efva%C)Hn1i2BN&vNJ~L+?3<{`rCqRVn4!GEhY-l zY?D>LIo^(sSYbB2Jjp zr=by~ZbETWu7n@hrje&OWIF?riKNp6VkTM0nGJpIKAq9$D(=JjFB0_j%>7qTZ&^=E zx)Uc<>{;DT0BXc{ll;+0mb@O4``ZVQN2SNxq=4ap1`@$MP4>I;2*FB6zNL=FKLv6jX5^rdq5&ll13EP-uHwMhnqs- z%UDtiH*-)7kLW4)O%D2ghA!OPi)2MSsHEu4z9p_vEl`o->E#3R-ov z`CZ^~1TS9e-n_qfS6460dDeOT!0QfGleV@_fgrDci^K%8+~myU%<><9kD6(vRR#5L zswpdO&{0WL^|v8O4KUQu51m^D5(L74x%SH%D1~@bGoVzjhT3y+Q4K#G zIiTXr7af?6S2Z;$eVV09?FR7U|Ad9n%I1!zqktsBaOlrG%3XRWcEIp_fPxA6>C%Q2 z`&Ea^AC+YnWzWpw-}n?=UTw<%Xkcu%O`*T!j#Cb;=P?>&}F<ZtS@>Q$ZuqM)r-!kKzQ6@ zUG<0=f-Yc8@AcQzl7}3Gknpx)_k4Z}6`c>FG@yA+>8*x*=We~MpPmMP9hd`#hMt?W zilp|#D1j$-tgkOj4_6Z-N6Y{xE4FuquEp0=Bom7f08x^xuf)*M3Xsrnv<$V0BbH#; zRwmBC=qvkyOJn2HGvwoYa|RqV>B>v|5p1#UQL2J_?eqDSJFH`t;ofr#>u(a5mb@r) z)R46mXCY}sFuefEGp`pBU}yz>9>bKgSOY<1fX)Q02T%k7 z^Z6$4@VP-=J%0o@T8LHMbmJ@p(`QZhU*e4TFk=(6C73=~&2AfK#?ME|;w8V0^Fd-+ zLDp2=EG5#YTJ2a}U!dgT-g+JkO*R|@TR6ec0U8L1&wwvLUkJQvGZeKf*?T&wW7CCh z{|;3bM4$eLl3rReRx6H^nOU_L03g?-6_>DZcw7v?BLMi0aPknpko%4ZRQ)BvR&nh9I&p5hP@a0jQD^Jf2O218 zbf}s9j^Y65`qAfkGY*9SM1}#h>gc#6{GNdZG6xuI;3|^q7I>DI)LG0$EUh2n9Obv| zmVC$sSIX>fy3-T|2T+hAgDa~NA3H32Jav(BS=3Jk90u{8rMt2oO%Wj;23b6LM;OQ zxM?dG4nofvY$>XVhhWAvLI`m$pppTRZT9qz8Y}UC+ElO#A>6=b8ec(_ir7m4tdE?( z!1Dksvi)YUh|+6pYz%9?9s&g6FFS1!LyOQ|@s*B_5x8z(WJLM*9AGVxK%up7=!4eN zeNfgG7iPeo2AoUH95UaS4mv}O&;=|iZ;eV>o9y1zC;l-0po;AQQq|Gqgm9rDNoXPE z(}SNmA#zR1zt}U(xT3ZL5*>5Yc~R(Y8`OUINKMh`s-b-^NYeJrn|GG3RV?-l37PVb z&OCM7V0dA5lv}g@^ougMi>iTV)UZ`Nj0lBJU_ie(d{;`V=+; z6=m%^_sg&3!dlkfODTu1U&eeKTAzJRcDnAjK%p$q%&EZ?KEP3GFXjK>*e_r!_dJp- zj<(Izi>!NOCL}*`B8w~G<VcJk)k1@z)oOl-B}S8hroiB`sv>w|kyKk5MsYaQZki}LogMycNy?RV zlD)GosOR1s+1O(`j|DpMneX%`4|7#T2#fdm6VUKf>M#idR_cP|YBM}*SvUMU^GLW7 zpFOJY!gz(TV?k>@-7G8b6D@Yis)op!ppF`t>t6ClTJc2rKxB#2YWI`x_OycIz? z@8t0EseiN2?=U49J1;(KQjt923;b}Z6XOyrBpUCttF@o&PB@+%8Xncv^45z*_wGGg zPiS+7aQx_;hid($%;lBgWtHc{wZ-1TI?Bc_=65YCr-UPd7(1EnqIF=}B!_QpZf0FnA{{0K{TbN!h zAEJYas}<09-R(h7`6FOKFoZB9z%$SYcYld2i&ic~)cFGwRZlbiHXf7VA1yuUn`?)_YysK4eczqv%7)x+zp zdNys5`G99HK4a_5SJ`mk9=9SpYqSnO>X#Sa&S~wxb!TZ7y8IE3V^J(+=lrg-bXug` z8lCr7#AHw~hhNWNbsI+|U3kERF>=h{vRXhqurQZYxU$JF45+e?E^xey(70Wo4Lh53shBeUB?)5Ph9`v z)4BS-xSGH-Ty;}ri`UZAS%kTkAtX$y6^DtbQuL}f@wGN#f=^FHwJh(aneeto%9joD z(9pH@nqfI}+*fh+9yUZ5bBHh|=`T7#@njzc?&=oPTzk@COSC6lkTkPHl z@Y4wQh_2gT0Wb(yd`W?!ZUka7@B9^^Z-;2@J3YKIb<+&M>$*0zW`oSJAD3J1NpOqjSt%hYz6 z_N6TeIP|A*F}&QHy!VhR2d^|a%hNGx{z-XLcTg`~IiWLY4d9YlipElyUJ5vljts0l z$XrgQ-#B|EoQV@qfqX+*Kb=59DOf|!)@kIoe}KERq|}&>>|fUSY96%&g(mZ3Gpgs1 zpkTTj8OQJQa)0=M*D4sYb~=8M6MSUhk_wK{sZ!(!BG30G+SfsMR&QO)oy~g4Xy6t} zB#BiGSyOp$8=g4`WcYXy7FnIrXANE7RA0-q^l6rgUY7Y{3J;99qIcPOidpn9#>;Q< zuE<`Djx;IU@gK>{pgL=7HGyT`Q$*BJw-OzCHUM$bDOD>Ur_cTiYZJc28=2$*1(@+` zL(T*ux)eHV+=|SD?@>~J%kKZ57Qnkm+HSfQYz~dvmf7FOw=7f#udlCFsbDs8PIa%R z-=yz35*@k;XDcS7tyHCU@wde=;SefsFb#Bec4EDaM|qSC&`&3FmhEJ05ojwAw7h4j z7A!c@cz72wV<@PfJS1lNxu!7ToT9;^)V%9smogAJ@`hsF;8|Sg&-}V4Et-{{u5E)} zfcRLe$y?h%zX@7%7ODknZiu)XfT&Rf!Qu?g9bCbPCDl^R23QwCdPY< zn-dcf0)1sQ2g3~ zXID2o_Jps@XM8%4-#%L^T5}^X$gHxdP7Cqc2MP)nEp$>4n}`KSU!hCw=i=lPFV!6R zK7e)rK56hslY-LfKYVe+TAAYGNbi{$07P}bfzt+x|Rn6*$sV&WkgCO7^AG}BR9CYHlLthH~KR% zv=RA<5+h^v4Ro11R(WbN_5MrlX1#BLDaJ89%x9<&T;s(-rgm^sePX6!uj}Hy%f$V5 zuI|styR5I31oL#y={lojXx;LLCfJDk% zEU6cEp9b*xT2mUiyF_}gnm3T1u8LF!a{svVX)U>gf4g2?myrbuwSd%Rl8WVs&JmkQPM(6>u<2Gd zX}O5hk|&~-Fx&h_StO+g(@Hgo@d#OXM0jb=TGO0zF|GRZK$YI9ytmhWvpQLzcng*R zI;$ynLTaSbtg4{l^bG&4xr_TOE0e~>nc0dc=EEDfpmT>1=|qTXg&r{}8QBBkP}pEF zQ&Ep>f#Z`K(ZpR@F;!Mpo|v4aB@DI&xBsul>EKEne#48EL~B$@`sq{edP>%`#d8rB zwcs}uLXyr-8CRQB{q`vxn=JRo6D)q;|K_t7l^KL?ZAif3*d{Lia}etd-(lt$!J9U^ zEOCaSN&`|>OIl*7q$;w-iqb>5b&aLx?-jW3es{a)<(AODwVS(}F-R;Nvj4DpK$p(N zE#9C&%&kzW$Xeij{79ehA+AR_1GSCgoBPr_*@Ed=*tfGD4}K!=mn4c-iB`;jr)lJ( zpY+4Kb*%)^94U;g#pJ?7ibNiF#%~W)OMb_iRQ#A;)(ua+0bQ>^ScV9LrPgbn)~e9p z8yl5~F&Gkt;Gl@d8fY<*D-lHI3-Ed*nWes~>%ZKlNVa;fIsJ!JpOn(n&@R}Os;+s73O>sVTe79*(y59T)S-H);4iDYvd; z?x&cN4jAtC>2U>!(acM!52fL!rI?5Hgj4DFSLz2p=ChrV8fmNl6v;j;!YicGP#e3{ zS<8G?dwk%a-79o5HD@Zk%%!e%=YDyj4(NlUyxRZbDz1F zI$Q=?5U|FPy0+IH*UcRqRN?vB zuJqgsz=x$36%y5f{tl|4NB^q4eSbn~7+w}9H}_J7?t^EHvfU;>f@NY&ss%jk>sSxY zC<3#IumaW{r}L!fSfG#PZR z@(}&Y4VhMykEqp^aeB;u=8A41aznleUEPC7?VrPSSx4PZX7lSB0Y4p}%+a0@h+aRZe0=TEEzQ^ZR_wIU~&zIu6f2&QqwH+9np z!76}AAfgR&ZeW%)WW{H}mkL*$h2|C9RdC-xTT*c(4-%EZ-3vxyxG2C*)kZFZR-DnB zUbAX=sm_EaptjxK{%mO@fblJhr(!J@&OEiMBk=iwNF$QTl-dus>{yyGh}M%(VB9Mp zENuE86t@So*F81>_m{}d5>vF-i*qPa zP;a~N9%q-iOA@Zr3c&Ob;Xxg$__QgUSmO{P3r9hKh{1@H3Egcvp#s((=&nC; z)QXHGBPrNLKcLLH6w9obhim;;ZAQsS29@YJxIr62iDwx?8gsf zJQ&pwGgAEzjhCo#`qzuRiX#Vuj9cc{8;yQt_e1pD_Ef0(3-13DZd`M@5s<_?y87qy zaxG)gMyp}l;e1bY_RxIY`HxqZW9e>V;pvED|4m`~e%IvMpxB6`=_%!P;f0SVBl{>@ z&BBjw*{i}`gB-Tw>eHy1R=Nksrx?|mYgC!T+JO!Ob+i~!hA!RdR#p8N(=mR|W42Qn zhF9};pM9wAZ|*6d9mlwC-lrbTD1Zccc!N7EX;Dwky~N>kD3O|Xg9n5orc%C zB4I^#A8=}W_=Q{<+(zd(yw`>tgiWT?xAeJA*Nkh__i}PcVVeI%-2Njj5^~)J!*kpc$7#S%_bpRTstJW&zZ_q zBCnX`Yq($^4fBP5JFjBzexApV__DW~DaiLpug-bD(GR3-eQTUIp=0_`s4i(27;^h& z(#0rAE!|G#MjTJ34|DL)o3f;OxO3fCFW}|N2Q-5hvp(U}V)R1Tjq|b{90vKQqhuHr zmCr@9EY?$kc2I;`C}(g!>0kYLe)82F&D~GoNI*DfW5`&lKH-4YA>((V@8~0Kv&h_^ zkBe@*+a1m7DXjmsdHTI~@Vr}vcILciwt` zZLFljNHuF$_uu!_D~-xUbG0J!lrav`G#ftrqRAx_KGNu@v|lH#so* z4+~f0hQ3mbrt{YAY}+BDR9%`25Pm!SL^AqdT9Qjaez3|4Gtqh&`N2=;VG7@B3pXT> zcbPwHzWut5%(qp5^I|#VzC6)f-ijAr$wiZCH7hTD_gci>DEitNMjdZ*C`?z+Cmn9`DpxdynU%akUys%sRYo~Z!|MP+CN6t^< zzEZ~I<}%=*|9$svA3Ur3|758T=GT3fFL{dN(Ji|&p(-yo89v3N0~F{abxlKAYV!pBHZFn=6o{sFBeH>8oW|HPIjYvSG8ViFXVYj zRBCl#q476+Woc|M8WYjc7Z_H91alUhulDKmB56bD5r$MspX( z5DkTa2ph2H#y2BznPV41J1X=P5mAZ-A3JmYM@}Jn@H20G%l+?tT_P{!_R~jaF~O$V zM-(||w4cA5x7o;ye$Cd|@@lxJBK&pPeb7T~{Y{GBJFJ{aqZ{I!+daGb0LpQ-tJ(XYCvzn%2Iotk@0GqQ~Tt-@t&jd~_{-^7zE5}&xMOZv_o zd7k^e`MF!-Er-AMM$fa3y}aF|WnNcdJE-<)njgRBr=X>Zj8&Z4BE3lFz~W1|@4oEf zW8da*`D89Ih0%++R=-t`TB|w!o6k$St8iE|du$+lXaLK2bIkli<$LZ$`F_Zu*-F}Z zICtzbnvNwYLAPH}1muv$u=XBQ7R&MFf=d}%hUMX0-luyDMCH-hYkUC)iY`=-5D zm!TEcz6D0KkZo<$Dgb4`!VZ)^3$_#EntVOYoGl{Drj5~`=~4=Ypo;s*R?&*?C)Pre zqxK%dmpcm^cu&cWD3M!n5KY#um`xjV150Nfl&+qI!c?jSy97?fZck*S6mJ0ym88otX zjrWlg3)Hy&0j37F%y+jmU>7m})aE|q5#L)>74dvf^cNIMAp#0j;@x(WTgP#F6O}`+ zufjWxN~obeg+^pZ{@`s7OZ-Sg=?ucs=zcRO|6YjI17eOV8IVgOJol)Ed6cLhT0^-B z&OBe6D(VM^_*t8@$m9kCoG@<<3kw7I^k*$U22!Pe`P-@Rn{X_^)mv{=7NRnTng$R- zz%vBRx@8~aF?_;z2Lnq0L>s@-Vac6Zxt7d-juNNrFH!G)}cv1V>=F31s! z@IM)#;_3TbIccVmc#9!>BFKEhaaruUq|spka2QbG0n%^ZRX3l07YNOk-{ZaXi#0qA z)Yvby%Ey(E&YEqeFrqx z`~SaH5g}yD%+9{{CMzoxLiWnudu1irdy}1v2q8Pk-pSr8dvE^F&-Zu!=iGbF?WTOZ z$LsZcJ!WaK7i*7^v$ICXo*zVb%KLp%-ro0!o>6waftUGtB$o zIlMg=yJbMkf7`Wl5CRE22uQ{L*G`?~d%*-_FC5z7Z_Yao(cBG#BZ$V7If$3DZV&zX zfnxEyto7^Z2q#M5^o79{`Ip^XlM)Z<3PeyK%nEOt!aA2AR*Hj{H^h(_=Em4AI?(Td zHv*2ukf&(u>`c(k0XQ+7N)H1mul(T_f{=oM1G+%c5V|%1d6ZSQGwwj!Tnx%a(_z05 zJXCwb&)JL3d*QnynzzNERszlmD6mN)>?wc-1J4c5uQxP&|F}BnfzJ$OpYBku1tbrA z!+1F4z%v65#O4#he=O&YAHIy~TB(|Ll^xA*L=UI&yF0UEx~+KJbsvOY z_;_%M)U2NSxf@{#o@FUq-JQr$%0Bjc*sgptxu~?U^%_g;Ft2!}%Rgs;_8L9XFnE33 zJZeb67wc(5^M851nGf(@s74erZHQwB`o2R}|HP0L(6FtpqB_9c;h>AfwKlQVKZ>d1 zbs0f0e7w(7Al${s9erUOF2tHq#q;;lCR^H^=g_=oO8NKho`cvEcSX|o!Q#Pahn%tJ z>8ov~^dr{v+|T_tyt`EsCH)8gW7YecRZx-Ar9tv@Pqd0vC@7z4FoR-1nOrHzgpvEH z^N8y|tAf5aW}$UIzy2q;)90F$RvW75F%|J)HY5u?~=VrpdPH6La+lF0gOp>k)#?m_MCHs^e#EQa_Y3hO0j zNUE9D_ptW1Cp`>PBgKKI-&b!smwsw44{#THWbOLoRBW%Ms*Z$`9sETmw>rV1MY~UK zQ^hz*eTKHf-LE`1M!~M7g6|vMjDm-aOguTy9Z;sdE=g%nc&p&6zW6U>G%(YWOH{NK zjH)eA32)bY%?sVNreL{(Ob=xhE6{ZYD&&8%UYhl|sx>WfpEho>O*5FOZ#Y71-c$H<7U-i8UqVHmMtbhR)DR98hj#yXfDZQpJRLKO~%^5tFAMZqYl?|9tJBX7Xel#F!v~>J2LRI1M z-Xi#SxyYifb-bcyyfmwP?Nsi}mN;`COSyNNY-i`z)$VNsHR~~o@n!S$DR!M}jLHWS zE(x}z&Os@d*UYY4Nn4|37`eg+|B+{ry&34<)G)O%pgOK#;!9_SG61~oV7CW0Nt))x z&TL~lU@Mk9|IknZxc}&7?dQV+)`+V#!ij=R=6;jr8CL0ZFrUveF#N+0e>~~=MUO2v zr_iPf&qx1&kiK>A@A}Z{gB!KVwA{%^&<&|D7PV+?TSn^dr@ln>D_}k7H1H3wdw4$7@Cji392C6ManMdNmqnN>x z-JA>o%CJ{}L*TErNgY@SjO;#-Z{Am2z2l24dZCR`6Kn9*mm>x3gM79OE1}f5%QHQe zRue8840`C5v`B5FrH+vULK5RH@MMlhNiv6V!9L!A zLo$a$rfR}zbmq*$mNY3opR|bYJ&TSag^-&{=2T_=bx`; zH=GA~l*T%|0G2|~9MI!HKP*QF&76oVLZ!;eOdv{@AZ4gY6q)P`CxB&D6Gt04y|m=m zEdF{N#7DvJ<62NLc;k^`;DQv6IJmlF;Up1-NkjAk>PN>J+wr8(FQI4!9s%LAd%@Q^ zr+ISO5w(4d;!iR5j%M}Qk`l_gxa8@aYo}g*G{Mt?vCrr9IWK4N2*f}lb2P5(eX?26 zie6X)tP^DpEl|SfYqF6aD#4&+r22&0!5tVu&%{HyqM$g7IYG@@|BZhH7G|;>T?K2n z&>)TM|JMRQb;`y@v5_^ZhD8^AY2nC=g~5hku)Q+{$-W3r@a0?IZ&E6<+5y?INX zTyQO^!vxQT*~}?4d^% z{HmoGuz?cbZzK}8a`5j*IxTk!*0Cpr-Z+5Bken#Hk%{*6I_h>`Y}5x2X*Gi^AI{R0 z$qN0Yvx7}|(oD!^Y9V90mOq66`g?eX|ET{-J24UR9hAclwJMiAJ9h@U&!^I4iZw_{ z|5S=8jqvz51&!j=$-zZ8;Uc*ceRH-Hbq?-GaR^R>S3Es46P`*fU0scqK@b++=@;bZ zhlq)6)$5(ng*>tgbdJU4IBaieb7#M6Ada_r~%aiMDk-KzyPHGV5Yu2-DUan8!gm%_Lh^fUca>YJDL)S)O7D$%>Lxlqs{GqY35fJK0 z=HLP&4>#`~r8go4#IEs}FejSgj{(exu(#0RAxi10tN#Ps_q*S1Qxz?TBB&1mCx(L? zf=P#p_5o;D?LTcg6@k$iAzcMG1Ay%aYYtn|Qk;q?Bz{zY1=TVYOc?n0gOk(K=~5I$ z38!xpu0+Gju!KL|Zj%aQd!MFHZ=ceUpv4~N=N%Wa`eB*Vk^b1(a;=5io^)K!Ue?UUh=JqhEIM%r`YXTIXT&lmQwZm?> z&a&~Mx<+o*&ziB`lww^)w$FIYAW@lU+0Nee`5?$L8ZeOR>Pq47+mmv7zk0z%?p4`N zIQ8`$rS;L)B8_y`?EQO%tK+6QfF7iw6HUjLoeQl27CaF&bS3G(grgdIry_mq9k8aL5OUsm+{})tNCnKkH$fZ%d zJoMdHjWP-cDF^Sk}1 zY~0bZQuXM$Y5}G2ivA(iKw-0Os`D>&mFtjr3Ezv%eIF!lk7I2dt)cRy-*x?_-Bs)^ z64LF%3Ch^o`ga6P?aTH{HAMzk?LMCzwsLoQ1sIoceIl;>aa>{TU!FeK_$V=1WQ;FW zQSIt2HD745K4trQ zz5YKT`=hlCl_2hSbpxF2WTlwVIQ!kc}L zDLGgvs;msP>0gakW^FsNb@EL>m!)~&SBcyS8oUQw%~}R;d1V`2;3)rer!1k)u~=Sp zAo_h2-UD-zr_S;WvKy{S&NHwe0(HR1KXm8QSK=AlPymTOkA1N7$+I-@OvZ6(uW042 z?~6uZteLf-lZ4cMPqPqzLxb0Z^*M(YUTL}Qw38V%Mqjs1JV!S{BF()0O6RNg>$cgv z9PgL2)sy&icwrpCdDS)@KW#Z?ut-&=!llDS7i?;I-1ug|F!vNy;K^6Xh8b8C?QgEQ zv_s>KjE&oO?saDJqrW0#DBZuXKP3LJ@pTX49RxZHTSDk6dkA0|INV_yL9&b=a6AU*%SZF>)D9N=roq; zM^CftKGvTWxtz4rv6syRdnQ$njJrhG(}Am#E>7u%hzLTlz1{8NgoLJ*+`oEfTFE-_ ztPy$k8d%$3d8oDw}3MdEL$OwANPd1$B^H!VR5WVM3rNFTl)ZOeFu0-M{}zUm_=3IGQ%O_LS)P?e zl@Dl?a(j`iQAEi@IKCAVZts3BkqmDz28g4#R}kgn$#};v zW(-FXeQia~96}`^KPgc;y;|3$rJiGRZq2(_lPGA@lP0yVj-o8~xcv*Mzz-Cy1JK(%y=Cqfy?-MiEB=0;d6**@8!bD@DUJ$xxOONbkZCLx{uBV*Ldf zD3J8&eYOw^6N0feA=Iitptks!$~)j3x4{d>too){0|bY$iu8}ZbEhaedV4EEE2_1% zV!)%S305#W{50Z(pB&oS3TA9es+Hh3flr6A1qj>8j#?<{)A|dOPL}rp2C$h3c+z{@ zN}rY(3qhuj$pRDz!zV)JCpq?O$$?Gxdkfe!f!JwKmy8#1ssux#6_dj zy*-augO!xhymw18s_<58Z?;SFa*`ZKMs`(DF6*Sjr3$|CTZO0#f&0dXnW?hL-|)cHmV! z);(T2N%t~jy1{4femkEIh_3o~$H(=|NlAI0RQ07`eI8V8XQDa}o=)?Y&A_xlO&89k z#=TEXGaw&bLUc2fRKowbcUdyvWaZ2HFCUl z+C2gNX9KQnmPaG}0$^yoj~0 z^bn8kRO8fxOq*;g>PCa-0=+xvG=A;Vg4L7V>h_*B!FT`l3EeE)Ddm^DCNAx;?UtnP zmV~FdntciAnme4R4H?Xn+Ts-4?wLfbuUvNDfA{ubw*Xy$bYSU{Ic58)UJb@)n^A_@ zIa`;lCHGZ7%}$^Cz)?SKUTuaR{d;zL=>i=#l0xJ$-TKvQ6%#6F<%YQ8V%aiL8)$Q* zuCJJziuFaCgVY^0rheC`v6?;>&o*I1Bl4zRNQR^E0(;!_9GzR!SaYV zHcv5a^DgV1+rsxHg>Rw@`W`>T4jn5P1?kttMSW!g4slxQfpnS1BY<)T(4xgpY&YOk$mkO@QR|LAVXkW>8qYGA_0cCfmCSJ_AMqD zj|^8pJ&+0cJHDEq`Tq-~=v&d$Si51H$jX;Sjdq?z0#c^V|%W)RaPKOz5* znwdkb;?*q8_o;HZPsnW6BKU)ts)}L1$4ZR{D_sOv^lg?yUQS8;Nq*lQMc|9I0? zzu@zz)#(4^z#8O1iB#bxi~{QioNHaPRu1#9qvQ(J(4bhNnw$_oDp>XEmZEqIgs#;A_IKl)Of_Nyf7=4I zRyQYp`u*&MSOpbf_(K?I41kbly0?o^jze8!H>6MjM*C76`kkT-iD9EPB1VKf!w?`R zU}gN37zjLwiQ4*dtp?hCVAp@x?qY)@9VQsE2aY*o^5UCh9wZ+3yi)=-m@|)&pDNvPuN*m z_x2W~KrRF^l1d@qHu!gElm*05G*jQziqD*7-Vp<%(+B7F^2naOcM$fu2x(Q2xXEM> z&Frio)&B>jt?_`7ChUL+|MK#ZI0PWr-0{s~$3itG7-tYM)=&}RELci-244ccgbfvqhzb|39%czCFbwM#QS&eJG>qEQJsK>Fsrazya+Lj-++1I0DdYEV!}^VE%H~K z0z&~N4-k!=iR;6h2KNdyXMJ!>03ej3YwKZe?nT^D=+XoZPxx}H3XwMXAs8C$Uk6k{ zFgK7z2#J_0D~XIcidxH`#+aCgFd@K$3B;$QScoLGi(bCki!E0eMo=#@6!H;5E@=LO z84CuDHB{-yhzKS^Mht?<$w@U!h3KfH;!+R=_L)rpH))EJoSZyAKQF%F)+~3u<1F~W z)D|96k)lSy7=?TetU&N4+!>t#n32_#D;*RIIpD|!Vhpk>23-(xJ7{AC!CAVHoAOMO z939Y|@N^XI6#_*FV#7zId$3FcKXBeH0*@hxLK95^)O#r>pVEx`4iF(kX2;I|<+dK| zcT(b`qe0}S@L?}E@Nckt6l*XmoI;`tq^m?kJV*$&Oa+efv52R%V8$yS5m4@d$PyRb z-qG>XFEcoTOjuv6R=|u1*B++I&(np4g)n{>B{^ZNgZfhRM6h^w#c_f!)T_1J@uqC- zEh0n?@8nD_CE>s9rfg&{lzZ+qQlYyNL5mpLsJN$w;q*ed+ zSRc4$X_}aML;@RNUs|j()vxna85s#VNDdr91_?9a&9cf(5QqRl4mvS8xd=cWK>P^O zUi5q!9{~C1!jBo?gkW#q0*@1-nPp;ndKvNexwyiaeH%lHRX3{2ZhLx8oZx%Gvc=h6^6Qvo(ccU6bZfEqty7T zOtNzftureTe6#b=Wdu?X_}=1-1dDbzt9G!f11SBvG|@=W8`O5m5RN-xT?wip5OYGu zT)6(#JA}j!ka_yJ1>k6b6b2Ow<y7Mb?z~*>@m@}^p0NzBCF%ZhtA}Uq*2Hi?rp{Hq;pvZ6-(Fa;mD!qOTH7qLOpgY z`wXa`-kgMH39&G&9ERMqWihq0Ipt`Yn+2b~yJ1cj_!BZZep}D3JOA4t=Ynga**4kt z$m*7gr`2xYqJsbG_X!(7@RJ3;820x|_i<8Lky^A#b~czLdHxem zRt$aAhi8!}US-Woq-24OpW+jaRxE!^xfQ&S`jnz4Bu6M4`T3aUslSr0YUqx&bj$*Y zwagb^`W#=OXm5}O7TyZ*>RvdEeYW*U_|_Te{Rf@MnR;5tXP#p&lyY@p;%I`8V@47S z^XWQ8R4Qxk-r5=y>#XG84G-?0*P?k!t=u>10;7^rvIg4O8wP$3T0ub+{LfDPyL9~@ zV7EwTZ?;jhIvoug)>JrC^zeLj#(zFC_(0g7OG!Y6$6m_D^Fs2ZmxTK#{xY{{;XSt6 zHF`?ggx$%eesZn}%ULlTr0(zp^^3x~@$R|Gt|u%hQ7+FTDfBO{TTJ{sf(p|Q8n(=- zr=tf>n8@}<=2*)D<<+h5*>jV9qSmdxG)Y?EIkE&;s}-id$iKT+A?keS&_g$+tiCXx zPW72Ldn_f5m9A(^=?^AXl~ernI#aFYsgI2J)%b5tWY@n2GuzTxZ1aW&o11QaO4m-Y zg}-)M8M^SX2^YlWKqA< z`wV-j^6=wVm)^S~zpa{M=e~U(Fk|1Fay`@TpDvG6q)$o9Fg9}yQ7-K1k`IGGYgi4n zSP>CABOBiyq8RO?BZ{ntTrxmeQ`K1Achx4We>piW;AR^(Gb5rnQj_&I6;5uo=j*x9 z$;80Q`qz-bMQm?`*llQ`<7_Waxh(ln-;4ty%W_-7gh+Zpv>jZw(J`P?bM0 zkpEGf^}a<8Nu>F#bg($?``dj`n*GS)mvUHt=U>bkMi&)@WEe?Z|ws&C+58Vs+(Lw`twtBK9Oo3LDr&jR7Kppg8j?xF^>DmsvJtS zrB2=&aC&$udVQqMJjMmni8M_s1S-kps{?j zWLv@EM9C?cs{;_-1Q|%gBusmDzE{TZ1c(q463PGEF2c$m<}B9ufT-i_UQ3aquk$=+ z#`!}DOqyK77z#CXVxfrLjNiU~W*`x0LesS{^e}6-z5__5BIhjMxXMw}jd1{};B!Di zlzi?BAd2qk@j<V4tRn%-m}2Tb+~V4AyNt?d zr~mtOJr#MBpjd!$CpSH_rf6*P+mt~HFUw;|x3Z*1e?r)kZ;_TQ_qcWnut!?0|HgQ1 zF=_=$D_>Lp-ac+<+)H9jXy>KHnY8x3R<^7~l&GwzY%?65`#i#+i39v8E?!@HE^EZ? zuhWMXY#i$;BAXhi9_00jY!?c{usM-r*pYE60-nTb(G?y&h#;Ud~q;bjFC|Az02VM@Gh2>uxAzPVZxGe@YLP{O5YV0Q+<7D&e6FF%~t zuz4{xRkz(^{L=t2lf2ldFYC4==B@vGNoMVuB^&ja$(6DWH~uK2!1CZ1nO#xM9lrD& ztPBB&)cW%$G0Mln&29W13MrwoN+MDA*jxOFUmLE}F~m=ZKc4-KLBhti&h8s}0a?oJ zxw5=eMXz0m;!kXI3%H2W)8jd@GIZHwzq%{(kUqhaAKaXf)52gD6cE_ob_DVID|Vk& z1J$Q*gK_ZnZ)o^ncP+op*cXUJmbY*gTPuVdHszJD-RN5efgBftUCAQ%!B(VuMR5}lD zK#jSF6l9gz3Th12z?@5KX$bvuATJ9}$GjV;5W20$c+w^lVjCe%^K;4Jk%BVHKNzC! z5&tlma(8LzaR(tIi2gy()j>nwssyYzjBuciWNwG6#6DfT1w}NgsAi-gtq=mZ?F#DE z9VT(r!jT2g!M?PCssU0dD2jmzv(f8RV@m#R4tQPwx4n2O)dX!H;9kjqxGQbzYq>A%6v>D4(&u}oD^L8?B3p$3&|K$S7?AB{u}qIfsN zkP#J8{|G}bB3uoMBO%#L8c;l7Az_4Tuu=Ez@tmo1k`9F)mNo`-I&xtld zKL?fyxZ<~Gl()3-i4D%c&;#UY^LbkH0!-uP>-cr}VVB}-$UMH>MtqJBV_WO% z=p#IJ-sfD2ru&FeWrVWXf~Wh}uMpCt11IoptY!ISBGi{4Dw?uuE^Q<0QT+~J?1zLc z*i->kg~|gs(ac|;&Y45xjL}y)D%^S45U*-)Pv#I^gtzBnx8@zA_IlLj-S7~2(9^y&v+pGiF$2guYc>sVpUt>rqoJ8F@nTxueD9CZ3=P3F9~J^(zOL3}J@6Lp=&7i&mZnq*SC1 zgItU`w=VZw>O%))?BSL#(bS1|3Q+0sBk{H7D`Et)k)FTVedUyWhK-Brd@qPv>SZ^@ z24T~~?7D$R7~WsCAM#WexCNN(6#f{G>KyW(TlsHx&in(t)v~6-?)JYI3|@s1a+&n>35RKwfHI;|Yh)8dUhVp1I(yiXIVtd03}3MYc6eziUQzKWXI zC3fr7XG1i=iK9B!qi9yhRNhKLy2ECx_d9WKz$&m;rY*xsR$YC9s@`BQHdt|`7}@$} zx(i3*zJsN0uS9=_4osKOTLG`KLFl!vt}flrC<2EG`eTyeGn~iywTM#e95V7cBc_db-#zmBn$~xJ^4`|mR68z3q9XC{r)8MCl!p)!=p$Mp#V8o*)QNfdAU^KxT4VOjZ*s3Ivpot;wa{eGr z_517$t!FLK<7DzbykfND3no}fL5)576KzC&WV+EO$(~=jL7f)&UxmAE{N9^{SC>Kd z{H_0jS%OfEc|PwB7hz!IbO*h|;MyQxuup!~V>X?dmImsS;r*2k@Fv1SD$XdBJ^h^| zsuL`3RB?TSn=VWgNg6>|LTJk#U~hvw32#xmOA%Qa&J15re$mCrLyiomQrxSmXSov^ zuGa`6j0YTY0?dRDC8HJT;YtQcQ3Evxyiu3=d$xJe?UoY;=-@#-7Ws=8kKed2+$qy* zD6md9koALaiU{%q@F`bT=q=Xs+r%HMX>(V1ot&z8(jv-vKl?t3JgOS^br>+1VvXc?(^#BOwU(0jc@56o=tC=9GEJ9w=3n+*CWDCW|iV6So=1dH?f|>p@Lmf zZ(YvNbm{j*VOg+`N9kFcv3B4!Ly-4C-fz6op=Dr+9@_Ee8*AsNMb5_6POFI;079_)YbCB2)5eA~ z{?Bc(USF0zXCO2WxSz)N9(Umz9n2ADh+73q>T6w4)WJar@E_=@1E`b2q-lFEQkv#| zHdQMlj9|zr0Ly__7~Y-x!S7It(5VSHWZv=6iL>IOGsZhICpbzfPG)~_7K|_?W|r0w zeypkdmOZ(f<*U}#*M(Um9wi1md0g}$^ibnvNAQS(hgfU$tJY|ejPOo@HgiIlbX)SO z!TK))4)Izm+D=qtA%e9oc@k>0FzFBW{0dYCs6wA!2;pE%M&sQNjt|sTGwZRpI53q$ zxx2W}50jKVKM0@HEfwf%-;_gZ!&jqR6f#vOFkp9BfYu%u_0Q#|WY6cLd!;@Y5`RdL zJ;}k^pS0#hj2tRYRAma7E(h~1tJ}#>JVjn&Gu4-s>>JgZ`$O0tBY|Y4gh%=5O+Ta& zzJ4m16McW_HPF=IG9X(Z3}>Pm2Mabx|6%H7qGzH;8+-dQe+Y*THH}lTCW0@X{_mj# zKwLn3@&LM=uhvz|QlP;cBS#17K&{05Ng>h*NNomH$DFD(CO$Z36G>t^bnA*}5kCLf>j46ZIExT)?4{JwRJTk1yWpWqNnpcuzoWeA3R|++k(^n`UEhZLxHdx5B0yAmNUqVk) zaIx-=9cuOm9@Kj_?rb*ypH356rYZuA0cS>N?f|^aKjmr!H!ZMZaKyzHyBLac2j?$f zxA1!)t<%=lrX~z`fFTc>9!N+?7C;3jF~S2D4v_7kQ=jd)HTQsM4wT!AaBOJjIGYc| z`R=@d2kROr@eq;E50)cY!X8ZkU@R zWKer5zeA*h-&LpIM^kM;jFhU3*qP${U-;bhVTo$I# z`{b7(C_F%vHz6uDul7R4mf>D0LZAEFY7jiGA`lq%rZXC-Ee8iv^&4Ety=^-`gs~b9 zLru{X)WD;w@N7JclUYUn=f9xr-dyi4{3`Xdc1d;EyE!Cb@yqZ7hf5I&Z$68_(8peB zs~7(s-(x!0HSV|_zT#=JyktAQ<$mVgZdoiPWi`)zFFt-&yr#BBjdA=<%PoP@8>CLy zS2@wOg>J-q7*5Z_r$S92l~Pz3-}<+I+>m{khsT-c9xiy4@SRzdQED` z4sycP@zj#; zIO(Y$ZIk=?7obO+}|^a1a6Wms5EE_np%2bhT%S2eVJEn*w{>V9F|`D{hS zqZEw&>gl#ev{&rGaow%_zev0PB!$IYwHa1$6PAW*lQ+DSi;QRG@135;rL$ZQWH7up zd9S{hB?w2YiZ4MU)`7;IrgAL~$^xv$zv*##QB%+ss3{|MoU{a6tmlW5roLX8KB~RF zUeYPMXH8g62g(vag$z;&yG$gX@x2d{8nuGl2Q59lCrMS>KY8@bVK)P%F06o%=M7BY z<+rJ)1%>8vh3ar}11b;_+QE%AWWfU=2!wr6x6Uyb$W4e~2cy*z@D>25!I2OO zZ-Al$ZF!8G0rAPNJy?U_4YL+|=U*-4_B(I5x4+NP(ghS=&ugdh-;}Be3NPllE9QEB z7~B4&lS;9JsifplUtqi*VjN{-j1hkBL3Z|vn8_X@1a@|KI~hzx&-Q%o=c;GlW7KRA z_S7gGk8BI0vLaEWH(Gv2y-54;ZT=B6&kZI>}1y`LUy-?S|IXBPLqc717Y}Xf7ph2h)z9-U~z;*lEwYx+S+*oVtO!b z=zg~k0Gbn_f&!Cft=$~S1gbmRz)DFpReR~UxYv?Td$d7ij{JBM@yL}FUR|wmY5|{H z{Ko#;@Xq(&5(Xoi$Hn89@d~ob1;al-#q|=dTJpJWxTO7!L~3tSE2Ke>Jij3wiHiHB zaUb1Wc*DMXoO`1s_56Vvp)Jd>Q$RajGO?i3_jHaP`Z@~Kt-bW7o0#ppTv=}sDPy(~yJI-@Y z3Wu$#Oe#<^#K@()d&f!}iSr7r1=wQ=W>B4dQNu_a*>@OJNn&=>I9h9bBeqxe8VK3W zqH#SLx?;?BRCN&>LHnP_&G-gNap#OP@=*E(7$TxST1ACL3?iQaObu|PLsCer?lnHw zWoOwVYH+3)FQ56=upi#Jge(?X-pcoqFOv8Bgf(+UysyH{*bGkE^MnhQLp7922=KX3 z9>@0?%wDU*@|w<;r zSL5qF`Is$jNG=@P_np%dj;4BcUXm1M`+Bs-=FS^DNi=^qJOhT9b?Y-B9R}j8asMw$gDpaVklHD{Y=Z4Un$n-m3ws@w>sV8|5$fI0C7fKJPc~Blo-6#yROt&fX5Uo?m6SGp zacYf+cfr35K}1G2)3BcIFLmDk;tsV7K;0lD4lw2VHb*V-UmX>SnF8|<-3?GDi-Mt0 z6%Ta}2B6eLreN2r{|Wp%Wbq(!3!q6JkuPe&sOk(B-v5g)g~i(a|58#`VXj-7thPc- zZ~%=1LYUX02`Uw43NTh9oUuS5A<}gq;yck4l8 zTo$yY+f4nq+-U%ln$Z+*^RZ5I2O_o_O2b+JjD}?bA-06dyiiKt-y0)^^6ud>P+Sgf z5137v2=2o-LkKr{(_SKtz_MhJrmL^dKyW_>xHwoeKq2v!wG6%l>c+u$3$<*(3RHdn z4k1M=h#vvaKjiEKr*l&RV~cQ)-k<&GqBzPoKjeK4mfn83$6&J%^3VYRw1)ef&1>=a^U!}#8;P_c_iJuw%wM^OF?BnV-M$CU9GnrH>Jy9`> zn8N5X;?3$e%-6B|7&X+M*Xpl1rW1?87bG7q$%K@nV#}mbI2if7$foGqws&VJnY0M_ ze$MfhP0hxr$CFWd?=^Z52WsKPwOBj19ld=};6^e!TI51xm(qZ960LA{lBL0Yq8GGN z_wi9XXOuewqZZsTDmsK{=0?Nf0p_%-_4n|PcLOT=x$A-?== zj!w$SA>q}`jUsP09v$=Xubz8$hC1)grzx{I`)zuH|InQqaAPoH{v6l&rnx18HLje~ zEn>0gS=2h{ziONFe11nYf{1bC9SWZ`q zH_IIY(i5qf_Y0va1i{>oEIb*G_vM?;Tb@$<-dKzB+UDBy2*Yx=r`c;pYwbRGY0CP; zlN*f`UrojIn&h>V=VVCWfZXah#>aQ!6nDByI!qsjtq8>gf&@Lk(##d9?EtewnC9Qn~V#sLpJIV!kcqMq(J+i-aE2 zC=p7$FpR~0u+Bj_@H~i4KB*Pk-`@C~oSt~BBqSj;W6(HrI_niRGouIkzmXA^-d+Mw zHPd8ef$g%Yp`iyz#`hgY;Mxj<72pvyIT+Is=P(>f(Yy(3>YzZ=lu7!cvRmwH-zd*q z85gbffm4l5E*tY2gx2S}Kmu&jJ0f3P~ z!7cC%(2=WJ`p5msU8%I|74xIVV!n#U-z6JguWSvI#D)Qi=CO$X0(SQN*KxV+cq`Ya z%=xr#KAkms{p_7&&x`)iu78_ukI8tIrv5y9xl)_-`0nY>>=V*(RhvKOb7E(=$!TJ; zYz-}~zQHow%C#hhB_pPsrc1hVahWMJf+L@NM+>F}3yA(1o;CzU$RF$rmTDfY&exfR`F5Hba?m(a~pTzKt*F! z@T2>nlEl!4P2!`qYb+64R!7a$(ZzosysSq5nWpw(&(u6?G@3t}BH#M2nBtUQaJF!Y z0ylyzUC1w$MUy=`Ej4e#g1ebRg$@sfC2nGWZP8C7mLt~xA$k>Scc)j^*OTphHg$mW zrSk79RpRC2W!!n>U>ypjRy>3q9Ez)}YZkSWUrNiXG+DWX_z>jNu_yRHrOLEd=$-Hm7hOj9AD0eXsIg#`lZONp=!h4ZCH7ccFl~Un0&^pN*mWyZc?CtCHRgzh}^*G<;i!YI+%D6)wn5Y{kzxyejtY`); zw!Vj(H>g5d#58=h;2i2LCl@NsTQA@u+KUe2T(>pj9 z&QMN*(vVRNLTcR>IMxAL??KNJ-1)w89$6l1Al))E5S0>%hnu_a=7xG?!~>3UfF?pd zT#IU8KwmIs4+vB6B2o#$br4b2zzuQ<2|cgV{pCOoa1oHqB9IIDp}Kg+77_#_Y^DGz zgHHlWkcpF196(UrE0tU?>%V==QmxNL|I!v}eE10b)_F32H)>wxyH z1d;&_=6uCN2+V|XifBd4@*f8uxXf!I&IMkEM@Xm$8WH{p^_~?8O8|rtbdT5}<)b7KKZ*?K-72QmoE@`%i!2YF)OXwiDE= zFn@k-^jb;KM6AI;Cc{|n1h@E3GE~3(xVhN$J{pn*q5v3m=pr`;O%6a^O*hBohwDSM z!y7!1F#?lzRn029I3z+s1-(XE+W)Xqy0kuKRj`EFY;KO1gQDltq8=jw#1cZQtVA{0 zJXcd41G*2D9VC5$ybpNuh&!sqQ~zE&Ji7GxJofLsZbMk7`?O7C};0)|i zR~O~Cf{0czX|9xIC@6!oPk*KeA|>X$UF=E<()FczND(s2)g};DB4W4UFo3w1Vt%uF zU-s$M*b*E*AZTW>^EfdHbP3pPA-NmGB!F|ocP%1zSom`V1qE=bLc{_?KS?wkL4g(b z0B`^V?f0opE;h>#JBaiVnWuLHk>NB}{Q@w3?kv?8SU!-Fgm{60lfEIlU7fokgBc!C znSz*C;f}yE2D{~#i#15hOhG`H)M$tdo%zTB#OiXhhjSYZ7g(zeo(qrTG0pQpu`^Ui zB1QC?!2Sev^oTY#-$OpXxXvg_ZopAjdXml&-1Y$?Bo6G<;CVxM_{(qpm4A0!xgWWN zSXiQ(Zg~)~AMoK2j&3kapPaZN*rJ5>7$=$h@sUo8LfS}5nYJ*Gkvwp`Z6Od{qDYRIZ4J%`_EO*qK=j9 zr49|J&F1YP^^X!$kt``D_p+yTUYS4jjBZ=XeYex*wdl*zU(Xhc%T#>nmE8+PD3xcc zlrE}!dG`Dn8NO?*hcG{{=OT@vfbbTa#~{or1y+1iGFoI92oz<7NA`5 z4lz|aRkEVF0cQ}Vu03DR10vj2_W~A?xG*;3GApH*EkH^*ShbhxU!h!-gRM(9Ql(p zor_MCS?V+*tEOIxYDErU_mA0jGX6n-p7Cb(qIy*QHS%Q(f;6VJ)z1Y4ugJtqtATrrtEoSWKq%;}4WOL44#W0_}9 zUOPR}!0N0!DL+2L+%Em`hb2y*E%wE4o*y<08+~%o7nt$Bn+9C6{K+9RX_raUx^o{kU+L?s|MDNpqH6cRUtct7#ByEEO(7w#DUlUb9rD5bdqy&g7Q6jH zGxD|5e1L%|&42VR<#OKxn2B$z<=kPH^5!H?5W)CxGhwAFeT+r0~+a2JU6zYI%38Mb`xUaukQ86a9cfitRe0s)ofKFco|F^zm({RqT+0dUqcTv3( zS+8`{fv&1STcn(?k))T%DipnRx|$eF(3G)rxF+IteC#suFh1mIo*;+P(AMWp2E`n` zyy=MOUmV=^yh>uVA85!9pF}wqhpys<1TiXfy-j@nutep8qTWN6`4-!@wS7rbgxM%| z63gf!j>qI{&&zq)hQmK&6o;6Of32g=epSXJ;>*B(=zg)xDTX_Ca8UllknA9DU;Ud0 zmT<-2NRPSJ5YE-7g5#E@O)g=Tm8kpzE^Ce{6(TQ$8--=#9`ru!jp@q)KLJD}c2@_5 z-<1Oh`O&~ymANgS&^KyuW94gngA@GlhEt>T(rqZ7c~M#uW={TDS9mMFbiU|y9_#St zHrd%>tkNl%-DjwISDFR;B&q8y`qe zF3Q@NX;cb|xq|Qh@pjSvJb-o)p(r{DD5Hg?@Q;yyCol->X#`+#6Ls$;88g59N9}|B zl#ULY!SCSQQwr@`p^e5L|6IAa@?HX^F$;~u1WM>BJ_cDX16FVrd5}L-L)(%C$K5MW zjlq==2P^@OrX%dO;lB^K918lxku#e)G_bPvu%gXKC&{SeEFHB`?Hc?oBl(u{hz?I{ zMOCuV+0%c@eXXJ+PwqjkQHYB-F(Ci_6B*^rk7RL!5hVdnmxz`snt&42;4f)q3zuU! z5N>(7kvzk(%CZ!kr{Zw^y>CzUt&49n-eW;4qOhkS9gG1?WEyfGpLHarB^l=0eF$~M zZuiwtGwLvr9({C4FY8Xc@e~>4%hb{ zb8{xBOUEP>Z_TU92F<{t0Gmb?(+ebEQKEh~iV2nbfc9WjG7apM&_$Z#O9jVJyqY+A zl+@{GbNsWNR<`v>x6SKR zF=LQ7cj`@?T)*-tpkL`|xuHoGj7no=E;LqG=lSZi`QA<~#ql&{TT_e=9*G06Ve`AS zE(igE%8hb)`2)ORP~ciL^i(TN2_?p_hc>p`80B0j^6?h4?;pXN`e_^Aqi4@*bu{Lf zQ%&Tth_HO9W7B^Rp^MjRz;pnTUuwg9`tl^+P_TgJG|R+zJ)p)1kM`G5i(gN&(KZBU zFy!l}HCT&<@6#1w>(Zp@wEn?BP3?P5J1VD

    CAuRV7!Y&iHyx8n`lFLPiK}~a8$RF~0!H?- z--yp-6>NbPcXtW9>`7x&(71&ozxZ;fE+KhAFx+o3raSxBBfA!UZX4mSM6@jV-Rz25 zcrE)N!wnv4IK0>z&Zrq+GeDpyL%R?}UAKo9*j@`6{$H{q<=zEI`UWa>PF8IZ9Y1XR z4J-ttpEBnK_ z1Gl$&J?NM_hFY-p3X{rgrn?%XGe`!|e-gs%4JmM6WA5&qtC<}{uQejj1-{i!LK@ik zO>n+Oj9kM?63d$t z0S$&_81d~vCqno#2cx{(!50d96F>yPOPi;Z4jRusEYrLGKU=Y2bO8eAaLkKLRP*9! zV%{G)iy#^oq||M7tujALNOHVYPg8!x&#OgAaOoPfD|_Oit}T7l`CIf^=I$< za}MtB2D7qR^qqMOoW-6vzYI5Z=ds;f4KI~`2EY9^%N0pVxE%2CZ|qY3b8N<49`Vi0 z6~mvUXX?$`o<%n`Q}xo(;Lh7b zco@B!FLOAXuyv(c@~*AxE5iN3DSFJ6q>28Q$lKE?BbaG-rZ$5ow2(6}-&g4VIWZo) zWEzLl$)eZS#Em9XQwOYJ1AY326Y=4=ji12B#$&l@;KfECIB4A?q{OJPlJqr@BS{h` zd5_OR)n_JQOZxH21D_j*3jB4-qFp;@EPz4Mcxkl#T^< zb>w^k$Y?Uf2!ir1RV2&w-`^GOApeozZf@qwjeY;%--7t$=Rku~cLTGGa)aSq?TDcT zCQ-Y>n}SVUVH;ySwPLl$(RG2InsZ3Ts*yJHW=+-+P>n)PgL-}Wy8?5e`bz2=s=zVEIjHKG4K&Y zP@R7NhHyBE`EpAcyTWjLnbdlcC@JmUAK0USw+OL20N5+6zHP?%9%~hktvS}U8xEFI zSlW}X-oIUhwHa>1_SRz~^2=cvqWA4x@w>OqWr7%@W z3M{z6VFIb1jYD@ah{|fde$ABLAKORTFxHMV(KS)E_e z#{DAtJ@@hB(R+b_h{X`vt}ZYB>IY9WEN=lG}iE*N{0 zHei7)PBm$$g*G+0o@2_4Z(?e8>CZ~FX5BeTq|xxkvAR}r?&GG}FOzFS)+bnj=$sif z)xT9b9+SVo$oicz$vP88h@EFHF!^0{Drcg^?b0Du-x5P zkT=u{Uc&5WTt?xbCKMSN<Y zCM^7Kx8zCvXzt_&>iZUb$;x$YRJWQkZbOQnaeEP!Sci1@Ra>rP`WQ30^*hd-tHW!K zq>Hi3TPuDAibGRc5Tl6gW(yN9{rcJmY?Xs%Xgxf7Hsp*YHa9wHJ+BxRyEw0PmfFuI zAALN%idNXE;rg_jOV1*RaV$CToq#Q2eJO9*I(+0JVOR$W z)kTc+qiDGSGhR}MvdJwBBvaN|p{FARpfkqZT zQWjYac%%^304faZN?FZ1gv|l z_SFCDkbq7b!uMvpAIy_M=8e0<4I5XQo-)$u6VT#eKp_k=(fT!#Ibxvomidi67!PqP zh*$Ns$bgm)i&pSrdb7mJ@1V(l0uLo5Cfpg5yd4LTc~y6u?4r>c#;Xbs-+?-Z%yt(w z$s@}o2C9>wWd)Q((1zK27-^#*MhpqPZ$Cg$)h^V?D53*8U4#rAV4-t3`c$5bXP6h7 zqX8!k6+Ov^&;L{@=E2{3;8^t(`U0V7r`*|hC>D0AkdS~l8%_XXpAp=~fjVALJaieS z*K&U6=DjlSvz5gtd9RatN62%uo-W{8bTboD`((VeFwRqfur5)W0hef0$U{H zht}RT&9Z`BG(#WW$_cA)b&PkEngv|$_k9rez64t#pW%-xs1=g@L@2dZ-Wvsy<0!Q1 zQh<~Oa`18lN14*c?}kV2Vw}6FpFgYrlQ0p5ie&&fjSefYd|A)!r4nnB&its2M>*zw za&bj+kqR*qsJDikm}vYJqOj$p>_q~*H_U=@=HSoV42R1AZtSBN0Mr4K(w^&-WtTPj z%*M$Dyx=e6{aczvuK2;Vq{2ct-9fFE^XA`163<&Z>R>=g+e7C{jQk1OSKb@8VIM&B zAhJ6r7qHBMn!q?Mb!=r%80ZlxK+t$$j*JVI!h(1?0_Zq_7BJUm`UFkD|X-JBq_k^gD| z*dZ;SrNeR1iu(w-*L1rJVUJ)n&;wg3MEexHx-iPay9X_v2$uKjYMXndCYeIPM`L{}zPKd6E?-K0OdIs)h3Lw!omdnK z0ipPdnB=Awq1m4wekOc;#N+1mev(Ut(4FH}&R7#)=f9`)1i?SlHWY%`3-j8y?(J9X z$M1Cf9Nvpmx*s}+(da3-X*u9Or=5c(OdvQaA*@x)Y^gT4W_KOgM1Hgt@G9tE^Xzw@ zGQED{$f5%#VZQIIj5T{4LF*rBS~C;Tffr`}{F zFj3of_g$={Zc_6-#94e1PobYkOWv!F#DGpIMT=uE=Gf@sCyS$;OV;73AM=Br?59aw z;rV;Lfzny(s7{xP;Nj07xY#9!EMNYSdbcA+;lT5E-nE%Bzahxj`G7n=oPP81TYKV} z;{EFY=VzGVYyCMs?pru0F#$Kdvb^XEG(RIV&%-mzBfI->PWq32JGKM|-Si>_V0t8?R5AjqljE@%-{Wj(BzNG z>GJ{a>+8O|NTh9Q1cfhX7YBCmDol-;IowgR$v!>JXo%w%&3vuev#mS*N$>2XHT$c= zf0?;l_xo?rom$R4JdE-rQyAV|L#CkH(GC>LT{}LSmaIw#@>&2{{Kq4P@w?$WI1SEn z>p^+%+USk*Q;7Qw+|RPV1-^YmlY$ z2u}9^cO)#4e0IZ?V1$P{_nK5>gN;Ts+|e-M)nr`FFUb>^+$wBf>wrWB}aEDqwItK_-ZW)E*L-vmV44Il*xH`Fx5pl6$S{>XNOYD83so4t% z@W^K-1oKbinYr5;V>hiNfRZ6$%4z5KPHH@nfdr4l@9}Ka#LQn4+Z##0G~rZ^ckd3y z73tdSRvkr1!$d&jP+E1aGk&L)HHbB+`DyVN5!?e|odza!Ko&1Z+^k4sOxqZdv%s3u zgqWK+V$i~+#$!i(QlwrpSDrg*q4g}R;p|Aj?Lx%1ysoY_FWvJOyz~$vshFgJd}X)Z z^|GEtyaF}MG7@=XJ8n<#`u}M6?0uSw#S3Jw%wxOwYB&C7BW_Nywu@ox1Rh7igh+%D zov<{5`#!L3lhV^ypvK?^bCPy{FFDsXV9TVLQ8-F#OA=O>eg4o|c(>GLXl{kXRIB!AW1*_c?|HWV8TZ+Mc z*8U;yOBw`!svOG;b9$po|F~#+`tDkI0VQIY+_JYW^tktJ<7R=k5xLpvXc(6RtFPa~ zwy~aBm!%o(wC{K7x~|VVP6a)ac+(*ubv=(+gmX8LetWd(ln4~@#_N&PE;q=AGEI7n{O6Y9{%m?r}s`UqbqBOR@N z^_*8os2gaBU|H?(0!Sx}vH^B|On<9h00ryaJD!i;)5V~7@)>L%O~qNFbps#a`oeIT;#CJ(Th7`4BJ1oS2^e z7UJVD_YDHy`fyn3>`(QN4g^qIF4tdNb;4i|ypPU3nm3IP5f7oclQ zfpH+*u}%nzx}W9^xA4Az0!p(=ZA4NBe9`3~Rv&_#90FeshgDeT0>TG02CU#VSRuiw z4A4lh`X1Ui(uDFYxZZK^aL@-Jf_&fxp%3VZbiX=xg2)WSZ=lObrBK5SDh^>G4V;}H z$Cbq@_v6NAXWw#?+rb~Rnly!f2mGaK#balH3WqQh!a51n13p*9H*xS%D|zpez~B!G zB1Hcm{A&Oo7zD5*&6D9rSP;ZVbt+sJ8tDv_OcOn5~9DrLlq92&puvdiLeNr3m>ciha*PywY~CbQPHCo7%u zK_!>A5nO3#`)_-5Gu+t~6BRek?ozxwylN@7iq@1c=cg`_;G%n7;m+8#^)$_uNA!f~ z%Sjtur17d5M!3zY{}dt1?)_CZ@(RIHo0=Jl7PE{55~Bl#)A31ux;wsy{R0ae56TA; z{)Nv8hiZ#Z|Ke-I`ayTrOt2%*kyfGewLXUK++&CJQ}oD#S|hq}cYP)?L0dYKelDjT zat`&jew<;nE-o&6!Xdi^wEJ!;Y1-Cu1ya&P6DJWsf--7oGnV6Id0n#8zysP;&V41{k~ zIEp3go#1GSA6=wp+6CZZ@!V>gRyZ7)PZkf*yd!x#~gR zQbgysBx+Eo1?bj=5*kKXNV4)D)_u32gMh>QFX^tXp4+Y;>lk7r-g z9Tch{tv9~~Ex|(~-h_)BZ`HAW-S->X`t#isyv$h_iY%ym0R5z~krA|s$tvtXc2G|g z^IlX>-ldEfpgN=wqp_0yn0{}!Z}!xwsA-R{E|ufzv0ld@??d*U>_M}V zA3y%%gn_OK1t1`~73$_qn8k#2bm#H}NEvAN;jif=SI=JGR!mJ^dE{Nvt^GhD?=54< z0BgHJV^4-AOL9@PwM$7X3m(Qm@M^RE5I)b^lMo>WDM@DPFGkgbv`M~Of*b{(DO49F zdw8K+yWxQ9CcxI`LO@ejTox7(sV?4#8`I!6ZTSzkV7m$>mV}InZzbjRw|;|hv}b8Z zo?1kzai)cAyM~DrW7ttL0EuK?vU)6UvDCYEd824H=nF%cnmJ3IeM~;{wC*cpV%$I! z$jIxCO}{H)$CbqbN$27MbHw5$F$oEHrwkHVj+^hQBr4=3{d!?QjsXkaP71-zI|OFD z$?Ojw`f-M^5<6aqeW>@yj)_%Jy0hw7N9y8Y?jF3B5KnfG)D*-!0Y&CcaCd^cAsbf=~*;#PO zetG%D-HOQyQ?1zO+Xrz2-|Y9tof=iRWKM1TaiN26qb|zBnw$MeYT7a5<+*ROB$b&} z^-$ApyIN&$GvEg-sm3ol4L?sIk60Wxqv-GY5Wc<@+m4BM^Tv3po8*K3uF`$0J!7v| zzteK7`@fATVfPT8UVWKL7#?qxJ%4h8ltpbMn`Mx2o7Z?~!)f(|1_SjmGs=93J~zo* zXO@0-Z%9DPGN!Rmh8k$U*KO*XpU2PnV(or~QK*q(TK>H8Pp$^dfVrRDX)q?sJL%T?1h5A=V5;0Lcfc)N6y_P%KpfSv+@UwE>DP(<#?{Q9>( zr#{4-z}3m#qdFG~Bao&8aF|gDjxM}nXi;OVC!c)5&KhKojkPBZ71TG|G~9mjMb~z> zld2fBk92t0iINqQVq)H9jOJ`iQ?^ozjlFk%g`nA(@qQ-@ytqP6Qb;x(emmr#bmxU( zGD}~svXx*=Wx;g3l{B_Vml)Z*mU|rZ*^>87%D}0IbPJ3qOf0j^Bs%reFzmtjhx%_p zH6J8KaAC^UPn$yJEsQ+l-ps2O5c7aXGE^ZOZaGi~gW-C2zvmI60l4FHyaEdll@R7c zKro`Sf267UJxCtotw!z~L6iXQLMI1;vua`;H$D)#?%ebp3ti zxqc-6--1z#b=@*qYzETTiN+i#>C*_3Wog|Oh{d6`>`ZR6R{W?6mQeT$fI}$rGbHL+ zcEBl7zaIz0Km;2c#zJT;4wPbOHq(S36dHpktr4bM-{*P5&rSfM4LJ`0BH*=UT+m&k z7C@#1Z^&F~r>Xza_J&`?(z0URDMtIe869PNbF-wT=47YMBKc*-mLlZN+kamL5JfZgb~#z;eCQD4=Ve>r3w7o59SJK8ZqAueNo7NHG%by zG9rjO_MQnRIS70&wH?XC=zUcm#XYkqm8&b(D6rTS0qGdBHQI%U`f3*tzd)Ww@)y2X zT3@%2+{uxv0=Hzai5BcRz*9NoL!s0y82>Cs{f1$Yy)9wW9G(EW#d)pKPOnk?bAI$x ztnE>3yFl1x9E<>)uZi{VB@JiO3C~%3c!&&0;A5bE=*W83gqFC@5^ItOdNbTeCq1Fv z`jx&=YKy{$!{^+&-FDeYs!6$^5-6q$cU-^=CD3&C0<_@UW=d(qAG#LdM2e8>Kz4*g z&-bB=+FBt*)3+e?zr(d*ph3dqh@$YmQ5Ru+g!-4qFk>tDg9-xtP8c^w55QB5s1AFZ z?gf2AOVA4Y;Y^L27r3P0^+1>u-Jt#sR?-^hkB%0>P>uj|RabX`p?c+aDr8QfroA6t zYS2i)3<^(7Ep6?6#qMK-bch(95zWo&x~W3%Fc{Dxf}WfBtdHD-KjpSjSPe$p1;oR4 zF-qcJ+$&v`TwVmM9SE?n{1*_&>lA<}0>W$w?Sf0PKoxEzja&r zwd-7ct=tufhHSEUb(Bi3M6(blv;qRWiw$CF(8BxJ?tQamzHS>&WW0+?% zJ;JKnJdoG9-ez@PEmnv$cyQnAy{tBM&=}igf5*?8>t*?rr7!1q!h24wy}8a;yVoRC z?B5e|VV4cu;mDpSQYk*<#eWznXIqiiVikYJpyk$id&w?2*o!cny=3)BrdU?n0CR!2 zjDt~T@q6Y*T6|Z~okydzuD8PV&ZR}JPWMQ311?Xg{<@$w#o5Y88t&uHU*z8zj)mY+ zR$as$R0;n;$+wE!K||*HbySJuSkx{m8h!-Sc-X>in7h3_{b9LkB)SaB^w9GBOwY8KG*7EC zeCLQ`d_ls?aoM7}&8{0=B)|YkYu7@My{VL!S2BrU$-&3z<5%6C&ZC5HZv>1*)~oaV zYQ&K*7X|$4?xkd&n%^Tyy9ui1raN8nBj5XLAT64-W${&LWM8)FOJUV?5-3~wZG{Tm|X&E z3?iE|JjywXmzHq$!&)6? zQG9^VAmsXjSH+-L{f~|Nm2c2~!GF@LIZ3?8{({a33v0(&2JSlWoB<&NO4*mFnvN~O zqX!)_2y|>x5{igOJsdzQBUuZXU9vUV>HPeJ z+%XF6w-PP%6)Q>=$PeoT3&krKxaSEg(G6q?`4!j|6nM~T+(_^Pxe5ur(8TJMs)sx9 z0u%K#=PJjFz~?nSE1?fH%4cUs$vR zr;lC(bS34DJ=3R%*aqAt7wN#AtyW82=p3tK^I>9w0;b1mG)zX)bYValAYFQqkXPu`%;nK=?o z%I8L(+x*uyGh|B_foW)M7c9j9^Td|(>ry1A`ZtI=F@baWk4+EYrN@T>2OboOx=%LHAfs>xasEO~{Qfxnxpt$p6?B%kJw_oP{8Idgb zWJi`NpZmjhIsak2#j=xDIb)0uYJ0 z=D<=8B$PsybVSN(_yGljKvO{0&ot43M>Jv$Y0|0`#4xdzoet5Gb&=^!#+qCHXq>+N z&sd$bqpFKm+>`IVi}++PoaW%bw#YQwtw+Pmg3P3P$E3mW#?h3XrZ>y~!=W$)s6NdB zLg>5ZJMfHA;9=aiH5L2Ek#r671CY2O0s_IGZw<2`R_2~(C#iQUv-$A~8%?$a6QJ5l zK+Xg<{GNcN`M~~KGHLLoJEu^$c0u6jpX%|8sGI1PxChFG#Enk48xmKn;VA+_Sb>}v zsGKjfX_?{_QqUHxt*y~pr>3URJSC^6rgSnIoRHFcXOE7Kn#<>TyZM*FZ0VN|H0+nJ z86W4v3-gU#t)~p?bybi81YwMT6EwKn5_2gyAKhztwwPFx9WGt8@lW+8m-SiaT5i#e z`>DGZ_X{;-!W@sJo3`c^gVAM$$H}RwChy*n03c^r;!3UAx*QSL zfR?$?ML|ScjOQZN>>Nx}|Mdbxx(6;YIEWxhUf?eKKNBA**7pgkeUYXE5zmwQ*}G(6 z`QqRK^*|U4fouxfUqnCyG&Q(M4_fiNU7m8m2o0OX)Fd!718M04_KW0ZPmZQu?uOEQiIZa4s+?e2Jlk>$5p{3!)+V37Bfn0r1Aa&z zJlGBA>Q5(DocleSWx!+oSG~K_zrvzX)%#1rSPnFAG~Pr`(BJHf z9h`Po3}u$u`r}_sQSD2I3*KtL^5o(7Wi3n$DK!w!C%?KH(|05A;XeQK_AS?8uLQ$7 z>$y$1QlEU~MfR|b(#ib2^UcENAACK${51)&wBHaMT#;Xw$G+!zUy2={gqx^l3MR4) znSr=JqFjfK4Ri@2!feuLbm8__%tECBK?@8!j%0VM-zbOG2HAov-q5OU`fz%8=&|*CZB!a zZ+BIH!FOW8MY1!_P5GU0SyIYOKe_i#9VbSIPi*PmDy?F^M@2sQy=$L=k`ULur+H*o zn@-);f=(lx=JxCnT>vI%g`602@#4e8iIJh^*tRo^^rDhUoG${*4HEHl?T%i|A@?fu zfB!b$QbDROUxlgLv<_7l$A(|02XG7(F8Fn2$_|ofeE71)$WLr52sE0E>ZRUPA9{Db zex>rV=ZY0C^G}--eyPEuII>^Pnj)G4e^+iDeZq+gd=-q>-}?>k`TOiE9jsi*4G3ij zFe)bqB*4*Tew(c9(uhf7S@=OT2tN?|KWgG|SobSR(1LG#4hn zZohDE4xhJ%$xuAmyjF|Jm(oWzY7wDZ9JW{!Z2sW(ou7BdCZx_;!r22pozURU zmhimhpNAEEYTQnD84$LMt?C;tFhhVP8GIxN%0W?4Syff1{=iCa((t<7)?!x_l>0qG zps5x*o*S1_RBr1OjFQIIKN7b5_JH{Cj}<>OBdilvm?VL31#X9lWt1Wy-k0*6Xs%Cez- zLhBUogw=s)`7W&;=yQLU7 z-FUm#E>2l}!2C!{?@?K!3TsN}u!W%dgNJpg;`1M|1<8ru-3>aIENsM_PwI+4*EA3o z?SqH(j^`o`yc-ib@rZ-p8f&@(l%GJ5_GdPae)DE8d(-}druXKF7H>4-Zf<$(*5>?sdOg=og=$EM|C&}=oA#$`*=XsbN9T|E1qyTT zg>*Rcb8M456ZaC;Th;vU8L#YK_1veaB7oMGyh~)$AkI!j>zir>}!4 zh1m+?sYX1X*P;5v$+~)MOH~3-n45eY2hWxgBiCGC%fQeSt?d)NSC}hfr@Hv_OwOkU zrZH2FpY3Xt@?Nd1x<>8WC%IS3)?;sxIci5272{W;I_OOtq2Jx9E@|WmaW9T}s{Lo{%127$YS0Y~+a;|cp zGQ>S||1P@jW*GUQgIzEZEdG(+K1e-fwH4im*GIs{b*x5RpVz1Gl~udDe!_Mg;Oy~Edv(^dkPG@M_RBt42ec9Zc7q=esWZ!$IQ1P;~Udn%`hZnU@EWgwpw(n2;4Q$z2;qt(j8sS2I{LBnC6*Fp zwhY~3uz{m0)3X`2G6iukpn=5?mFCESnLiisxKPpbEC+*erj7xP7a%QL{rLJkjWnV z3jY)&3oEtxx~=B6asGSd0IUNtEU^Yx%Li^?P{oh^`=BfZ?&iMo_wK^%1tpK|MbBiv z5CstaG%fFyls)30jcT)}CdCOvlKk`+6=%3=%XdT3Ays}eF313?ClPV>Ndg@IUzd+F_~#PdxBx_n z3wF54g8Ui+kwp*yOrKj-PeKZ>6N1?A?||az0D&1-RPZufdDB59>rxD7$~X6oQfd zkfw&Y5$>w=8Z90yGN5(V-G(4*XMKwCVyQC3N@*I zKpbe2u5^npi?wzxp zg=5E%=w;Zp2hm}75-XV5c|%R$ITDG_0Yyd9Jyz-LzQeAbA;*o71}15V3PD<-M%>9S zcxwunVgW~#f9Xc68kih$eoD5o5N|)FOPz}?BXVUeiOjYBrc}UG(R7uh@R0H4eD5%m z%6w0THCl5h?fszY@wN_PEXgKOY@CpA0mrbDlfawqzNpV5Q8J%+C~9g`a`Jw~Y zgXNGgDRdK;SF(O!mSsG>?WopCK|CjdM~GA!d8W`7vwoX~m@sC-HCq|alwbT$|$NeX_lld%ZfHw4AfZUCHHQI0xiiovjZI8 zV72+0KZ`0<;7X>*t&ZM!hBb_aXQ&#}i_i3?ZFYI z0QnAwUiuHN$L1$gCfhe(#SHap!rez-6~5}q?``d4Dvx=(>e~`HCGOteR!u^q&GFN_ zffP%EzNs+tYrxI$Torah_gum)(LZ!I)i&7c{l!L%jQ8~!U8vJ;#HKjb?SCql9f{K? z-jPK8c$PfxDc9)9I7Axmt^J%Tnuwz8DK}EFr_*a*yv$|~43_QGU&V?6zAH2>Pa0>M zG3gqj+#7?S*&T}23@tbCJB`qlK@R-aRs^#wU?LyG-5UJDrPb9@E&6kXp*3JL>3VJ3 z80b*@{_Ko6GRl$@4|&W9QfOk(m~aOuegCfVs03_WZD?J<)xt?T>AF!U0854eEB*;o z3_|MQ;ZBK&GqW3i9U1NTK&YVKr@Vr7Al=eNg-D4tW)Q=iAP4Lrkh|=6=USwhi7j5l zjNb&eF+it+ze6obPnjLyY{#qoo$HskT<*Ox>@y{C*`5kArxX;vzXbtTlTxIam>oXa!+usHocFF+@;rj`(@Ipr$;g`lW#v;IKK z_6+~=NisP;E|LN{VadGy97-gGen0^CIO`EAr>P(BNC;?Wy3WEL zBmI{-~awi$?IwSO0dq;p*5YW7LW< zR^CWZwYkW>(NCiw6y7C6NK2g<(pK)=%V-F)vYqW}y549iOL;YG*+(At41LR)%J#<@ z%g`DrOi`q`Y1Myzz!l?jQSH-VC%AB8<9P||w-X3YhM1Oz+Ej<#T=w5Ac~#Eueu~>v z7oR2GlpP7VCx{m6oPT-G2>UxW;dr~f4ju+SWdwh61cyT{^S|d|UteB)jikZzz|W?Z z_UpvM62&L)rCW(TVHQ@u>FLl581ufg*SjAl#h)V0m=?5%17B{18PbJR)pcJbsW^T_zH{U`gm9b zOV&uGiC~HgbrklO`r)f;PQ=4gF2}r3V#tCgE%ku`f@48nFtoRfsOco06o@@3#>I1Q zE+GgH^5wx$V8ZB%wxdQ@<>^b*7K!%VASdiBCQ^{`KNvI%&@K!b9Uc9-5+W8H(2VC! z&Wv_AuomDG$4wa_O2&x_1Q=IXLIe6Gaa-l&@ywbd3)yQ#DUm3lGtbjGB8M)Sy;Y7S zc>bf%XFOqyn3%ZD9D6ScML1~iC%$h*D-A_$gj`MxTqh*B58=(pSC5(98!ql!kzQW7 z!GFXpkH)(Hms{#IDwLBlo1#XwK{WRZv>Wf`SApK@cfT%`T7~7DGJL=NMR-BhJG+_ zy{5ZC-LGBoO{GZ$d5Y255$z(?#rGNd5UL09*Wh)>>dB|@D_?zK*RqmQ<_i(jJJb8L zOOd_&bIu2qrmr3aTU7os7;?JuF4XWhAor{CMJlKx+zn}EW*A7fp1j24!e2dEOa48c zgBqQsdC#2infZ{@ok+bMDmhurin!4941^$QQl!Vot}n4AE*2$KKh2!T}8s=pui3`u=r;|MVmLD)+4 zXhf|BQqTU{*k}rPfk1eijaDrSTL2SZv%*#TG>B{n;m^7L3=+}^+%{}}V5(^bu@sKF zkj%FSL*VA-<{X5J5$O;(E&n*od1T<`Mgg#H5bR*GRuVsBMzjbvbK=1W)NnZTeAQ8y z96z`Q5|1$J`f~tU0m=7`Ga1aSEl?R`2=U`bO_$u>r)_i#@O@8P2)vOP&;WY{sEjah zD`X6>A=V^Pa4g!LkAjXuYPy1sR@fr}&H%9j8fE*98j#mXxCYi96Ge(G ztd%?#bw192g4{$qIF+FD@!2Emy5ENy0u>xvKCVWxf7#S#-&86;#eI$93tiba zpC2@wRvtzl$%JG1XCOVM=SF5wpndc$LOCj5q5RfkOJXU^Xt#9HlR@s4QA-r>uk3Oh zEHoixf3!*xX{T=n0>2(VlDftEK`(c3{@ph7IRBy2eV!(3g0c6ZGV1l>T1qCXE*bb~ zX8qnWe7MUS!gg#{i@iUW#2$)z;P$=~8;G;Z@HN&&zcb`(p7^mSV8fdD`KwmDH%HTU z^L02SW|ToFm##=M;yL&}gZu*lLni~BQ5Mx->6^nE28I6|bSDpR*cE(@E5K*Njcnk3 zh`x}lBNayOFJ>`7`t!*X%niQrsLzyU=0s_c>RuYlY+uD&>lJaARpz-}74Ay9BS{rk zJ*b~^z7J&Rv-=TVb9XEWB%c4lj5dtN4U?au6_4 z_&-3?na>!r&7AlSEVdSB8YC2a=Ag(3Qx~K>k>+Qj{-xGgA{B#Mg1%_qB4}p{XFA0` zsT5IX8ex;Gw#v8L7i-I`tk~-FmZ_{&4hA;=w!al z^^ABsVQQrC$A;>rC>Tq~qPLA>f8Dx!ZWKEdC zaMemXNiI_LPss3ZuY6@ZCMG6%gp67BW#K9ris)$NgAu<9jM$bK&t%pJ(P3)fxne4 z!=`tgx3kr?vm-6PSb0lQv{O(?s`jtC=%4#yI0K9UehR`->Sb6$ieDx+vL;bB8T31m zRqqmIkfx?D=K z1d~v1xgfH|faCGzgwkycuC;&;-WQNKq^6@&stLZRD1$mN4qUpspa+3|0|D($V7c+s zK-v)E<`7z@CsXt1G|U+C6Ncp#GCgySDt4818}AF}r?OHhzd?XXRfOUqQAzG3goFoQ z{`W5hUND#G?H=PH$SKi^#Q4wK1$g`TDzKpXu0D!O5qa9r4t?4nY0!Nhw5n3R-^Y}y zfv4V>cE4+H{B4%1K94JE7sI(1x)dX!JO~OP7r_N#HEHnwc>2nysMh!Gp*sYmQyS?O zDJkg|5$Q%H1?iG50qO2Olr)Hxh=kIDASHryNsI8m=eO4TuElYk4+ArM&))mFpDW25 z+$H+iDKJBr8unt9m_K&*a1NUD%SqJI z@TO6HmRq?UqXTJrXMPq4DGZUD?wP7}I#LM=%0j7y{6xyM$Cv zqzD`x5WI5O!4T*IFeboBFPxk(e{gG(T9U_BwgB&dn1#xCWAbQ`(H@v;w8o-%qS(N9 zpBYRICXMY~z}$^z6q}5~k_8dA5|BeVQw@L0)+;M7ZvbkGx=+|PJG8k94g;@=enHYn z-J&m1j2wEmoV5`89cGi?f4nifA5}eq1;6weJ4LcYmIcgmV2Obl3Q!zqF6K*sna8%A z+31hUA_raLSm8Wva5ym2TEql>=1SF&7l_=5%BX;OwE2JnLGlZ%!aUq5B@X|b%F|l1DFc|S%mo=JaR}# zt7;lBqu+VyHvn-#0Anbq$!(d?f`G(;bStEBw+}8GkeE>M2f$$Xs>zTm7Y`DRcJ|&Ga$Abi{)BimFK{*sP{%>HX(TvM zmZ4+i6U>z0jthgZA-Kw+PJkGYU_fZwj0pjot=awwDL2Rj50GHz(f=!wxn#zVkOv@a z85us0R_56fPA7s2HjJb91-^aoV5DCr+m z4>r-`8eXF!ng$ZIXGsT7CwS2K#`**g(mxdNHQngk+8WD=x=Zpv?zWVUj&J#a1>yBK zZ+*5VvtX4=Yl(ZR_oUcYmL2pAM<-bjvVnYDiwF001hmZBXDG(l=PLgKQj}ruiK?gYR!2_=g%e z81oTg_9%Dl5{EzdR!(2H!qcp(EYC%AhcScGLbYGtHk}QB($lws-#VbP@STl%!naWj z<4;QK>Wq=kat+w!C1P4NJlW-!)206$+_|C;31b%1QrHkmAHqTSG*s2D^ZQA0v9L<@)5H%sp=4i9a3{3zg1g0o^@NHRt;W*d%>>=m!H z7;*GVgRI!fuSsO%5jMIp1M`w4o=xJRr4(IriYF`M%whJo3id5%ZvGS5)|bxG&N(DH zKgIGtX22x6J+plh)mQk&3h8v5VcC@ETy5typQj{<2=??CKYM)XZxmtR5&NDK9@^MC z4@TY*#|(7(-)?%P$>^neKkT_s+)Ar@{5#uTwB~!xO8e~ zB+UztOs$M?6ZTqpY3FfTU&3gdnESdEC%AID0Jp#H;iB(yoXV$D$~Yf70*Q~#mCe2{ z;xmk2Ut9KC9^pL79pCnLS2kMmL?NC%ga7zY5tG8RU!RLSqA0nWp~9aa)(4&2{m8V2 zn#;YyvZn84Zd_d%B$x`CwAL3T!`9tztn%mG>RR+3vYGU5ZBdcA@vx9M$~H>2riKz* z5pin-u4E{S^BtT{881F95{ZcN^xiv8U*%gt)n+7DrU=^V)8DpdOd4cPN$>GWmTfYY z@8DdCMa-*-g}5^@PAfkeel6DQ|DW8!?~$^jtUIO`S|j&*PxEUF)N4AWQnB+ADG;;+ zgkNno1y;J2eXP_b8>htat+4xK?^rP9h-ha=6^Uob)|fNp2qb)ENl;y9TA+M3Ak`>w zyD^hanM%HEM!wUNT&W)58Ru3iq%=Lj`6wr?aIXrNUp^+UeIJ8y6S%-q0Y{*KIFaOuae$Na$ROHC4|o zDcN)@Xtz#|rc{b}byb_=`Sr+ABuc+yY2dRsuyEKjmIq9CwN;?FZ@4p#8^ZWIAQfG~D1NMlmx3zywLh zNzzAHP(pAdJ}h|=aIkP&BH5_rWpmUq1wk>f0rvmgnY7CtGPB7|@+`>z1FNJh<(9hy z{;$d5M|K5hL4c@g7Guch06<`mz%n&8* zz%15$`OmWcvn&fL_ND`SovFS*hW-U;12M>rN;T{&Ose#`B-?=gohL=L+p+6%Hc4z#qLZT^#;4O18GV|RP0SXYw zyFs=fWQ73!y5^(2%l(1@h5*DHQSkOh>vM%6v-FWLRtLY6Fg0@Z z@6e*d#{`jD@8hn^M<8oif#FFWh{c%?ry}4ZLCW)xO1L+6z!Jl5z+CL@FD~zZ0D1^) zd4J#r$QiP~1X&;qSQK1v#mQhh=mpiC3#7du2O|K(@O{kS?}KMkFW|%ECVaqEm`flV zOdh6I7&TBhS&*a&!8AH)Sl*ZQs9MQ+>=QfmD$fYSCl z?56;SP5i44C~k0qKKtutPb1Mj*%^?afMb{@@cMV)8-|y;w{A=}YM9jmnQw7*A|tt?D1K`c}LBJB=2siv`6x^e4`e&O!U zMH_ZQ_PGq3TpBxz<50FCDoS$>B1?}$x+&xCl?T<_Y}{CVt^^%ram7<#i}u`7c}KQM zO7ypbgXXMD-o@w>G9s37Yj$^PmJQCVDRWUpY%muixr`Agp?Rj-B-8N!S&cO@=us^T>NicMJ}~mTzngr zoS@Yt7C79#WkpOEhTcVxzdw@fG2sxLP(AS>VQOAeva+*KgEr4q^Q}oj&V$LMWYQ<& z4WEMqoh4aH_TP$~o9ojn)Nwq>=ZQ8ei3u_;_~GjxJ|pPk5nTJyjBQ!>{!og9ggpBD z!mS4-Lk=W8mMor$n0`tk*aXU$GOG6bm(?$|Rf4TC=KQsyl8Ksa=8nh6)PwoGMyzy; z8eM50h@~qrItF<8NNYCN6Em)$KR%6L%F7+9RgybNsR09%Foi6h+6cY;6WOJN!zB!VU}Bs!T$tSH{Bbc@hpuqC0E;wf9miW3&| z>qiRUl_t9gCZ=#_It8pN5TZof74G=q1Guxt{_s5DPBQNAYB9f*C51wLhZsQ%Tv71 zQ%oPN7ml99Xs+o?Ysu|4iOOIF-!*ZJrL>Ime~}^jjIi{9DvIxme51|$53~JqMzpYX zyO1NPenqp8`|E=aHmPprLB^ma`Fyj*e89gqxliqx)ho*Gwdd%j9k<0YlqQRYS}>+* zF=h=TCO{M=-z9e1?MQ<9Ml=AwWjs%1yzGdEIesfbvo2*|ckkaCsAcC~lhvB- z>A==!Jr7!m<$4bYyQmTpcoWp)6Nl{*zl<>Ee1(lRQ-)~bV7jsm{zp=hUfLelhZ~*{ z2Su+1HiMub~d%->N_d_=VnK2CaA1tECFT7vE~p5<5zoO%f|tbtF_=n_vcTQiwOlp z2zQz;73nl*)W>Rmo^6IgtRAwFn!B*KXG9;{Cz7-s@<>5tB%ZfN5gnmUlR5$1}CCX68>@*#ne4N&Y-c8Djx&^Q^(S@J1_97fK z#94sj+R|)Xr#W4fQ&epD9Y1v(Xy0JqqY^HeT{ebg#FiL0L=WHt;~9e477NOeaz&3| zwhpp~+~ijGAsQDYKeMo#o*9%&x)tErK|?N}rzN0lMMKNs;Z9WMcj3wU;+Bb>ujrwP zRjPo4k{UT3@gi}HNW}R23(S4!ivW?_(! z95zfZUwvm!vC|ds_|R!tp0dcAaFd553zDGYGMdLsvOvpjmg4@HISam_-{0MqHX^Vc zic3p>f>6A3G<Lea?Z~wL1}@RALI>jsl!{}?edU$QXpZ2 z3jjJDL2Ci(Kx~j@fO7=g2!N_e9)2Wkg{3p&{Qc>WHiix*w)F<*fIsj&{7ncBCwfV*Aog4@REEGSf$M)uH+1lIBI!eo*@ zc+HNh$chgDF%O6C)9<4icI=b8SHUYE+{VC3 zy&im>JHG_Aw%W5|S(jOM1+s`1zFm20O(b;Dy2}Oikd3d`Qlw>jeT~0zeOoP$S(uj> zVE4`>CDTLW$I<#;;?weRKCeTqRyV(qD}g!=!5=Q-D`VJ(B(dD)f|V=Fze5R6@wvGs z8oFd@M12kB#lV%ov*x+?#~ZQq(JAU}+e{Sc z#{n*fLpQ3tKd!=TQg|t(S^9nF(1s3QW)dDxWc^niZ^)EN7a@5@ADU!od_k{HWNv`knN&YPYLY7GT(I7 zo6kSm#uh`c=<_D|EvH*D>2(qGg*i~t&yJv__bmO;mzYBNz130h*r4{y#M%AiIhB2B zN@YGb%)PK7K11GufTZ3tELvkHzfru9s_tZ46|4rSHyin^bnnR=KIK-sYTA=ZiJK$t z*;!AL9~hh9-smyd)u}jm=SJS2Emf`cpFml4SJWC*2w-}D7)x=V)8Kh6y-9@B)4~8f zA#UDP?c3OO8RIXDhsH2z(?rTt?oz0}Gtfk(cTxL{h!4Ga#c{&K{K!KYi;TIvAK{|* zY{orYU^A{`x&fV12%YRNBlb>JFPW)~#y)26w)5Nj&ZUNG$BB-0FokYU6zvcf6k!-47=c4%KR>2Me6 zw*C%t?B&pK)M|TONhsdKIH}OZcjey(!h)U;Fy>JHNQ|jp?cKcJP27z=)KKcqgfE+p zN{lJSTvKeTeJ@*>iI|iPAI&9)Non<#IjUL-IH~?;Y{nt2w)_>snXiG~brDHT_!Q{t6dyHw<0Jr(+tij0r z1pZKzNx^^8dqSdY5(i^;2Wys?D5;NVa1k|bfvl|Yd0@08r$_@4#FOlM4bjHD!+VW| z-;M)L8}bgRdDbq{oQndk3#GMSxZx}OG_Bu*t-T&>VnY28XZK>DIyULgf26u7^6A8P z!XE_2+7^X5wZs`qN3~rDQ#2oWD!s=)UCcjy`b=ThH#2$Wv|+ml5aw zRri;!t)4!RC^`^gb$G9^I)77YE=V#LNt9RTWgOlxa2wWiA)&q(;*&wvWS(~t5#z%( z07F2^RL?E+)B>%!&{D&;Z;fUPBVAfu)tVow}P%J>~6ny**u}d_xTZg z;hIHX-nSy0a4UnpmTo+bCOla4AV-UjE+HEF62;^ZwS3V+^jgqZ0DNh-*gG85I^xLqJ(K`NoV2iO6$FJ(1mZrhsmSD0 zG@Z{Lzd#%Vz{C9q?ElRd+B~7x9>xDr#E;Fb5Y$*_qDN_QfS0lhNRuaUO%?i<#3Yjp zS~v|e+XBk}K^fKFaU)yOAVOQIY?JM*IytcO!t;V3(rGip>4hNYFf9 zg1c?!DBc)z9hj%JL}@@pz#<2+Tc|dIz>mS2LMTKYBVbqtwPr7=HZzVk+Id4Rw z{P~0Iw&o}3ldaH~1OA8@75D^*7Y5n8U$dhSO-9WC%t41FV;uDH5KmG#{R|+o=6zT~ zHOtUuJfu9Ea9=0|F-*`*o4ED00zcu_7V9PXb;krg(R*yUU7c1Qf{?V&xyQe;t)D$1 zpSPvtR%Cp~L6QDHrMM6y@N$FzNWoeMoKKrEZ#S0#H#z9{%qcO^Tn9UCr1SFf4=|Iz z5G%V;r;qUC!}Fv**W;|w=VHT$|9u=D$)qql!X2dbPg>kF{Vc2SwzGns>c=08CjB%4 zT&dbX9-`Ad8=>+QU;=AVIk(kID7B-7g9Hsa)#Pz=0i15)gd@nLZ8gRzpWbw*j7VxxU)!f&Y2E-RyQYU0cHzsn(=;-M1TF+jKt&b&g8k1#A$C895JXh80~U-<&{78icE}ac<{;Cqn&yW~3KD*6nzO#Jfef;B zsZbOh0jC3Rz!gUCRw57{=C$hfrU-xkCZ?a!&|}6oy?)jEbcAqcWup+Qgilh^P4Kt8 zXYU9@ypPsFVDt={{Gk2$o389i|AI~)(=wd!@?4xPPRdO3!YOIZxpD$_4nH1Qiqnn9 zg?W+byWzQvj7qY67TrXRS+^3k_?8AK{5ppp+Wz`g{h)mZZ9w{dI(MbyiH5;HX-DY@ zZcevxGX^XO3w#P2DT$shar;8l#dj2K~Cje&Mo)T`v&b=xk;y zr%Y9v>bo^@acFw6`)O=BV@wpuN6{}tYlw_TKF6P%Na*NATTaXpT)9h%ifPQ0a)!lp zPUWF>z9x;Kt`zf~i@~k%LxO3s%k+A74fg~}e@~W9yQLIIsD;-*bd&+Va3V{dRpGz2 zsF|e|3==Ys=%;*w1H1-C)ixILn>%kzpRxz%{~ahtMP)p>j;zs;mgr2GhAx{96w+lb z*5zlnE+lONLeZ}#pV9cWq)%vddV_g*3`MzAw@~~(!~M&dO>5`4Nm;-4A(C$xPMs16n`%3 z6sa~8-k16NCpi^dfJ!I==xR=aY{)<+VwCl__z#`c(&A`?Wapw*ghx;`7zwNzrqC=|I71En>M{Z!MDnulHkzULG@9LT#An z+>jMZODEO6<#X%h9|wIJ)TZ!IW)w6wMji~7B;4dmYDS8oU2AjgQa5IMUTL1VOMWed z#*8E(CRR+d-+lB6bw6cA?e1hzM6$E^bl$q`lvc7Dw071-geNSv>SQJPDX|UeU1%gY ztX*^NJlGhfyL``!jeC-Jw$-)Wn}}_0uRa-O!R0Gzg{zRtXOx~dYHlkUqcHJ06t9ms zazKf)ZGiGsJLM^BW*q(2$s4zjh4P{W`jF-y-+y>Jepwcw-{j(#tbU?R-Go8Qr-gY# zeks7piC96LI}@@MX{H@G8t5C85 z84QS}t93C54?or#agxVZX!M4r%CTon={;dVlISnMkqYiD{8MZ+di6>C*8E9WKMkYf zIKmC8f~^JnoLD**7@x;~#h==)aEWY+%@xr=YpynaYTFQG)6cjzYekK>b$>@mC`ly( z!9o6F{z27k_odPXsgu7U-BOkqcV;p>O&L;eqnSTYUAj%1;!j3ul3pDt%Z9FApp_HM zk(~zCEKsb*4pK;jAF2$pM5`WWos7=Rc zE1}9zayL7#od0PxIoiw5sgV~kKYYVa$X?l$|IYdlv26pmOHeFqYP$~=QJz0*GRh|$ z|A+K{y$m9HQRGvdHVE#vkZgc1VVOYl!B#KWRtTK&F!>h43!(2Qq7s}b_qBW;^JVc@ zWgGb&Y@5xJtAG$fC~NZ!AStb5NZ3MXD;^T#(XFK!9!EY=jc3koamm41+JDtS%J{$^ zIKip*7D6xjAi{}?M#U3dIQE@qdrjICLl~aG1qCXej+?3A z^kk=Z_d36Bkz8xIPWt*#7rGbBJb1_4Il{4MP=ztziu6=ba}F^%$5Yig;mfu zFG<_=4hSd!Zvdp_3ADn@=1VU-yDll3r2#4U`SZI!A)ZMI_TG@=ipMP{u-P>42xJ)a z$|EVU>gp9R8v|YjQY=`f;l%y#Vu1!-p)7{B&;?LQ!;%jC9FnJMXb6F?3Nqh_Ayx~# zm;GQSI}BmCLO_CkD+FR7r6;ukCspUmAw+e6L_i>Lks&v-(g@xFUV|U|7i?yrtEn;T zdh_S^=qgMl$|bsBOT$DUl_5wa2xL4&Aeo@0o9nYfWKPui@4#z2<5m|Gm_q=*Knnii z2T)4Yn9yNJWDJ!BTQ!VI5;>nPFD1b82B7WXh|uUV1YH4)2wpIF17bM{n??d;HZ~YA z!2qp>67+k3ArRTuxq>Wgf*^(K=nR1Hw}@zMk~>t2`n49lNi?qNV_&A4m!J_7=g!u2|IW{G*|#D3(v#p@ycNQ$9(}OM_JM?^`rR74y z0`pk7Ub*%LpIheqPy<0K6SC)(I1(8C`e#X(vMehPrnIGw;Dpk}ZqgE-b9n?>@locp zn_K&1Da2zs>J^Vk4uaphqiSuesGH;UM$NpA

    GNWp~~dtPb_4qm)vXmBPfu<)0l$ zAmNu(etrBMBeEw-mLq`vUw90PO}6;p*`M+OVS)6Cp`rDq(U#Jxb!t zVUC*|^Yor;w&Uz%(lV~wF(G5!oO8aU0AAv5*%<}~NSEBSztT|3Y^WU=ZRKI-td-`_ z?sMx2`lR?9rA-sH=wkEiX#H#}dz5i3Rv64&NrZ+nQv;!w!idS4jj-C5gI!|ouT>EN zRIQkZ$8z0a+m80iOcu)fi1=jO17&U-UAaum;%$@>V~WykxlDSsjO2vy9(C4(7h?&S z<{T|Ga@gIEMAbHDBtxG09HQ8a&5`Gwa2wjumr+dr#aM7_Vhg4SLo1?xCdoP-_He%7 ztGIXuuai1ze(4~8xud^=H5m)5`j~wmR%+YCn&_S6XwpB7CKFP!G#k;uBUo&@Ci%qw zM12HTR!*~)ey)U~x8(lV`}@L5!YVcN8Jfd?j2B}{jXvc>x@7~ml|%0~5%Y&(H)i1~ z+@Z8Cm7dPiZFuc^ak}jpEkSA&YTJ2SIlAeen)~V|ia#=TAJ6Bjl{nk>B(>B#HB16s z9D4$MlrO!n?tQ^$7?9Lj6MM||=|(S~*D^3L{z(^O_p;}t@cX_Vl4cF3rcdt! zj?DZy_{OAhC9bN{+58LyT>@wK&tTG?F@GY)Urlj`n6vFu@|)G*G6bq|Rr_{GGWrXS zxq5K~sVH~sUp6H=iqp@blec6kqIW;hyce%Q8_@aJUcf5v)tMQDhvLzyp-N%U+hZ&c z#m-x^`m=<9Ec(gLi~W_P_MyL}gFYNG{xSh~6B(nmpuOmgTLg({Kycd7EyY4Qd3Oc}Hm8;IVxo+gLIU7uCH zQMx6S1`J21uM4}4r%aVJKVND2s(3|^hRy^l<8T5ofNA^toiYoC(yFx4E?fHo(@y=V zC=pMms8L>^Y;V!)y z(|?`!u;SliCfHztkrqjXYx;c^)3hh}*a_f+jeCebByEE%7}gI6cZGlN5yAc%Dr!K?2()?d zYfZK!ehpHPC&JnT?qQ64Su6-E`~-#Vus(Y$<)>sip?hqV{Ivl?&p0K?g z6vqvd1Q{m@&f1(n+OWCs5ei{e);7e(!U6$$0|iO?zFs*TsB0kP-y@5`pbQ`EjzC&@ zbb~@w>b@f~)T!0f@HWo=ezu(i6zTKYJ4ECu(PvvB{G)p>ZIOPtm>4`t{L4kQ4 zM_e6ca7Dr)!{-9<1&(^;2(knOAoH=C*Rt&{c?>?wh_xV+PG~L!*Ae`HJQjR9#=H^m zFT4??mxB=0*1!lP4P8qQq3;Kj&1jE6r6~X#T6h6?9>5e`-?{?#`(l2kOCWg-YUyiUgk;M2i=9ehCuPF64@z>9G?SwW3y zC{}M6yO5wOm6wx)v5fW-hzomRh@BRMISBBX4ht5FH|WVwow+)B4}E7WY&Py#g4#CI z2SgK8S1K=_f~WfT5pxc7mBzNjPK@4dyp`4p~tzdv-ARod4 zEG$qU`iKIhmr>xI^IJ&h?CJ4;ffw}Vg&i7T>f3e3w9u`y7xR`8iM5g zuSxV@0jcV^nA$DZ<~R^R9p21i3Af;Acdd?l51J9QXT6)#`=q3|`xQ?jSds>jHIv3Q zWNhDEKy=QQgtL(_+rXyf$4M+yf2|nhI1e=iBaNP5564vJ<>pqOWy_!a2PbG791=e> z>~f)$>NPQ{*?BKTU1w)pO3H1d8|!H3E?mqbEN5wf7imaQZX!^4&zg|tdw?(iO~GbL zFWGr+_Lmxoi@-OE6aWLPgR~CsExq5BP^yeV6{ygX!eMc|RXas4JsTR(im2bI5>{1cS_3fR+&X5g_vbDegJ{ z+jZlMR2?IAPNt@|+YNg65di9Ez9-6g%Rx> zNF;w`P5{i)Nc2i}j^V0@p&LG~H!c(C8-q->+5(XoY9FpoYGKfNe>(Tv3*z$Ypm^4_ zb|6R!{B|Jkk^FZ&>Gkhq2C9i6Clttd5FUhsJr&vb366svxC`LR3D|B4h;a->Y$C}| zMxPSh9>^7d7a!*A`(eRc3y?lsjswUNCrs87{)*>7>X?Ff*ZU^(6id>L)yMLZF4}4?*?37N_KlqS71<=OU$pm45yP}-U!R%g z>_!f?pfl#dUd^c#s`@9AXdzVfN`f>NhBC_$=pm7MUQ@$Nz0_nUt7`^X0mdIZu+uao_c(&ynCIX+_nCRgqF!pq(qHqEHN54|mo=hK>2w>k?)DVgM7wpaM=8zN^HRov z-#7jGeZaq8GPaDQ^geE^^(F%s1$JwPq_Lqed z_+MijvTHXz?$DwKU=0QJjsGlGRN2Jjw3?>=$6r7;v8(rwF zl5HM%DPeiL3H0(8UiuBahuHkss$F)J(gzdy?L4TQs~XN4_X14MbC<=9ovY(M**1pD zx^kV0b`cT3PH!nfiM`4#d)hh5zls7 zOnRV7slA(s`snW}3(!p?y)L8O-Kgl?tqJ_M#3GCLMGU>eL&91Ptx`?T`||4n?A*M8@=xTJml%;CDn zFH{24`&9&;Q+_{mc4J#cg_|A4n?vfWjURJ$mdp4`o(2Vr)^e7g_#Cv7$(rl(1O#{G zn`j4CJyLM_f4Kk}I?B8z0gKQ7e$L(W_j-P7C@eLPeeMkGva9vGYZ}3FY?on>>Y;Zr z@-zN^)8&wrY&(56pLWhn-+ApVl)udw)eu!e_)lvxO3KhX(qnarYfH<1QC z@8(CbXiacolv3cY_r~fw>ADaiqF#!Ll-UjIW@Y{vPoHwNV=t*B@!Z1Sim>73lVe}` zon7hfl?Mc;hP{F*_tgV=S=p~C^Vu5fFQYV;SHEs(u36)3?^8_w{`hO0=;UKQjHFo|{c3pl$5KUkKuo+Ena`f$a^tYT*-`@tG#68Kr-}U+> zg~8#+{+Hr`d$g&kU%LhM>}k(jZWiT#v^B-=`rfA9nLb?34;#{xF9*5#iQHMI`CeeEBl9PDzuiIJ|MEQp4hmq;NVEoX+ zbQeuG3j-El6%t$&D)f7y{6&cI));e!dLbC-zQ2I{6(O2g$QOJ+eB)n0$v!a3d$cVER)&Pitfn^#@ z(0K4S z5KaCMV+aZdg$FE=1(TbgD2HhR0%|dNkXon*$mq(tNf&YJ$AQIsmX(DP@`nSft`NZk zVhW+6+ii;3@Pf=E@K6CC2qUK?B$~n`i9d9Qro`>PnQb^CXh#cXw#KX3hLGWgU1d%X znDA5L&vtIu3(EnCB$fDAy^p^R)=o&>08VUg8}vy+Qn$40miC40L8iL`AR#1+&J&wN zhDC-VDu7#iku>!N@FSOY9AO-ee1>|Zu!X)Yq;49){f^WvU&+9nHQp+1TxdtAbmCu3}gTZ3LXxi zs|&Y47KH42133lc5jgVTUr24mXL%2Pde~Axx!5&Esl(5c8M6VTwF%%bWN?Xc*(9T zYVW9gUOO~0B*nZZsqlkF?2b@XR*ZF2Z&kMARr15A32Klb)W0w(pnx=IP$zYoW5w-{h69hV7%&QFS+2A)bfGKJ)+M zLAOeZL&K@%oKbXf_8an=#QwB!JtXTU$87K>_bfcS42uh&Jh4VB@c*nr>wx)0E8;QD zQ!WCn$0Mzm?{m$298AxO%=NZ0yu1oGamTXMHvjVhdm)Z@ zf}sVKT0c>WlLdG^%$lBf@F8Lg{*Wu> zJ|nu#SwHn5bUVD;y8Qi=*ZxfWyJsa&^Ra^*Qfv2dt*xUFUcX8xt_aV&Jr6N^vB=XI zIr)EhZ;E0w@nj7q70IQKzdbS!>hQOC`I7 z{n%%Z?@;M(a15Erf9WjuX@5^`Qc1r&lw>aQK0STa7VwX)#o1BkzME^isN5X7bj26% z2%~w-Z|>@K4Y?09Cp$h5NHP-c6->(i`6nR#>FP7L9LK0trGR7v!GHRhXPBEWyqs?5 z+U1Plx!O!J(ON^edA1}*e2j%uB7@IzP7%2sjPW$ z-GLqFC%nu>A1qq`R~CDP%pnwn#+xMZ9lwqQ*h&RQ_|^@@MLzagzG=JAVJpS8eu+a= zx7jY7MK=^d(A+Zg-_nxRzia9HPahGUJ=GsJdG;vn6<&4?42oVOXd2SAxc%?x87Hr!UeD?Lc5Gx7F+IjsHAs zZPqO1-YW0=3Dq&65p9;*Hnp;{f<^1CGE2h5%R~@&o~*Q>4np9HV}(kh<2*b)O>74o z#+`i4$%xXeH~Xr+Bujg^7o5`EB^0ZsKk6|OosZiK`v-pI-E_z0EZP51Qz`azM7RjB zB)PpsD9G7uh7vvdARv1X2Cs!3+ZPDqKHVBD{?gOK+f2|j2fC4-c#28JLfAn&V(}6t zk4!V=qVjMq>-?|M+hNAp^a%~Dt^ofK%Wbsl8ki$x%n=c^bac?PQ_l?|iMlHSoV8q? zk_z&CTv@ntBsq!WEBV&wwc8x@uQ>lbBF~;;f~IDs98D;;i|V&*|4@<)c*2*Yw+Qfg6+IdgP&<*^GMgyIqxA$W0( zE4%$+VFY^;!70@3_>l7DXg+_EE~}vx-zo9v1Sd4eNOe>{CrefZW6a3RtZaT)P*k+^ z50nK`Hc6cX5&BN&zwaGrZ?8D$K1FI9v?9H}Kb%nek*> z9xN`O{`5k$>ZFZfd2FZauTGos9?BOK$Xk1CcK06VjK2;PMYc1f=mI+nQdpa3&!Qm= z(J@2)gmpQk6X332hx}qgY!w7k3@P)FmpV-Zt=$ai^J_qdf%qEi^&pLg|ADUtO!C0m zfj`{~TA`5{`k*h?ttdvZMCL$&t_)^S0Q!(A;7Nnf9#p+x{%zX>P?9pOJY>xzoKcA2 zubA0Jj*(#f29)aa($$xxWpP4C+yxQ!^=966l-a*&vl3{O1|TWs>X6|^05+W@FhIkU z0qZfOIY9h@o|aSzN)O1^AaIq9jqQ9O@aiEn+?1d^V(>daF}t~(fxW<0FW(jDvJyea z6XCh!p9ZYo_A6;9UVxBDI1*4YKkBH0vU;TS8d-fP0zn2)xV<~yLPbYs1KH_tn&^FZ z1VF6g1;bH-E;!tJ#XcMoNZ(wH{(-sd541qO1k?(S5TfU)y>`S2k$H~rn?UY4$j<%x zRoslY2X6?)J6ZtCLaznDZz<4l1+l+K*$`r;*38byNfV6~q-UVUf>uWtaJ50=I)u!E z{0zcIPg=zV1$(g={2+-EMRM402saxw20jro{{lqa@V@PV5(Rl8M-({kJfD>0Ryy8V z<9*2RXlPXof67NgiJZN_&)Q3eT`{2{VSOLvzq{8{79|1eZ4spCXISk&?-=2a@0Yp? z|6uq^`k_SBqmRh92lZbP)z#;OJbZsCIX9_?%PW+LTd_{B9u}q3C=o5t^KXeHZy(+b zyu7WexcS^wZL{8Vqv|hF(p%3f+QG`-GqTs13v`jDG0n}(bwy>yOygAf*nbl8wcfRR zQ=8*1q)wYrO^;t2~QCrEACUb zT3|m|Be+iIJX~YgP(*m>p0TPH6fb=a;aH!w{Ux1$7ypv^(eoa66-cOMe|p>O z$rO$$6mj_xoD!(WkdwvhRg)Cm;TV%dKHUu!2csGI)ThOp-ng- z;+L~EEw%g<9$tWh$AzS+yicW9vZ)kgUVqcW#Lpq@VzF4?rmHzloQ4&=EE1FVzBD(^ z%m&d2RjxvtH0f+Bc4jp%R>wnqBaJx?B1Bc4=>$ou?w3XX78}$AQEaTxj~*R{@NB*A!TQnWpJw!>;q$oA=*FKv1!sY!oWgg1DJZkM%Q2)}Jqi*J z;9JW}Bg+vLYL}zvH~HdXOLH*pzUm#xBFhX{Yw?-}ax=N$P!3 zdD6+l)nuhBsCfOQKptzLNNGRm$VlKR0As1PibtXK}gmky>(F8vO#x*AhZZd#4W4(!FwamPt;Ho_yx*2PrBm1PUno3tDL@n_1&zSpz8P@DqUNU?Bu+KG zlPi*CMLztVJyS)i1S|uJ|G=;M))^|yBs4JI2nEOLEXUeO@h(5@f3!lzp@L$Z?7=D9 z(G#=Pf@)hKe2L;krWh=y6O`bPqJc6^wzS@Ys>a!!$2h#`70CViBsP(On969)P9D-X2*gH#VlNJcAqd8uNmO*C(}-@xOglUR-heR4o)# z4c!YmT3UNXR&?HbAaD8p{W~OqpESAHHOngwrBpmw1V9J2sK7C7;EfCcUDvG9WQ1Iy zz^U`;Q@ExKgk6Ku8|*~7s&JIxe*p*w*6X0<-Bs0+!oPD6_2awWNiiYxs0=sV?u`hz zz^qMn#9Qj(M+1?v~Mcz{0y*a&H3hU);130Nl2{Y9HsuTl-F`higK2CC=# z!ou{ofnr!PDtulTzvUQ+e-*QoqrD{E=ayhuT1ms>-~L~m0k>F)*)(W&_`qq)?5>EQ~`ky zl8!@u>ios0El!Y0A%cAg$vJaPRW?tMBM1DtgKWkY-{ht+aNg9%esVIyEWQCa9`AnG zEeZH+%=1yb>=KLQ?XxKS+w;kxWdLm)-KSv+Yk7r{p7KlG`Tx=M6;M@e;ktAvEz+$Z zAkqRN-6bI1-O>os9V)4mNQ?BLJ0zu3LJ*XcmhOK4zW3cR9A}(iu=bv7?LGhbrORN3 z?YyktPa{)i$YCBl{_M40#BZYUulLYKbQA0E+ZEgtWjyHfg9AUSM)Z@bf6V@jl=lxr;M3*`el)Exo7p;;^a4?)hv zZQ_Z{_9a8NB%5N)ta`xvj$vpjV?|e?p1e8INxT(wh`8z`4cl`yEBTUaHI4I>Ipe zhj~fWj%nzK0fn!JH63H7|I^gZurCc*^NZhs?K;`RO>XJ!_in+(SA@Ftl0+NUl0#+0N>ZXOFphi{ck zg;M|9zzX_~@~o{OB;()vj4x@UvF~H_RU~$GJPagr z)Tg@Ko9abO6m1=!vcUlQULuo%%B|jgilty+jw8_@m@bU6~hbRd- zu<}Ck8DQPeW`^N~gNw^0B%}oKAeNS4|I-8aRj=e=+B_Cf#Lkxr1yfvndOy-ZOi+BelOHeXp%P2(=!932#YXJhC%=w1#NgK^f(eSphp2J%pk1p zf-b<@`!npH(BXoxoWLndt2ozio-tk?fmy>=AW4`0?j1JBLx6>V|AFbC_AB4hr@70I zTOKFAUxkbpM6o^b9Wb+e9I|>Uw)s!D%pY_pkaaSnpbga*aJS$Vfv!|JTa_+(01^fe zl8oVDJLlMb*&nc%NnpWisrm0d9j1w`?K?Qvfq2G+DgsoXX%NEJ-P2R3ReYhZiwoLb zL~}3H{34Ts9BBm@2Dm#=mh z54##NYU*60GPjE(+b4(MBmR11Fa`}2KsG@CAfV*2z9MDfOpqO{layOx4##J_fl9zk z5Q<T7L>x&It! zAWMjiE^E191)M|M$SVwCFoIz8bJ3JfpBBLL^yq`!-f>w#I(#%qThFBb^dJ)dfNruW zpDeqcDcirf+&wJ2nQTQErmtde_eBN#E_f0CazxEjZnDvs7De%7(T*&2kEyHcN9bL5 zgLw`f<6($#l)%!`(n6?WswYQ`FLI3`yeJUL;ou7t-b+g{b0oZcFf@$-0i>?34j0{9 zO?5h$c~u5N?atQgx?4oU^Kja;PDJN0$L#@!8|a$gxs~Nk`J3#&k&FnBj+O}lC}d6K z^cezBL8W1?(qM&z%}&v)PSL%`P|k!P=>C7Fm4o{~5NyL!;&6WS?^hM5uiz61+zik> zMi4PH7jWyB;eTO^XxX@#4Y+i=y4k%Ifw2mh&z7qdj#pVw!ORM1l}A&_Wejk2H=O}z z_%lT-*w_C?jROu-Ut=_rEu>FjUpvf2hHnV}_nzsmXu$dmCz|c1TfL|Wc2Q^8gHI7< zJ?yC$X=5k2PLHx52K=8EpwtNy4U78iNja})yfg=uj|H*COjXi5DyEb2<7__pi-ybh zm0$5NhN2(34+ywN`+m`SDM6wZwMBE99zLt-zOAsrFzGyCS8o;F$cg(qmGwO11E;qeTo39{C8%>HddaVQ6t?6 zUJy?TSvs8^e0oXRT1K4F#qs!v8r_AZPC)CsaPCIS7*Yr};a77VJT=F@3AdGSm8MdS z(x;N8tk*~G29G;Pk6My4?C;7W9@-e8+Nd*5%W8#d_#LC!c{VWpbvjWL)B zeKr`Ix+aVqHnxo%+!ri|1QMUGlW7%eM61#tvkxBrVvaG2?ks8vdHzF?sL|7ogI|b$ z-!k8_u%GbiWahsOt)F8Y{V9t=O8Ru2qd^r>^$iIN^~$4Dm&@T>yL!d$7Ds`D10kb+ zhngsgWPvh|1*&U9@7ISBx9g96!*mvJwXyxS*Cv@{dA=hRoZQ-cO|sauaJ1P;MAE;R ztlTm({k5C3E5zd!OTw1)qh3W;&JtHA6g3P-mirvyTsZS8@K_S8k2w_|qV*LC_WHCtJT{^| zq!=fjB7B;>AkdO3Z|s;v@56YHU`8+3gVrggvxDq8HbtK5b?M7`6RN`_xrUU}%}JjO za2PDl2To8x7wz}v%@uknst3?**r$8TNYDy1;!o=gP|oWPMZ$C$Q_pC?>BXOfdWaYKW)(aEZ)P(JI^YdoaRMk(_vur zF)H2(mHp#zOGbhMuQF?K*0`6ghUP0Id!|R@ym?o=@f7$avRLM7uOmt`=dhbex1xk8 z(d2Rrk%)T6sS1CZ;g!xxD_}am?V?Mp=v(<16@$n1Ojya5ujgoxpz9sgy?gOdF;Vf# z*22C@v)Klv6{w79@Rar=iQFuzT`%g&5^|``#tzVNy#Si3G9P2V^OY8Z9ck| zoyz~{?ZsMgZ7B2UL0E+UvB3-k!~$Zc|MMpoGQZg9gRGAW$2V-?Q9+J_c#w4Ee5Z?8 z1;CJ%^Ch!6B^iGBi2cWBnXo0KZuL$o&2dT`%jq6uts%Y{omcvw^6}Tb>$0EO#)G7p z=W#A+8N6RCk9$#n1L*&G=)vYO>mSER$GYvc*?G-O*G0bGu6dUU721mrV~_XP&T#PY zp<5cZBt!!QLMOt`yF9~~yCios-K>F%!CB;>%C zT3;IJFzdS?X)J}+Ue|K`9K%aV(6Uqr$G`k39Bi@Zk8N{!*eXdCx<|GaFr zzt^WzjQyBFb+TwNj6qpZ`J$gm(gm_zpQmE_KO$J~=YSWy;&- z{7&!^{YEZzeOAq;*o6LjZjLE+2*v338$jD)A4mT0@kO1o8+YOURiguz(^sgTUp?7wRv`!D zy0x{e{_*VG9NtEqrEXMg?3SyFipti$jjyjk(~$2d3lK5Na(8vw^0~kz94A{YoU0u=~? zlgU*~Mi4aB`U?PjB5uR}zp4>#LBW26@OSS}^!5-AL>rCTrUH z2Y>F`-O=3~mB2=Q<6T%66H8qf`(fGSj{eCzqYcz0{ED_Iccw4Lld0bLfr@CkJ8wP_ zVBm$8Ni>$=xrOs!<9{Z9&-5nv;izrA&N zZ+aA>wi$9{6ln97MQNeClNrekJ>r!qx%9<*)mE~cc8+gG*l>H2R= z+A!WCMG+*aNKtWnI|PU0I9hzV6}JsN!|&Qi{pL^LN3|qAdENH@W46G{y{yU(#_0JX zr8^HL@v(SO`nx&=2wh(NN-8mSeHqAt8^vw$-_LxYr>~xm4IceoeO8=%{LC$PqNFgiaS<`ljUK>1?G7)%^X>cOLAE%PeL{ z24!kyt_a2qtCyrZ%$^t_y`~PpSGSq_=IiI2w5bxs_w|AdJtOj0ZDwsx=FIb#J_P%o zI9D~Pbt+2@65E1va|I=*s(yPZBXuaLER}4LI)gF`B_oDYT`^s6f6TgPXmlRRSZSh*ziwR)>3c{-{{)Ro>J3KYns_N4c~36V zU-?IM$S7j4(ghWc`REWfI=*>Mz9ySRm zW6CFobrHo1w+#NfBJ;s~Wzg!CGWq=J46ZY^bJLj#H)T0jyIy<7yS|848iwhB^~J_A z0;PrIk*0D2EMa`Aew+$Vy9{;3oWJ3Qj=y~~Q>Os6_K<(1uJiE2*a_o!dm=S1%17Zq ze&jLC9iaq&-s__gnqw#0_BuN`lAzp1n{VjmA|3RjsdO!MQ^bYZw&&T+)!#~(vB!Ki zz9-_T)jDr1P%56RK2M^fse9W6f;+Nb_8;vA@d!XqMj|Jwi4iLk1YFE$-_?6#RO z{2Yx}qnDavmtyA->z$+AgswbQ=Nw&u87PL8iuB(zF^*^}tDRJ@OXQ&DFPG-mD>wT` z=lNqpmO?aBrPDLp9$0PA_7dp9Z|R}cuQ2sUy8n-vsM^k7XflFBARyo}O^iUS(YHx5 z#b@i4*qIDXOc29x0^EZGF6QXY8h46PtdGP>I6HLr%t8fjv<@3&SF-!Mre&}9& zz@0*z*e_C}mjcxcI&!wJ;$mk6Ha(hVYSNNbv{6&P0Q*yu*yw+3dXPH?-X{71i#r85 ze@p&jrKX{|@bxBnJLkEK+j22k7Csj@XjKKo0L0jnDY#i!Na;JOwc(;y!@dA}B`6=@ z-FzM2h>Mh3sdcun2nFcIe)eZzDRVDNqJr%JKP0}uhSr8!4lWxwlLKBuANVC9V@m;@ z$*yh|imc9P4>%bmz5ZrfBu=5peSYO@XEphjV1Tzln&cZR7dVk)(ngvaBBct02yX@csQ7lA>9vv z7eGovsB^yl7ssNShLX!jgk5sTq??rMUNLD0L4r9sIgJ6)C%Q$-iR_LJ4j%?q;2$>n z770sCQ|CL(f_TUfPjmNZlcF;cFnVch!v<(xU+);#jBH^yjBZJ4{fpz%Vf*y5&Krym{QXGhg+K4VD@zvy2a| zbV=Yx|89B{E5(p)nJ)Jb5o-+3A}BqqMK5&`4Fhp7!2x)Mm~fgsKR`EW2;hL+DN#Ek z6Ba9wo`)D$Ppx4h0@D@D1_JU>p=_NpcUXC#!Y?ZZBt8=dP}r zleX{!&Lm;>fS^D?jljG0LL_soi_{pwE+H^NVD)CNr>DvKEIz_(1?UX04Or*z-_d|U z1GKYgw?z>kWpImstljZ|+G~eNC&0I+j04gU`Wj0}SBAd@c{k*glsSJK4*^Jo{62)= z9$qm59Qp!)F-%b)M$$1fv~+ZgfeZu0dX+o|sSb=&ww!x_%h5aljXI2KUG9beJeQ8Q zUJbNbKnUM#?fJ}9OE+|U+@?xoivc^`1Up{+x8aK*l`qVE=fLg<|ULkK5UeGdX%- zjPvwdm^s=QQTyGa$FYJ5JI1ZwFy+-wwES-UD(9NA&Hv)p#QyXl7{zbCH@QY57MfgD z!KvMYbG_MsA42PfU(+gcE*8Rkvr+$AV^-t%HIDJ3tc2y-_2z7N*TUm?S#&Km%4ENf zcNl4xcz(-ZCeKduVl&z}^JTeg(L6-6KRD;>B=?@Xr~ScL^xH$sO*4TS=gVh&1?|?K zBA07A-y<1)*=L-aZP|=#$$zn~x|u?WB+jtHb1aY$iBWzYAeneC3QLgxy3<+SmkqnR zNk+6!Oe@Hpp-LY|N7YX^^MWK~D|gL9E`l~!a{bXPU5i*lmBs-97K^ZUjDJGb$kYC; zlj9e2VH4~{A$97B=61GLvjdrX-M-r%WBB>hsxnL1#-n4_ziq6<%3l`s?}Tmfe>qJy zM`~kOF!G*CYR%rPpc6{gRXgL3ms?y?xI0i2R~lxi$fkXfb)RzJ;6FB&_FrcvLbKf; ziFWtC`-o20u+5h^haNezzn%<#;w%5etCRGLwk)cq@b8&U?(KU;`G-CU4WU23%u(#! z9#JmmT!onxaUmIVU>qeLbn2jDIefa?>hw}9c%fnM63sTy`US^!kz=*U#(DAu^`J}j zFr~SLjg0A>_6Av3w1V-4=I+JDW7YJ^4%RENpvP*Y@4)7Nrz>Zk@4o7fweiFZa}sn3 zO?OJiS9<58=3iXi?TNXRdRu4&q1fx9T>rlFD2QO}l3)-U<;7NheC65<8NKAxVukw9 zg!ko3Lp5rd{jU%6MIIfQ_M&}c9V1y$4n1dKG7o=*v=O{cCrxcZE{`GKeRoB#{z=fE z7av{K2%u0=8HAD=9|!mcSl*R473wO?wIxwWB=|CLOgYuyat%^WOx{-H9*)|`pza^yQ<6KU7xrE4NI!kbt7o%zM@OT}6@yIhyT=Wzr~&@>Yya&81f+>b9S;>WnksuX_D{uuz?Rdi}X0tkL)?eT`zpFfPy{(RlnxPW5g2|BAE|6)4X7Z7 zWcvnR=$DEzN#PWwy~DN*`QvgG(U#9cBx)egl}#9!o!GLxRnPt7xRg>@Ct)>wzh1s| zdmVK^Veuc+sbw%(45aYns)?g-P)>S|t0&c%wS zkaErs$on7N_IM^J2p%q1kkTf61cC@o`yd6H63q5gqbq`tm#sz$x<{c|Fecj70KYgR zU0hi8(vSag1GZ_Zo*#a3l~_!n3m`YOtAX%iajfi;0x!R&by)y3 z)?-j*JUa`UDvyYWa*5V5upVG|x1pN{-VDqq-R_2v7S|1>;$$>5Rsc9ayAz-p;GBVq zOQ>k6nO%mWr}Bn|K0wXLC=Lw7ThCWhArub=tOlqwfGI^UpcP;nh^ZTZ208hvUw>in z1i}+kDzj%K)?jx8Iall zCI#>9C%fW2R7QcA2NLptbwiYfA~-@r!>&p;c)2p5VtV~L0iG>HLNMrzAo2-}KAQTn zC6jiI*NFp`@ajNE1xd%C*j)|~a&bH7kqfxip66Y4T0JA6nko=olvX-Ar`yEDkNc(~ z^{{#!JKITClqpL(Gx*)YFG*dhgz`Rxzk5$8^76kg(YHRu6|kVJrxDswEgiACh%nHW z*{ZkB6#4R?o$_Um`a0Mbh8RRKzLE-KuOAB8i_6cRKg(!{t=c%I|8i0gwVtEyH>=3| zg~9z3cU$9hPWj`Dl}8r_$+tk&@E6z=ZTc%T>k z2@(uyQteDEs5Htcv;6L0L(BiwRJ*{)clW_@oyQ}JB_1<*1?r=L0>;7uf0-wgGMfd) zhIa|;KYm9tqAJd8H#HE@;Wa8}q4AX!@z0>ax6-MiD&oND*|t;*y?wuMFX2V5)v7rO zlb}(GZKU(r+jS*l z1R;qKuTLsZNFOwl%aYFjt3thN$x3Va;=9{`^{eEHI}`T=AD;fmR&d?i>#w4)3VUDh zb9;vM%e<_&?|D+q>lto2Sx#l4L7JY zG#{1V$*s8Jesy~K;@d*uK$+)+=BlDBM$#C8k?%&bcptjZV_k*T=A+5G4T}dhiVp9c zuAld6>yUKBHB@#N{KZGcnm#tXo3cHW*ndAScU;Y{!1~3=n4@5rrRk;CxrBSTon3eh zMGnr4-y^kHmr{<$cL^lyetBIiY%k8#Zs+FU@9vcp>FRWxI5r{M3=^3?es)xk_D!FPxZcD2~p2Ymg?PsJ^TJPdwGDq_x1{ZZG z%o{HrTimh0u%M8?({oD~TmGBEaSf@sNw(t|o%q16XtSjL%FWLzvGs2Sag;HKXYu*Z z0!)K^9p9$%JGvgOI@H$T**-<@6+pR5Zw9aEQuJ4+1JVrENQS>_;hXMb`Fswkg>zJt ztxrGrDAT7hM@N`&X9lnxPg7=ZaMY^LnBI1#p<*14wfl|5(!}QfKHH$7B9J3(jCu1j zX`qXoT#^1i!ROC?s(lA6jGiSt?_C$vNmPF#5_}zM;y13MBK3FtHiaNb#5`WWf}3l& zB+bg+KJ?o+!`j-D!X*9I&pnre%RgXItt6?E%>{n>C1={Z0>lV+#?`}k?1wz00o}65 zeM-d!!cLTriw#jiBMI;%3Xat*Y}wl?C-izEt+DT#%D1(nCN$i*r|L)$sfaURH>8=^ z3k_%#_71(NWsK`#;F3amT8;2rLU&_)M`958vn=_gL@0Mclj zpdQGzQj#~p8P$(Wvo!`F;)KWi)mmjz1OG#r>D@Jc?+SriiPN{a9w1`bfA&Q8w z3=ij~5aSjRS#3Qh$p2A580lUga7z*`0|~?cm7pamqyRoXZ>Fao5@axy3pm5bT1{d$ z9Bd(~{D0jPkaz;XIpo!XJwzsd+!W>-P-mWaq}?hF(y#!V-XV2+;@#1OuoSfR=%Ms&BCz)D1J|Edmu23 zpJ544i{R(O)AGN{q>4Na)V%-G0svhFYUUuu$gVH740->tro&ksc3kkj!Y#qY+Ud z38A~jmorn4k+;?gzpqd{xwK_`D+tQ3l@&{asg;Tzn&pPI41}&}JYVGyYN*yL79Sg* z-+|G}_k6$@DnHk2ec|mPBrqGf$uL_ZLTRoRFhvm@=c}nwE@9#5%9b+(2L`YR%vPma z9|u+ti*>s*fBk&tcY`F%x_=zqpq|q~cV`M3Hwh)+W+LV{a0pE~s4MhUjfe~&WYLH! zD)^X}eLJCm>$7oi9OiQPy)(Y*GX4vdmvA59;|t$Lpke|+H=vASSnaL1r?(lP8A9Mt z_f&-1L9YW+ZTK|ufT|C%u1$a7Yd;DRc--T1HZ*_r0{XG~Nn7^N;X;UlPlQVeK58JI zft!YKOd$lw)1E-~ft(3GOF)Vt7|rc|Hy9GK^uq zoMP-u9HUqJb)-u7Y^QAeliGc9n2goZtnb%<@0S$poOAyg9$Z9hML+n$A1owsE;~lF z`1xp_Ya83EIs9a;z*rGt^Vk}uWkNg%$-@~;)YFrhdY>NQNB2PUsw6-?1A)mI%^|@oc*F%# z@|w~(e<^x}j;ITt8?u+=gyY$se_nZeL^jrJ87vs$8Y!ZE5%U8(W#M^Z_@?5wXr}?p z7w0R-;?M4^Ke&=ySbvmICwO(dEKmNG16xduz<*z*wRhzd+m1@Lly&IZf8&rTlpfvm zXqiGO97EpAJot^t{a!H&?&#h@ImMvL<`9Rw8!5T_28tKQ%xrhjFhqN?rL2Jn#HcDPLz1?q|wWE=^wT&1{FbM(+Y_=;M(wUzk8Cie}} zGW7(OS?$WeaKP$(-IKef`u>?K`mqG2UImp!*2ulXn8$r4?=8r^O*f+*AA4V&iaYv? z1S6@kf1MEH$5%R`0+^@WBJWCi{W4U9`l~Sx0Sb%#L%#mpuTw)zaoo7v?;b`k2V_M# zv+5|PeEt1kh+h8lv;=ZrTZe>#c>eN|92xmYm9JycA?Yf4{~eFIH)rjqbJjk^GC3Gy zHG~hvrs@3nRc~f=N6r}A1<3T!ufA@r>_1LYd5DQhmDhdi&ry~(iY?Bm&42lt1@=dN zB%92mQ$ObBY~p5|QQE-c7LwL z;yAUe2~c;i6I}KNm$T8Z%O1k}CwjLYYvU)?Zt-!?-}+%p9M*h?PWfTh&kGtIrKP~! z|B|0gbCH@pm($bXijW#(NQ{Xeo>oe(OfzD2z8GXy9EgNe2QKc9k21<#3?uZm-(phg z|8BYk*^ProE&lY(Z)@u&@pGh2*#(a$U(J^rgYjnEF)UbbV0wVoW2Sor&J%>;6G z_P)Kc_>20DU7S{noK_`MnkoL=<;1FIto4laHW*>s0PUivD-}H&a1i+DS=Vkq{{DR^ zDJco%clz`C1_l#IVPI`;`XlmlDBbm(B>jj*+bXYk2%Np#DO6ZUeJkB$G#O{T_mJq( zRD@hI9H&;UPs_qGyyDd{dp1Vxe+mc+?g<`bqNuS;h(ebmW6MEe8C2Lvo;tzK1QyTe zAgvV<7K-n6uIeW>Wq#3s9Jqpj@mi@SMY-p2Yjz}fJ}1ug3BsBQ86A=%gC5U>g@>SZ zGWLcfQrf}&zaKU>{GWP)lH01#@|bw~CrcP=+Ka?IR(V!#)EZd-o3w*+ZBSXLDS%uD zzTJg9_W}*r^PdDp$HrDQHQhyHf5el5v*Mc4*Vh-9YPdr58oV%IM}>a^gG^&Hn1p6l z7CokM=id&yCRY z;QfMP<3Xs2hes`@lqPFp_1y{3i07(7eKH7~0lOIYDyn4NvhF9E0X|`Nb`}OW*qPy) zfMWnvHl5RXhwkWLfa8!fV4oD&2#P6pcTtMTcu-b4pY>3y!sTEnf^7|^HpG+#QM;g=f&fF6y4gvR0k{e9<9(q}1mTV@)-D^f;pHtT0>B4? z;9$=LH84WW5=qM83U*(>R=~|Gtsu`7Z|d)#0SX`RR`q}q7K%A3gr0-d4ME-@BB0Bz z`paO!dg0Gn51+So?%wR|9$ajd@xa3Z0}-sKy^~W_b@kWF_alBgZlI?IJDS&a&D7a! z>-B6Lde8r8c)l5*_iKCZEg;Wd@4NwD8%WDRTn#YRsMrBw7y+RRXpInE;sKX+0Ru3O zfG`$ePC`T&Q^b9PxfzsG@Sp=gW{2EpR@n0tThbCSIeR|58&ep zIwXXC#?VJaSs5YP0+TX?CR%i{rz^X`YQn$L%Xwx{{a(&r|Nrx3HYPl^+o7sM_!OXYGASr781kP4}UO)9Uph-pcd(Til4P z71?B!cSabdok((rb&YuXhvU!4O~2ia_2#@mPR@?cJlV*iSya^AW?gEGD@mWi{_)*T0cc&k|YOka@10HRyvr~MqBnY zuW{|BSoZjuM7@7Rkkrazk4-y4TuWwE`zP+F^wCgt_1~aR9VSe(Ya^BR%QICUOT-$+ zFnjAui;Z`_C+BSm>eQAzG4%4GH~e}#mTLRW=$JHS*;A{*mo9?F z!d|-@+!UF0*O6q3T((i#;LV5HG+DI{vq<7gi)s21hwyr7C92WdY)i>mlIq;7pC2X~ zKmK!$sv=D~Z^$3v-xA%ryKWV?PBIjf=5U9Bw})q1SCeXg?ELim-avL zYu8E{Z+VCoTQp-z*u3e~xhwQAOk8m^qWgKv(C6zc^f8&^XLHT1RA9*hE zP|yljoM_W=Oz`q{9}2DRgLLwBBe)Yw_^GhOFfQ!TxdL zGPa-R!7;BziqgirvQ%$h?N-J)o!uqt=fVzFmD(V3N;U zn&y(rkH^8a?EA{2!jTifCG@>t) z`VjR0Ln7E4cO|T2zXdX#d$e6i;8o^z^WopQ0}6s6Yt zGALc%YK)4B3Exyoe43(!VuT7h)4*1*l}3=&K+&K(H6BPWJKbusUgVDhNO1i;b!hVi z9eM&J_szVY2B;v(5^6CeO;WS7>9qfdq_F#-76`Od2)C*JT-ut2=wMHpH*hIOAu(RF|QZP-=LQ)(=p1d}c z6`+#grI3bJ&Ol0QD=VsF#!dAJ$eGEyxDzHZ${VdziV-5tJIIr-(YyYU~s+(`R&RIhpp zg%=fJVT8c)CG0>wv<>h3A2w3|w7>YF;;wdOnh_ZMm6+GP`m2#ISwU}#^MqkfTk%4p1;Ym{iEIL86&2wf zfU&qvqI=9|0!bR_$u5xy(Dn$xqbhsyyGgeAKInkT*sOpy2S7U$RzWFks?2l`q)ao_BqIWL8gT&#U52Tx>es`c;?gfiVJR$C%6HN; zGtFIG2ti8>DSxo22=_Q-FG3>myKCifUIgaT2Dvf&-IPvoy8Y171?kw3c@6R@c$iWC zNiz@v^>+_uWJKFIP=kALTEGQa*hM8m%meHt*yR4VFQXHh=_j|ra|xp~?~Be?W#7UP zxyU`DH(VN;(hUZAjU34Xkge!>@{gQ^gan$~LI53ZzP-5w2o+NCx1v1V z`4q*5A<_AfN`{Gp!w^rto~|xEPf~CVJH=CSS#aO~kKexRQ(sH)K~?4r@jVA_ORop) z2AFDt`zK3`@6hnvZvP_vap^m4x%s_ubZ$1hKbUCcBkmI>B!`!W;^a%qqg{QIMI_o5 zeEMx1ms-c@Z}R1DZ<17H+3&pQt1Rq0&TFKhe>>(3t3vA8GBY|BTawjj`xioOU0w)3 zcb-Zd$(v$SI4De7O%7^fzoTJCKvTuY@Xz)p<)5Kz&%Ytk{jRisNmp{Dq&vxajeqy} z8QmBJPj7OH2^Dugoj#2}SdF*oPc`-|9nziu#-h7MZqPW{tb}i%?x$YMfAx zNohmWZ+)&GKZ0ko1U{vQBE_Fq#1rNa$1joOv5{Bd)!K8`+s<_gZF6ht1x}?kvbajN zJ#N6NPcZt-_YO}PspdcJL2gBPB-&1eQ~|oZ7|kyV%xqP9Y~3vPLak^pm^DtnJ2Eb* zJuH8Ec;XklBDNlF!dI2jt;EFLIf`sW^OeXmJf%$lk3H!6lbrztul2f zeM+MVWiL>Gan5(-(B+ma9+&ig!h|%lM zXV@J77`6R2Ac?-<;-eAmUaey9mJ}m+uqoJvyA_wn^=g>ylZ@1jX^mf>&`;@m^CQ)4 zqAz?iOX}Nc0}n^fH81@bB?h0-Q_-3ecp66Kf8vg~?0-x8&}uhjdS!*ctI#fNpL@*o zHvK2*yH}64;v15<*vd&lzI=Yjx37azVMFog5pMNoL!1b6B_?y5M#teX;tDl_#XDAv zo?}ZE?_aMaH^a{BB;PKEKEFQ(ZypRW)} zA&{QTtk(jSS=&v=sMO5Ck9=$E71Sh1uqTI6An9#m0C-fsZ$U{JTU&m7MPQx(Vq#0U zI@KHpgKC++$Mbu(3evD9Ggfc~LA`0kvhFLg4;areJ!t7qZvIy2{`afUj|-J4>z_1P z&($eM^MUQ_8I~ZG?L(fA$zFlBWEj-H-(SwxVX1}-luz>FLJBH07ms9$K2nuqPws@g z)<2Q0;ijXebwx$+eQl9Jz}f!1<6o`-0jUWc@-zV@dt)gmGrr6_JxCc;_j-#R@>XR| zY@GMczQNfKcid}#%J@FAMv?EHLZNvtvTP}c88?|${-! z^gLSs@Icg6FtmQ?rVmUND-V@UZ9j*@Mg&xh$~WvRt(+fiu&IP`h}rB^D(8=XmE3tZ zQhh;0CuN$a@e?0;xbnEGP}cF(mAvoVBOiLgAvzgg5p{i#&Y-P76BUIPaE7>9u$95K z2YWuyfsoPG=UZfwdMBcj3tAGAC70%dhaK&J!40W>xE9qT8-wy^IR1(REzHGngI z`>g#DZZNxmq(rh!4*B!Ppz`-$OkmvH>{a|}10GVWs9&F3sEx5Bq9#ce{IXK|P_n{%OWFX*JL$eFA&la%N9Z7@4kO0pJ2!;ef z6_NAMPm8ecgNX{d9G!iAqW}&>YJ@O5|5g<%4{a?iXAcjVwr{Y50_p@<8=w-&ux29ROzAq9yZuEw1L6%cW^z|mplwRnGv0RZ9wR5ctOB@CWtq@~4e{DSHMXvF|s z(kEmVrZ!QDqLDGV;OQZMkGe2|@z24!K*3{K=D) zJTIuQz9j>H7bt*01K$I~0PwSj?gAm76C5OGSJzt zfXo~oLBftjPIxM?c@autv=H&Di>cObeE&UEA-@Y^7(+l}2KmI(GcytoiLyn+t4rYN zfE5LB%bb^jFg2A-J43|pJrIA02x)k~Fq+}hihKu4b`T+Ss6tB%q&PPi$Z)58kD&F( zdNB@V=WWjr(Uow@feDXB#22fZ44L2_3=nvDd+R?QATA8dIBO~ck_;t|st zkBrJQL&N^LzaNU%W@Y%_MLA!79&T(HKepUf6}j>-P*FtAJQ$uw#l&15ydp~HNq%Lm zN1lx5>^HWNiBX1M6ry-ZmwEczYneq-w#mwtxa7NOZ`CZjIOyC-{OgL8(LK;hZ;cZ*z-Fy}WUdhK z`lX*B^|veoE|WE_ME>ZgL1JAo6m3JfIOMVxb^c8@MfO3Afhn~njQBSHw28o@cnzGi zlhhT?K}BWhHpWwi#}hQ6j&EN`$_DJJF^n8W&bd9OBG*7~Lu=LDsADU+ZO4s)x!(V z!jijh27TzvE7RY3MfNt$kA80>t3xs*`KunfZ4={9=Nq>(ZEv9#AhoelK4~+vuufY4 zbXCreek0PrKY>sC)-=?Ai$6Sn>fO`*zubn|#3uRc(s8@^=d|(G zoh}{Tl$E}{&g-*~Si=c#C&a;EV`|qvxFqFUxp;%~(oWVxpSO)Hq92!;$|M{whD(4} ztev2ZOi%y?i!P8r<9ikZ4mv$IZ}&5#5b+<+h}x03&*_X>;S_;_GlMzpdqn0l;&nm}&nUyfF)>*d=kDbBd_5e`vWLc>dKiufaRV(AM` zabG05wo8Ap!m`zt3OBz1M(UG#FWr?B2Hf5ZA5^NSLKCbG&ezblGpu~k`!&dnD^iCS z@2P5!g#ec>1O2pT?z7pu`6KCCwiRq6`?jvH0(ns17co%WHO-4d`+qcjbyyS)_x7@M z$U~Pjh?KB|bSWvVl1eNgp@=j{Np~aNBA_53AT3?eC<3A&rG#_|NPTDD>-Sxke>?%> z%Y(> ze}FD`i~=i;BgvRu?(L}{y1#vPo|$$Z9@~jMSUn1(i*=(5d;2i6x4{1Wq*yV%fdVec z1kQjWHr2Y~4M*h7%`4X=FDD=CNKvBWT&mrImL5RD-p6BzI%dRXN0=V(*rJcrqn zo9dO5zW%kHyG8c`i|r+(rMv7zUny>bE54J2=6r@4X9)aR7{eLSF}!TVdcb5M*{8~>~x}UH*gz@^mrG#{*&iyk3!ucNJq1DZ~;#j z4i32=W7|hyt^>uBEV>7g-p+BKRvjXKT9-!w9DrWq1Y}m-7y8^(m`G*-H*Oaow8p_T zR&B!|vv>jM5jd|vbA9J31blZX zn?SB)52$_!g%7NqGO<4Y5mX&mDBXRl$Gsi(3XmE$Mp7%dDX^;>kOSMGtDgm|+j$U{ z7kpGixlO11N*~;n?ZH6TopB_c*cZ?o|W2tY79LDvEqFl#YQ>F>L# zkYWLW572vncOi&?KsYv!*=eE1Kwk}aZ5QGo16|`-E_TAZX{br?z(J2JQVG+A^jl+` zX}F_;;Fdv?1}!Bt7GJJ**x{wexI!y2cibzE`8lv?!7y}y-vXXNiohP@w*H%Q?#}|( z3{(`1c@5@{#HvJQXrb7N$X=p2AYWtW?8FsTdc4iRQ#)4x$P3~x!MZWXSMEQpaSV7+ zZcx?ONZ5t4+ZRk!V@*`cHxYm>B{t@|pvwg5Is`~z^0?uuz|RE&CfK0gf>sw`lH(fr zQxRakoZ4-$+?&!?b)1VJCPqVOpIYK2kJ_a*{PXK6-h zb05~cKY@7-T&KmUwu_t4RR#{hS!ayL_Ekyo|YU2+@F#6E=62S4>Pz zmEqQ4JQLukpfrRB#P@8s@6*aYF!Z2j&-M7L-s-(5nQbxR>HoxKd3W{9^uUY}DYd;B zu-0x{YCc^qPT9I`dQ0mD4&p;Ya?*mAz@;zgh=S*0j=N@`={u<}7Gg53IgX6-Cz3eH z(fcdw+d+A19Pf5|6E_`S%dMVoaa_8)KCq>$f=JSD)wzdae zX?@SO`!zjR5Ua=CT$haYPRILA>_vrra@(6qVK;URt)v;u<^70Ni#QvhZgU!(@$YeUe5&gj{*dcTo!**V;G~5y?s{z4 zi|n|Iz#q8WdkYcRHsAU4$?iMk6#pI8Y!8vS_8^I6d}TcfEkM_~!)j@MlN6}#DgSsNk5VD&}0dXjN!#8biw{~xnr5TJbXnahx8 zIum~I!Bpi7&(#dZJekst&*72}GM=$GhTE-&WS!jpmC=7!y{oazHWBg21&a{xrs}sS zQ44FXhgk?lseuQN`58T0K4%Zx3RtPxyVXCg>f&B1X?RI{b&J>gs!iahAs_NO*QRc! zwZxC;-2T}=QH6# zMtmCWLCD{Ghby65s$GlKm7hkbDjV;<>gwUuu>*3d6t;Y#N%c?z@nx!ezeXQD-WRD9 zTmI)mU2iVd_>S!SK=I6dN){g-w^@9rkFdQL!IjD!a5i1`z;)YL+|8~jQZQ1b^ON-= zcbaQ@4xfdE1v5}*AT_T0&vzLEgEAvCzIfIyx$nP(Ja?O6)m>i6}`Ud=|E!6Es_TFBlw#e-8Bn~!1lGUEWh{G zYpB#+is@Bso88@mX2$oAGs7^}Z})iMg~G_fl5E_&;1mIh*X+DJ%CWZ($|1&;C4kV2 zqFuz|k9Gtq9zWedt~1-XKvx0ESTW>!-;TM>HKr)^l=xw^V&b;{T)(DX*@V_>m&#z9 zeX55KWzdz|nV;4ywcOl3| zhj`hu7n~$g`tO9?g;hX?odhGr4sn20u*&;x!bw5Er$LW{nJ2-}Oo5+@S=xs z%RY=%uuz63_fPMZt+7*&<||z&wb2m5F~AkfDpfaCZIURC*iB)ICkXEXU?02&!LKA; zlMBa1N?slxjkJTIKQI(}m%s~13+UpsY@RKafMFae9!$`{wak#mSen4LsAd`m9drta zJp3>CfxvSFJc782HQ{1Bp)s!auZLj_;rqIu^NxQs5~76beRlOvDlBgP}9% zx;%Yx`Cp_G^4Z5-yr2$Nf8fY=qDXuXKC9yR{&AD?x;T@B-3zP_Fu|1Y3_-LM;4No| z=9f3&Ug+sxv#9~J2g)FTE5Slxus?vJy|iSNotyh=Zkr=fEn#{JHVUlF@rrk;KJJf5 z1D*gIn``r9F#cyW{mQn2@NKXhuok#4RxS;xqfq{#$5D-EUI1~GE){M`Ny%4L!pRSx z?Lq*;ftDJW+)z<1;n(7sWpDG-bcwf}Xd&8xJ`PPfv~0US<}PR;H3-716yCy$2>w9+ zkNo+X4t)GOU>GCc0Ok-om(h9#2&IheA&WFa>l!mMX+} z!5C2(5R@_|W0lyU7lYSC!9RYQXdEfh@UCu^xAqLJC&SMcF`-{TBgdddz`1vDhuA1^ zsQE?)o;DCoK}Lf2R&d>;`FOIv732IfFMqKl4 zP9Wtyq?j-v?$EaaF&nT`cvi4iiu=(Pi=vFA$c^JYnm>UkLD-Ikx`1 zFe2yl7n|=y=?|Lx`JK+0388Y2*^I>`+h^&5FGF}XRq^hAfBf88kwe5fX`FakJblzh z?Dq+7=Nq!dXNTr7DmAXlhO}E^4i_c}iCdC;NSDLH!okkk!^`nECAQmr6H^(qE>BUr zpY}(rGDpV4T5A8;FU9@(=oR)2*K?fxFq7E1p3tzvY3ql%ccqEn?@;Qk9|Sq9%+8~n zf-%y5|9aWH&a5=GRi`23gWXob<#E>b&)$y z{mA^d3PnXwX&IX7?_9FG=J8S_@!QMeEtHwHYF>KyORVTI`!5xL8^q>M^r&$o>{CeFirpR*rTwE*g z!K2X-m!Lm7wdvTQ&rJ&OOJA{4M9#+=+6Z8oI4&o-j$20Br*yxgo!;2uJCW(OMV*@} zzFeM;axZTWAi};?!SU$|&K1%L1ajs~=rz_a#1Lx)A(du6ngF*%*9jRW(C{jtj2Fok zcJEr~l;h|^xqNHv?(5K;94#6DZ|x`aD2DXn8^iXRpBTffSy9DVdX(px_k9gH$89?E zf+d9a8;cf>rbEvEMGGpjbQVd{TA7D<`Yvz&-?U2(=wW;`!ZiHLS?y)&c=X~xoBdiFH}YhgrCM{E!?NP4Wn}We zSiRTlLqe)k+wwN537k|{&3rsJlydMZ$O}>}c-alP)>D&dRUbY?OixP={c?%uv(lxa z?pi<$+hE(StVqa}E}`4Pk_!d?tSElS#CCh2c+f;S?ptIb{P(Rof`~YPXSqq^uHKWD zM;SGGXyhg}F{)Sd!mh@I4(7Y!#y*S1=9(be!K zgTWRC;g4UPLV4uct=-6nt_qKJF^Vd}%L^cA=JyonYDuBq;-F-KB(TNDk8}t#@;1oy0Ac~aE0tE_63L2$`D1{X|6d3r&@Gn3h*!7wb zcFuq|p;}Q=go;&!N-~OM{GiCfX)p%e{b1(_9f?$g3busY&knn<9bOK?s%uSgn64>1 zJ0C_ynrJpMg0TLQ7z<;Nr0jf1HBcH7r?Uy ziU*E203vWNboDVQ&oBo9qrkdUPhX!m4PM0^Xa$l-jv_&y?WiEk6>=$|8kCl@Gm>&J zl0LLirv8%UBtc?26?x@O`um~ZE)e+q+N~c_Fnw>Sv1_(l&ru9Lex<2|$rpgp6rv)m zf9fJ6Bv-mC#4|JjRO*ma1t*}7@Tvz0$?`in`ice3z4z~div*=ksqpT=rJX3dN)wz2 z6hmY)`0zoe0CnjLhPb^<274snpFl&D@~m=-BcBfKcnm)Rv#lis1wuG+1mFr}U(vWd z=D);Hu+nrKaJ9!GvtO!l0*nNk4(?c&b8BJxFNNSm>^(|XShsq?uD@Dqhi$l719Nr8 zXDYv#($bf?u%%L9RoI*?SG^5g*_w+~&fnEkez24oii!FQKpgnm#zV96qyE{_`O#co z?USjU&1WyJZns^^!O6jqU@N0tdoyaAgH&USNvC7@w|EOS_V0A2`)6Q-KO@(Pwq(6_)z`Bkjez!zL7A}1%u0$?PC z&rp{kv>iTQQ0MRfRYNZC`u@9Dve2eMT}9#&?$n^B7@~VH^1BTyfRBLpvnY@@2*C>7 z;Jm2qy}L0j;=B38ys!$?eXxxIHi#t%pT5sR`obI8=+LYryN8 zN*SYvf-VunQ%p;oe08W!VT< zTwELy$>IHvp%ua1gQnZcsd=^+xYBUMs-{S}3bRT;UGB4#+cSVHJq&PGP_JR6?3xBw z!vX;v86Uro>V>-zvcK;NC?+akwG6 zx-$Rlh5RXx=+nh!YqD_pJq?KTs(#zueOXakXgk-@Qp*>7eMSM>^E-D0F-(hFtFL~W5=`*-JauZVxf-iTTe4{@G-lCgPREQBHh4o# z{v-Zk-M}D;@ZZstt9fDsZ6#ZJ-hTowaU#q)%Z9aJ`y8AMs-&=M6aaQ1paLdcX zOfi#LA6Z9z%U_9R(%vM?8}vD7A@PVI+hp@&PyH5Y!f~^IjVV1(B$+qtdB!&#=;3oNov{zN^G;L(KUI%US7{8{#n& z-uHGPVm+ITonI95gIJ6;i@P$(M8n->LVXwMY}g+gZY_na{yzJ6pA<`sf>lVw1Ytd^ zaF@yn>z!rs^j)dd5bJ|COnA3l&vfdi{5RftIPL7wZI7(t_xoc%J zE273KthkcyPR5$R;OL5mGU-qtX39o$2ofQ z8b2G+x<&n487=HNS3YL0!g3vj3RS#If3KgL*VTULhP9K|htSz_EN>=KMPj50)=DWZ zcTIYpSzVM=Z>9!Q^MyZdD2?e5GU=_;ALiGKRe$oz5Xe+V+;@3MJZep$U7ijyvN&FX zQ0NTkq9#y8)Ny}&scQD=^=xXmQ*0B4t;tERs+jffoyan3RiIQxoJ>CNb>=COY)i_CvaqUS~C-1Ir3@LYRdDY zu{!8+y>{yD-5r>gkv*r6nXDjJ?(*lN1}6o)j7f`2qPydVS4uk@?Zfy0N{14Ik+K3n z%tW@b|NK9z@3w3~w|K}R*coo-uj5rEt~G@@)`KzY6;l=D{8D6rR=UW?QUb(J$o%>Fe1!=HVrZg-*?5Q6KtY@j%Oo{^Mp8_)d|wuao5-qB4W_o z$-_g)_CnS8)uzvOuz4cS%I61&Ucn4lAx#yO$*c&=?LA79jL@=>=A|&EVt|;2{GBw{s6Fq*^B`}0fUV|^9k)7z#zqqFqxA97B{%Cu|Wb!hC_oy z2?>ZIml4d;1lAgWGr`ga_@&SkVJ2&gOzGbjcP5}%M5q+vyduFt0!I~i7VPcoU`hk* z7Z~x^Q2pQtpmQFU1~vx;j`>So1Y!NoY(O+plIPI9RDv|oH2lK04#xk+QONi zg__HP+P?Noh8e&npjuf-Fj~US&cXug@_gtg4-r3T^z8ixVbKA$}N zp((8W=PUmS?CyF9v3FnpNoyK?((D-+Q*42qewHxp_-n=Sb)@g5J#Ad>zFEhlMO)g4 z@<3?#|K|d@6}>51avD)kz;(o5#YyUa-pn5US&ubC`c@jA@ZqHYhGDOxYPXf}wYaih z>gq=&Z$&(ww?3tvoCxjT6TTLC=B!>U-ZHe(q5L-KVPH$qs-WSgMXLA_4gU^lY5nmK z>B_UO!PA1XrH^ymo3moC`{I)g%R7bB&Iu@_v%U6Ml_S_6&D(VGwrJK^E!E$zp7H82 zeU-LWU&6&SMUtBPFkI#*PwX#Jv39)4`}8}DJA7+lXEFU<*OCvqOPT}+V?~%(M0%Ce zXBM_2LH!z?a%`ah-2-+u+8#_)6^nKimO`UH5#Obc8z zUVcH8tl{&Dl-zE{)9HA4y$Rm)bt+>^d9r|lE_^I{l zY0n>&42I=C(m(k;`zozVBU*Sq>r6j&d5nEVG!Xqb^U`5&pGIhdI{=q!oE-JeIY5Ma zhH*{L4ow$iMWPUlcZE_j-ztXns-l$@Hwi%>@)M2A8v$FPwrmCNpM71iK3;onEPbj{ zT#5no3J4N3uPBZMYGNZfL*h;7#HdRrk*iK=&LZxutn#ap;%*!?xvbA6A9)af)xha_(V9jC$1LD(Zcq2b)sb zqXADUixNOx(U0@lF%E4PP|$@u=JudFNNm?%N@H{x{S_PZ2qljf(G&D(#ddXO_`|11 z$aqQHNhM=5x_*)GY1hnOid|fzf3`s=Ysb|={Y^oBb}b=m%zfXAE;;Z49y@Q;$*!s> zjS?q=0{6T8d&BHmhGbEs`ERW37`m*#cCS5WS-M4a?ntn?Oji4Va@LWh@G~Mf(6M^M zn60c7d5sKb_tSsdP#@7<AWvHaH|RK2M9idcOsC_FuQ7aE8u@bysxPV2Fw5% zPEbr`fwu|o@PPh%)Uhg`w~wm8Kt+KT(VfY;g|I_I&k!?&2&N*@UV$?%*qWoxEf$kh2l-gZ9#fZ?DO?Kc!6iELP`>c zNV0IV9w$Y|%nTz4f`U(q=e8*kN-wKW#@F}Q_ui~a!Mii#m}*|N(@c!*DlH6LJ5whM4R0`XP7TqA7b~zT3?#ExSw=)&{70tiX(Lcc%t0rDI2ok(4K= zQ^xkK9(()Cv1jC!{GCdsa(R8jS>i&_BV=fTMI2MKE*1(*ZUM&t6?8ykW-<9G6ixnG zS_>Q9)s(DF4gON4X~J3Td4$)%m-Ryex8D_ow22!z>w{4Z zVn|9>POev##V-WN5FoQHG^?caF>jvbsw+C0d%=>Tj=Sk`6)1^H|RR7seA z-+%lV0|vErqD0Dfb;~9&qzRbS0aM5PR@5sD5g zvB^B&!+{F`J$5(uKOmjL0*1nM7Iu6nx^4glGPbB$zk{Q5dn!F?)mHTCxig7!2cuA zZG?8kS1uktO#uG@@dGO$u)bUP^$Q2Cp}~0x4_cUsZN3vCqH@*O!Nz?Ij~?W0NhKZR z#z_UI33PjQe3+y%Z;)Q}Y<4b+9=T|S2L~~r@nGgBVz0hX=@qrQglCSsD{YGa5{JLuL8nOcJYt3G7ujad4Y3;iy zU`k`3`K3oerpx5 zq4=oYwv-Y*X!!GM&f>QTR8qR|4f2ZKp-$Jh^Tv7RTJ##C-) zimZ2%cJ;_CYfHJN3Q;;o90*JMGw9Ev>Fi^yw@4zLO#MQ9`2WT&xJ(EWnK!t<)*ryH zBEDn4gZ)uzJ7a14D|5Jp{GeN|MaG{c8j&`~RT|=CZITWy*A`OKtn|^F!3IG%#!i6*fsyGr%f0fa**-htY&`5|6u66P}r%K zjjFs`t$#zT!^EnCuSz+F{%?!yCB>qERBtPzjq9d^-|qN7%g*we zYI3e*p}zgGhiYeQE`M-bBTX-MQney^g z(>Wzg$5d@;nF@vpBx0X*zScYOPJX~^cT=Fp9zf{+(+&0uv6St;&tYvNvDZV!Tf_6t z+`Jp!aPRAyqJ9_Yzl?JIRLrN=tFD`HyZ-4sx-v|MS*8bn`$f!uKTpZ>WV|9aH)XSP zCdam~V4-l3L_t{89RcbNATguN&R+6QdVGZYI`u{4a{iuNj4RVdP9f0=WLn|`07D;OeJ{=PlSm0p z1N{l1yOB!lfU(1{f^$s9)d7QEpxYVEH^6N3=+jA1T1aMCLc>cR{sX+iVT6PCGb~9t zJmEzSI$3L*Coow87!M<)CRZ*n;b0Yh@)7W9@P?&)4|sHck!V`lxfvGHzY+D`O#qX}1yc|gBRQ7JFhfYS59`E)o4>@(mH5N=^%sa`UU zm>=|Z1Dgy>eu##~K++(&aFP(^S-esF0Y+XM0^(4lcT4WlAmwv*y|;Q$gCUD87$_hx zk%FiL%|c$hQ&!3g*I0FeV0DcHk1!a>VM;{DB=)z$APDCQ&B%h28rLw;Dd8ncXVqn3zroqS3)Zq~6(MHY>~SSl1sibc0O9~bUJ8Fq3?tlD@USC=bp$w3VWvJfKTsin z9st(sFm6K?D^f){f*cjdDFg;Ld+Dm){oa3$iR=4KO@s@i72yd9kSvZ!LN&uc60oKh zj<2t-4#FTCxEOC!sQMu6V5K9$umS)82EHCJ4x!M&KVbB^wnQo=fDS-J!9OZMzSrCU z>A>_NcA~yoC^O*fA!0zbP;NjxY(ok40Y39jHZ^dnfCIy)ii3jG!&^|up!L%&c{lg0 z^@Izg3MfWW%uoz!3s8mt+Q$OSsT^N?Wen0;k)Ev)&PWmX-BR0*y zM69p*x5U=*h7HQ}p)Uk^Mv&0*U=ugZFl>kb-^cjGhRIk+8Euth4RayJfBk~m8YmnJ z1X37|$yp5$Yv2|i3+fAS>fr$WaE|s8Ca?z@)Hry4g|B$QGk~Fz!el&md2s|i-%dUF zhG1}iFsOwZTJ`>Y0BlfTXOE$P0Lhk)G#r`%*727ZJOj26054$Fsj!TLjSR3H=lhed z9|O(72h<&_O{B_qcc2>y{s(jxjJGYkMuZg`Ky|`$zN+fA_lpqb_FVZF7?LX3kXcDE zE`mI`4Hyn@UeGwWfps8!BtS!eIPqSLQ~d%cQ;s1Xivx5#utGwzY;SKbh0C9@A?D%K z;0N2`6+t)##N)s%$Jr)K+9_)--08EmybB(=i(@O_^L6uZ3py`Qu!G~z{~8V;N+ z+!{DHDsvDqgKiDdv;i%IPY;;WC~@&{c)ox_lmDQcLalyk9SGeP&!5u+Hw2zjXc=KM z2%`feFJRPE0pMl?x~F+KD-62>YX-(2jDqGH*CPxl1YdbrM(uiO`aOjH3RXRbgV6AS zNE(g?2N4xtJvzmRrE4ERbN+uiCHRWQ`osufxLDb)&bCh-Kr%hcm z7M)r2jxi$1P~{@~mQ%b&8^`@;Cz8)H)`@n?#BI}a4;qtROgyFX+%0%aF=5L&{Is_Lm`Tz3b?7SlPz!p0=f0KG~O=hBt(pV>R_Hkk;Q~J6b)ZQrC@D z`n~=J`;K#C-F{uqekJaM^uW}XqP0Tg=|?R&O{esR-TsDVx*YF6UpbHxCU_f3=lxkF z;~!1F{dbJ>jBr0vCvFI<+xcU0XU%}oR@!R@&(I}70oJcC9gf$sUWor03ya1sB%NfT zu!?T}dK`MVa1_-@jqA~9>f!NQOpxfPSiseEU}B-3@ae>femiQ&H2YrjZtN(phQMs| zoMdMmGU1dvyy>{sT-9d5Z~0E)>pmA>vdz3Z?rhH-zk6>*v?m*ISvp73q81s~8s>=K z@*S0luf#qxUt}(s@skv{+Ob+fP1h*kdzIqOlgSsSw_pGBQ1YF3?XXGHw2@}-jWOvT zLq#|qOMg|`HatotzN1_l(#G5AHlFarR*=q>lGd0|t+%X=;#3mcsx@wKi`s^0E zrY&51rRGvM9of;Yj9<)%YG}k);}T=SFAdV_nbf&n!?qto-}!+Sja7`!vY-m!4KOY) zq6@r6)yscB(_k85SX=z3>QIxSS@nhBn*!DdR&lzG8hx-ft2Qz6woOd-=&=8Ua4gS|qq=*E5mWFxTg$WL zVwB!8j(AA-+qu}P!?Dza=xq^MS70u^ss*^=l=<#y%ZB_+=+Emtau{v z3ICbNuNwPi%NTO`J_(*b|B0zhh%KC-1c?by*j^rme_wG<)6QDlsAr^XH{5$fPW(X` zAwb8PkfGO7T51$RLKqTEPx24%LAl&NzbmDWheL0?z!M*0rG73`J!##V)m8m%-Kvk_ zrEAP}4$T9?FK?-6XlYQ%I#!;ZS5?DTR_i25u8fy<@t>Ae3 zSlXqp!ElB9oPI~k!9wDMxcal~7w=Bw)AenM#HT+Y6<9x!$GN_)W(>VY=1TmWpFgGQ zgG@ZI{-I>BWn~2-sY^<($h@cv?u)OlYIF{n&5_cM54WqA_-BgU6&SbMZDP*NP8w?b z&bCvu?A@twGhN!jbU?E}kBMfss0n%Nwe$NG8+(6(V~pAdo4h}dCf``=m^e5m#^-8= z*$w8%3LGv<63HIR&lc=oP$W>#Ak*hDNsv~AE3De*(=`Y7jFJ5aO2pLqAqA+((r(V##*C%ttVS>ceRS)D`{Z zUfZbvF!5VtyTXVL8w5zelhXVzybA~|-Tu@BI3Sb(0R$|{VKV-tR8X;wXJFk}rkrFdo0S zZg^L4(G1}M7hB~^XmA6|flTznZCfyM2M{Tc3%G#3Dt57tVswSqOvolSSJA)za!QohwZs{(DFsT^=D(5QCUY=G<=7zED#{&4^n z0gM3UZ>Gte7-EkvZ}aP7$d=HfLvsjPZJ=F5+yu+ByQe=vb5mu+sasHN4_i3mXt^C| zg#M2`g5iK%L{?u3?}85*7B5h$;p4+JUl0`lBouHOf%X*o60Mj3ICaRG{1*j`(honL zLTEc|XD}Rv9!qk7W1!PTkzm9(9KCJ-$)Ay7IxP?e?;h`3L1zXh3JRJid?)!h^$8wQv! zLQ9Y)`ZHH7IuSB4U{$3IyGXGu#m;)n)wx>4r?>ky89om+FqEeH`3ll zO~roLV7L9^9rk=1tIxa7f74ej+L9>zL?&D_~~;)(4u}|7OmFxD^IfO2zzAy`@P)7 zt@t&H(^Pb@=ep|FLDN*Gj0d($8XZp_cJ_6M6mbHZzoSn{jnaQ z@E6eFI%@Rjia(o?sI-qr`sY0GU-~my5u?+M_uIcc-Mo0e^VizinlG+py>3wJn;B({ z^hk|hqDc;}+3R|O9U!0`ojM|2&ngN~gO{(E5t;Q~qhmdlqZCCZ$n>RLoL|lTsbX599ABhz5 z5Xt=kA`txb*nmM#KlByeyT66H-!m++S?0N)G|SOBB!mXbYN9sj@g!*fSq4cBwcMT6 zF4Q*}0m+;ap6c+H(S8EUdrq#gbi{XG*^0z2&HB(mZQ)L-HbIQ_54Ght);KB zT*2(`+M-GW-V*h43^V-5wt6Fpixzvs@VAd>OEUkCDB4KgLU`QQakA#g2vRybdVOi1 zs?9Gujjl;Qtg||iU1&H`xOT8FPjV}o)eJR3D_T(bD@BtUD^;jnw)o`rZmOgPxbHu?T2VTQhH~bV&Vl z`C&?ij;x@FNEZnS*UqV|=pT?9Q}{^p)YW+yna|nSo(7z^ki6}p2=xtCr)O|~PlCD< zX#aTgBgv^lGC2Z8^2{gj%u1qjGl|EJ~TW%inMi4t8I&5zN=G8S?8slJ}#f7 zwlj1`NjT|_p-z>NW}x^#+4s+7m`S>hGqk(_FV|zDrJ=!O!C6`YtfVQGW8k>!W@^|@ zJCzlhSu9pM@k*V~L^${kSvbz{o%s~ani{|F&%V3s=*ckGM}6|jIsY1eKFG7T$!M%< z{1?pLKu;mf%-LM&9%X$En`%53$5Jgn8K+VW9an5GP+X}!pKtvvIiH)&f!3pXMp%o` zgz9#~7rd9mGX0u(VjTLS4Ej@_4xm{vo$~NsZ>k8m+VZ`9dL-wmz&@DfMU`tK@9dp? zEIkD&EjBiG#S=d{^FHjh;&0)cWcQXA_-p324INC)Dh*BX>xd0jtUEIBKJ*nih&+$o zkG)+vr2%|R2t&~1(w83C0g~Zw$I%QGRx;RP@x4zSU4eBM?&Qviulfrq_wnfp;L;9O zQ~k)Z&ph^()3=%anRG)d$N&!y58xqa9ifF;qS`a(ah23H$)16NW48$s`{Id1D#Y~1do|utqdaQJ!6uF8}7lcNOf|biu0;#SO zLIxgWfX9JyMQi+};}JHKnhFQu16WuAR+3U|oqCmt={Eok;HM8a8}3R-mxZX-67VMo z*f1f8p4&fh(GUu##|u(YgLkoz17!2`X)F}$nyM;bs#*d86(W~@XF}}+W8g@Y!kI?b z@cN(L(E#h{ldkQ#zz=}uujaV5rRD9a)E-MAOga#dTg@tIO{X$4GZ!JV`5JS4O-su# z_?;Cy)VlTj**|IU+GU4j4p`J{VuclrXv~|yUvG7TCYlHDR^?Rm)RSiR+}zw=QLT%M z?aSQ3G(jsmJoA5F(!4IukLVd0IVmDhva;m|&mr{UVZEdC?xHdvFJSKrq#0P(GRLb1 zNgeFPW%2@69S*q4^Oo`}hg`p@m2k59ct+1hA}WqP_F(j zj0xaK_-OUh(5N?b-(P)xWBKO5y9FLaP%;Dd1FD}iIJ)~>N<}uT_NeLf|HP8j{m@_A z63NiyofMapD|#xVl?)RKu1VVbpOU?3o-J|J<}PN>tp?k5f8v?j7t|wGhG=PR)$~>8 zSL-H6w13(Amk!UAT!lL*E3Y>NP@8}Cy8qir{PyS~@mJz;S+v-ugsFW!w8K(mGTFan zxX5iAS<>_?rT%KSm=8?~F36qt7~dX@{Ie?P7d<6}w7ylI+-Of>D&N#+T6xesMfZKh z)QB^Ul(^^d+!OvIiB%r4_Z?Ld?B7@P8Ov&jWDy)K0oLb>i*J4;$7z%mI*_8n`1+Wi z`SOat6y8tus}5;-T7l&Me6P^aZt~9Hx51~D&l1<9-QW3bedA{o@{YCooDwE8j?8c~ z+eyF2e6^gqBT~pYRU_q2=#ir#_0Q@Y+1i!#PB#%#H~%BGO6ioJ(`r5f4_YRwiBl2f zMIuJ2<|s#f7>HKb#wUUG_I+^Eba0-`%OXx;v16!jn7@9Ov^cM&OzJ ztDHofUG(=&>);4$V}5>(XP1uU(hpKYe|}d=J-D*x8@)0>I<@hHOl*+YDE(7yMe2RQ z+UHtV2_~L;F?m#oj1|laU$Ol#(y>b7$?$kZ>vp5j(>9WM-FT}!N}pJkM*VA2ah#t< zt8pB;u=n)Gm`hS8=KIlpMcpp=fK#_0&nI2jMf%0` z%a*-AcD%TbFQ0z@!e*>}#7(=kt|UEk?*=bp-z&eCYkCygByHbuo)10k-U1?Bv5Q0P zz@}8{(jDO}&T+2(ywj(k=)x`Ahgau!bfS~Q z5cpq*S-{jWL7W9kCykK$%>e;!tGmku44Y&{q&`b z2TXsNvY?Q?PmsHJ;3%&y~6v%^809eab&^t{Ee$Kyg$0@ zx|+sJ>k15A)ts6vj5M`kg+xU)#gZXD?#JmJgCD;IXl~4-h&YKi{rK5LRa6|dVGSNp zUVZ~)0II4tYhQ4hcKFAY95A~Cg}=`;lFFND^CG|9wY2-;n}n9~-U6?(;MH^2Ya?RS z-v7HDm+Vzi+vMf=7L*J(zx@~#7BzWfH>SwX%qlcrq#NQr-1#a};o0oqft7>lN=-}l z8)Ml{-O;kt38f<=rB}D`!e51Om}L&*otUIN?&%a(F!Fv<^rmI;OYWGj&}6;o$GqE_ z>bc!vpPs++{aODYJz+G<-`2>JDIWi}#+v5bJy+~#JT5MSXulzrF+ye8<8yNM1p>LY za4(sGd32JJu##x;(yq7zGQ&66p=oI0R^)+2hHr&R?Y%;SC;9fwA&4%!VRBJot+YpV z#w|DQqX{WLTdHqurYIborQUCjGyXlQke%E>+3iPhLRfa_+NTM1M-_HcDeAIf6*wYl z2IUXRi+{dfw_Ya<@A8si?x9+;9tQt#SD~zPQRUWxd;B!|#(>u62QM7G7mwrqJWNHNC+(}+jn!WZ{%@Xk$i zkQN^HXQezD;~wNO{)8!?6o;14*d`lxBQn{Vwj)bsQ|c-=r*o5fG^0jWtk7tMD$dxL z7#LfrqhFE*!5i~8(S0Q7C0PR%0$>MbK?f_AQt`8Pv35w3fnghW!#VZ--|`ymYI&`3 zz2Do`!AX79=U9*?1aSr(qFNJ2Fq^JRxw^W-Oy2m1f8SXh@N^W3d&`jOpZFTtN9kV` zr~8Dj(3^2n>B;w3V?~8({b@_aty0i11frG+wg<;;IZo8mD=5_4h6_5&ViQ+Iq8NzyEYP5zW^%#HYF zf1%$R()hax;R2R-pddxzKC!oty!TcKq%2eJurvS{dR8hTj3Tu_mlZs0M^`e^)6otN zBmuC-;2*>^0FPiYhXTw^g<%!LH|O5lmq@L(rjgH|6J1Q3nwtj~77ARdo;x{#JhvFh z#l*-6QXpy-;uVtQNUd2n3(kW{ejN3v9W=X<$}F%|H{7azqJy0 zh@gi8bun0m!N%^Z-*Ve|{biU19sCVn);=H~V0M4j!u@a%35cv}s&M_gVeEh0#j*zu zt9$*|^FS^Hd2)AIZTboRZZ&W3o$Zg-fbad@UNtftIAS~J+b;mxI=(n+8-%TLU`1sr(%yA&Ai%98uW#TCDmsXP|w@3&R z0P)Kx$ia8LTV@)Zg8}o}gFG;R@8H7;L;;x_IuqCip83l+RY33*Ft-52JT&;-1_4a} zctoZJ^FN+$9ohZ$_NQ#Qp0ri(@=r(XcbMslwX)WrvQMF2!|mo)M%+Kn7eWX+YOYHe zn>}lHro-lW9LkSon^S_14bz?c^s)}s%L;Ea(|pyrhfr-;RH4}7*O&IFn3X9O*8a=6 z5Hn6*X#OPcAe-+r^}?f?v{BjdD`T?%O6J2+rs$=CFXk(p57kxsnNBZA17gcKtV4BE zsG00P)NJ0w^NH6m{1;#OU|Y(as_=ezbJUi^3U3|<6V~RrNFUzABkxqoh+cD9_b2yFSmHdd7Ke&uUUsN+F^X%a^?2eI^k%FXPcu zd^8@RwJVis(9>ULf!2$Un>U^`t|p*GXX?2g>6;XP9)4$8`>lwd_#LTu+EW!qDvh*v zAFS7tHhG>VPpBIPErf8iy7k%D&FFr2U-!7ncgs|}n0BJ;c9XwDqn=y9wCHEcoX&d! zWWN>GAMKlH+H|f>R&UGa9E2-vxvSs3S9G2@%w)?U3WazZQHj~ zh?2c3A|oq%uk01F_uhMNg-RiNuY_b1vR4Qpd#~(G_I{7+em?JicXx4Jzj+?#cPbM< z?>wMjkgu$0w`YcOUtF{d_L$10uEZ|BqstE_TznWe6V%01$~T1*0}!iz1}=Gs z2YT%tbl4j5LEz@n1qvy^(JE1+Yai~{B{urap%aVlek{GHnVqB7rj`1n9siv_jny@x z7DeBu*vRds{Ucoc@Sd5Ay*ZoUZ9HGmx$JQ8OJGb$Z~3)CZ)la!{6SdzLGPaosY z?fKiIB!Y3xDI9z4E@+{0o+huDGBPF7K5EgKiM3$4u_ThN1x7@uqdE+2Hj`*3w*D-| zCe00!I+;JYr5${~>S};vfb;lO<&$3{<(9+>A9K5)R)po?SjPdX2Vs{3?=9@1FB2TB zACJ8&)0n$Q?>yS`1QVvHe!!Jm<57{pDx_P0^kLklFfPpd(VTUS-{$wqhW7o3BaCYA zifsZ0+5XBO$PAv#NML5^`)bH1{u6qu%y<1_GMYtwso`g1Mq+fY8u?s+(sKUgWthux zrV&5usK}aTZstqw+iyS9L>mb-VuYKgJ6DQSexuySTRV0O+kW{yhR}KE3E#i(r7g|o z7alz?a<0NeV{(n=57x19+LH`YA18hMUVk9)#ohGtZI<{P`cDbYY40#bSB=*Ax>mnD z=4({)?!7G(pXxHve@Z!nF`R!US8}TEp`~WPn}IVtT;67jNGYg)!6Ri=PP+? z4%8W}StPXApQNpSKl|vkGfm%@CJ3QZ@cO(zH2ljf%+`LpwETO=;MFs((YxdRu?vPx zB0?J3D)!1HoK~c{)N_QY6-XDobT~n`g73yt*yDSw37$)g=G`ht|CY`Zbm#K>F0#S* z2(euPj=UWq{m6iwX45WH6}whpMH)_2Q+Sm_ZV={~kre7>=Q9ar z&ZehPxUMV>hhV!+g*b+EpB*rUyf!9;5@;AK7!veBAqvei&{~>n!iHOul4!Kb@%_$YBt8P5{bDo zOoXcTEf9B611VBa&0-xTS3bidYB|`uG(Mh)bxEry4G=i^d*OGgWF`y@yac%=^c2F% z2R{VsBQ#|~{)O6{5)?hUy8ZsphrwS?vF^ZF}ffMgxf4%O*RLe6^e55Rr5faQ1t%oTj+rn zy4ZS7gP(%NEz|K;1?-bQp&|1{oDq?S&CuD{4Fe;f0B_#Bfx=7r_yWKu;QK)1w6U{uv@Ub!@bH5X>sLn&Omn|} zVU}rrbXn~KRst;d>ez;9?9ZQzgNPUWBUYpq{pkRnD3{sw_V$AR6UqqS|HEuSLQD)P z0#7~cE439GW}rTa$LF}v`AQr9!|$8}=7>8q5F$ta;0`cx_4+KJ-bECNhD+W?LjikA zUn*~Qpir)rGYk5Y1~isctSj74UNwb9u#m?a!t@LbWv!$;(c{A2I0jZpB>v=ZYMG@H8Tt0p7ngQ zy=|B7cdP{xAw01?sH-&8B1F(ebC)aJfOCCTe!4elQ^Ll^)&f@^Dvg3r@ZkD^r5)~9 z$kYcM2j(lNAq0nYA40jFyHD1%PX+)8kd$4f(PCN6SS-(P}dZ?i-sqwSzBBDtO&L%Kw3xHce(>GLZgMJ09=#7`lEEO=%WL&Rjl$V#c zwtpZ30EESFT@K+gvLb~psLK_HYg#zrVc~#FAs{BeT;RdgWa@yu?0{vgcS9d2exRhO zsW$*zOKEVf95+XwnTdzs!E$l{dmFe3p$EVr;9?39`*L}fal;ESc=i9f883HluA0s~ zZg%D%x&IVQNB`kOax4uJ>`6g{Yv4710a{s%j|tK5G-c z6zAy874nA@==?HSnnpTD1)wS@4wD0zi~O$3#xOk`Io#dwwSYN3t2DUabicMSy{_SfdG5>2P z!-S4^3y|Kmu>!f8D(Isg2gUM%^0e8umRZV%hK7M4LTu3Q+&qGZFngLn7(E6kD`D0o zmzJ7cuS&x|_c|%G(l$LBH?0S#e@B&E_^#%b^ZT9TD6ubWq}sk;e8Zn3;g4GWc4xn%#xGRFnHLuaiZfK5 z-~NtARw>o|o$7fq^JLR+Txdov>E+en^D0NZ{PU8!omQvt4UtYf=g22+evt$heQfAo zXF}<$b``H2~ zCw_t&DNfy!WPR~^DJP%ApqLLPsWsX~2fmRU{KyK$=Z9qupF4SvbPn%2r)}1rc+fh_ z`}2%8`6QHk%x(me1zYnf^$bT?`K+Eg+*qSFtDVt|zvyrY#(K1!s2uqC$iE?+NrbJI zzu7d6tfg6nXgx$ zM~kUMb}3)$EBo81Z?8EqmXwQe&Fn{cM)gV>Aib;CTJ2Q2EZi-o^JMc!x%4XpdJ~!nh2P zE}d8dy-_1Jo+&@WQ0Q&`gCkENZ!}oSM2hnvDTzMaYvsEoW55kj!|Z>S5Rim; z=hxPDTV(i4=Bt?-`=$cafW$BohJxeKK>WA%Ex%5E^>@7lx7V%bn^|a&j-&hPeTvp^ zIDVEhEhFbPcraR6#BWkwn&LJI`$hFX8XV2HKpIQ^yISxYrpHwI;Kl5$W}|Tt@)8!2 zhYvAB735`Od!GFB!tb%Iap*){+t7M7t5mxZ$6Qvbr=q<1^_H9i>avd8CmvI* z0#2zY7WRpGSV;~(kCG2@?z{Rjc~H4Gtxc6!Q3X)l$mHynAFV14TyLxwiSSTTMU)Kn zQzY6N8>7ri7?%6n8pF#ILT3O<5Wy{-_)gPvd*1l(`D#3n51)FLJx})@0qg-ZKsyi0 z(_;pDn8dsrijkP3XL8jGzyd_j6Xi-xOOgX4;)Ca(TqCuZ6A0>5{_B3GKc-u+df5$Q zVW2Y>ZIBq4lb&1j!P+j)5T{}*`)7tF+Nfu}Sc#oahKn(8lT8F!W2yQhV~}!m(J~BH zlG$13TI@nv@h{3W)v%fSzSE?9LJI(#X8z;?8m8~m&zt(kVCzM{EY@Xa6#0bqxceUk z1qFm!10>`0tT`#SYj7~yxt+e{S-jcHf{E|HVEr^M`+7bx;Sp*C+4%%y3AQX>?Uo=jIwJf7t2Z!3 zWk0*Fi$<)Om0!X5j8q3qA39o8APKJ!&8OeDzmmelGGGa!D-iF)?3U9XYQzd2=gn3qsr-(UYI4cJX)dMQas7$D%d zA)pu$X9wsP#IGPU(V&ch@%Bkd@4tD0=0wh2xCW-v;?x#GH*tI zC!!l0bVkr7s?40(+0g-*Fyy(w%)H>3h@dEe$~$R15d=~UAhn=Um?1$Jgs8(57KR2k zLL@-fE)fOvAkGK5J7SQ9krU!{i&2brc6aeH(V(#@R~9Dh0|4z{*Chjw%7iU!hE5NM zln~XWT3T8Qkb8%S>jg0QbxWo(<$-qth>O5vh9?FX<-Vr?AiMc&V3C7i7lJ3@DU6$i zD*+~ATx$-y@icvAJjACK6DfVc{Z*8xm~d&<_%4v^D8t7L3!>^*?ffG$Kl z{yPuBiUC`niFA3|Hkg9jjiZ1i+%kKJH$U6p1Kq99IXDo(nQ^lFP?H zeHdWjOXjaM{{?%XUgum?MERMIix>xkCD>n5gfZTKC2k9bH0IuM= z&E4R-!YkJSy#t~1b7Gf2ZL&g1?>~{b^x@P-^wt)?T>YwF_lkUj+v*wE(|x3K^D zd7KJug*4)`4mMRK=rBKa%$5roj zx2qIYRZ`2On+p&uyqsKi^T}pa1|Rv^5(}xRUM=56N*cr|XeSIsi?L$x=clN~vChlM zFZDNM=PyJ*ZWUAgjrr}-7h|_L1A9r!WM#j{qMDjqBH}?^+IBg&$;fk>&02AMH&D)b z?|in|?xm~=D&D+{!F)^kw>`_Pcd{{t>|~C#hoiaDjBdBdW4thps62wYyu)m#2opcQ z(&+g3azk~XfOWkEE1w7Z(QUVvgZkqJf9$XW=BzJYCxZ|^lrH{Tu5xSP2odYnjJhy`D0{>x!ZA%V`T6@ynw(nYu^cxR~PNq$~+Prq_B;pHsCp4;}dUd zgB=JvzzoeIC>i}F$EfgzPLgLA5(=8zRZSO_ANmQq4IZ9fOFzG$lqW0H*|}lWCr9)z zidHkZGPyq5vm~WdfOrZQd+X4WrbB{sVUH+B{Mnm;8)4^a`}_3Em{W?@Z2MX3Z%(hM zhm%R^4+4FkDL6{gvE|1k?ky;J4hZ_oN8SpckzgXBW+Q*hzLZDuP4$kp8mh9~Ya!&8 zB&4!+(Qm|RA8BbxQQwO;x*yrpA9ZkRre|94zXlrySv#sV2yhupNO#$L~zt0xk^+lW7frHeuK_7AA7D9+1 z@4Zo!J?XokaUl}`3Z4rgEC*W^{gXZqb8$Y}aD@~0Xpz}I%E)CRdfZsu$G6M45haeC z?=$#-gt(n)Vv&>NVNkh@v4 zg~`$L+^{!O(Me3fo4{+#8#kB zJ+BB`G9Qv+-3t$qxl2P#MP+8}oLV;UGF0mRM5PwLWbyYxmrz^+K;hh>$z3{ULim56wO`V z_pF^ZhoubtA1M{pDu83i4yju}YDxzU2IB$W<6M)<*b5bbmD;bcwSW);5JShIp*`S? z1qx6&Hcpah1SxT01n7>-VM;(F=q^v_F+=cTC@->K=3FQ`=65cFOd3Y4GvCIZE4uMT z)-=U};}Z1(5Yhm-4A2SGu^(!Uxh?mpQt}_oF7E$8vb#S`0)0xL?>U}k#U5d4G5iF| zeye0yGZP|$e3(v9I%P#Z|27Ci!{J-RdZeaD^KSUIW87nsi(ou!COAM&{U=`uK$b6+ z0|mdZT!*#TSz1c7b%D$amSe<-Mn*;kvYwnVnDzjT1v>J9-0a>SEAW7bq6S#D5#Sn- z>Paani(rfccLLl*HO|X-0Ax%5(83la{q-0Z4F$yKA0)F|Ky%drR5&n$@G3z6i@0bo zcEQ)hZd3kk)VHrwFp>ytZ9qT<078HP#?`IBb`MbLS~}?PP$?PnT8`5=UCWLH?Rj^V zO>ze!j#)kwA~<1ygiQoYckuCAnwrq}4&y#Spyp&2ps+v_LVdffAey%)ytL0EZ}x@% zt4)WJ`ld7Pn@~XNfMZ0=lQ5Qty=S}s9ufvhnWoZKz{(g+&mPmo%EcwgoUj-PrCDdQ zCykwe>uzi!I>{?5bN=3b1eON4TfySrFMK1Aqw*g;35+Y^UPF{pLGkU`0&c*sr6n4e z9t}-RgW+62(<~sEhOECpg9S(;5V{aH09-kY$NLb;{Hn}W5MVciC~AG|y~2&4<(f1vLlNGqU713XNh&;z9O)6%2^uVyQ8 zxD0@i1E)h|@)_;zlNcFvSs^~Y*2R5R===rr7E(RKta>+(__$s%jS24NUw-Z};j*qf z>8dSW7g(NNakZyCk^eq6T{PBFnT+R=?sD^hV!v*14VA`OG0n$p@AS#k?6TK=D~B&U z&K1)OdSg$Ue<_82^1h6_(rKPZyIO5dL-ym#8q0d_=e8DMdo*RWp?ZJ6CZ!-jtVi{# zt+|YCRD6A=`2(Hm7ya6cA3ffccDrn2)ccFbk?iY8%x^fTElqN_7M^LgVZ*;5`p*WiV^ zo|P`0(1t{Z{DW`AY1@WGSr_#Mk_`;Adcr3Jt@`7YsoO>wHYGMwNmH4Ob$5$<6$-g} zG%V_BZGHK_moV^3Jd4zc;94ghqNPnd=6auhzhb!Yy@}FGilFxUJT(6O4zd^Gjs3#$SXa{P#S%j>&3k2hztSpEf<23ytsuQ0Bu;l25heb;>(E{#t*drbv-z_L$gl*HK z;O+3`zwL663j+C^!``BmiccRb0W=Q^gCtzx(@#flH#xqc2OB*Oj*uF{v=mB~?4`s_ zwnSD%$47lr@4HW;FXR&?qZGJZhwJHjWx_LUN{(9kbY3*r1RFaXA3M_NyMF6e(|iIl z8o$Ngkst4+CqG=AS}sk_Dz;z~AZ%1d>M3|>r)DIZ-IzdIZ6Ssu#unbS_n^&~bg_X` z_T>1_0bfG8S44qEQ^(CgT*;uVdVb0iYx8)W6Lrhjtck4I&LZMyII8d#Osx42X)Pah1^{;=cjjd(kFUAu&){3d_&a>_&;rDbFr zGbM0qXhe)aooN zP{SIUixm;^ZOK_7IUMI_V^ymZfn_I?EVE#r2VLb7SV&)}S?{&d z5D&^=2j31wo6wE0y$+Pjj##l19J-C4MWUH|YpOEKH%c=1jK$KnYQ@8u@-bEE2p0a| zA5z*e$DgB8+k$-j|Hvwh?O%vl)(#eah{yLVWbt^lcnh7Us6H{USWu*5u zkz`@KjarsWsC5A+MU~AL-c`#YhFbHYjqw`)k-of!Oyup5g_!k$n}&1uX}{}JzN_h= zEW=oqFMT~oFQjF{R7d64%h(6gb$?G#0+70MsQC#D{i=6jKy*@=y&AP%dFLbH%IXX+Y9ty*xeYBJs0 zkaq#$4k*eLGlYu9yOGf4p~dGL3*0vV`ehYFl$Q*xa|9aiMZ3XJALe#z>y}Q}pHceg zBw$G)k*F`6jQfZ8(Kqh{`SN5L358RSw})xu*MCz!laj1 zZ5`-UG}5*ikyV8_Wg$Y7Cbn23G`U zzWQuAGJ&ONtAcQ_Y`n|PyfDszOWhc{NI{^4t{Ma=G!t2Vx*3R{+Gt1i;;R zK)+y!sR8e3pfNfb=*<69z26gi8rTot^ky^Qip5ng56Yl6`KbI)AHl5xCl!cJh+{N{ zQ~;1f0osa)6M%^X#MCgJ-0b1rfHd3!zO^+7XQ!$O3J^dIAO$MF*G#v0saCYOo=cg&fQ!DlpG2Jv&$WDzzvAo=;$Z{O3qP{@w7;WEfnF3qrATsIT}Sm%!`J==LNvr@w7TS!}s59;Fb}e58}2uOdY2nlWrgeE) zkAg@r^97y~Xi`M3CSsC<&It_@am*~ubtHYiqgT*i3izYiLkar6i_8OmdQlUY+hBJA z&W~cB916JNAXZ!6I0qIHs6#l-AdWLGJ3ZX4%^Nh3SXC20JRP|Z%X)lNBYDWPdPf-f zQz3QB?EaMSv(*w4hWT_c%8J`lyklEo z(@9>_@8LEa^HodfOhD#oV7}#MB-y8NqrKXt1ER@S`eWLu&y`NTP#(UIgr&;W7o6WM7p}uQF5y?|-!ZRXbO|L$l{avQ6Xs?maTLFstY+)ICE%hcr8KR$=o4CUFs z^@?QkLV2XBLU6uBO)=6EYSJd(Hka#v@=H?nRf1y2(p;6k*0Y(i(mzL|9VPb9*=2~r zN%_PqEe*%=j>=fG+GBHsBJN{#mQ>+Xs|jbHYpd5aI5AeN#~%+3#7J9cZ)iz6tdB6^|rW`w`!oMr$4^<4$L# zV25Xu(>7_|Ol4FaU(hw37xukDS{_la2;%rBlqr3xXRG)MLu?AD?fw?YmLTG`s`KN- z_7PVb(iXI>{Qhs%a$BtYeOE)AG)*fk_K1CtdI2axyw-DwZoj1#@ckjn5U0*!5E&8i zZ0BF`z=`!30~npkMO-gpu|B9nNgg_WK-H z`V!L0oHiW6qL!?!duu!$pC2aniM1KK8YZ&MJt*tOq&_0m+I-h78#UgFgz6&xv-1{f z3UX-Y+jl=7gF!`JRcb~!nKr)ok*if3Cz|91TT3)E8z*Tm?X^hY`~BO@dbL0Q{{5_- zQe|LI0m!q{!HNP?4}>AIadGA9ml|kl8iE>Flc^8V)MY#@~ zGiS1Kt>`?wPsU1{#JgSlt5W$)r}kl0i#0`mUgUr(*tJO5(!7M@VA#3Nkz3{Q=p`&; z8ZsXdV1G&|8~hk%474_CUWOc|I8skHvhg<)cHEPZvk^5(=$S#wR=um_f$DO%dN5|a z{qQ2t-gUNl))VG9$GheRTTK?<3$YvwH*j3pO~<;PV~KbbMM!Nn#QHUsu~V%=kiQZa zM58MoHnItIpV^MZ5yo4-wq!W@lxvmg!_hi`7o{09juia(wd2zPlqj70I5>X~+F6r9 zdn2EvOp`K07dMfs*5&9roT*Yq(z(>hj;5*a+B>!pfFHEZY=FfPZaLQ3ptxX5cVTXM zUz^F@=19XwNsqmc0n1SK#@AS8$FZCNe^C4pjn8Ko>$$WI$N zrn%RgOF%##{uX$onmdIf*2Tw2DaBf~CTL{Rz;D1Z)NL2~ zAc)Jv+dCPU(5D(-qP6JpFrk2q$7KZ@lC2^;+nSq^Kzs+F17h)|1=5B91~Q0zg5M7+ zXZYr+{2mdwLZ>1}Z7?{BVZw(3q;omQa&;f{Lx6_C0H9H#Zw7>qBTpgmbTh^+^f#gq z+5A9Uk%Kfxm-zrvlEf?5VH8EEqb6o%5Y9?asDZk(1ac>T!xs?Bhy>}ilc(n|5W@i` zWnA`aeJGFMK)XhF1r~q!5QKz~oL@lTi!O74P)2ex2o>lJW64E;^~+ZudMPL*!fg@Imc-o5PGMO23S!w3`uHzTv|kIar=unDv1OGR{SzV)^{0P7BKCqrm%@f;DXln`m5t9*eQcPPL$^U!p=_BQ7(77-mkW z@jYWlVrjZ$hx1Hi;0vn1enhuPj>-c3cw%lB6sNj@&J^z1mA~yDkbI$^ZUqWu>yJit z0M6C-UVj2eDqxr}nKmBguprhVSf3>L(pKQ-5m>3mtk+xE_W>ve6Q{%w$C2*=#PA~s z7Pw6S_Dkh+3j;iunB^7*Mr}tenmm6{{r$r#@UFnl05IEBUKh!URd8ki^a#j3tY+XJ zg_az6>-^pKgfKhWBzeFA;YGaU5pd!`KsKd%)*j_?bL_*Bf>U`jcKt)|`7a#)BllPn z6O}alyUf^~4xRdG)8XQFg(5B8|m zkm~m1#;xN*eN}gOXV7(h_ljAnx!iGj^|!}W%bX%+^dApx zpoiEx^j8txPAf|rJ0a0#SX|^53Eu1>srX&guW`QzYh1|?& ziB!gqj+c39+j=|wjLg`$ie#hWx6)Smj(%?hL-zzJo&BC1f3w+_N!njtTkjZ;+9qC# ztp`8XS~wSa&-bp6dVr-clDT$EaY~Xwa0k`bDcRWLT9It~ccx#VtLlW-Lf9bldz=mH z3WcMu%C|&b2;|!6MTrLKO00TmFAhW(7jmRDWFH;Z&;}c`sy0)nE<0G{+!kFO%xyNu z1#bZs!D8%$Ig?Yo_)PW^?}*}{Kfj)njN{ve-z8mh@m3Bz1H~y9`Xh=xeRT~r+pdxH zGu|>D$=$sK$_G4p{hLT87jm$0;d2mki>a&7CU zMW0ZY9)GEOp@-a#HyHBCvhMP}T@^`NZh~lyTa?>_svdd%^t6OrtFReeo0`hu9DX%7 zKb`8~8IfZWu0WM_F|1glWQ<&+@f{W&Y_4dnPWMIgstwvdhg@q?M_I=5c<#PKwlldQ z3@NI&UK$nIFuk3kbjz?ELg90?-Cm`A8%~%!YR`x@ZO^=YeHRU-esAMddUtp9_%d!b=hn8AuvlUR~XZ zknF;ngWF-2CQVT_UmcVth<)bK#w)NpodFN|G_G6sha-s8{K@pjybjmyL8_#6nso6Z zjKj+LYVh8K$f*18C0TLaWM?xFF{iF}$5}|z-Z~q2OI2Q3EuJ%h6q&naHpFg;`6ie3 zo~9=gRt9nzpG3EUwa&%XbYo|>jz|9TT}&-nRPA>y3-pRjr)IRw`ps1DD;g{17-F6X zkuPr>_{GQ>@V%v5UwpY97?!I@mPi@vQjU;zq_?-i1ci|6CZ1y408}u zWdCc2A|#6#e$1s(2|?{nC(VXz-tmRqfW4E;(+V5%omIAt%S3;Hj1GZc`n{Q^Uj!4NUBi}mmO#kZ}Zp_1Uqe6Ih z^Dlco>Bp=tc6j;}n-MF>7exHQdHqN@%aC{o(wU_ytrzy!EL)LRUMNOR_9yL-gx$@h z`puenuhchi3?tzYYcFlDd77cJiLrC=deTemitd$B=9Enw*DNEBFK-_Xph&M5^*5>2 zE$^`K;(nL!5#{^i?Igw{e0+AyG{7c2Adg3Dsqkmx4@yK9XAo)btG3TU#VKfFd|9QD z(i|c@OBTk)vF$@Ksl426!^2Ozf{g0ZACAbr@x6X`HN(W%LsnQK{C6N*@c2aa%iW3x z|8TyUSq?X|i)x}Mc;b2f2`19>93lV88MSF2+W3rStaZ!lbuy}u6~6~gWK1FVjoe6G zXAcPUey<+T8~$0;^hlQw%lhQ3K-0t`!tPhlK4wYayt{j-FIh(qK$FNp%-Y z9-g9#9_h$c`3(^CH{G2szF!<>I?@>Buv`&x0Z#>HhZ@UR`vE{|a;+F7iy(Re%tL6W z5N)X=bUKd;@s?H`q%b1ptF`W)Fjjk&GvB|YN%8>GA%bdp!a#nvKnVPeVGCWX*yxX= zZ8`4GQ%~vF3QU1R)5+;&5MkRw>0l-B*H+1eg@s>DlFTb6zCc75$p64nkkQYmC!eDN zz>{@lGD9cSiUHjfR%Q(@Qb0{7!5gZz4&^7R`@m^iM}iu>8;8q82f{_RK~?p@Ch0*^ zqiX6$BN+IhHP$K_A|7BV2k8`pLY_Z&iUPW$Yi&$y@hvkQhy`U_;efv092JnvgWcCS zHpW|*Ar8dm->zt~GtgKF@1QT&a={*HEE$x4BSXB6G*ii@e_g`lD^!<=qrD%s1f_|v zH@Ckd!bF4L64qXZ@5@+{uw@f(2Gm^~P8pM2Wr=Ay$kia71AwiZ*+Xq@?Z@z#F~mX8 z$8@7#3d~y|Jp&vItRhaUeH5Vo1N(syglgQJ3E$9xkPC9-Ga!ERJ~qY~!VroGgg9-% z1t}UWBO@cow_pVMWUGTq&>kl3_|05P+vz$OtwQ0EQm4QC)um95lFe z<_^%_;17T*K;SrwbgChg#4;KB(vpn_y3H#^FT5eGxtPoJo*726gA2XAfqeQO`)Wm-wcw|GN3bI2G z9t|Lnl2TKbny$xgx*;(HhA3dS!6}eEZIe4>h2V$5vjj`V5@d3~_$7NZ2I>7@wt6A$ z6+CbC=Nko(!=Z#M^p+Nvr^7-C_57r5A}2-Dg|Y%-u^ z`XO9a=(Gbw8NM%^vnXjA*z)|yq#BmlQe1?zi z?aR=_^RIf>KhivVz$Hf0)qnUgvh_lFgXhF-o1Me_-}=Pkj&f>y{*j%URO)Fxj)A+o znq=!JBdLZe3`;28GAkizA-wKRD_`E%;`_h$I>hgE?$~-&+sAvlzoi(NVT-kDFmPQY z=JVjQ55@e4q*AK7;FW0}5B~?6*<;SBy3LNZ)^3vO!fA$7UX^Rbb+XkSHT=k;3=|fo ztGOZ>`zJrzlXg-snzrd3EBsvJr6}o%iQG+2@?%SjiflseBm#frpn?Bu(O6&P9oNWb zW1m9v1MfT6V-GyFBVV2`tkExFl45)Xk zK4B;G>{$E1aow$SPP>^o9Tq)pzE;>5L>Bb>;?gvNOmH+a&5N&nOFmb`wAH-D88uj~ z;aF%l&~5q-)}vY^(_Aam?CC(-AumaMd&k5Wf?mDMw80qnuSA+F?y44bl$%I3({`c+ zE=12W8+go6>uocmb@#Xw`1_OpkQ=6&Is&|JV-vhVmur^K9_MD1;qj)^lvl1aIoC?_ z?o(NpX47(^i=cL~tGFY}ijNayuQ~Lj0&)6O<~e#XJi0h&7O}aAW$}|yorly`TotNY zOlym0v65YwgS70|QDkZZz1@@3s;qbn*|~rH{!XJ4LdHQGyD8en!M`mvq?W>|AQzYN zJI}GBNYX%;nKh|SXlB_ae_n`e%qZAJBvEYKZrX9ssd50KLq~`V+2=KG(V`C1!qABs zB8IRG+2Nh6QG%u|39NB(vM)=<^3@Aan<60tmW!(cdOD%bTh~4XFeHFWAalLjqyzS0 zpp)*6q9BMw`hZwgyBSL$lwt1rxEgeWh}TH{<-eZkCXdM7fSZfUy|=<3J_2=`z2Kf$CXLi4f{?++UvU7W6+H%J{_cz|x0PK&a&ToaI3I z=VOE89ZYFwwCu;t0ep`$?hD#hKk6k zW*X&k^ez0Yl5Z9_o1|z6O$(w|caBLTkGZV=JWjlWCyU0*M4?igfcFyDn^u~Crv>wl zHZl*Z?AC+36XSEVoX^GhEu-e<{#truG(*M9d!_;&kts25oWBEj z8v2bAv}tJB?MD8%O=FRvp#vB_!>7Xq4(!}@Kil3$f@$;7^XP@iBO7?(MqixlKo?y= z|MnDB85qkRM=ecOZla-x!ea0v;HGiW$ryp0{AYfH1&vpv5k0w=aJTV7yz%C07XqYY zU{&9hxIIou+ps<6j8uBe84l8b|GC`In80`e;vcBrf@S{cgRtSv%Hl@WH9yl%JNO?6 zd?icyoqEB!i1Zz{6CY zk+Exs&p4auOpXE6)!N&AslRbH5d^i@e41ZB`nfY=&j^yi7tMYlj~76><9r3+FQRU*wy6B7lbp`tb1L&2GIsQ}!}pXZ}Gl3y?7`fYh+e zO=g9$RBJl@RoWF{=mpo)r^?gF`coPx#|I7oj{EHh=)#{1?W- z0YPi90rhV1Gur`~=b0~z(Eo*?0U!(fWc@)OKU@qGEkaOLbrV?fki!vC2aAA*go{f^ z2y*2BMq9R4j&}pMuN4eVBN#L~N_=S;wuF3oV+0~b*4B4QFLa(hP${7I~Pd8Qg5n z8f(>c{A_VJ?Y+2`JG(-Do~=ze#f!)Ha7{bAG*)ArlCv|sK8 zo3$wCKYFeJ;e`hZ5`_t<4Oof4XcsYz@U!yYyA10Ex2;J5-DW&D_AN z7}8|G2?K6ZKo6Clf@wS0m^?N!1KjH%76if;OzU6jhQTxb^ugmKc|gMu6##&XKY<(e zy~G2Xzwm|@8@IoUsA%|~(G@m5eHp?^kXHg94mxK@;RA*(0c_SxLqkI_Y=IRQEFWcP zVBX3{gBL>_im5zV>4@nKB51*R0xCP0r@{M&Krz4sf(tx8q}t58WL%H~y#bDKC-_JN zf(YLc!fgOB228mb>?OpIL1Tu07n(QN;V9rHpi@jm=sk}X7v&aiGi<7f1bn?&qsUKnKVa+#S4fK;U3O}5tM&kGs-Ircd6QlkX2()`rjX{_`Uye zvwyFt{$aMJ zs~GiUX({t*&UUm>xwUT0dUV(lJu$4>_04%bOH z#9)~IPGj*Jf2CM{RojzES6@eV80_)d+hq3(eF@I9>h#s%@^XeB7vqfvwLe|C^;FB< zc^{JYaIoRr&Mnhx{uS;gIfXn&j1k&a??7z#Q5~ydrh{XWc$+JCv$3!LCkHma|Bzyy zi!D9g$H6w|CgN1zyS^Scn@z=ky(QmWXwSVm$?GhY^0AFYsrlwUaaCw5$iS~&vLbHl z6v@{>MP8nBgyLRzv^(}Ht-$w35aYjwVq=Y~p2o^stXs8GM{Vf=GiGCHueis1^sX9u zq|%~#4?Z!PK{E*Egque_DNLRP(!jk~0)d=RaOApOq zU9*M874j59KjF66g^azogIH(dk2kTlcz=QfSEK3tRpW7Gi4&;P?{^_aHs1}^jK8qA zgq!;4H!GeN%TQX%dVZasYx>K;3}z9V8<+k*T)p!k!2~}Lk8qA@l#JEDGXn(B&qX%Q z)oJ_cwBDj;z-YGr{7D0ukg!RN1YV##0Sse}eSnTl^ez7~m%g255pGhEY*b3TS^?8^^4Wqnqeo_PU{(Tb^mUVLsc=(=4KXEwpzIuCZe0lWc-J zbuTW1Stn^zrlzJFnp%y{FrUqfde&>&;bb$gcB3>bJi+fq5O9aE;cSPAP0(w2!ps!KEA*6h8gMw>%T=qKN;F;mB5RvY9M#Sx@MF_XV}`!y7Jqk z?z5KKTvT88>KLQXR>$5Sea9@=Nv_u-uiqiKL2La}cp20mPufISyiZIE#Y&yB!{xUE zcPHqqfr`537rL0}XA=@CPT#iQ?YG^5_eA}tIT5F(HV))%+F_fAd!OWUf0?QTi@kQA za@EDD)}3=H-Zhak6j!A2NhJEnnkd6sVVK+ej=GQ)C8I%q>*Su&&%F!Z*of|}T_Vfj zNl#Z+oFT1(6l%J#OV4bP=9?cJFWLw^t4x6+szbNSnh|1OiT&R&v^KE zR6AUL+V#B<^grF9pq!mEwx|=y8E)OY{r4mUWR0GJ{`KidlrxddAI!W;<#FTljfk0F z-|s=|ag|(Dw-7k`=(NttYtG~RQB$yq$T?MjN@dkRc^X@~O@e*>Q0Sx(UHMFuj%Yjw zq4~yBMI@;JJNptT%ODpt?UUPFfVu(NjfkOpx(w1L^@0$qWQP6*FW2X?N9AEMC!S!j z?8>EHgg3t$LmV@A;va*me@U}0TC;<0bC8S?Yv15~*zu@@n-mAzqBCV!yyKCcm*DQ_ zs^O`byVKs%9fT*hs!V-j>Li!0c5nl3|BiXsB$g#oF`>3)5sfU*-YGqr063iH5RK|b z`D&I zH*8a{+N6=`!Z-IhDw~>0c4EAoam&A4hlq)m3CVo=Jghp)Lef2LHgB#zJu|ayO~#J< z@BG&<=>#ABY8|aL^INgoB31kz0dYG#X4*R!Irf8%HH!|F+Ir_d7Tr#oK#+$NSM~et z?-<`)Fx(t-b5Bix;sl7(unGAwH$Xd~UI&N^fFa9!!Ig}Sp#@RLuwFw}JxrHyQ2?F- z?HsfMK=2(HbPzNJkl|2g0ca2)O^}3Q`ZU&$HlYX6Z44#RFoTBWmxEU}CgT!Kge@B$ z6i8743peH?z>EMp9NsX?>>*T%{QMt)o_BDFgfj+U7|8R$smkcyoklT5 z5a{Zc(zC2-U;wzNkru)|4TcmDKfyTyg(vun5N9(v7s1wpZV}WUaIz62Ro!l*9C*%) zZNUE<`^*P)i=ethaKd0sfuAT+m#Yi{pUf-aXgg*o7$wHoZMtc+#)ZoPC@Ev;55zxZ zA_TNx*F@CyIZAE&m48C!7QE}WMA(zmj}K)u)-?L$%e=hDFON=WPLDXJKa1zY8#i>L@X$?mbGDm+ z*R#v)OJk8`T~x}*f8LAs=+@4Nh-`|CVz?l@ge<2p^OCLK(&dS}-Qy7l}Huq*6#!LDzteLH^b4UP8tWczxIW>3LqyT~ur$qM4cQEtq*^4wI* z9I1wyDHe%cW|VUa-0y{g#>rANj|y#jN`J5u_i3{H{9@gl6g8UAXbq2pP8EB+FJ6z~ zP#EJwjF%!W0}BX``^S#IPacni8rL;b5wSBqrhzQ14xE*X6-!^6l#KjWJ(*4&Sx%>4 zN2f{Z4x_yjyTi9SO^?Fd4xZE`?X+S~9*qI)8D%mp8q1D}-gH&LQy`Wm!&eyIbrZ4NmIyX)+Wi0ur9qXOO|uZ_`F&&8-o>R^Xx1A$d8`AmU!8vw4xtuZ z=uZ^NFA&L`vEqqMT>jq0_`Hh&yUz7zl5nazT`oC9NiQn z76vyA%G@L_{E|zY?IgUMX@YUhN46Y2(*yswx|Y_qD~X=oi*F=KA~tl;k9W#@w)-`3 z{=p5L@~3_cp9!3T3C%~fdbt$uKYAFAmajzp%XBkG)I1os&J4 zZnpb)o>h$7yd&ESjk}#{s)@09gtcK=U^w=1cw*9&%I`Koy1ei$6F19G5bS5RpJiZg zKV*Ym+keoD4;m@hMYIa~@6;vq*zn$t3G54f75>n?-%UZgud1ga#A#A|7z3iu>3AnS z6NbsGtD5|lb&aoz`Pl$RN%Fwzip(_PzW2l{UD7K^ws~d$-DmH_OlO-`d!C$YRKD+JyXO9+$aDWT zvtpMkQ8sN*%TlTO5s*60sT)r2^X&aiIiEH32e@ivA5cw-gNyNfmn{TBZZj;rd7i`j zmhOxCahK*-yDi#;^t`8 ztg6y|RY~Bd*7JSG&!8D@#Jfpgdm*ELK-9i6b`9%^k7B{k43}~_(I!6&t&v;>kiSVu zsp7tuddX%T#{sWzvWC-xzIx;$o4bHA+3YY<$^Ay@)iw5B#j>^7dKJn}tdZhc(=K;G z>m7Zg^^GcBudQZdqB{?)>@&y@XeGUVUngE8%Ac?*g}j0o8HP^D+QzVyWWCT)E;*1! z!M+M^jWQ@XG|_~!gCqNdBtwd^g9C}e@c7geh81_5u?oUxKmZjyMX;xAJ|1dVfPg)) zR)V4rGscqlHn2mGQulaFyV4KE68;|k3~vH5FJQMVsjbc3{?f~mWdS1pQ?jqwG;r|VVLWTs4%Vd=vty%&8pyhZZ{klR6Hhl0L46#MZmQ+-< z!3!%T39A%7on|*2A~l7iTA1wh>u3D}}FmCHSI4HOO%#vBvAQw6eS$9z;IY)Fo;)J(> z;{dM2qj|9-$2nOFAdD)MjKZ^8!6(Fstkl(dwY8^dtQ%Z zR^1k;=X5%{tEW*apo;*LBHVG!>HeCNoDdw7z&Zu;X;u$gTP05q(=tuqtj?x-WGyPR z0Sckh@}}kx6Ov_O42Zk-f6|fT>lqEC*&Y;W!JP^w5AQDT%Ymy{5Wzs#CNitII&8XB z2l*g;Q0Hy>=a}Ay>fUWIu|(DjD9JQ)aEJhI?cjhHA_5UJ1w;ZtIXUF#p%&He;li~* z#Nd!QufUrH3}j>qA~=K#MUqS4kPTlUT$sn2oc;pTNOhBeYXTTDWaO+~sDnfXBVs%6 zzwf=phk0S{3JJfTIC5XI?z%S}yCV)0kP*Wid-h`68PVavSo(hoQTPueEP~x0BB1BQ zF0!w_gXpr_VT}m60hZmu5hoUTrm9@WWjI&<&Kqur+kRJ2pUQ6?pzV*5Lz&J^Q>OYVzs_+I?&ifxv5CdRm(sp~vmvMZP;m&n**Cj7gW z?*0wdS`cl=l#E?p;T@ANZPn@MeFF4y~gy zfv$zXu4Cr?;^XSfY~kd$DpLii=lYzv-aNx^X^I{@8!Cw2d{ijnxb3QTMWa^{wc+O6 zv&tSuIFy22pF-F+m&eJVX?wgjpsJ+(CYklctDGjMc*;9Lt9|}wS_3j2mm25`;TI}D zM*CV+tJ79W6sM`owv(k!v+rUnDIWD1$d^Wjybr}nSsb>|}z)h0)tJ=J|aCYmXAw<6ftr?KK= zvjQ0AsuCUv^$e91Ct&KM5C7nPNZeO`r;3yBL2SdY_m9cd6=KZH+k4#6)5RXbo!Cz*|xdtAzxH+$RQE!7)wxrU?4aP^LaE=&(!yx*hYyM}i) z(Ow#}*xlVO52*8SZ+0paK3X5l^pji(T#0HqmPLuei0ayNC>xai$=QP%k@Kp@NzURb z!S>Ox9!sfR(gP|=3oSmf=MK#}QEzpJ1r3TG;|rA1BB z0@RVU8b$~(0E#ZVwGFczD4a&x8=h(C2)E1|eggl4@J*19y=x;5vaF`jOp6s)| zr3IobPdu5>tgNa;@(J|%jGWym%k-G7o)CQ|x&4OLUq;6t#B(E(LDQy*QJSev)g5kL zG!3bSm6LzXZ+>Tp#o-Z+Y7hSqMny?qleDnbLKpB^SAKn!+OOH4W_Ybf?`d{ek&2jk zT2(5k<@49k77UmQ1)sdXEAg%}lM&wdgJr(0=CWrTk~Q`{u7j!86`$9Kp4*ejRM`N_ z0j&gw{>5TKf<6Ngp$aRR%lW~5-%#wQBljhVll7Tz2am_A3|o}O;xk7_0l|PMdO#!& zeKNhUlf$T#9whWIMW|1KZ2|g%AOMB=1`Z2U=-w;hY8vHT$qsrg3pH7m?gw znM@;Nsj%NptmSc08@JRiIZ&Ux>q%2&CN5xCPp%2acVnr&rJI-j#q9B>h5?J4U_N5-JISy^jcIe@YjZ5 z4bI(f+e1qS<#`y$9GGMlLDX6`0*J7!tl8WD}vZR zNdNpUfLJ(bK?1}*vLN%gXE0|?;lEZH79P@P`odQLo*^)!Docwds|PK?FEc8E0IzvS zVc~cwm9FxOkhJOiMr7eGAUGqhu)C-VfKP!ugf|`DWp{RDjcE+ZJKp#{PTC-C1{TOr zVF`_Ach9NAxYi{wB~DW%eZ=KFMRY!lS1l+g_`LQou&zZS?D4Zwoh|`J0rBOVg5n}j z&SVh>L3l7dg1Mruk3>z7WK=ZRf(^l#1KSYPTl@=OhS<9Mk7b$@|I-FT-1B^$(gZL7 zLG&)n?hs*K=NG>}I-JiT8V*M*WF!F48So;~hh$$fHF|vg`gMeO9FTT;G!YCvTel6ms3f1@zz1kAqs4U-r029ESLSSBVHz0?lTqRL9XW1=~ zA~w9pi7?6!lDOOPi;aIy;%81>QBScUL{9}nG@p%u$ra>_z^MV4CQ{n0iE?KY*+5p; zSx8WTSVw>|2!#1a%nY(ZI5*t=@*%fQtDqfxzOc5zE)O9-z~FgoXwMpf3mZ&9NFXu{ zD4~ZP$r^@b70KgcjYRMsSbFaI7cjB3JGD-yJpF`g{C!9YFK?Vq56_`Fmr3g{b zkjgmT0pBhJG=e-3jx_5V06$lN*j)fWMfbEF7=OIIlLx#n_qz`bVT#^73T)rfPrloq z_mD{}OjFf#~C)r&w-2^m9xiw&A6 zz5n>pu%zrD^k1-p$vxEm>^_{E&xbp$%YQ2$vvoU&fQ zJKFKwaR=Dd_Ja(FUwwVVDg$n3sLd!qQHCo_1wAVS1_Bxf0FJx~aCC`l+GnpJ351w2 zkvl(RGrwJ4Ho6tXWp#CT4mG5JW6c4o0`W(GqrVAp zaY&XR1Yld~a8n?$(I6!J1Ff#3dL~ow0D5lJ9}LNX?)I|P`|tIR($>b%S^1OxSx+EO z0<`QlDE$dE%+sBD8q6m8Pm0{D%?C*Z4T_nubnUn-okiSxx9RV%UK;Wk+?W(vcD&M= z*9~vp-Wbq2BSyDz?QhvB3!G{g9Dl3Jsr-%k(I8L071lKCgm|DH%{e|kik`4s{`Ok2 zjfa$yPE%*EpWTvqr^G_D^6^_wyp!p~f~r{p*%UTDxESI%(_yT?fcXu?$4v&D>+i^*$(l%Rq&Tl7MP5EwxY!kO1Ip7UV<78G{JVw8L(p|IZ+m@|Ff4 zL+XTe4_3(pr{yS)#4rwqU;XJRWy8%2weI0j)yq@xjj4xK8k_IA2m@?H>MHziATnxL zB8G;D5cA}lHy_~y3kwN6cO#a3;qDctMZDmzwm)2FtKV(kSdSaqFtJ!;D5|%QRPtO` ztyp_wWhHOj$&Vktwsx;^FLL%3{0h^uuJ%)`S{w8LPW{GS^2R@y4!W;k$|0LMWJcMd zc-0-r25T|QOyGzLF%I^7zweb!AaMnwmH}|?K0m+HW&EkFjTm{NdItvJadm}J1Y}nr zt`*Q4!!ibP3}nF&69ZzbZRhv_*ziEv@%`v0S&MQga4nGJX2O{uHn6#w|BF|Xg=FGa z=?VkP7CN(M-4I>kmwwY9BDeeO1JVobB*`Y;7yfUNG3Xfuo>(YBhV*~Ib3sxQf`ZM( z>mQ;X*Nr}VAW}Z~6$jn>Zr}ORzK+MDV>_ol!yQ7SK*!vXiSg+a4dL%>_3Zy8($34= z95wPsQ~6ct_q$p<1Mdz$c}By4z%iBJ$E0I9TTxM0)iypVfMs z543M!@Zx0C*B`a5Bw zdwYwI(51LM2Mh=38T*vHPeqYj2c=}uwo-Nw()^uTxg-G7B>flZx#P)g8MBpTa0tO3 zkRlKST9^Gkerx{J;RjHi+KVtJPFuG@P5`h1;vy}0AbP3aS6o zbx0b~;-MQ7q6Q1I$LVl#mNE+@skGQq^C0JDeff;Fox|XxB1-w6Y+3t>g>*kk*a>v` zaRPb6Vp*Qm^<6gh#aMWst~->3(rt2ERkFrwPF#P6MS;2?K768D^8MzFc;ri_-f!Q8 z=k0!A+1YL?3tAf7qWwebkL|y9s@d&uxjd)${y$~OjwTh4 z*BZ^xD>LV7F~{Tf)QB1@BzExsArx=Ki${n51HUe~SXn61y)E> zOdb#tvS(kKQA9I>BVw0vDc*PHX>VE6ED(#ewD=lXLg^Q>kpaSlF|57Fs_Eb-iMs%R zFmHph4!mHw0&i>X0KpE5#%>|9AV-e49s$NblJ9sK4cOfi=j9*%T2VKUr6d)3N~pVfys;e!5Q>SP`sue4+9MW4>;H?+|g46 zjE9k&?hy{2;au#{Q{EMf7!_XOG`_f+{sq%rJkLl^wY%MzKMk! zz_DU}0Qwq;A(*NgZGCw;WKbp$&}s<17_VQ;MJ8ip`4apJ-IA}xw&sh6cccp7T?!7& z3=iT*gpvnd#WBIG_~27RSq}Pwhu#-)Nqzy9K!Whc`KEC0SmTO~o;uRxsSJ2Rhsokl zc3Gjt0p&0-1%~bpIofG>)*uHNy4s=i1dtO*=)e?_Hh%s1_?Wc%wTX#jNm0e5H7NU# zS#L-PQX>N-E5rg!PwR@F|9Oh=((o6EcVwjSJItMt$WoZ?!cPF%4W~%BR>Wzcm<_oF zK#`?w2*PgyC;Oic2na_o@ZIpPKTwPT93@EImQ>$qWKzl&$KveF{wplI`NZzx)X@t8 zhsra61Ob|TlH3?hzAQJ=23j5hcwlZmJ~IPp2yx)tfO8rgLT0ZnW|24||E-Wnk@+e)e2+5y@so9VSw90~U1GXq2Z$Y^6Rb~rRl=8zbooYrcZ-SEu zLX19tegj-4dKKNl1dAc;FiE;0G@;rqKQyANP30?i z!@r?97#QOPqyxB=OaofWG~C~4{z$8bYQ=1X9M_;)G>o+wsMfxdT(MQx z>G)vBCSpvDBG}7z^w3?!ih?(locD(_@7K;H!T41|_sYwsd*+8Ilu0iFNy;8@amO55 z(tcggq%HMrE`F6txqgNE;u!sDa%|%-(y^dbm*DE}K4eT-A`{o%sE_^`TI-i{*1lah zmh#gyS*w+V@~=eEWdEY&uBPLZdb9{jv9AVqqzAu1_ok~CcglZ?qC)%n=tX!_qoUQp zwT1ZHatpVt+ekN1hW9+S9AiGO5pE?GQ%0Sv$T)w+qzL`#Bd5Dm^mll3(X1hqeatgz zlyWLl7dwL+CuNSPYTBM!?e<~DzD&3$}O4TG=jZ2imCP{BDP&|k;@w1fg z`#yp%Z}#@9MJ&$y*!*Ehc8uEtAj*^ToWGd$i7Hj`jPmHLFIPtSw(S;bY}~DzzmZ0n zzlvoKay&U~94YUs4c@4ke1{E=!*5udu`#kCobhX`467(L5i_M$s^@7!HYfR75^uy6 z_xSi(hF!%Y!%xTb+glr{+-%lsJjH!+aw^43|7a>IhS#R8Ek|d zPW$YJd7%x%PT2tCi`ZB05iL$-MBOeN>f0HVI-yE)8EmryS!?!7ITOC^c&4TL+Fv+j z=)d3qAr3Y!djFK?_lOCz5n(K>7x17c3$xPsFZUiNEH6mLe-VS!XP8>R$Vw)22-ZuG zvw)cvMhTGZ0liFcR>RgE1JSO3D;auIQRc6a`J~M2K;R&9RI*$OZZ+U+gdFT2FBo*7@wVGj;ERjDKGeU zv5Kc@ID4TY(j)Mu*{eU{%!o!Y8Qdi)O7|TtVt<_D zXK_C&y)7|(P1JFVHPgwr!RQ^vJF)?6huJ#p72wtc?q+FkDH;Opk;GPWGArbGPL@;kALuwJ58L%&LiY=z|y z8?-3GZ;Kw>apIIDlaVQ{@301hxb}KTk2SQtHihV0&3H-ODW*kCBRh`T2`Rsu$7Vff zFP}^^)Nt{nzB|wT(IHftWZ@pyt^`I%;r#CUs@4s|ikwkgzzpjTgN9T-`(2=6zh}%H z{j^{3ik8>c#Fe{`&$?A&d&lk>cj8Uo+vgfM?+FM7E4?pjD3uihH}patWH~CK9m@0K zb3Uw%9k?`E(qBA{edzP}aKnd-*dTtMXN66b7 zSrF>e0<_C@4&F9VB`D7~+LSSBkH4e&Ce zr{6)aK->ff3=!tTFca3E-Yr7aW!>%NaJSA%h88KJatyu?%EP>>Slq zrv2Ik9&V&tCm-Eo!sp&62^o)~4P@4EM|Y0j!oblB4hDM_MV_C5V~pu!Kv{!r8d)1) zS9A)6HWVo10Qwd%UD*T#8?aS*5uN|W`hrVG;vzH5izyM|Bh-b%gz6Dytq8i}Y#vVW znhE*rVJIR481h9LgAQZY<<7q@Y~>|-R3sWttKb<^IIv;FA0^gJ|rO>Pb;)QvnUZcK>I}y!iM1SfXyDf z-4H?cMH+=A)CPL$%eQ^SQ6Odk9vA(;-^g76YXMX*RUdPNEqwrR3=|gQR+j^Tc=wC4 z4}yfJytAI)Qw;$rA}A|>jFbh?xR0POIJAQx5RnW*WD7_JK-B<}!L(7!d&^Bgy%Ju( z4iSew1oeQA;mHQf4<1_vu+UzfyTTs;FCm5uND&%8({tZ?h;-_rRSLZ*ZgGNBqY2z2Z-ARgp^i0LsR2(5Z$BB`61v2 zoDgr~20#uckf{rYZZP+Sg$2pDR#vWT0bm8+!Z;*00lxN?*}87v_arq%$5)M&6f%1{ zAi%2HaU*Ko8xc$ZKkxeujt-Hpe*;wsJ<6qnPjH~k4yXpur9aOb1&$XEr{ICt)YAF} zCkm8AW6a1cZ!l89%Z%#NfYbt9;>gK4zK>NMoyebkIV0@oF%!K#60eM60x*N@UZ9nw!l+I57(v?})hk;gu1%8Vr+y)$Z|q7mJ;xaRA1h#K zH7Fg9#7bOqU}OpWh2dOA_0s$4RvNlF+8uGVt3_QE!iRs**5Zn2Sl*r+>FU=U&j_Xv z)Mb|xP-oVq-Er z`>e!{6-|WhH0u|f468#GL3%l~ld0_dnJLc;nWqhh^2&rbvaJQ)$eP{}QYZ+|TK(Cu z!R+|5X4~eaO%F$O;_nk~yE2b+S24U(w@O|~HQU(@pBdg;mt1>aPM;((Hq6Rw+cF<} z7=ocadeYFy2FpR&%Nu zF6-Ak5m{bI?;~)s2gRwoiPp%`TAPP zoO_%tTyFCUt2#{zoo{xCwGH1$h!<+TI?TS}FMC^NWn=s5mU7WgByS#u1hDXc1{{Vz zb^^U%w}Ud9f}eNZWQOyJ|p=O)%$_iURk_#kx$)YwCo6_BLI&XEW?SW(eRNN()a zpH`Yixv~l9g8GCc_aJVaj~GHik6>N1=IahI{2;g=AGgO2oEm9aCPwUZ)0L0=u^I&I zEy9)w@saMS z+qd`4PgmRrzi$wKUod3H4-W1IC4u>fJhyK114F|HVYj|M&b}RfjdZq1%~-Px_RD1$>MM@nj$M>S-VMB#fMY5nT@+Z4kxe|*^B@+Hlbutxd znJ))_m+cB zFq)mdl7{Vtek+i@xLq!kH7QpVVBBjc>w{&v^V%WStDf~OBg56 zGYQ&47qEy-$~2cg4N!H!rVN{6w+|Gt~G1a~QLg@S}Pb?isrtx6fly z07+A^O87Ov_1>PwIwz_E>`zX01w(dY+O|}M1qG;7m7HCjP?I&$cFv&tS?0|H(Jo0Z zabFUc7Vf&}p#GSe6K>_M6=lb7rH$`{pX&mV7s$?7FJX^q`?jPgN2my<5P4J42fp#R^6xg<+y z2ht0%MEHFB{0qM8Q1HJ{L#5LGE)SVzkoTFw92Dlx5V5368QQGitQX&xWf>H9^WGgo zxTS$d1Px+y@juliJQ|-Ga-io9i*^knFXO^Db$l%8iOTQYng$Q-iANF)?ctFqGi7da#_tOWnXcC<h0e z36CC^`^hUpvnPbG*mW=EVKnyl_CjX%~7`3NkR^pY?!D&rUPZ z{acs2G*@57^xQuK0Op1qL8fpdGzR3PV0gfH245@0q2$`zR!ss_KtyWDq!~VO62A%f z!T^#14Fw5B;EIOO+Iz(#Kunz=IzH7x`|Q|;SKN8x!XG8Tn%axtFwl5Hz8@_JOMrz! zj?3VxjX0A6Z7T5$f76KqbZ2s09$#I~0{Xr@vb~DB`b%>~KMQR{NL4Z%)RFZYiTP7z zfeb=qt~z^?IE#SEl#te6+8Zf@=AZ}#caq93u&iuZ3KLbROMx0Zk-7k}k*mcm=9*4e-gm`s{TmRY zuit6=NdT{$#%yzlAIFKK(y73j(13ZpX2vte-O%Aiu~l(g+D3>_p-r*RL-X^Qq8Opo z@senl#>u4pqxX&>!ET5lh`}`^||NC^_S<5IH(f z&YSWdu;jpGLPJ9aitq3>tcSK_T;=cy7=ViJCU$L z$`(6{`dy}O1huPX(2^!UZx!>)_=FjgzPYyz zsM1N$vjg+Sx~KX*CUI4Vg)6h2zIO~Yg=gFPrav3i)g7G=XUYyYA5a*eprPNOl|;Mi z$M-a~?`9Os`=>+UBuDY|cf3x{x0!ovOX=^-|M7du6=m&t&Ju@#dJXT9UkkqJT2kh5 zLmj9Udw1wIX1en;&9E>Sq!Wf!bX7I^cf6El+y|~M2mZ`I5-0f*>}eO;dQvB>Wq!qe@ z(;b#yQ2V|3`EyLrO2IFA6m-Crqec#;gcQr2rf>JS|8#fr^z=YHmkPD0OD9qzu9gS5 z6w#I}EEug6&tbqKAul*RQCH}Aq#yzhC4y>lG!~ZolqRMpm>=?e9NU6usE~~@+dpN= z7ynuDwVqG050^bi5cQ6-W0y~#xU0^RGPZ6t-KcbV^t6*y=BwAUhXgcC99rcTgWsD2 zd^L++{l+twCGf_x{CXpp`|O+Krwt)qPs6bAba|@e`LYJbZO$3`aw4YtQO4^UpIlh_ z^VIb+b*z-{ji|gNh@Mrbd70X%$1Hdgy_Gg^wYq*W1C74=6*b9Ile%gJm7?d?s`tzs zJD)ad8!!nf_EMSrB2K%-YyO!v!eWT9V&aE-C#A*h&#XNKQg=2@X$e%zy04=(y`L;f zjZ2Bc#XiHHQr%v#uK{6Q^|TG>*JLuEgPH|bQbj{kH&d-(!O8v4nI{!@^y3l@BS?Is z?&rhzgRHdJGBX@ZD9`hPFQD4n`-@vc`{gAnP`Usa+jyYij7lf~PuJG@bofQDocxRB z)M*>JG?;SbjlF)!s!B+Bgpe3{ui<3X4;e9I`7%9A2A3eye~53|P9 zT-@ATzhCW3m{r(M=pyX|#M$F$Z{KR!3A%y*Z1?0z^%Pdy9^q%LkM&U6#@9(MYy7~3 zXN{=M!%u5e!uFmIHYR`Ex}>V^*W5r0T=h7E7|U#e(f-rtWsw~jc()&{p|wWPak-0J zQ?Vv)W-b_fpP&5wY_{jddFkm)^h9>D4cBj$6WMoNjaH0S+04`+2~AXlxQ&U~*=YPH zzT(ZO<7<(6Ri641NtYK*SI0!Xc3`>(x)v4B*a#cz+QiIE`_6H?MVzn#_y9nX4k;~J zSy>F@y-8!rEDRIYz_VxU)_`GccR>;oN9bE|)q~z$V~mwAEh}5Jd!<=4c8ih{3hRYX z44(j{OT~GBVW3n!LDZZFn>S3}4&53;P}jZ%;DKgO-77gZ7O+fNk)FSMu^toqe6ULO zEfSP+D3aDpgJwtSkn~*E2`jQ;UQo#qjWAAe;T9(th@)o*i7O04@(fG`Iva&WL^!5* zKK_Npz^-n3h(P~eZ-gpZql72xr+2xzgm#&R6hjZmJFQ!uMfZ50qdSox<-I)eEGa!`r`J9H`Kx^|_;(rWK9r z?tb)ul)wqoyIgTuk4_=dG0azXiXK{+A3gIrU!(!#`X2;u%{$e>umq-%03MNOamc}L z0m>9k^Uwe|f+==BfBghfxSs;{gf|T88#woY8R#Dsf1Coa1&N@Bt8S451>-h{pqo z`GfO6;(>x052$C$C#{jyd2^E;gp$DA?IJWT%w-*PSF*(}?txqt#-1P%2NmWQpKQSX z5P;N-l)phFc}IxX0X>Ykp$R6?q2vtE?@AblLUEaI=38=dazvd117QGNqRA_W?ZrQh z<@`6Z*gU)s7~9G^i9&)5n3w@SF8%rQqeXGtvLauh;9qMVpjZ$M!R*=&7|_doFaae9 zym?Zp4c2g2s~{`~TA==eE)%FnhT-eK5YWpmvH4*ou}sjXz?(x}F9HVV^25KYyf&&J zoaW2vHi$ft&l7~4@bzkFYcC?np-8@BW={uTRs`)LF*)3j$6liYLDT?trFm~hqUcvm zDx?pB=?6(_yzc$?X_tV@`QJA%2F9RLXC;LbKHN|sAZ$Et*x4ob-X$jtY=kr)kV(OJ z1F8)C*3fNjwn$uXtPC~e<>tch8?KSTG1MY%FP2TG5^XQ`PEZ>%b!MzH;){8iydQ4MkXZ+*R4$2^&} zhP{C9xqLz^osMzkJBubUnEFTUh9!j2s0w>+qdr4dgFhYkCet}WhlNG*)yD~bvI zba{U{zS(M>f;xTTsi8|V%9xy6_lsw1q*Z{Avu)H%M5MYsiD_+MbUSN5eQ3Wm<@H6k zqYoh!8Vj-hV{VVhcS3xgOPtl`e;u@KTQ>&CBF}m6C?92vBt?YNH3?Ba(yin@qqe;1D~CS?llj#X~$2_1cDpB(f9rX+%f z(}9Vmj7j;EiKvyN6*>Nw%nF%8mkO=os%w9TGtvL>6r4V%2{5^s6@0_FIzQcN6cUU zWb>;(HqkF9p9?qMboH@%T%t^jfq?@GDYi)upYsFjvHZp&TAx|m@%q0Gh4It<6a1tl zanxnUwF(Ufk!IsR)Hkgk#8BnnHLPFt-KREwrVuNo!oR?1bm!+Oy1Tr7QbfOSRrY^- zud8T|92*<8PuWa=gv&Js-Jgivx-D`nvaz{e z0k;hev>qUHS=gnRu!?{Knd!>1GD!f`JgKl~ycYzSQ#EuwLFWiSIfvGimz?{5=IJ3R z3!ZQyz!Gp!gn@_>@9ibvuplImEux1J_OPDW%dJ_+L{lhG3&-v#Fv~7u2c|JH(gcVQ z(5yh{)^Ru(PGI5Y`L(mT4LKe{+Z@p~o@acZD}l!cMv$P9Ks4x}oSw3|PEY?PD4=f< z9G7J-4%P&OqGG?^m;X5yy5NeU%yWOvda#VPevDnL?~u$0%3z{T~ig6?F$tU%@OND;Fx40l zcy~S(pw4Ij(TqsO%vbx(ap6V!#p++2PfBpgWsM2(HaBz!D_hc{H zZ!oOftq7)y}Nifx-3rNfSt4Nu&9Dm+U2h7l{0Pn36o^ZMr;CdSNW zHIv9vtu!Lr=353daU~Ec?&R$@d3j7dgb?*<86_(9kfPB_A4}@A~wq}UobW{qCRi+#txTjSvN<_ zsC`d$z?-skIIVx-7#EEB>4iM8!*s2ZYDNFNbiOQVir3A1Bb6xL9oT`#MXo4*G^Xe7{z2ugn2bzX`v(s zTx{kwgot|l9OiG@o*3pqZ75LYcF@;xScx8(lad4i!NqCT~0BSk);{{AKEjE_c^ z8n3Am`Ead;eXjS6W}?M?OslXvb9~k=yt;LJ^jX~Via=4YO}RJafI z_eG2Bmkmf@D=eRxO&nd|s8*;wt~Hz}nzrGuwV88r$MJtzk4ox&*Wsr|X+!Gpa+(h7v`BUmX8o&0skQGMe6QSmeH*MroDRzV{=c$t1MH?YXcVrJbtyG zNDTOr2bhP64(UWEW4ksv?*U;3HnVs17%@F7`=BUeEDN<$x+mdNE1?NbZ;QbX)c!X$ zIzxxl4lQ!u`ZB9$x12!s&l24OV|VOO=?}9z*)LhUjvz;PsDOITV1Q@`4xTWyWg$t^ zE0VLzK(PiE6|9>Ktv>+=g8UQ_41-@6eU)bdhdahxtfYmb`I-@a+u|Ew&Kb{Q4Khm6 zPw`t}57xAWkvH0J@Se0PgwvdCmyAjcmZf$O|z&xj&;*KS70Ww6JVc+2Ppk1P1@P( zZh`@sWrY?965*SGv2kq`(5}ym#wTf^gO{BQq%cG`m}90Oj*4@>vJnXjgnJ zKfnR-PavG&exoEME`QYBO9Srl4q6tUuW8=ud8$)3{Bc<-d85XUFj}?J2f^m|!-@~P zR0J)|rtW!8=K&^WUX}%%)nWAmYdi!UA*o+ol^$?@gJn^JooQMcw<;Sl9O0qtDvVal z1`jtf6=f&W)Yb;UWS9Lt9}!q*!Db<}Q;&pA!;~66*{8J`>?F7zM-ygnfuMhG6#ITj~KwEu&iliGn2>5rR*J zvBBmI(<7gU*KaPK0bvREjSeR{#P9&fPcB1~-#l~!4aV18S=cniC3VLbeYCg<16vKd za8@D4b$mS3$6}t$8CHI{TMyGwK9dJYb}#LT&Am_^Sc<-BNMf(pV2xGJEXDmNk5}W{ z&C0FE_gIEPonM|SaWu3y%)C}2o+l1`R<$h{k6qaik$U{$>)8=yE!Oe?M?+M_fTQ== z+zi|F%JNP`}A5FfvY*`yu5mp8bW?44tM%id7jk4SgJ2>S~O+D)2ivOr}_yNUma#beNra-sQj^{^}Q- z|Ke@p8`>6Ek%6EYr|osT$?;9L%5d!p?O8Qy`TLh^JQ0RIX{-hs^IO}8{y}nO)<%iR zYd>Rh9h*sNgR^oeYJ&@NfnzXQ{hC;RJL_XwE|qwES&~GPiUd6_d0yI*;67U_dc@=F zic$^trY~uW@ONIkdnCV*f9H7Opt`{nv$&J2Jr&y;XW_AB4`Fv%of+wnAv$6#yH`o39hUxTZi843Gqm zoD*unpuHYZ{&q*F_FMyfATq*+^HY`~PZ-5~0C}NC5;ra;;q~F~^ywq4jz`Bs`33n9 zwk%bkMNfh+ePi&lh5AH3&NAm+mGwfOs(InojeEQ}MBiUm4w|c^OQI(-&7tzjuR3zJ)r!~$^1v@NtZ zksgVoTMvgKS>kfis!5)85dT&DtNesXcIf-Y+rcAVi)w`tZWq2R$6VzlEmhX7z z3N$M)u_3sh(ttksQ;iP1^RpLv?M(IGpYfifa>bcGFBrW?zOhMVrOdkeQjYa7F372e zHhDm~Aj-Tlt~{=w|5WoS>E>9jWuF{L=G)cGMZuSascR92$`?-E3*&!FcWPMrH>3{5 zP7+kyzWp*8?^jx>@{R~U{Rdn4wCOegU>q6J3bdz|Sd0HsHvDwHAth|Ijd2cGBnEMNf zySp{4{c4KOk^u@LU(B!Dx+vuF$tD4_qFTe*cAdv@-7HMW+EB^vL^aKL@v>N-y`u@G z6?-#H{a!>LEd}hEkDN9sz?bmOS{rS2UmyA=G!2V^tEs63V+o?ME%qS4(*i0TCa>g_usJZU8kt2=5KsbRa?SJ{kz*d7-K{WZg!Y~w> zPz2K5`VAUki2DF*S@^#~iBesdbUO^=bvAB8Uv*Uf?ZnQ0)SQkBH%m)s1e9FxVqTb*p|gzxZwsJ6G4FkUWqB3*u=yoP}rG) zi3aMf@mo`rS#IFK=*b0q)WG-xC{`f}fQ00`U*^D=g$#t@^2%yzKIY~ke|VNoH;seC zR}Uv=kPQLv6#RyE-3>5KD>uX6Jhi;8GlgMeC|fb+`DjQ1RWX2G`b>$dCi@`K8Ne67 zoonBPK_U)75+KqV(>NIQAcpx@+|tixUWF4*hh6yU%qz4&p$vBKJJ-=tmUjP-rmqaE zYVF#k4MGV~X)p+pmM)Q!?hvFyT2kp$B%~W@Y3T+j5s;QH2|>EM;f%T8^ZneH8`fIP zHRm(No$n!QBE**FkIGGy%6qgTvDfhnB?eaZ z2vjx-EjGZT?tLLkyZQ9K+fU>LM{WJ^*IynvjYvApZ>P?LRv*xR9W}bJe8*q6|BBoB z=3Gf(P*L`498U_prdS$z)dt#68<(_g56}}{Jo($<-eU4|6P;xLm$FK^fve}D3rl$6 zeDb}wl5v8!4domDZJ;;&lE<5xdG?lXfLQ-wPK#5Dl{j%D&9RgZbT__ziqj{owzRY^>KQ*z7SgbwdKS7WnHt6s*gm+ zmQBVDG^39dDPC%wf#D$)i{dx;$)= zx5a^uoZaL{@xFV8qt$a|WoLnBVjiO0gu^O~5|n`py#p%GRe9Uc&XO^SrQ;t=^w#B7 z_B#xtg|E~a(JBWQ{uNbKWx9h0WGC;?BFRsyk0K3BBgy`K zETjFH91w2I$7Yq(ahOp+b;x$uO7GK|ANcf3eUg89yO$H&%EqWvpO|U&Wy%+`z&Uyv zA%nsZ3hPm3={?@idFAYqq+s&cgZb z@!=#HpHnaxp2n8%fnveU15z|`85RQnOb&9$HvF_7-Eaa{U_r1P#U#+T{PV|(Ya4bo zU@eMRx$*77?TNK%L)XI1TNL~doi$PG-M$fnbLA^FZvL!e2@sw2uwJ7#PKPdH$&iWw zM=K2PiUq>~;y?UE^mUw1jQ5=qT?)jz)U&5^lnSD9VxE+n%PJ6YRACQird5%sl-&<@ zh#6^P>KW$Pto4rRowp`^uT3E{CEWgj6tmTGt{II{>k`i)P#8C<)POAlXP#7E?^J-} z^-Wydi9oZOaH~o)H46?4TsFRI<@=mg%GuM_rIq!qhs{hS{SQBz;}*e8Ix;@-CquO` zjD_Im=ZDW9hpI-33su5oo_4_61_fHb7#YQPjrZ71}$x_LB%dpamldSeIz<-X; z5!dsfBpb^|R+F%orV2N2W^_J8Rge0k=Ixv0{-gOeNH-RL1`y`tb;4-z@9%Gb0kxU9 zKz!j+FAf0ytRAJ9A}-!>2!e;Srl7n$qM%2RumraKH8O`S7Z=EgfFEC7&1;pa zDr;$OZf4)8JHR@lsa(V8_Zo|}eEQ`Oxedt4+IGwCtoM*`}pf0Tls`RVSZ`?6Or-@Ru178tgmxEer)v_ z*8j08T98g~Ln5F}=G9X=BJ(I|tBI$qABZedrH&dJz6m-XZ3V@mx+vb?t}`$!U~kR) zl`#K?iM+>nz!Ht5nx9v&NRE+$mLPy|TVmVU7vo(2{P_pr>wh*mH%x-;>ScH%AJ}V9 zM?!kb5dB?;SF*RPWA6?Qv37?DOmL7}(2EtC{j~oj_*d}N3|L_fh+UfI{?gCc7nWZ8 z_gwL`=payA{lbvkS6BRdqxK)&mn`?GUiZ28gEkG|6F5oz|EkICV*bjEtzX*`N$APa zehb?4I05#OcmSJ5!sP(*hZMEnX~$tc^K@GqZ+DSz~umwd;5ly zG}RoW4k97N(Na4dv?;%>s}Soo-~>qi1tSxa9o#%H5 zp&;o3VIbjWaReurZPj3GgVX%KOgZ3uBRine1d>CH;nWAr5P;oBbkd`aA(TSBFf9T5 z4=DZ(scGP|neam?g_y=M-U0A7KMT+#G+-~nbp{_Zu!N9N0)GnF8iMokU@!-Y8%Y5H z00v@s7>VaUb4^2Nh@fya{hbSY8ykd$L^c(Nm5B8hApMZaq?wW;`AE&R=?7*sh#>~7 z5;U$1(Gg85s;ZCfZNWzcYzB19@E#T+MI9zAVIN%xHU65oWLG2ezxtM-R>&(vT$CX3 zJRNOhdi@fLL_iqk&|C{_If|d}-iaejaWE^w!z!BhDM0|NoxpVxj7?Zq0Tmx}A?J1A z7jheA0sa!a`_VuSTU!Io`XWuwN`vI%-yCNA_EgqO0J8h%jCPiF+_AzB$C|xJ%s43Y z6iRnu_^G}1KUV1LMyKgxkyN_i>bcv-4LDhiueuPolA|XN+_2!Xrl6Ogd7S*`rd+JK zFPg*reM^_JSXVD^=P(@YWuZxfL$k`8AKTvGp=3xJntFbV33q?*SKl^SxN@Eo950u# z>4he+;q+_PU0Q6y*L70%@aZ^aDB4n7WgYqL$c(*zzy1^l5?*0JePNX%tx5Jmosb(d zih%|b230drQ(Q(>+n2^eo%@x}hYl0J@kri!by^C4oc@CQS<~T_7?Gmw$V`~lDGIr} z5Ki~L*Ew#l^pUI07pcBPA9OvFpvm>}SPUH;Imc8jLHkbz73khrZJA>@?~=UKO4gf5 zNUtT=1!PWnx2jLEz83Dnn9H`k{gZaHcO(6yu3a-O9& z3|0yC&+Ffjar!sVeT+(1hav}@@$xtwB65HAP74W|Mrc3%!-`kieW**0^r zA?hG&?7r!1qa=3Rli&)+L|WA@`;$7t!Jj+)>^Mu*wiPYiIc5ke1__CK7LA8b7nhb; zab8fo`7<*!zs(|>X|RFFP=OW)jzEt^I9H`@eh1JN5NqHulfljeiw}5r{0pm)&~a~J zFWsvHUE0_#NGuN2Uv@aN-P(H<-YuUsz8bamri~sos_f5KO@HF91vbDm0iV|I*d2Jo zxpQ(Z`atpg5+&0h-lgCpg;}~mYVNF(stTif>Ki7NDr|=&ry9RTo$M0FPZIKk$|9*+ z`U=n0r*iVJQ}l1Y$%|9zXSGcmM3ZVt(@I+(+5X92er`>2lSB1Q&f^M*;dt1u~f?7dnI!b_IdH6fZq=lJ!dQ!Hq9JewT?yY2}z$4Vi)rFrT;WIeW zGzAB-ygN^y)Av=%2}?3_GHx4j$viaeCmNB{2Mu$0_fBEt-2 zQIVH2Ez$*f%5)~<6Wpl^-Aatc^wFIv`A=UxB^>l}BE)&o%xgM?)+(wf!y&st@k3Eq zRg}8Bmv=_3JbU0M$+<_E*JIC~)7zfak~LJz-lZbD5vM_2X7!3yu&BY0twSKMkFr%g zrm9?pft8JI_ruR&Y$=PXNj$3fygWDon$W^!Wo1!gCTk&P#)H~<`HpRAmU;*|UmIM? z_XopBh2#?H%rO>hsK5`v6bdCp$l9s_bmXpRGtznvu$FM?-cld>Z9IQqe4zA)xM;Ks zPIfpb*?J@&iZBuz!f6N#yo3id9ihV33<2QKnS=tzdBoE!ZKlYs1#my_9)UzFJ`r-! zFg36_;6#I8ffAI~v33B?EL#+iV=V{(4bC=0BTzg63l=D1P_fGmOy2>3)U#7JzM z81ngZ8r@Cg|FZU4Suty}OUyDO0Xt6=b8Od#nXM&IZh=Z@MaRb48qW(>c@SuUMjwX3 z``OEU@OGfl;1_4L+ezuy+r$^FAS{9gBrxlH}FEj z=P{oAbPVz|NJA5KWz!(#l$XNfmSSNxKbbzt6jTe^{6m__X|W-dwA$% zA+u{oAm&IM^lLOP*xBy>dkLthUdfAbZzCrjAfjNz0f_@VR~POI@vqb{@%^YncvS@>9fie?YsALCkFiK1&$Z8ZSq$5-87S zuOXBrV6VBJppQ6CnmHi{A_ufTp3RWR1XmUs+IF@sry31mv;e>d7A9%Hn~rzpk-}=& zVR1nH1VxPh3H5>CKiQbMv|7p9y(V;w3LhPYxA8Jlr1@4JmM^$I=doA2y2qbqj{ghG zg&8oG>GfRb)p6(vqV#{)ut$D*B6PJ>x&e}R1pCsx$oFh*grADo@;Isk>(&K66l1`U z2bmg(*OMS%d$VrqzsDgIJt963V5WeGJs-U~)iw5Hi0vA9o!hrG4_{1RBR8k(r6B=Z zrwAmcEk})4?toL%tsO)7+j;NSIUYo4z_%x|Z;1!0$B@QIBvc4mDpm#_L6#m+fam^K z+my#$jpx#E0RZpP2V4s@e;#L5o{5l43~7J8NJ=(R^b6zjNzcr=EG!^Mg@~#uU{f$T z!c7j0;zQvBh@gTy1!7{pt~A0O0B;#cTA9J9L_#3z8c*{Z=UivbC_s|{N1{^EC^Agn zzK*0K!|#EBI#fn4JqVEm7ZrYBIw-3UryW8HBC*cD;7<8BhF=R#25I-bAK1*2oK0{b zLq-S0o-D!(6GT1nvP1iK2hSg5hmfWMdq*^++u;=V-pz3Fz zoVAtgf+>AO^065lr5K-w*Bs%`3|wdAdH~Rnc5*|OQ2oXR53b%XJS|8L*6}g-%;`uK zLY?ZZ%mWnzkuN~Sz(WdvJP0od=@`}ZOoDh!s6|6^n;};LjAlH^xqS=j(#al;#cOiy zHF{B59jM{&X0U#!chkP+IxFOxU%O#AQMBJaX@R!R9_1v+P$?ua8}dBQV!3>3#Plo4 zJ=dA4=~5nMZr!QM(&&Nm#$-z@H>dCs1=6mM0V|fly%J}Re1t(Q!Pd79hREM)SP3d( zp=29T(N>kuJ##jV|?9HC7T^ zg~X=hSFR76OZrI%u{pOgt5W41`?hW5pJvVX96Br5Z0V4GNf_8`Jo}@Z%GX%dz}?=! zR&DJ%6?<4Je&9oP`sW$-E*%n8ATRsPaup$&OPWPTvD*`g5!DT z2evviXo99Q-HZge1>n(?{wjAH>U{hV6#=x&!p_X?dC4CcNl4DgE}eZ8i1N|VZiaQ1 z0q2XW15-e~v8t*W+|h$(0Efd-4ZeUbcMVz90PzP8BObtGJK;0d2a)8;X%WSzz9l}! zztm(>hd-JmPFzyQXG&lMs){G@_B)~5W2FGEX6$pZXSwTvN&8rD&0e!Z-MgA0=?dus_ud)eYjWf)*aw*6Vj~y_s+V!VwAR?s;9N;;2PN}}vXR`uy!-j19B1N#NWrEBpZEMSjEg@Cyv=<~a;hEfZdQ_pZZ=z0_v73p zVN%hiBmd2wbd`{M+sXga`v*C=cTL7WC=I?{NhLY_K6XfXZSf$MKD*#M`eF3hq3_B} zRw-IS>T+tiu$du)mCVGlc#wG6^RnR|Dh~Vs-l=YAraX~|zW5YNBSAg}Ky|apE+#m!;ndDtL4RKb zLn{_V_j(rXAP01g!bl5s8kVN2sz5l!Wd-ytLA8XWS{}e1oQaOVFDS^!V3GVv%KcpV zdsP+fJW*4;TK=QSAJhJTM}Fldb|$j4`=}4!Mjn3tsBa?hG(ai6@H-Q1MtQ7ZB+4Ut zHSGAh_DTM*IgnZL^8JlfRaM|B0F3CyA_}%BkAT2uaNwTrw8Q8z&Qwn$mp7*CVE45=x+z*nGrvsl~&Oxxr-P|i>Ltf$K_7`1X&tVm;$}AU^D<`IGql$ zVyu1xAr^@Gp%x9u1pNePxs3p?ZFr9f9QyzZ!fV5a1r-niCPEGn;O$_?0(tsBZip`{ zodP)4wr&d4MsJTcUn9nlHJGL%Q?AaJK=AZ>H6ARIKuCh|7Sf9m;pf>_Bbda)ERB9l zEn5`Tw;^o`(u-`cw1Cq7_@vKM4!jkRJO_Ec^*W|7nrbuA#t#c#9vi}w7gTNE4@R`k z`>sxeAP@*H0kl&?Bnp!GSW-f5)}KGj09vUZYX`dkPD&CNK{g1IN>`v&g$zi*tAaxb z-ee1eY^1m!#t%&b5&;ztf*1SBz^{VGes*>i1?FD(0ccMuB^NwfX9txBq|sTwyu;GGbyYP{S5egcpNJ9Z?dtyyhm$f^X4(X(9kYN*{%S>IGzW zAmRtY2W}R4KT!B8_+;HsW4Ti;|HI@4;@qJNG{U>n_ZdhL&_9Mtezm6=jyfUsVoB-q zpWHBkcOfYM)3I6PnuA<6$!-nRA9CQXiCQNl3)J!>SY`PmDFj>)Pk%yI+8S@Pl$f;- z)6=Jaciw+(Ahyf`%zKpzEUc3oi?_ft`|$cf&H3st@K#*)R~|f<#$pYn=Vl@|rc=Yx zE_>R2wpsFF3teMhY$_#&J#OG=M0R`~S1hI9MtJ(HhNt$3dx|;W?3&TGWXZyB2OZMy zFCB+$#&-8GEe~-qD0s?fMChjc_(oIIlBrWF?QlbN&v#EcuQ(Flx(kP)=2AxcW^8Vq zS+A)Kyk#=nA_>{xJV4D-m6$pRcrZAUv$COkD403M)X6$4*?wPL-n&-4q4;9?a(a9J zqKI%pEhJ-7LHmA;5AKkGO_g`!!Looq(>h6OQr`QwnLHC7!uRT?-1W2$rrwI`-rtSv zK1-#@!SNVB8wkJeGElwlN=$ZVU-CVnQaeR>$R~-AClaTeRH+vu&%M};g|%BE*Z*~` zH%uO3+M==d^tyU#hA91(>T^9>OMSKGE_f(7=}(-_EH8g#sLK(;OPDIOG`2!c7`WkL zvq^qyFZnn+c`M}mp?0iQ26xfH%5d^rPF^c#ro*4Qj(6+dwDUNY<15!_f?1r#ThUA% z{zTlkU4$Y|r0(dy3Ovc5EPPWfd8Vis z%at$WPXmqrm5`F($!vLO^2+tgV-tVpm*K9i>9;<;;*$OPTvAmfO72QQ^-gTpqx<11 zs?kgrKc90JbNq8Ff%7rF*z@6Uf={}} z=#{I4f=Ux45548$QM9f^NyP4;4zX@jFeb+ekmo74=cT`L=8}=PQhv53yh*Bi<)W*5 zq8fEj@$B-<^J>e}W<~2_a`*c-h#At%NP>c-qq<_Mkkx#`Dhc3oh;;l6U)+Bk%8ZO( z3`|U7Ab#EVnlvIb1%%!p0Zd+Z!9K$;D8fxf9ez*0cD`+EeY{LG10QzEE|@)Fx3h6y z(}H;uvJhI~`PKKIDmiw?cI~%K{xH-kDl@6G^zLTibgoQ%EoMTOZxWP|?2YxNjzbAYgG0)(9 zMQ1`fJg^+4$n#V0+87p|_V4|?pM*CS7enn2*PTbWI3dPGU&#HF5YZ3H>tUZh-#+l? z<`HPm#J=nNcNhC!R`ceip#KU-xJK|@-G)G}<)!&hL4;pXstH`&+nbB-N@^Ljt;DO! zRVP*1y|W)7m#LBQr3m7zSV(Vrum{fs-)1q8@yovMDzcpLax&jA2g{{QtU~Rpc)VUy z%ki)4)S;o1DQ<1Pleg&aG6X-2gyqtpgj=V`A9hH9ra-#{lBIqiLdM6#r1d;BCTrLn8o;E$(B^S@Z*WlgUTrh99l=Wg>_Z@<@mkB+&@iJ+_ugMX zLXaGHU=KmuD^Z{}-@`SN4$@)3fkI5NlHPELfYSlgE|8D6IbB%ZClKqYVPI3LOR+b6 zi|kAlGeXlqs)_h_(x5x$zh$QqW}?tnrjw01URYU z-mpSwq2T>?aZJ~Fb8;t~^0oSZ%ebO826AeyfKU5ApX=Yzg*!H9|LURX~Lx>IGT zrHx4kSrq-hCsERldC|lLSs`Zq^zZOwYglB5?Vjd2j0EPfIV2khy`gb!FIzrgHapG_ zym|9pt%f|+(q-R5{v%z@(*QWe`%iVtbMhFPHT0fpL$sB{lN`F6kWFGxa$G|Z0q7mU zZ4Mcisjcxx6rms#0#Q83al$){{@2qQp8}Qv7&c&{g%mV6O#xRJ9#*|C&j0(|qY*>x z)9yHzAV!lI%MD0NArga_e?Cs0P!~x~5?nJ;N@9q>cxeb!ZOht$6ji9CVI1%_SV@}| zORm3d(mij?hUDeJ0bH{~5ZVsD6asDz5EDTr2D~e<6hW&3+{+mLwlrB&t zS0%zMBsf^1XcU-oL=3JL?LnL#3lp1HKnIJY~Rw1UC|N z))c6{P-GmTC>oVcQ_%Zg5OI2c&O9mPwkknVOHsST8}AZ4p$c#v)kr8xuS zMi6oWKLDQ{?0r^*eNyr$wIXR@EuR;`cnI}n@Ye$;!T8iv>w;Yx9kE5M9v|2yP7~^T zejZIb?Vnu`EWe3;exXpF8wNV9YhyC1sx>=Q!X#)iIculFC~rXQE}RbIK8#^7)FF0H3X39jNjE?bOiL{?~d} z_v^SNd_HGji;*HWn7hCt03QWJ0|+?k2Giwvkmn9F;PmjVxxu8Ys#@D1lc@wB%XtGx zVI)7Ej}K|<1#Lg@&KxB0L<6n`9r@bxKxRCG5x+m0dWTq0q20o5%XMZRBJ_)Z$A@ri zh%rW@dN#!zNYOF(5M=JfXxvitxVS zw?AyH%gY0K05Xuo>|3aOsdX=vD}K?lKDBh?c6oyanHgUESt8ZzK!N;yj_mocS(>j3R#YEe(pRL-8PL)3GZA6RY`LTy+__=B3=mqce?^@qU%tVz9?wy%SoSBNvv z{Yv)B7nGE66k3z3XdUe&hA9+1-4*HeqzT2U&B$gK2Po1UX2xs2eo|a_*jVCjo{9{q zKhx-^FD<=eIdhiW>=c_m_5SC9HAm8uKr6XHXNpdX{r!}*KHlu<)!MPm%aM)81~`tJ ztaor)MOVHB;NYmdz-(<=cITWdH7JR$P{dvH`joX+9$gu&`!{zQ<2UcwgU8~gl1~`o z$RGH-_w{K8IjlbwHMc&|p-|jRG^;ZrB+-laM}w{x`wmExdkomXGuDO6%&{VT)Z5oCO5j z&$bm!Y6K)EkPyu5v4ahX7n#|9kTTrXhKNF-0%$CsCY%MSmIQ|EKi}0>apb|4K+uJ0 z|LfLffvU+V9u1pu`-C1Wa6y&n>O@j?!y^rDbV`rowAOV`b8i4G({dSl)FL6r9EsgU z=nZL`e$H1>7RCc79GT_;mD4{BQf@)D-PA_<(UTueaF42QP2zt z{e%hr$Y?2jN_+bY??jAxr5{gP{pdrCuC<@;xheOL2=c$zS9B)zm4>8z%5l&!KHWzv zb2N0>T3yWqU~%t{f4BXvk*Z@K&P)7aFI|au>c+|LLXCR@GbxX9k0~;({WHXqD);F* z%`L5L=7Wu#R~EFiYmae&cX?7hML}LAQ8sAeX&QUpOEGL0AAiU{EcGEdZ2u2M;ntki ztSi&C4`@B&K_6ByJr<-JyHn0Rub3;`;zPCu^QB#A33dg0>ItU4w;p#At>ofF-i1jr zp7vSd{I<5YoBQ3Hf<(=0wL=>;5(fTT7yp1sasbmX#ou>gqB)N%#U5sZ>MK-FuYcQyd${^r6! zkKq6xPysk=a7UiC+Xxuu@d)tKVlxG(=O9{Y^4cj__akAP(D{ftdhljw&7qcDwn@)l zZ^jEJ{bjw*ts6KG4_ux;e0!Zy9Kem8UcN2p*mK^jS^6a_=kaYUrZ>j>a~JI^A_YD) zz6(n|9L!}-*-{UJW}}^F2@_qKZhrzrNP;RPi)M}*J#CJ-`>p7?v!jLcrxyPm$BmEE z6Zbvsr*|eB&O5gDQH+1I5gHa|#;c*Sv;A_;VBYY95T_a0qQv8B7S?u=^q!r55;at| zDGou-hV_B6*XhqT`_wq)lcz3UhyI>Vi=w)iZQLRi{NWKHDbk7Bh4!~;jIO)eh=;4O z+sHa5e4VJ{C-+nc)R|=}(f7YmGkdq{;EG#YPqAR&`>H2%@}spD)f5M6P7fNHpYb)x zXZYHZwwV*`ey-FNy_<=;|7Jxl=O5@3f5qrK3Tyb;CjN?YaQ~9#U+~j)iKmoWCZ*O@ zU2sR%fCYT!<#FIkDcr((olw{qgl!2+spu=yv+pciWrxG?4hS3oSOD%pUl|q?{hr=! zmTNVI`OozN-KAJ(}u7mqPcsITgLvvp|(G#5nZ*_PM_VwqFSG`)#Aky7$9z?a2 zg!lC*T~(dDhObcx3vEUm$}7q{@i=x2Qw-M8*P?H+e_mDpQ1B<8MYZ~3#6LAjKXZqs*P&KYzZMuntzKw|JyZ=>L!J1Jn($WX`H3Zam$KRrQnRTOPsy zJHoC6i9ThGjeRg#Lw+!li~&45j1|!7H9tEmjL!HZI?$x-3tK91S>$T$ zn3zat2tQ8Ra=X^I2PL<^8P&n%U{aPVtH==Z6P85e{@tD0@`wfK6S7X5`}^@B+F}-R zg};N91qnc{t3$>)FKd6ux=Z+M1p_`J$5Z%?ql2W`ffE+)R}14G;C=!z#KdQpMyO&> zxfoBeb#v?P=(vFt=!{#cm3^?Xv4QcNhldAI^uYv%e7q+`-_yOrU|od~STH4f%DTPH z8yFOraY1IA;0y|kaGA#^NY~k7yeV9Bq!q5XI8_L6UAGwkjM-UPn?d;qvnC8(xCu&4 zsuX_FypNu>+JPb+QMs9xF`icRBuGI-u0wLq z@de0kVCl|$o9aUI^g z4_B-1b3Rv??6zq9bxfJ@t$(A3zl}ntLAd?1P>X)~(xu3B}$&*Ff9mPG?!+3mc<{+(J@w6(poGBtE*N1eHle5aBpim`?E_rjXbko9``UPg_cIkG z21g}CbsMS3(zqGY}K@+qtTJq`M8Kb%|7X$A)sUEHu1X`>gt#f`r{3uf0Fy_upF zIQ(tPzT5u0n@W=CqHMZ!ao`D$9zmJI7m<6h*L{T@$P*p!uq3B3zs0;nUqo*`T|D!c zRdbJR2qC@R9Y`>J$hFELSR~;aNM(SfFe|8kgK<)vCSw~n>)Cw@D8Hj|OE=bPF1nrY z_lW@wwnnwjmfRbIzJZO&^-7Z&p2+y_PzOFGtaY8hc$xT|vKJ%#pW-n5ZYSKAjg43I z$7jEfI;f@L5o0Tv+x7fFdHzSNU^i!bh=wb{X_Io<_zH*U7F+y&cDGTQn?tuzUP_)5 zVR?K(0g`(~M;zo(_u9OI0ahi1Xl7C`W_(_>1dq#KOGnWD=kY_{V^Gxqb@vf%3!1EGP=HPgPjkY4WVQ>Zd;UNxzA(!9po9)GTMTcJ4B+#CB?WKM$^0tlszDfl%EP2YviN759? zCCX*L$R5rbwp657ADf<9IE2Te=M_`p@^ zZ>ILYCc*DgEtjj&_Rf9T+Y%i&?9Q8*iJ@Cs=mC98WIR<_5a*#U#8wD;?SjPX<>=Bw*G}(dL8mYYj0>}MhD%1Ov zFJx<{V-phtycLjl+icMJ1em8=L zm9d|aJs2kv$L}Ufo{rABZ_$*Xl6v2{NwK2;e_DWz6F>iA0mez%@Z$JRSylla-{qU% zvZw~7!^*_t4Zhg&fV;JNAYIyrY0x1~oTZJM+@v(3)hy9Mny~wkJA;=0KHh7~nPzmC zAK4bJf2U^OlIO@WlAz>y&v*xaQL_u}XvEnM9gvXX`o28aa`f7b-!F{nVNBRq2vt%^ zT*Au|H;EdmCgLi{sSjtzbrng@)-1nT-{{zj5?*lySXHv9Q ztIty8NY9f|guJN&ny}JF4x5Yal+sDmisE;*>A5OUwb0Tfl>J+pS~PZ`*r;Jj-pb$5 zmPFgXff0o}80#MV&#+4d3l(JvN&&!_y_I_&FXiu1!YFMM7hMMmKp0d`+;r;p+;wN< zRvdWYz#3R77hD&R_8>t?h=8>VLFB<0iL{$0y_?pD3^70l;0%&{NZ{gY%~k_n8whw? zK5&8PTHtb_i*Vs@i+{o+DR1AX`*1dQ=slP_13?FLRsi|~Wi5J|#E@hGgf<+Z;IWw4 ze|X!FHX$Wt^x713BFw?m0t{$Uw#8^60_gya2g5z!)6grQ?aeb~t&aX&rV+Z4FD#8+z$yZ{;@QwB81!=nUA+6M9h zsq8?iwR(gzy3u(85*MZ?fr)#ffU$5>y?g<36QS9FCfDqpfhm78?oJo zxBr&RA3#1RwSf^BM5~}}16>$0h&k2uKm?C7{P=qyLST$$f-E=0EehJto^E!inSx0M z#xls-6+<^CQXT@$AWU0;zR4vn@Np**T71h4diX93lP@e&>9fd=>CQ~Uy z=#V2C9nhIw+q~qQ%t?*?k%oDHrti?{{reoD{6l@T-zu8OPMJTvuMsBm_!;{MSHli2 zlGY3%>Y_j@fN1Zyp${~}@CE%(+IVulBqYxkFDli6_)*pq*N(A98{$!;y$X=1_SoD4O=G8*u`Q2pCOJ{gM zp8UP#38VO5u+cy=Ofgi8WDouY2`1c@u#X%gD#|%-y#MumhQoab4{R8uA<`JBZiAb$ zJhu~uURcF8Cn1@I{t+@|7gS9{(TMHdB4P#BJ?T`3C+&Hi=h4>j(beV5-dqqf9JS!# zGlm*B2z-G%3Ltu*#zD@Bd~pFZq4we=tSKvNfgu>Asqj6pia7vHZ-S1yu`y=5Egay; zQUJ-7R^rfFM?{~A74U>p5R)6iOpt#7&yv-IX2}m(IXUnsbisB4e+NYMDIm}T1xBC^ z3*j7wxXB(^3*u!ynx?qNfE)w}d4Ql{DJg-pFSvl*JUoAaDWXG(jv{Ek5%sijU%K%p za>dNC${_a|HaMiL2%aqPXef9KUPHLy&4j1ByMs*xRjF(+PnG6BkXV#Q2w<2$xt(>} z2W}>~Uy%Ymcum-oV3CDyGN8Axm1M{NB&tiC=T7Li1|9_LU~n^op9>ISSWn@>ha@q= zT>yNCEg4)jcy3D4gHh{j?6-p_17+I2K6di1BUPJs(P^Q;Q4RKG{I%RR?;Wo_Wjx!J z8NtMrPsyFjp@OS?Pi~>7P-fe6KcgByT9Gl8$DfPeF83aK`I}Lx8J+MxzL|mlN0$lv zPX%IFw~DU0UvNlCjvqO{zs`!Gvn*#8GvAb(nv07q_GPEA&sd1=r%b-)-6@E541@DY?4) zKB7jms)L0*>qJqtTadtQ|8I6NMuJlJ_4eJT>k7Hnn#9SZEBG>DRZs7*$LFE)ZQHcA z-+r>c*2N;Lv`U1XA%Mg8kmxb?l%8+EpOqcsR3Fx99Guvas_gDMnniw(3gI51ooCsB zRLOJixpy2@-gL80$DEat>b^@7EW_6SX@N$BSz9Q>lIcQGVK-ltpe$y@W{>iP2}47i z->>iBw&6#*Yd1w!t8VIX%NXsGq7fY2HZOmvUp>_D(D(1*t#A4ht=qrOL~%~YNa?T! zwsYOc#AsS}T94eNGTD&+$704OC>0JqUG}Tp=}Nh?XA~Pw{;+0uE)c}ah_5;HU@v-~ zkyu#VdLdx*ascmxGUT>hP$@L0X7)V1tt zi;a-GUdYSM{X2#Wa0BZ;F|-dqsIS&MF;82?A8_j`sqwk#+PRS}pL23mNoGdCsnX}X zTH%%URDb+mmD3xtBlk|f_H>qK`P6{Db-e`Wmm>xcOp zE~OGa7y;ef9bZwjBSMVa9(upUP?qHNc>A(+aB~NSKTH0JW}A1miLbRMX*}H^_1VDP zDoKXnGbRV0mDDi9g2`vKBJ3N9Ee7FR^*iYN5(>Fk3)IES2ig>Z8m2b15X#?NX=#4I zpsdV8kc&~c(4XmVQS-j?=PD2P0>_Pb(Xro!&$ic?)JPv^wf}ll`YWD-Jo|(0rXpiZ zj%DSJoEupmwYQ#)ssF2jA29z=`rJaF)hp3RSE2`+u;K$=-yX~vVBVzT4=vkvm)AYD zs^TL-QOi{U^x)NK!J@Jwb;aZch`jb|K3YwpuhC}us^9&sRX_|EkCgZG&EJRHe@O}_ zGeB(16wA$hed4V{z;M=-bxB1jfp*B3#R47p9NEHe&#DE z|IIjfai)Fa`ml{#J=b=)p10vOu>`qCzf9Q2LS8^kLZn>e{gV5AkKz*K*mwk_crE5@ zt;~lXw+`GGwu>|$&(OTPUrU@6B2hPi=Dmh_S5qOl>$=|p##tvz!SjUA2ghbo z!3|||%X_JdMhfbD*WX?`f6C=0`K0(MEUvA+^eI{U$X-V0#GvN)_u2*@m+dYK7eA+& z`zbqMm-wA?Se@N{K$FD0s3(Yy4T05u)-vz>qT+Mr)-?H-9G3(@t?J|qBLJY$|Zz6tU>#F?0 z_pj=t9uf%u6wQ8L&Tq);NtSv1~_kIA_DU1m00s^x2I-|l3GLKsT&Fd35B0~^81TE9K zfSzOcg|$4SAg|k9@S=oSmojE5hdj(qD1T(*@OBp z&j5REWnu>nVbRfd5GZhNE}f|b$RPE`Q&mK$_?eUoF0$Kp^EDC`9+*Jjzqj2}K(G!Y zFHG#(4Q}x;68&G?F%q~8(nX*vkWCeA7YJ^+ZYm@Vfi}nx2=fZO(}vUGqFvxE;^4)R z7&#<{4~!+tPIaJlfUl49#la~2p}^Ar78#iuw!!o4wqc?BAf*p!&xMpaP2B4I(KQ4b zMN;x0ybd;*Vynbg1zA1ag7C_w$<7~zPBVn&EOgIE0GGeIXuRTTJhW&O&m{PBTNyhW zf+7plGA1{6CoGEo3nV5vR$(Omuh8*-JohP}Wr>I&Q_tN!NnOYJL(pAjJD{?Af=4Ym zH8nIKP04fpH(!3;v@&_HeI3 zicSUntniA;Psi8bNXpS%K+;gbJO(z-!rmna@T=F6kL`!K6{dTUv{ckJ&|3N?EG;fV zRAs_KH-?LxtZcs}Cz8NZX$2!B_-P$@$>A%Db&sL45_VMB?UbZQK7YibiIIAQyxjOA zNN(HOKAKpbs|fP!dR{ee4ckUMJSs=Q{m;YoE>LrI>_@FM+9`VoIy&a2euxrBD%>Rj=b^M` zc=o1#k7V+jJA6j=GksL7VTIJMbT$snP^?=BGX(FS?Hp(E$HZKYihrlUcr1Dx-0YBo z73@l&e0%Y4m37_4%-I$0N~mvWI&VlOz2ulMiQ(2YdpoHacBPy%VTWV#(cUDO(=`gQ z&cqty{{B4cP9+^=94)@IccSFO9!gz(xm3)Y*!h{kU-*g%D|wBz$P?%Dhl6|X&~rlt zZ?K2AT=Q+z3Q%1NLoH#ZS0woGmkEttG>3+D*?(|?`9)jkUtittLU9-WINoJfv(Axn z7Os$eFwBl>d;hK7!>}-{|LQ%{!<$34uP9Cjhhxp>ZFPAK49)iC+AT1QJVFO}jJgFM zQJM(OuLKQPe&w7l{MgNkZnkVAJrMln7kAn!vraM2!WaYz(-Mn)r|Uu9tl3FIE#GX_HTUA_lmM5_VKY(=Yqu*QP0OvA83Th zVMgr=+!Aei_0L&w;1(Wy;N-uv!ux*xk=qmAwfOIf~XXSmIM z<62aM%5^e6lok5dC1?@HItos{{^N>#WgDq@Lms_&<1J{5_wRoFd6Sv^v>|i}Yf(m) z{OK=+Edz_HN-I!+&=-V7R%V&l(LpwI+Tz)gjW%;NeRRB_dr3>FdEP)7{Ae{; zgtbxnK5EO?{euPV;Xdt_)lY=0k5C0DaO$Ht^P`{)IA>Z%&RIgxuA^-NT z=LgUqLOdF?uX$pOG06ClDsfLw-AMeL!yI9X)m^KwQPDUP-B9$xwU6B@e@QektVVCN zln4YY9~6f@^ul4mW(>fwcZvvpf=cP_A0+=750?s6=0l?y1_et*{EwPqQ5*e_^TD!D zsh5KvuRJ0=CXaQ>5GznJG&K!%YY?s*elX8%L_i<$L&V8NvWQfu8qf1JS{OOKzj)D$ zmgx6h#xEG~(Q@6w8on-JT0ZRXYlY`c&{8aS)q5sAq4Fk)_&a4KqG&=3^O^i|ytI}) zq}6w8HTs&4e_UVbz?gCh8gWUQpQIg{KDf=t;uPnTB{urbHj}c4l!mO2@p;|gu+{Sl z`o6v88bw#-`Orrg0iqE`Y-ww9@rDO2C*lRIFuK(4!V?EXc>X>FzJh=K@1`LVd@~C% za{Q zzSQsCb#G1Zqu?U!zzDG#T*25o?t4Y--Flx(!}A_vT8cw}!wbrad%;a!TduseN^6uu z)pvOKlj6Jo3}Tqv2`9czNzL!KfZqJ&i{#iJmz_sC=iPf66`aEouH}^>#nO25Q}hw_ zHv(hYLoAEuoyodX8MGzX+D}B2NTn%8d(X7VY{D%04X%70c_oO+$vAlyQJtNX9`Td< z75h5YJ3N2?x1kk{F|1jTmd^Xl=rcNVlba)(BDgutMmEIsv-sV-&2GlyXzlo4mGI;S z^xZ6jS8~miR)`*q(^&_L6qHoApoo~ClD;U|`ex)-! zc0cv3*X2x36tlkJGDXqA{4zV@E1Mak{s+sq%_k0Sq?gslln+Yf{cjI0wNDAC^(r|h z)J8NEColhSOu^e;$<*zT)#VZVe>8n}AeQa>x4p9W-aC7RY_d0rP@R`J9z68nzand)nb<(U0nvq3@#x`HIS_=Sp)0) zI4rB4(zN9w;^MbTjoa#7p_UKWzvHIL5Omam_XDe|jy~xe-{r;$PlKo%%qdw=5}%qyr?euU}V=TJMH%+f(q#Ef#Mw6hXT zv9vBOF0LDeK@;NH(C_Axi_F+^uzO;e2D)wflrrW|Lu+0mJ3wX-yapy0Qq}ZKOdF?& zr3Wbe210<%us>^SYdezJIMBmamu4|^=oOgqfzv`fs;t=pAxYtr4?Hpm#5Dbo?f|?! z=>^L2^tm}}0uaqVicd?`NY(g!#M1m6MT675GN@XzHpZoh$tn~jCr z2L3@{W(`1(=VYO9R4!J_7}MfRf-CV5s}8O=WJut`0A!|prRq{W3#b{VZgOMou=3RG z(e;Y<)z!C*SuQgZORYOQ)o!(*dr51jJWY8JMcv*{=LhsO1e{SU@AP)$;~EQ(x@4l6 z+{j7pQ69%0GktgdZbvPH00THTFfjfX-~Rbz5Fu+3W8%j9kHDzYeyRb=446uoqX&Ez zj2;OgR?4zH?|&dimdSyWo(WLt8>sCtbax`Z_alV&p}G~?j7?2V=a&bvX!-nMJ_+1^ zgiiyt9nNYm?rKMV85y$&{2E+N0770Tv(U^BT6M;FuJ1C9bPl0l<31^ZM4uwI0wBkc z8FvT)3UG2BjN!}I@1NiuZOuIZavpRyVPW9{v(MlnfTaYy8r*7Rzzr<;2BZ?;6U>T3 zW&(qm)DCR2z-a~^+zCp7-viI;TeBkYntINO>%`mxfR2!^bXU9gFSRb)gN}*dvWQ4Y zm4x)vZP5g`Ip3c2~_}{gv{3n#pNAAWvNz zhTj}{p~&4>i*JcLo;DD_xc5OI=#M^^Nai1HZ*i7a9;Jdz4Z5evUkswGoBs~l1TCy; z6Y_j8rMlLHQ}|@9T#Kf6ZYC5Rn{ECw^gV8POHxJZ1O^5lHl!n z&qJQF zb8rSv*Qpn@jR$uQ#TZLu*@GHVTIvMf8m!=-THt78rdQZ7X6P=^=hm-89>)tV?<_Xl z!#T%MNWt?d*{{uAS$IaO=XdIx7^TvJF>st4w=J895nLtAPS(OlxJ1hLF*>p+Qjdy= zi0PUlp(5!wG|EH?%8C?bDREr~`;g&>@7OtOv}Y*q^(wL(`TQ05V3?9r$oj!AddUWJ za<4j@J=cEtfWy13t7g=6!MZXYb)keE#t)gzv+l6}SeR40+lgUC2h-w!&8#yzs%lwH-XA(HCxlDdhG zA3cg%s$Kk)Le5AFcz#AXD&i<|=HRtT`2~-2h6l`zZWZCTw3Q8%ib^Ma{_Zuq{kndP zdCpUM03Km)xcwYbA-Z5K{tZOny+N3jq;HOiH*F9<5v(DQEy~WaeLYi;RiTzai%CJ6 z;^ek3Mk&oM`KO&F0f%P&gJTWUo2Ak(Cp;+YT@!F-?pGe|_dgD6adqn0E6x3p99NP- zaR0VizF%m7>L;~?l4}cUm+i6(Q?EaN84Bh&f7Bzm&9UDgr>1tx`)IeHy;ib^z0?KI z?BG$6Uhk2*hK7b1BxbT zIBsOLQxa-$-D=at#Ewof_vE0-A^0d)==6uE?TYsPVA%h80V0zcUSTjO zInA6eej|>Q z_Sm7)-y~b>@SxjLw1UsEuD=+xzPsfy9V@LlS4C=Y5Av4;RJR+;lKE*qNd4KeCEyg* z8JB%U9^LulDVd8W5QyNmx8>vyp}uZVI6TxZqdBG{Vzp|swWTDT6Z=c%ZMz?)n^CmU z;2!K11q}PnF;iOA4@w6T(5`b^Wss5?8^0R|S_rf&nZeN(ZcJkXW|#+2xMXli@i0lG zu(Y={FQgZLl+Tuo8^eP+8cis@CEI$$?W310&^e8zMqAnj*4$Rl(UxKVZ6p?-T9X-! z4&eZN#slQYV_GzYgxz-%FJb=yM=k5=GxVM71~C$47dhG49liHbB1C3OB?c=toS6r~ z28vH@_naks$YE`NAXT4Sln5igxcOqH`42Euck#Jjqfj+%Jv@}boIbvDwSIpGrqt{r z+BJlFS;L3^ZNc;)k&H310pbs+nBR^2Rm&>N4rkXqJtfO5jH$~6`n?NVyp(WUe~Bij zuO1e9Q7mDl{HbV&{}~d^b9g^RX(un zBrVo%D)WCQ4Os|4Zcg$q74?M4GPQkm!fvU$8nd8nWVrr13b?RD)nImxER)fZ2j=Kw zG)RA7ka(r4-2Jet^!$2*``nQiJpfG5=C{re67XJSHz@gV91zFO0b;Q|lE~}cZF=BZ z;nD30h_b*DgF#^h1}e$`90LHp10yaF>T$C9(hIahP+*Xu%E)YAF!HT!KqZ@d(@6=I zXcHu1!08MIDM?95W^iDRopM-yM6!#=$LVmz5u3E7B_=Wj2##|0%Ts8gL55eHzq#7a z`wu?}SRyr&(DEY!21bOt1ZNcT1Hg3Wt7`IXUX}p9!PS`gc^yV=@_{G|^ecElC8ebo z^)7$wLFaa+{U(@u0BZov=Vh+{B;2MCEJAn%F{13_JQ^} zpxDq=>0V($6UcKcIT(@$*oauEs<~OO+VnRZyPZg>&PDx!a;k( z`wQGl8#79{Ou!T%81?t>B3-0T6V5D?zzs^Yf!BODK4M?cVh#u>z26oKm?kKcl zfq$##n&8(KILG~;mHoN!zJOBA?%su=#UkLhn3$jhN95C|)qK(5Z5|m(bPzYf4_3l~ z{3Cq20C0yB!{3kqq>Ky_PvT7x`(}#zeEie<<$dtJ=5XRnF!zcTuSep2bNTLzg7n12 zE`jCXgRhglh$)ZSZMm`Yol<{84r%=u@`Elc_MaF8Gkxm6ne$_gSB#$W1w3m_&kJFj z5>?4QbK*RT5Z6N2_uS3*{~)bcds_3xP-JZ(Ui%KtWTae!}CYQ|e#eKHoMr#I3;-y* z4TB9=VyN8VcdNcow@SwdrQ|Ep*U7WX^bZfO(;OC3`^awUiF^x|W5>P5Y2v*@(ip@? zp)5zkGdXbG`K)Qbx=Lv@sg>nx57zRDT)B;+_{Xj^o%?%QqV zkOa9{i0>9#lz#q!QSqFm%z*Q5p~fsDy0@GcPBE|8xjaU){4qbDL7_~i&?N7B-YeF7 zRN-6ULUGS*1YZqizZ`uw@&J8n-0xjbtZXrTsNXu%X#dl=hpftKn<0W8-lIlb^P;w= z#(_Je;u-mF+NttS2!1u^3Wo^qTo`mDzioOa)JAQ4R%U%B8NqM#T#oR7xchwiAJff5Uu_9y0*<{26ue`FNEGO?++x-*J@v07RTOQ0o8<% zaM$xo&UUsSo~UNp%j?tf;YKOHCWvN437ZvY2N;_3*#`5>z|v%Ar;^o0P_Ac+zSKE) zV_3TlD_9q2`|E1ITFwVqo=>_s1sdEkgV(%f+^CzzC;#Qj{M7rirPL-jJE_OdLR?>% zW}BPr)6_vKCxQAUeeJ4FJmHtewa^O<8io#{orsyOp;QIFLZ3aa{*Fg9)dxE8R37ZQd^N*=TmV!w4$UbM$vHPZs zT5E&OUlxA(A;G9^rEH8%71o`r?8Pg#w526mn9EsW781y~3!QD-hcoWo3e+VqWE04q zSeU~a8#@BzhNUGGgRH+e)ljK6&EUJOcO7D{zzx8oIaHb~g2*VXvz~tnwx;R+*%kRK zUr>YUuE1DCAZC8=Udi3}i)V;}3NF6@Vpl?XnBmk=PSO5Kdgv%154!1K3WA9WDlKuL z^dKbUAqNZ2Aiu_3fk=>yT^rureGhvu3HsWf$Dd7U^mKGs!t*CLoX7%r2lCE-u0RBP z;qyvv;k`;^GAv@_@)e?}(ENzoWf<0aeEi8l9}OvcY}%@YWIfPTzPHy*_?$G?4;rwr zxPyOzI}-w`kVybIA#OebiC!QGGcVr4%K>i&K~5?G3k9449m>od*cB}~k%$LyThj9X za}hEZ{|0X;xahXyE{Ek8Ap}f2|72r=-<7c1ThT#h9TK_l2vVJ`+A14u~l zBU0V-34xyiWQaFJnyF#;^no!R;t%hE`U;U_*f+z8k%CANRAFyc;7ls85ZF82sC@GH zaT_=XA(DZV*+HJ=e-6^q6A%vp5y18j4bZ@tfcOkmJxH@27%ahZIl!H)Su9qVO&kiT zS@;R0OyJr>9#%lq{&IqR(hC`AdzYU;&iK!QFC%ysHH$-+B;o(S%Yg|px$h745D8jw zCE8b>mRP^0y1F7%XE+FWjRD6u3MQzQeoD1#JO&HzX4KzkNar{}i8ugiMPIm3Kk8+z z%5F#Cg6R?MX63!c-kzQp5_#(l0&sDMn18}Tf%kyK>=B!|3HMOUiZ4)y_h42c#6N&X zg{hc*NVXUX5i2Y{D^*T{?g{1INXQ1%P_W^qHSKfU^WV9J`~?J0z3UU0Y=)Qu;r0O$ z<^VmVNJ~b;EG$|1W9%!WjT@;8MATw{Fpn(LfWf-w`-ejA>SVAMa@~K6Qd z^GQ~7528Y+HJ{rfxC(@g|J8USgqD<4s|P*k)DasEVEWrb0A05SJuq8{De~&{{?)_( z=Hd>x2a?Slo$RJH_k(c~>ED2~_IYj4;b6R>GgduVcHz)FO*4QpLm(^s93tYCfd}sZ zZ6iI91La3><3~3R>YT>spvMyIjgDR4kecG|qkzDpr$K2q=KPb8V)Q~#d*S54toUCi zBfJ~<29Pil82ez9Z=lv>>whN#22U_Y!Uxwh72Kx)YT3F@KQuIy(KMd6&d9$~=YfW$ zuiI_cfQE(Ff=)Uca0%bJACU52N#xVOm8VD=9jttr1v()lKzjo-_w{i4p?$ln*SF@GqF5)z&bl z7yTn#J`c+@Z~-44);kn__1!CxC^d)9p>b!6FWx$XJ)GYHe0?*(lz>Rh8JV2XVdhba zOkbaFtL{Aqo_|ABx&C5Xjo0frU$4uZS{1pLcs z=;1$uwy}fYBX*LpabR>Juhn!mE8i}@oSu#*fBdGI=!DkQKQb@~zd4wC@zUe+`B&mM zU+E=-^@BR*Z;oCu*CzJ}kQ58QRPL}ia{u}KPnXPIbQ`^PUzNYiz1)$oD7@c%46UVG zxvUK#HR8?Dqt1y1Zj4zKEIVseXGAI3uO(;a6r>~R(Q+t)WcpcLi<@T&rSN?$KE26E zj{ai6l&dXj$LMz;FV8Q_dilWT{Egb%b{`9}(P8S%YL zo3c-`pV6n6H^Y6X>x3}gV&^&Ze!mo@ha1y3VD8J@%=1@3*t=Z1$_ zdr1n+e1FXIsSSiW}j2nBa80+XrK9gWzn>m=& zos0-IqZ-A&AIQODQ6kIiB~KAA@>0RR!Q1pL#_CZWv$AC&(>+6zKg`8(f@~j^aQMut zRW)SfQ3~ERkg_N%wftuDVl*}9DaceE=>M&CfrKlP zE1RD2$s>I$`8=*5{d|kkp=&x9z1vokR3XAbchoIVD=04f7FvDv(U>Egymi8TnP5wnu+0W1x_f;lnr)yG+yM zfP#jJ$*i>(Z4BD?>vaAG-O!%g4k}4k_}uc`9W zc0F}}gZW+jErjH6w)OT(30Qvp_9r?`D#$wG=NPbq&vVBYihR`z5+7VW%7Y1K^-r(; zK6*$`L7N;)XMElDF2Re*4}~v?Bkfqjs*H|J(C(NXD_OBr-THKsgg4=0sR93E;qX&M zl-Fdz?zlzvifyf4d=}S*tOeQG?T90%@4S7)9!^#}X5h$Q((1^>p=?un>Hf(`KDFv~ zw2fiM`Lv1McWIPR?3f}}4DP!)eAY`pbXRYDt4v$P&&lq5MrcmO?9X zwXYWMx`_bw0-dkHg(V(Ioe)WluT}^@W^CmyZK}0IR)EN>Q8jkNj@1QZ1dN$~=G^>} zV2uyvfK2-r+ndqaElb8?{YGY(_5A_Dq;>Sc{DXMN)EdAPw39z+P#=Xby%0Bf1nxx9 zi&wF+geZp0C;>d8dF={30E?!J3PHGh#=HGb?1buS@&5Lkpwl<#+E&dtP-)-ri@dC9 z*6krDc>0R21_uX?xXA<8KZWCHe`R1`AV@DiH)983X+{EeOnIZzWbP+9kU>RqDSqgV zdj+M&n&{2iNU3y)>x}=|%p3p|sAtwKHHMnTM_>;GA0KRO&L7H_g7XQ!4-5dGRrp48 z0}`jfSnk}SFEmHiJo{DN@4{9OS|qx|Z$qGkX4IVbVg?+NAhOWNQ|pR^dm(}6;bD-K zBBMplaNsmQ0=_Fcz3+)CtR9@|n=2g4>E4+#8VzJGI#AAronEi&XOQa@8=i9BFEw5S ziy;Kg2{_R~(}m`jYH-Z~=mkpX>u&FL*zUo~4~$%-qM>Y-s_^_n)!RS6jjfQIPtQ+pm_M@PhD&f?B{Pv??7X}v0INZw8L(MW>Y)6U zjC=FN;i!21n`FS65M}_abqRU%v&~wV{szbu9w5NzD0nd>ht-HHk_fzQ9Mm&{p+`tF=>3#w*3z!dpDN+#bT0=FDTo8zC zAR%T*n3$ScK}92Adw9SR`%;Lu%$cO&8e1=4+3UHyuwae<=yJDD5H48p$^uZ@>-b`@QthHg~C>cR<@IlTk^Q@QK6F1NWOUrKhimQqI;g}uCPz8E<6 zm&rOiMYS%3${2~jBTUzkN$UQ{FsAO zKg(!jKPa*c_sBgwuR9uEGCJ>KAV_`}BPC_N=EwP|V$1C6uM~s*{f5&%(FyP8MIO|S z-Tu1NmScL@qyEbUv&8c4BU0PB*5X#2uAi>Bf3zO8pT*K7$u#PO2MtUn+?%5x9Kv>R z){gG#l{DpAzQLGqD8K)w>gy3jdPYfYds4t$p7v=#*GS0lb^GHJ;ob|HY^67oX+ zdERY~lGR!a=UhO0qNX}S*y@J&^)2<6XR=gt*II0H zH?Yp8-O_S57SHa*n+$dySp2+4G)UCPv0ycmTHiuEre;O?&D*6&@SxZtD$D%Z;-Tk- zWb7;Z8Ip9J4^-B{J$81XLhE{6tIUND6s2ZP^(|7u&|3d+J~_{lKfj^ux51^?bk(@E z1061Uay7@1AU-5B#TJ)cQ^Iko%IG<5vrp%cUI_1R}$ufMNzQKm$Tol@E3$MFVjx_rF)Yi zPHi97mrWnM+_#rJ^h0l{ zw?4}YWOk6R67k!bZzU-j01&PPcPMMA{0pbys7C1t*3DB&Juo5g>c5Jeal3R5Pqzc>A>O5 zFQ@JnJ*8iHIPI;m&*FAeUQXGin%(TPaSz=a&?s3qb7tJ^mB{)eW0mOdOylmB@Y5&S zqNF$Zt?*2lkeT3!>kY|GG0F9M$(r@#P2RwX2o=%=T*og%e}h+8{n2nT+{r9*s@fV; zN1V#!hMM#CNW9Zjdbw`eBx!4rYH0AK3Fv zX#T3)Xry=;>J_|&XJ@1^8d?z?8-DKx)9ouym&8Id|C!ehFgMeW8DFm`O)4M1IWVaG zoVcqm z+o$pAzU}-8ifNrs*r^7YIu~`$7kJz^jPFy>*^V~};_JONWSL&-je5oBm~=^F`$XS8 zl_9t*bXgYT+q*@hziMS#nj$79VV1HZK@ZQfgv`^upL3u`*LfcgrJ>etbWitlU~pc) z3Of8%q>;Gvb??%b@AHF+d*hZ5w`Lt-WHVhPb-c)Q)QGx-Lrp?|mt$d=oAm1I%I!e3 zjDFATVS^DJ>;dcWJM@no)NNSQLoxC>{oeh%`{l4VAi8sfc!7~I!)$z@6 zLYb{)`rIh1LYl>i5>#)g-I&o9K*@c-2WCiM0%3~>CS`cdGaW2+K;&&3LF1AG{>S=y zQ^+$11X$i!?KLjoEri+>QF%B7_?3*@+>&8OsQYY%`eiT>0Z?+TLZZnKg`h1rE;UB9 zF=JlHHGOy?U8`ug16%MCQgnWWL|Bo!ku|-bUcfs55Fw5YBq3;uk3YvGCk8g>*;L&G zsng%zqPFV&`}bg-16r)~{HC-t4B*29U##~R+Ib*a#L&%}=NpQ zz!gj0;D&z)j*251t`5w`9e2Rv;^c%N20a4->H8>(G8v>&p|57tcGVY5X-0gVPA#AV)Wn`EK*G|MLRqzDYt0^q!Lm1jaZe@V_w@rvWZ}6dLR#^E<0N~PsW3TgFXQoy1(0G?0OXXC)osa*xsbyLxGw9n$~>; z2hz3__m5p70bgK)3+A>U=K#f&D~p}c02jA`eM?e{V}w$fjJ&)z76P@6jRO$Wh1Ld( zuRaE~pBsT+L;~&*rGWGUP?BJy+Q{P27aq>M%}99264oAn@{JgO&e z57UIZJ&+-aVAA^y2EQ&3dPLU-3Kzs`!Jv~qTFIwC{Dm?DTw81q0Bj39tE=>64IiLJ zPv@y~`=~Ny$p64`FGvz95+i&lBt>923UKF0-rDHB32ta`-sS!qU~mU8N`A~h+!-zz zhGM>%>X%v2U#qIBTA)vEYHn^4|4|vC22Fofkr7*JH^-KI!7&1PhtieQt8Gp*xzTXYb&F3{;cC0ly}g z^Me%FBh{49;l6Mtm!qrpB?}fIb361Sz`ca^33Wrd=m+p@1i?Vb*u9J&#(912@6_w8 zH8rL&Mxr(fJ`yAu_0||~^7rnKQQ1oAmvEZ0#y%o{@WKhpb-U5CVX!Gb?UxZ%d!Q_C z=Z;wBGuHX}G`3RQs$4Jmono$rn*?r@RK+Y_tGKcrfhDQLiMOI1kAx{$RDF(&Sye4w zjOG%e_FzfSe<#ly&W{p(-|w%;!Ao0sT`4q9ruuaU;ka!=L&iOQ&1|_^_5JQ#CC#EJ zGzlFHq6T@6nnHB-oR_B925ZzciBdM!YstZR8o8K$ekGj$a7EJV$g<{1G#G!%Yu(Qy z&MJs1ne9=$dj69-I?!*}e9aw2%v(uF@7){rUbNBQ%+M;VqxKwt7-FQL!Ln9Cs3JZxFiY`!f#f z!-3(?#&mwFpNC5*$ma0Hzd16Ps+UX7jk7jOhYGdek%@{*C5nTdA@ERT!=4Id#I< zRqxFe1*vGaYdMn|e%PVnlLMRO;4KXIJvz+cDDdCaSkS4tKn zke4U((EaKi$vER_QyvPLfxXxOxqax(*94=(Y@}qHNiNg5jlp;-cI#TCAz`>UIBP7c zHly9IG01T}NcM3{(RDDo6(|%f71~2m1*?J2B%``b)Wm`$Tr!^L<=aBv2!FI?w9Wzms?fU>JB$kv*M!BphofU(2;LFpeR7y zczHrDRC5!Hp=0Uj%~X~ys>)*1&-$b|)Z9KQHFoC;(mz=oAt=&+1q^-m!-APncwEAZ zRrLl9rA9#lu%FMJrsWt{u+8Fh8qNdvKl?Ao?U_EXlV#p}$E zFeD|?tt!Z(D?c;a(Aay8sVIfwv(zo_N%l@JuPI3CNl9qk6z7yj-y7Jc_qK{qP%W}? z`kkx2c$3@PqRV#T-|$1#lGxWm2iva3q^~&J<8;#1+C_J=P&vQA^jdHf`jkA?F>=et zN=`td_@;s?yXn)4`C50%F5|A5nKei$o%_Ywe+ggt&w+<1~Epg52w&ZK|deg8b! z@XhUzY~!ihe=Lh{&)yh)3@$7%OF@4F;?V-8ENJm4=;{a}nByh<0dp&`7viuOqNq}I zLtvBOF>ZT2QcI1am+?q+wBXm4_ZM}Vj4-IOnBIcGLSCfx+g9Vh-Z#aaj9U0uFrYUV zT@}T(#NbZ?ni=#SE@3%7NpZNB$t-Ul``w?A1Vv>nD88|eZ*IAftC|aqcJ=j$0~*I| zn%kG@ml+4v#HMc+odTsEOuSPx2o@b>I^amB;hH=8Fauf7jbh&J+!f$};K&iH8Q7Mf zAOj5LNLMBdTd|yjaU1}!kXdx$*5Cfu!~zXJ&dkd&X#&(a1Z1if7AQVxhWfoKzGz?+ zp(q8q^x#ipGx@gw001TlA|5a-G1p&_0Q#MwTm-NlSl9NzHU`8UK#)mJ%&V=di{^6( zx-Laf-9y->uNQ|iKDlqqCXtd>ND=_E=Px%H7j$lm1YQ9=f?R9yi8$khvBEs;qdUht zwx<_zP;djZ6?m{9mZ73qs*}L`BoYN`Ug8XsW z<%r7_i?eOb6kqI;5Onu&<@qapoUwoMgly6aDsX}K1x6M+Sa?Q1=B^-Zh=3sAwMxC^ zPczSJ!{+n)nprel&$B;W^IUuqpr+%gx5MJ=jn(~J#%W_g<6cbQW#3OH+T86Nd)x>6 ztgBI3UCW&>7UI5UxopdhCyqG98j&rIX47PytA5q9q-RP$=MC<4{4`j_-s#g38oJ=V zxLv2>UvJ1Z79{K=|M@9tR^Bgmxsc-d7mp|U<#hD&3IdDX9kjIlCi^8L+sB~ zXQejkE|u2%BYc^lwi%60!>v4>JAO$)pY*8*$Bj~k2J4MjQ>aQM0*5fO`3bmIY-

    }@&bD_7)7*kOTq36_8M?^BjXsvYTSoR8B7!j#b;}#_r@Bazcd1$O*fRzw`a=&XJgut^M!J=1ji|VFNC-LteB5r* zZUlz+qsZCG#TWdC4|mp#8&*7ixQek`kM*#aqWC2w+Xi+-cGw@t4V=rT;{NOsU^Gn& z(r{9EsCY%yb5NIu?&nTMxs7fuQFw4L8L>!@H)Y{q>0BYvBPM!jYdhYT0o0j^;pV|= z3c;C|h!rqJM&lSOq_TOj3p1woz0#dC*aFikhr5FZU8Bw-XFOtFtaLnT8=v!4*ZU$U z7D(|qUf{5-=l)-dqj~|YqP`bZ*yta)O~bEEV;Nr*QK-E;dJ}0@sdU-NrlZgm=M^L?!JpXUA3gD(j*W9Rezc z6wc!(OIS5F8$j_Lb`vbkJi=J(4TS^p`0u}T8C~=dozHO%)w-VfbuH}L2R|bJ`F5M& z2RB-r%flUs%Qo~}9gCIECw9FS%pF-gu5`6|e@+n)l>32I2QJkU91M4n9G?3}oI+C< z*TjxzY3DAECL~TLrpJSprEz*g!u4cvBLe1dn>=?OpDwIlgeMgX?~{y?V_@VZZgSL$ z>$#TK7GLXOCT+jUV{n5zwQFp2n?IWa1OJiCJLRnhcF~W`JB&k6F1XADe57_drnHM3 z`1LZ&H)5|?^P#Sd8h_NxxXW69A5Za`H}(4NM4mlM*Kdmc8*W(6wDBjUa;0fJ0J_R{SWwFHs-W>@VA+*tPcG$s&b1PG z>^|8iy0~xH?ChGeTeuNTyB-(wSobq;z)uTLhWo8ValhX*vsI#OFTdBKPyEd=WN`AJ zQalG2izsTHzS`cBJBaTfKx0prsqYc0@g|nv{>U}zC3GRGT6p$HXa=WaK8auW>JwM< zrHJ2@q*;7#=6J+B^cX5vs1i#{Gxa{lkHlm#b$CP%ki9|Kb1qXV*+m#6$WYX+r7Sc{ z_TXOrg1afgC$^n;=}w=1oIk|7|*N@N1W`nT^`!xN!t$J5tI3AS^X?c?uF#seou`n)3CFd=+G^xw{5M(+1#6C zM6+54H;LY{uyTvuM;C$j;b-g5uZ)`2H?6gpiEOM3=^6!wbc|g-(k62bn7BSe2ap@T zu)owp==R8CM6%}2of(=>-0_?Rzs1E#j;Np7Lrie+kUzMc9j-tv$$EoAwwdoej*)~6un)3%tQ zuf_NAdk7rtq;QR$ov+k2bRH>cP-Ia^6qUv3-j%H9L=FCA>Bdkusp?kBRTBR{EkHs1 zzH4{w7^|WY*~M*+Z()^NqrV=H0OllU2W|+gE5s*)d>_dY@G%s@85{b1u#5BvTWfWzsY`zs4nc1d=nU z5r``l+r+>jlMJv$QMJ6l;DBHUgog7whvpms2qJ?891`du(o{r5Ne-JNB{;B&3|Bc{ z9li(_4?t-OlLN2Iay37E7o=M=q(ue2o-|`CDk*uWfP^^U*ka(gJfvfz!yB>zp;svZ zb|I+wiVYiIKCSwyZt^TUQ=FxdJ*{sJf=W`Kvl(SBJLwc&U1`$1idH5{d!6PW6t*q9 zCoYln%bS=koC)7x>AFzpk5~G1X+6)EMz00j4c}W^SqV=~VDlqez-h^@hiNvT1kOwH zneo9-Un1TvHq z6vmX`_~!XL;J-So>3d+}?ma3FgtChu$wtqZ}_7N*5sQ8T_UY91LiqC!b^nkK5-H zU0OUG2m!Ao_r?4U*p{%zM*;6@7nCUX7h>G7fEvtPMw$i7H0rMG!Tv>JUAwr5z-#Bo`4 zgU=uW0~{q40>H{j+V-8NGg;)aDU95y!b4f=ItQ(aKUbogU`cBN(ApzT;!G<4iH4Te z@2`3?)*xdVouB;P@6j4zP7Jx-hb<$ogmL!wc|N_neW6GYi_#7qrzXTGtz3YyYvt&V zsj1H}k%s7VY_W@-XknvnvS=q5J zFQ8qdHO^|qODVE9qJh9?NDUr&1e*Z5Nu6$NwQseu9|IqeG26-G2Iv-b3MdoAqf+W3 z7aVQY*7l~EvM&2elnjWTaDXoKm;3w`Xn3(b9Ia^zX>4rlpukMo?*|MIFPio6z^z2D zP?Lm%9P}XG@V^gmdg{)`))@iZSSn!K`@&Qdn{O4Zt%-d$G*f^RpbbROQtSF129gNkTKuxOtN{erTXB{Q;yj{dPH_5*9 zoTQW*<5;q5(0*2N^}H!Bn&ISpK<*%XnZPoTF;VQ^5857Gb;lTAR*J7{WuKPy4a>jx zpLxBR@{W-(94U@ay(DG5u<4z&xkJG=U)Dj}R}=i9h_2;8?xS7cQWZ`$^8-9puj~+% zI7X%opLO31Jv(zEzr&9k{x2&d$z`_Lw?(ABJ|v^0>}A`w=Y9}aAbDsKKDd*TBc~I= zj80@Hx~$Z3VoDb}C$zr)xM5`Z4eHL|c3IZx9hcS@iTYA`AvZCuEXvJU3VxuUD5*>D*2^FgRZlj`Zjt6Dgji3 zfpQBHmY4hpvQ+n20us@cCY^0Zo%E1`E|e*BlmPm&x@@u4@1D=IIa z)!V&I?)-ZBnRdzr{`R=UKHD=)o1$;4IEVc;VVlW*c)eLC%{=$_Xx+HqRtZmmFwX2qib4GGgTwy-_!z7??V}@yqL?>%CSCY5+r4kcBlQc!=0s zO6lI$q~y#3YpS@|tJ%G!emYriqrB5%f70&^**Qyg4!vITWeSs~OZrk>aj6iOpwmj* zj~vsm-;gd}`sV%b4zXhNI2Ed)p1pcCuV}u2#(8-zqIg}u4(=}FT{4GH&D3)5TIipsB`g8V1?ofh*-1&g z<{bXK>oULeC|8X!hwe5@n~V29B9rjoJiLuVH`Iftpm$_fJm&s!xv7<)(A+@?gXPs* znrhi=^qL)1wre99wv;FxvVq$0{P;BkK~mfr>X4JdjQh-{C&yo8{NjD@$5;D1M`+$E z)yUSqyVR4OiRu=eNHkZIUy~ns;8U|uLTA2Vv(54V3z z*k?~Ewaems{eylRT{~;<0y+p6>e|6UD#*ru? zpYy!7`%`=kKIRcUgccC^J7t@zGqyx2BZsn~;HG>X^OZ5ZTcR9awBFLIA!^9EF3}*5 zk9gaM{ZJxUcMlb%MLiW;U}>#wv@Ni^SMljqzyeb4jYtfkff5Equ-%1_2v}Jl8RUPB z+sF$7&=KvsKltw#!`HK_n>4 zI_RD51h#_*QgvJW2}KW)B_6mW5cYNED<+phu_8$8Ag~t%cZ><$Fy=$SXlqg&juU#p zH!`}-1+%YEl**N9cK{r`)FY4Y1oiC!#PCHRuLl{JNm3qY><}K{axaXS6j3BIe__BD zs}4gf6Ht(il^At_Mk*_|zzaz(+njv}x;@MC`$9r(K%2leA2G9Dy_?Wo8mvtb3hWV( zHYTA}0OtND%u8(5MmhdZgJ0e|Rxu#j!@&bn@JW@9Pck04#(n@VV5kZ}D0Mtky9CDG zaF`+k^CIbcj!P$^EUc`chVZ<#@>jtFE)CM51ZW0ka)^2^QT^XC4TeR@oEGCND7;uq zj320M&0DjFhZJD&9X|%D4CIa!E{GtME&qoKuJx>;20Nmg+&wq|Jsuws8ilC$Dl4(_ z$$;!S^hQ$*mSHW?8z)`XE!4afaq0PQLQd4m(Q;PT?UIH-pgACj!)@A!TMv;{gqlkCJu1TL1|z9WaB2X9medu86b}NRu`) zq6IDL7N{v9HV1CNzdZ}DAfF8$)R@J^MUBgnfL5Qd zMl@8B>x;~m;ihfcuPQ-ujXMz~rQd}QQi?7M>6S3(oj8Y|!ApFG0S*~>W?sU*3cNe04(5R{MWhmNl)*&E zK|m)N%>I#&D9}cnPEDUt1Mi7ccJMmGU4vj-<(9)GB$)c*Fy;cc<**;*5n%WtFVqB6 zUEH!XXg3gD0et=dJM09yOxWolVVpwPWZqC+o8VE{UixMqr;nsn;L;a*tVkEC8M$_1 z>%gn|+}Y-_sbpCHmHOikm=UFJV8%4G>u3Xj__dCis_U z8rw6hER9ML)H2BPkSiq_vuN-bqk<$p_8sO*)*Sj-4-)yh2zMtVJn%KhQNHnix**Z>#s8~dI480E zzR>>=eFVPb|ZK{m}ufL&R2A^NG~yQL;*p zf!FUNnaJDvF)9=CJ?LC|`W%7@b%&Er)Do!1D+3i199}%x1|E?a~xtLsSfVu%=9mXe>)geBGu|%J1U}9d2i9 zQnhJ3X$q`|0a<&l0ghN{)#X-WUR9ZB{SVmj#5>vHt>(NKEPPzk5{m6~HUY+?Q9lLv zTP~T5A17+{YB6P_dj7+?VqHidVr3`M#j7@itNAUhuC^@?33G%c$S~Z#`z%AkVFMEs|Bm$LT(m@pqkh!VJ4G_WW~XFF+VB#C^w?+@mfr63Ga_rD055E1@;a8_e$)UJ3HybPDXA< zx^l<3ZYuw!dp+%9p)Sq6Z2EBfQ?zWnh*xYowWHh{!khvR993_aFBV zGJ(&gdE^g_*rj_}vaTRezszF6__nQrdBz7z>cF`xfeE+QoU;PIDup?)_SQ2f$skSM? zWVP}8l8x_(Tt!fpG#YFcfPpEJOO#BWf5N?^tL9z-hnm;~_cYzsM>;qAE(s500ph4;7kw-${5WWIYSlsSe+Ps|=AmpZQ45G;{! zS;$CIutfb$YIHCTQOJ!c6=;@O;(wNn>%>uWYUuSC{OJ} zm6MCwL!o8Hho6#Tb~4=&-t)%=~AP$F0115(I7g z39T}fV-g8ia+d=-6kOT}`qB+073f}XKjK(aqv4=myEUQ*T15Nybhf^ps9ACpD}`7| zdKH&tz`Krlh6nXNDyvRY0fyGTfs7|E@&K+LfLIJk?0}VR`l#PcrOd=To}ZT&N&QEd zFEuvUE+ph%e=zXy!*>OLZP8a!<(3`qwrgQDsA&EvVqs7ePdF@*1aO8deCoqkX|E(H z6rx{^Wk?m6?u@2^UXBMwWx{TMnW__Zsj&}f@41809n$3dh3>_9Q~C4tNTDRqL}v{+ z??L>;ax2$s#Sq(!~cCr#tQ^>;L>e)+eB`LZBc_EMZjE4(n}l z8pY)Y|0I*(V^G;6Mz4d(01O{V;||XzYXiVB0vUY(Nar9U+8oRXB-UNYGipF}&ygALf z#k^4CxibcGOV}QKcv4~t5<`EC-*;en9xc+dG7S4YP{jcQ{Clg!3AGQa89idHS zu4>G%9huw$GJwm1#OwV_u>(dIJh6ZRA%7SF{cv}+&Oc+g-t;R`r2s+q+3z7a1*Vlr zO3bSUPeiMe^RJ?4??EUu$^e~qNy71EYa)q!qp!Z-@%x42jTl9&{t?~zrM@(nR$lC? zUUbX@n@0z>bN~zV!7T`mhTvUlP_*X1!6PtWBU6J+JpkwgSFV&f7#bPL8W|a(2Vwjw z5&s^pFn}!xYdI%RK9WCv{_bL}`CL`)!{Y&hFP*m1@`Ih@B*~nlI#ipC+^Iz9Orm|a z-v0Tc>zb|V$vmW~a{gaUU3pjQdd)F{mw6OZb4VEq74@Pk0>k8j1LjF4=$I;E16oX8 z)^ySF>2f+-a19tUI|qIsJ6rIwy+`h3Y{-6(qQGwS%K)>4sTEJEO+JN)CCbKW#;D%I zIGYq(W8lp+soWr*;V1hw^jEsM{i>m)_<$fof?JHKJ-=!WJ;k3E-?_2M*z=AgWdAez zcAQkJlknIRla;ksK}ovO*QqRPq?bHR$hO@~`@-MiLg}L>8DHFe@p3s?wP>k?^7VYX zo4aW4MC=Z3wqUd0PM4hXcjNaG5)JNGWzSCrt+CjU^9u-eAQmd?Q!MICpXmo8}t%8Fkt8HZjJdp2yQ;U9q?_- zFXpIDZ?geM(n81ZW0XQ{7Ea~MQpa-=-xIMj9QbG=mZ45ra=P6^CLm|=?Y-OP#>M$X z`_#$CgzrNP9c{6j7a>y|qgqCt-)8-y#SR@9PRTD8Y2I>I)<+RO9t_9ICNjM+zIpJs zISdd+@S`r2_S@*yuv?L>sX}wvID2<;4AjWw*+_4v9$^Jzb68j3!4c58_^&ebrRj`) z9>e8IdRih~59fJ3YjHBkH`Pk{bRo+e1Zg!}q)IO7tc+WV6Lk)XsoI8jB`{21zY-3< z?a_^UiyAX3!Z+%Keb3|%do7okz35o@_0PN5*E!$&y}71mWv=8R zr6Jffooc04M)g%q`*NUM&-y(h2LR#%{hH)W;}@R9bZL)z))#fB=fk-ShRCz6J&ar{E)c!I~z1_ zSL#7(@6vu%XsY_`Pc~`wm0`CZ5(N`y7vo+vbn?+V`fEKO|7%il8)#fEcOK6$SVPyh z;A6q=fK4*5je(N>ezf_66{?KQp!Vg@TuIZrOHUdPm1j5a<5O#tv&nub4-!pc*W;H6 zr*p@s?Rd^raWIuSUbnxikD?>MW-D^t39!>I6tz|Iyds6 zJ7M&4C#^@ zecuRrr&HHe9Nw*x9cvH6h<@-}(50A3+r;?q4sm7JyQ8Q(!Wn;p_CpS)36DB^f3-bo zt{{V*rLdljl=C#M)GhSjLlzkBeDo*X(a_dTY2B0~uF}Ok*br;^9rR-4&z)T_|4|Yl z{Os2;bdXGKcXhx(yQQs-p_1gsl_}($uv((3r)9;;L$ek9V@b3d-dbzWT&v0ey3r6 zjG?TgZ2UC>8n0J$EjxlH8_Tc%nz`_YRSa;NZjBHepMd~>qEmHRPom`ZtVe*e!yMJu z47JYJ?OC+1A-JNS92AE{BttU4n)3idBw)^qyk|OOZJhvis z;j$e(_Gyh1wWWdHUb^HS6KG;gNJwzs`~GC>Yy+`Bzgipvau5_(73M(x0i|OZI`mWS z8jgfNY|>d5t{FkY6rwGY0(t~$-9haSe405gD94RwB8kuv#w(IujWF5*dom(g0+9^_ ze!(0Oa)e<8#Ynk24yFWSejc7U)G4f`Jlgq?T??HAFaZRQ26zP|h~T(#z=hhuQbuo4 zp#!!PUBgPHqsh8rx?q~fIjnSi$}kA(PGHA$72_^+VCOQ>lyj7hkI zMTO-4!+34GfsJ8O`O7!q2lZn3tSgz zStNwIB^^8a7+YJj(Pxc4tI^4fJ+(A94=!1pnL)9tq$3)62zrK|rvQK`pos$&enkgU zfD`Dg069|rKnTbrm3rV>$J~gpR$PSW_ABfJE)Vdjjy#%z=8UG!e@VHx^jMIGJG9F0 z*+^6I`tFS=EWvJUbBq}u2w98%@^R_;eZ-B7cwL1z8iJsCg2|r*GM!-}4Dz;_Z3XsJ zb{JlK%JrIOPJB3`rn=fb&AC#Y)D?fa`@l0I+LOtzZNpgs+E_hDa`7E5MltX&c;Q zC)5EE!9*Z4M6Lx5jpfmU-;7xN^wWrAb#O4&gP~cQ|5bh?%}K-P8=pTAK0SVY=SXC1 z2dHmwqC-mWxEtLZ#Wa+CeBWW zX*W-@_#LuKa0Ay~d^(FY7oR#rM0`)H@TU)sC}4Q);6MmmF$}vc9rJDBfV}O2{e>t# za7A}z1B?X&2xNA{Pvs_nY~sV(W{yI|ctyyQcHd|`Ks?#N+W)Jb0NC3zl#X?S$)7YT ztwUh^X%$_t+^*AhBao-rBcRiB$xuK#Cvp-Ip9L^z-&S1^)*5yQd?-qkSiX|k7l;Ci z>sgHLS=46O0e6S_^>*NqEtN&w{!)R=0%B_;;C_XT5j@#RJgz6S#&at0r2ezSgJyLx zvS*REauhn|IqDVT`@t(yVFv6TgjZ{|gHt)a4Mea_8#_%4Jy^!MJ7FeY&SeRr$xaG; zf$xtfi;tF&Fbsxtp5@=6QKe3_iKwA)cl$UvLp_6#@fX>J2QZnLK_dCUedn z_+1=qMLBq5!pZM#lN?{DrT)7^M|tS5$}MlGJEL&mb2*fFxkmRt$vf&!U-o?iX;?g9#x7e8J*FUI} zD0s%+3a(r;&wNSbA>gzc5*t@Zq89p^!?G`2>8*yeT0F@?ab8Lw$ycw1{i&aii_6s^HhTA+#-K>`z7?PNs6Bc*3Qv97JNtPJN zE$08mHeA>BASnw@b}Wvm7dWA^>u;k9rZB8@W;1N4=z1{c9Na}*Ib%gi+s4_0udu17 zMfrP2Qu1~MN<}>`^r{MKlTIR1M^vQe?TWnYX#6?HZ5?*8uj0Jy|Bt5cfTsHY|G)Mu zGuf^^5-zfLb|R9UP4-BMtZPR0-YX=ZvMZ#Jy$RW6MvAQL^?%;JzyCR(b2_K`bl2N` zJ>HKQV4u8%8-b7!YzaEe@7msL9#|L~nLssfQTYTipz3*Q?%mw6T`AQgd?RDj@#MU@ zZp*YX2#ei@^HtU6+gC>eRX8tlz*Co)EF7qw-!*#k0TWtnY2C z*is}@khM@|fUr5k9WRcQR2U6^Zu7<}Lmw@AFw~0e&AK6kyv>q?%_tbj8PX+6!t6Iz zBa4;$>bk^bFBU5D_xbc{P|X&5r8R1Fb~R`D1=a1G^P4uLSiD*d4J^#77dW|@=S+A> zUk4|-A_E-jq!3j_-dDxU6ryM@;$}l`^Z_GEZ_W)Dhe1d>RiwM zo2;CReX1{;ew~@BaDhEu>y#aY%|mh#p~>K~kpmf4oUmf$Nw z7SCtC$9Z+qRJ0rVY?lf>AJsO~k(y~gdFiW2%0<<)nK*k;cJ|bWnn`UHwME{?-HOjX z*=5%p>E%z!A7^Fj#?MI}OxGIpT~eD;IdIlDD3GB(QF`ZSsY=l@npUDDB1JTU@7e(k zYwEs`oOyfMsFwsvJl0<>*6Cfy$$=Q$l0vNBMS^e>l0XTIOat~LpP0#cTXgz^2G9&cFR8DWRDWs1 z7U=WpS6?~*lG8q@Qe0LfH0JQ`1J7mO?gzKFWXY8NZY%!k*GeQjwBJ-@j|vTyGcfc< zq2xlX9U0l%urt?hhV{bFr6&dsEUkd!0S^E00dBW!;CU6~(J(0>6n`UZu;?ZM=Rb=gq{5a*H}F z6hp*w1qC|gtM5WBFh(_lBMeDsw33jKh!A=eVa{8orD2-29%j`YqxxVduj8HbgvU~6 ztn%VafN)e`QHu3^*Sy@HqgOJ2j@It+VvcyZmwt@L%#n0{KkNQT5``(|6WJ=Bj5b-( zTEo=QSEn1FX;j2~m_oZa7-UvFlU0fDxJibQ_pdLWNBnv_i0Iy8JL#F%I-=89E*a!3L;q*l!HJ36bBJX^79FF3xjeT zY!8VHtm|$8cZIGh!KN0fC1lzXj$^Q&EAY3`s!#xqeLLT--X;F!APlF z81q)++?fF8gqeXgglZ^^twDqGHowm)M6Xd5VHF9`5`1x9rruIaY0MlR@p{A%TfiK1 zHN)FK?>P^wD-75tW992}rI&5i|0ZioPzie_;)|3YRkPc|C-?a(R$B{55-@@I}pX;*|4#IgMo-kDr?^P3nl6Qava z_OBjY^Ds>oY^-jJ)!``7a4~{&Isi|-v*iEA>mW}}YROjA^lQ9Qj~Eac2$HKq`Dy^l zKuZIy9|Y6^Ef<&?JDZTLa~5E*k;>K12{kWk);r;*Il{Nb`#Ld?n%!{of4r0@9aVD7 zAVaeOL%CouNa(Sp-1`%E4KU}HO#IO8rs>~%^O~3L`jO9jR9!D)idyU6+cm9oTY$MN ztgXKE54io0&oOg%(Sl8ph86)=FdJ*&%qJ@Dw}ET)->eGhDaVRj`Hj$bVCuwa|7ix5d!Q`ap;-|4 zir$U)0jA|hdf@}Sz(+8L-hVIqS&V^X&&XIH|5ryxo zY!VR-g|x^FX?`-cG=?q1C^*l#s76Bn4mh9YTD1tjb-?Mj-Nxe(P?Hw_`_Z^d<1{06 zT|&tCW58Cbo!|`wiLh7v?M=GN3fGh(mxQ_3@RvIZat+(_Z&Tjwa50j~JdDeHWnHDU z=&xPlCFIrHg6d+i=8}3+ICG2^9r0?H<6g&+3sn%7tTK_zAb)&IsV`^US;KkUI1 z>S6RM`$(8%LL^(8S#gP-dSaeN-gI%j9w40)yKxTF2jeWM9|TCgDY< zNE-_EI4aN{iJfJnGCkDImhqnWg#X;DJq~AL%RlGxk2liUrNY;5G)3xYN$%lV_A~Z- zyMJze@>=U=Z3+^Va!FtY)knoyan$%!|adjuM+WlJyob z8D$_T4^^PjAmF3!wXNwpxp^hGoSN08~c4e z8A01|*^)~<%9`xE>eX1&hnNMIudgSta1S>GKgB7b;+uXwymVqtoSW8p&~$P+aAzsM zpptF$iMltbnEuoW|Kt#{0{Nrr`Yo|ynRbhyjb@yJZSEjF#o}cCN+m*{k*>p^qJ#NY zA;R>`;XRpF0IwsKEpGp#7F))-6sG6a!%->tTP-fCG=GuEa?$cc^>fl}$UAa$0`(7Rv~!X4vsZhSs=C zc5KYGgb8-$xB02XC^EFXozyQGsmrWlYo&77*kkiA&0cj@lM;H)*4KKSDPHl#e3a+Z zIBI|-F7)inyDwNt2xjR&M)tBIogHYD{Ve-d#+f-Pl7F!|ffIFoG}G0+#9FnvDCm!m z?Fj+SBZ98W+T!%{RB)g9XGB6CVcFFZJ+3a5TB!JT{vP{Q|2=JKk|Z0&7xIkGp%zlB z(!vkMyVjqsf4aw*9-BX+=$hhzwnZs8S!!RuUhwtyFNwW*ji(Nw#c9dAo`_*Sd}Y28 z(%p2teGNL+6xIt>;sGW$Jt@z8hFjL1)zb~V>~_)8As*jnDqR8yD-`{x7uuU`;<}K+ zijRrAbaMQza=gsY*)aV6w)T%optX@*nT2fBZ@D=MTWP2YZ zZS4DaZ4OCvirit%6Zid2KxSmZps>BvOMfE2_2p!AeqGChG+jx-Ik-D1nXXyPMLIL* z*>)70_Voel?PdOumbUS6{6BLR9V@C=_Don>zu#4%zaynAuxjIEPkZZuy@!({zRBOJ z_ch^-PsXc18LREyQ4DW?@ijF6xsWb%Ywc>O$If3uB%8|{Ll5VMV86QHaV+xiDrb^7 zm+bwdi4LzP3ueF7BhfX_b$YX0|wKLA$SNYvSa3 zM}BgGP8Xb;;r!1___<1-4@);XFhvZTC?SQ&TAe)mCGic35Hz$&t?CROKJB|ckWUg}%C%OrBlZf|wn8DGrk z-qDit&Y3$;(vm@O`Z_gp?1my+^3SI77chgZaQ_RwbGR*+m?A-brmlr=Z5SW2;REm{^}xzk)q&E9TX-l zu4IHZgd~Cd`ukKCZdHL_5}tQ(bmaYfEFvpAuxQpX45`8kXYiMI!7VQU5ZH?qf~GtGTUr0jY|z8k(Ie$Ia)`qZ7$0DD_2)NS z?T8fEZ2DKp3zQJ%scM!CJH3OL8w5v1ia_zQ2ICC$noZ@X|N8HXgV42ssoDqIplKGt z6y(2XYI^cdjs^*6_XF|*L@?+QLDkYCz-;9)18i2HaOkfsPz^B-p<9y!gM*lSC8nYb zvxd2`;R^kt7a}4`yqHJL*uWFg@Uni#>I~BX+;Ce?WKae6KaFFM9_^W=e0MlRG7}qI zY%ryW5VRGOHZ+JojhOr)GvrsyPp=_;K2IRu0;8gXIg*(76XLNzzs(&$;W1`zHNYW( zvmYw^S1FW)q`$#2k3&(M0z?phye4S~ES^r;fdu!jd=S)0v${tEfM&qZ1F!~4;-a#d ztf{33UsV7Z1SF;0LBkO0unc^b7)uq*cpYgAJIU`<0xrT#)57tM;rZ%jI-mp%+_VOfI5@CO|GDw-!v;q1e;I{{=W6dhz((p$&7K>=)Nuqk6$dKXH}BcQ zhMZRfa|iIFaqA?J49e^9N1#^{bYvO-!-ScP7Io1I1Xti(;}b!wJ0GFR+1zjAoz3t4 zt9E1i(395z?zrtAfY)5b$H!yYl=hpxORB*to-t zCnN2xJ7=e+6rmIRya_C{zz%{_&8*2kbLj{~>QIf<)zt=b!k;>bekyM5dCVVM5<(+yeh;m#ew62k?|dC1|H6|fl~#u9P{i;Wx5(0_ z41t6yQka#a_<;p)#YIf2pytm;5+Nm8g_J~P;MiM|DT(DSxSrz{-$_t1qJcelN(Hu> z85w215N=Mk5@Zp1Ud-Y~UX0>rnlYu#EBr<+e;E3reA5;>T&^l9k|f87lVlMqDJO{0 zG2o;p8M==CipQrS9iu?gp5kRE(Rl8VdW?VK-OcK5Z6x`yX`^V?wSlUyloaJ`FN5!g zn8Uzz`uDq28aYg5mrmj;!cP;e6Jz4-5O#kD%?}fILQiHB2c)z^MmNL73J7sjJx`Oa z9&&IHs&m=QXZ&68mGh^|kQcP$=(I)Xyqv$))}65k zfd2JobN-q9A#dQ$cfX%%*IP&$n0Z*Qg)N7L7~=@dU%GT@C|;;;%LZ|QbAId`^!$;@ z0@-==eWPh{LTl{M5OQYKXQf+ZI-j1ioc)w0EWt{qK&mzd4Mz=e3EY)W9Q3i7YJH2= zr%x0`YG1m<=@N1ihqyNdYXo6iuuy$BBP=n3fasFr;Sc`Wf{oNush_IrW8<5T*LB$9 zKA{uOQlh#ZGg-pG!{T?B_(5ci4@wGE(W2CA)J&E*$@Txs;bsYQk2W>)$S~g{%78o6_-vZkh+VEtw*s{sP3uzJVLd~FSPsV;?Ws7 z+t018>yzde-i?pAP9PK5rNA$pcP&@u$&1QDSTOmhHVaKoBr<*0^Qtq<)qf9WerOuj}Y}Dc3rtEba#3(KDA~yZ+I|~nzWI7 zK;v_Dl*pZJ5{r21(|W|DadB+zG-9bC&SmEE-~y4lDrwKGYvO6ntEJNYYwl6YZXd63 zbtZF+Eo}w`>WUfR<7g!j1=;!EwZ42lCMQRQVvshIf4=I5n}fCJw?t+y^(7BgaNL$Q zm9`l$P$8#XE5dnFa5?kdQmEd_`D{N9TI+k;m=;kq_XCf`c8*j1uz`W=vmZSfOidq? z>3W)%FVy|71VPd2E<@19Z_gvi8i@xdKv7(pSDJ)zl6^&2};Lpu% zU#lIZgLSiYp2lB?Hz=7^^kwqU9;L>!rS+gtSMkZYceMlGRh)NJ z*g3NXU!r7hMBib0;YVhlryhm^CvGMu zizvkMi(j33mlvqBFke7a9;{Rt_DBkcH`}A&sr=H@HN9jip-bUaWTKa!zWTFaY5gC1 zA(2!&k6EqOROOS~9~J*X8<7)ChEPFH1Y&>9#Iss7BLf8!gtZ|J*;fK0s6~A&m=AtmeTu zg=k5729QUQyx^-7%7=##J8*iy^)5CEg-|7kr1tg^!8i2X#H)RC1R-xKY;#FgRtZ@H zjbje3M&HAP9tL6h4$uX`#byFtJLjP3^TFwg5q%&A2s>r-;LHchM!>eN7$8zOuYnD* z3(Uzsms#1r1rq5(D<0~5*Y`6*@#tzhE!0<_H@eu)nZgTzQzND*Rb4*G2Qjg8Cny*I2Drwfz-fFYL&ykrSdRo>xN9#1phdL4v&4q zS<-S!aM98a$l}7S0Dv&S8sHtI?P52k(Z z?D#R%ZgX&;<7)xcz-@A2{#98HtVAPAxrD8 z8n~R3?AGIHid?vw`&1cPPn+^GkBgajHGztdr~0r7G5%q}$#sBsIFzM|r=~&=jap4$fYJM&plK!LG2O8GR{)C7519vC#fi1j$bon+_6{)>wfAN zz(SgI6r?Qcx?FvTFm2^>Btoc1Yd}(I>ATpP%UO;sDw6m1mnT)mc(pCAhOGk>sf}hT z%(Puhaq=VM&+f0XdyBwChlYzOIR*EN4Zqt&j*YH&46dEaSCH|>x{p%LG`TBOH*K;K z`U9lL4MZc=S+C%#AMqCJITnXd>jekwjqZOsy0-Fcn_<;Lg;yM_OqR;^Z7hA7alzc) zR?yiJEkF;){=o|znyYi+#i%ng)rFvAmgXq` zrg&}Xz=T$r$V4bQ=Qtm_SejeRznCM=%9RS6xEaPQ%GUR%M1n+F!${b%=*3@|SL#J` zOs#&KXX4~LGUva8>f-0lhV~ORXQY0JRiU(0Ux~lp`u^j|uoDX#Yasy%b1hmzgunn< zaPOnQwI$Ea-q>G}M%J#R_lPO>i25p&NpERppVJ-OXQ!Z5VSQ@FVkIA=_%vY)XLlFAvazBAlQwIhH^N;XiRxAelmysnryFZf1X0UO(Y4M7rHY-x7+ivRf!7K)Xy${ ze0KXT?kG+BBE9X&R%8v2J;#fT7q0h(C;P1?J^Hp3wT#|IdRUWx?XB)w6hmAHP&9`j z!rCoK@hqpRIO6X^VXAuOIb$*QEs7Qs9)E5q<+Ma^!#3t!=YzjS0?h+Y?Gn+59&GCW0d|DF}GGd3!JdhDIjo_?QEoxL|Ex=A~89_jeh(s$1gT z=^1$&stu;2E!T&(Z!(w}(Z8nE;yPNmBw}!6&@}SLCi5a-s5ZzxKgIo2X6q8U3E^us zdjid02Z?r7cg4(ieVi0Oq7&&!PgV+lnK!$i@~yMRDCJS9cnhd{iNtj+TO`(?rj9MC zvrw~ft1oY{;2}Tk20oR)m-kuPeKzRP(kcB^Hq>cis>e_D2G0}`W-R!{ZOCs}bghR? zUlH%ds=XF0J~A1yKy|n}VlEFCFV3M99t8MFA2S~;LE#AO!;GtG;J`&)7p)aoI*@&-1A`Y=9@~U zf|;+wg#=ehDE4oN9@Elm+SpfwiLAb?s*;F!#23#XZs2h-h%YAo+JQMNQVHv)OxR%C zL2#>jWOC`P!~WN+34%`g2jdv{*rS0{vqTCL*FZd;Hn31 znI&76%nwDxztBfS89yZ+xto!}_<2|GBYN)a+gykE#acFeJ@fHNOWz?jupWE%!#(s< z*?TXF54_@+1kUjFjKgbJxiIwvg))-iL8m$wWX!X3inSDqDl{Lpe?N(mdSs}E|I2{q zZ<|0XVFGhiy+l~;P+n_m4^fyzJK5Y3%FT?V@C02tF#RF|ZS|^1%6n)DJ0S0L(g~6I zH{mK{%jjL0v!bqasBoEFymEXt{QWh@Nz=+|sl&X7bwgFO)i7b399*nT^9z4P>~ewv znMtCf55JHJEFFJsoSgZM)%(n#%*T}!p^S?R@$C&c9p7j8J;UZO+t z@ja^I<=^RK9icU{zBdH`?lpxyfi|E=o@sI64DA9ENQC=nxQPd<&*|NBXu`K&0=CC` zcmR%FnIRjR9KVA<)o+-ttAAnB1Uv^>#xQdJuCf31$bz8^-~+@7AomIt7%-{|`2nIG z_=n&KM{r?j1%a-}iG|gsKDPGA=s1Q;zdc43!9_)mOJITBL4l)RHxo{doqyE-pbC0? z5lO(Z{HsZYq#EXw1wIgn9Wbh?wQvCznR)_TMdE-x9I_d?oTP1GIqbm$k$6#PIsHF@ z&5(?I1{xr2MF97Kam3ZP-!6uh2%eJR-+PCQ00zO%Rtb~}1d0K3aw`x$iUIqQ5NV=z zDHSOS9t%WCOl<~)7XhB6=wTYuFg5<5v4Q0u-mdZ+B6olof&?nK)c^>>Lt$oQ|3!Xb zKC_7{$>47Q%Z9f!mQRm;EucPlZ5`GqR#(YxF4YMp6$+?=1a{5-zw+|ygsd2Da_vzD z9^eR&Iw6>d4Q+53CZtTi^><}6CWQ>^Bhi^b06TkP1Yx@)AhLo)C{z~p=f^`yFu&RN z6b0a)&Fsp6vkzLx*1eXw!L=7mTW;_>lH(^B`LL0Y{P;{+1nx1IS1~CU7Gbf>XvWB; zz&YheJthWE8BAe-2TlRZYY#spm7?i9NW!r(GBI#d`|HN=$wF2blY|CJO9d)gN=L1Z zK7y6Yt}syjToz&~(5_rniAf{|1TX=ub~TgGvL3La5Ge@FlZLHAwm~nS(gS-~^hE*e zQSj<5>3d!$=_IDS_C;{sjM6)5|aT79~kf_D9&-|XK6rn<9 zk^~k_Dq6}}Kh-K71sfp0E^O9iI+jBL%y2~S8nD+-o`7467OfIvOMR6Hsa~D#k5(|n z42ykr>JL%h&OR<(^@X@HpiIoV>^l=PZ7HsIL>(XDf`_Pu$ZJb@Wu0$L%JE?%*nHIY zmD!l8s5ymC!lL*QQE(REPq-vP_1=w}!CtJ#?#gZauW{Dw!zyuDB)CliFyvBArkWVhhx zR4Tubz6&=?M5?#wYk9qK=22;#4A}8_iU?NRcpDJBa9UtvB(9rx6veCkz3~Z|#bN8! z4AzQ?-=6tXGcz{Ew$?wg^Yd4op);lVEkkVSzOAv8I=iMy7r!pby5mS4c{xM*&DnSU z-n)yVSP86|?XjG`xZD%6B=qdYw;Y45$?+NStrTn$Mz9mKun{9rWcY=2n$Uh*uU+F- zd)-t|yU2BN?x~fF zv<`&EP^YjCIaMav9LfAiu4YXY~k!PX_|OEsj9;cj0NA^7}6f|&Yut~k}q(lzuf+`DL@;f zM?Wf33zz%QJi**t`;+gJs-=d{REH3E)~nwMjU>_22hOwSGbq)5T~RR@H5gAXOw_!w zHG9>&&=x{c>!Klp z!Q>WwjUTl>{lQ}F!BOQegLtnOuxA_9I#=JJ*ThQl{_4$YMC3EA5H8CZD_YKFe~n~# zB(zB3qXTiB;GNlfT#9zje+m4j*D|Ud6CIGKV7slvkJa~6eEZz~E~9Dq_;?-D8t3z~ z^`UCVRUc2b?^yG{XpuCiyL70<4ofENv@dd@T+BxcUsRE{*ddux8gXl$G6;M%%Za*3&)@Xljg!~4+_PV7m(we4>mV*PS+`e0oAQy^gz)|3;@LTm0YwpN5~2qCC3ZCfj+XOvm&U$f^E#ze{lN z-2I~`))`Wr&7f%IBPR$_@Ac(P9AE{kq(wJo^gw+=oaW~zD4ho zMy9>AcvP<0g|xtqC!%5`5J>BMu*-LJY{Wf1IN-wmg)uQ#E97Sn;mQWYhk|XlPg|M@ ze1ceUm!BoX`Z=*YW0EF1Q;&D2wfoWX-skdhu@(ML^Le9!-Me*XEn>uh$m*nf{xi$L(HVIS zTKe8>!ydvk`|)2XRJUsMWtp-BL0chd@sQC6D}Zw%Vh0F}%mX7&4xC=y3+DNopsk_I z_h|g>>?8%tZs^x(f;nliCl%W~7DBbGB6hmu=3)Ap$n;yRxf+Et8%4UC^97fcV}fgU z9hhyFe486AhPV8Q=IU%J$J0{NN>$%KdQ?PJsReftH=W6JUky9r@a>Qv0xs$m%8Mc& zY}rWR_8pL_mfgS4%Ykk2c{f% z=Dn$2XzNJh{_2od{!W|RkCq`N&)Z+W@mx#X*I>p_`8^8}B&na5kOE{qo94heFS|AG7lB$Ny=|5fzV=584@E0fiM4(|g#^ zKmQDnSD4jd6Xk4$tE;OOFfeGV7N3oG6I+58JAz#S4V-RjspTe~K}E~+2j*4Ae3n^#u2^kEzvPH07_frt=!FetPI zL*z9de}d5|l#JPqqXW9*gyiHdx1fpegD;0G1qVmy>u_xUWOjCUkH?CE1CLbiMGd7F zX|*AR(3e z;vn(?TR4Vua&x;3wlzpr$e(Y=gEt>usk0NQlFI9S3y z0V~c=UuKLY-Ra#V0komvT+vV+KL~(8YudS2?6EF9QDar?7(mMYzwYKMVaDO6p-X~F zml`v-hS5+bCylUw;%77kLQtdSe)$bx&LABDwAcSiM5vH&0l<-b;?RXn2Rh_aMv1TQ z{N*mLiBts`d7T}mb3WFvLn567(wBU8Krwv*G$e@J@M-xRe0wt0e4pl1ewV{K3*1G( zrwblHqgGFd!UBZ(SI+{-60r9If#6zpdwv|wEEy9X`P zN_RE4>u=6aL&G526#M+c(kawz^f|(C@glqw32@pAXOc3@`A1^Hx~}kwfrtCIdQvGR zD%!qUP#uom{3D^E+V9LE_z{|Yw)1Rn_Pm+}nE%7@V1J*orcHq~4%b@YH;}4AFk%N8 zSSDU*aR#ge;A;ya4qO@I>UmcYB3JoJKp!B2dk^TndpH{aPaUMzoy0-MylL(}Xy#W8 znQ}w+{Ia#8Y++@U)b*0Vnewa@$cR~f;;)XWwn$*cl~M3n(Y<-1Ibz^elR@+G5G6#y z7%393{VG|6b^jVyDK1+IQZ@Xct_z`EN_r;{lXL+(CntA7wpte)C@@ zMA!7;hK!mhnrvm#q|AI@if=`!Yp9nLywNY= zW-<`Ao61bVN>-DV}_P3j)uEN|9)I){+@`-grZ z443|hPe$Mj_;S2HKUBsm-5^-o%iZO~N{(}HEJY|J1+Bk-B&%&5AKxj>h?ndclc+6& z6b(U=#sAhPvC41I7HC~-|G`p@Go5`ZBM==KY};D9{=6ym*9~M%3mLgj^_!B-5^^72 zT=T5C_;jxA^|CnyM~7a18e%LSf?2-)v)+qyGMmH3W-3~i3$B%w@8Q(f|F#9bNO>us z#RC3TYIC@e1o(Z!?6^nANA3>oFSe~K6&6fg2j8 ze9EEWg_F3pghM-mWy7jozjKWmx#ay%9Z=%l0bc@RshrRu5EK6i6+;j_z=sfx+R_^LSj0jrbkda7D>_#8Bx z#Z33fGpF)S&+BU$>6ALEO*ahRZ#pNPJyejDK};Q58GIQCjI7K&Zv4$2S|a7PkXv!z zane~+xPrGF`7UH!*#47OhGJRIqEz^vYbo`g_Yz~=s~m2pG+p=7+a8rMS>|&kyl6u{ zn0ZJ}h+BU2VY1m_{dW5u?yRJ+)LrgyJPMMl{Pt9N{;nva_3qOznT9(OLcz1wu}!f}i1w+xTms&Hj`zZ?^P3Vs?r!SZ&uTBkpXs6_rkdM6Z1r-LZjx}R;JET9 zq}94ALo27f{HD9*;O%)KzT%n# z#*swp(fUUxB35km!Udvm?`uj$@c?onxd6tw=E<*t@fg;Ccvzv$7E|?waW$><)8S`f zRy2X?04q}e7NoA?;Ve_B!|AZw(p&XV2j7r_{!Z*}PIWaj;1OUN!PA*+7@8sf_8s^{7WCjx(26$W~8 z`<9E}*(Y>)#wn4SJ-YlttGM`~T)s}XYnmn}h5&;M0Ek_|_!Xi|s27R;2IU5AJ;~f( z!1xUw8;HZfa{zr4mdETbOzz)@0$n?N_LlB5fNs^ZJolZ8zO=v?Efip-{ObvZU?DVa zk%5P-Odo2(w#W$E$N_xxE923UXQfbrwwOa3&nCh;_5C|0Wd_4n^S;bLDIiOhy(q33 zljHiVWIn*ChL5BMqHR+U?sYSuTw%tWYJe7nodCc|jB zs{a}HRryj|!5SxE(bT`=4CAy=b7x+8lQ0-Uu%dg^IO>TT5!8(zi72n)!0MDG|aqwbMSpeq*h>wI77toDl97Qw@ z)*ZrrXp^n9a&mgk$uI}yvKaOTIyS(C1;#bZ@YhHkOop~pf?Ry=17iav)LorGmV$P= z@6O9vyR0kus(+abcernLw?9d(>)}*BwA2FNh8!y-5rNvF9fR(?XW%phXC>5d$;kz; zcaz1QDuiL6@zMy`=P)&Ipi@G4(Depr({K&jheC}pMks~#x#u0$*r)2G)*QO(=P3AN zu#z>!LEo1aRF{2q^0Z)rS>DEP_MO-1yMXWl_zCTx!VvZ?5cL zs`Dzm+g)WKy4&YFgZgXm8beJ3;j~2%v_$}f7$so-j4yooL(pWm6m4-&9mA0;q*3 zO1}fW3I%-RQ~BNM4|f3?W9)a}af2<|Pz-Mk200*-$(1mdAw10LU~U_<`+<2i!x75* z;OW?7=VoPDzgK*2oPW0dU|R=TQ)UIDQiXt-hFbtfMFy2Ehl^n!CLOZdDcP1ZX;#hf0rwYFQ?><&+WcXGfyb* z`rp@n(PRH=S>cILX>5M%qYM0lm|F^6Pu%vYNQkSVtQQdfDW8h8i_a@bOmMcGJPb)u zz*Tyv6qnrgN6Gz#wVAYAb~YhLP~=Q*Md*oHsG(IohSn%LkVR6snmfZhIL1~i35o^US5_OxC`mO$*X`$4f?r7s4%cN~c zbvjxL>>}?uWORomQYE+6Dts8`@?%#{Tvm1piyXQV75SM4wI!6PjAV(N87h18*Ldd zh&?Uxzps-?xVJkdf*7JnqT%~irFo)j!|zFfKJ`TQMzkKHV^K;w z|J-!;1Lt=7#ktBODeQ~mx%Hj42G5&>gbP+K#W91AsK_QZ*`FUr{y2Gin^XfoQPDx* zYL~`uTlxyEVn++?XRN~2c!~HfH}rxMiD|U(?fI!RCpTykIIR?JPjAO7Z!U$J{KQ1ygI}AL+Za_1lAZ zF>5|D_slNGa+n&QGT3L0pvbR(mMeLSbEo!&P1?}lw~;3>QyocqrBz6HeIQRX%7;nmB?p8LUfM?+$=p+IkcoL3z%pa%XJlG#=~WbLE{*1n zX@5u^PFN(MM;9KRY{#FQspR_sZGM4ZAUp85_>Rvv^X%u_8^wh4zLZc8gjiz~lKio- z?v2E%1i6}6dX6E1RD({b)uRL(~9 zZULiW^oH+-!3!I%M}Jg^_~u5H>rL`4FXS>_m^z)R2YrI?`up0uC52(akLM}2vZhTW zDFa34qPbtobdunur)pdyBgQ(uPo_KfrVh7^T4oMyn?i$r?vmT+;u!iaI(QSem~cI# zf;@uhZB_u(ro1(kB~4e=6}YzU;=;C^`PQ5JtGo`5>^n6h(l9*4K)?B)gJxnb$^c5l z(CY!e>9oWCZRHj+>|zn-2x4Q>DjE!UsBNmf46It%vr9Cx2!?!$GTCZU9H$X9PC3CHTZJ{S0=cgfc4q z%n;@TfeTzoKzo5oc1II+cM7^cF^(@6F_5M}WF6|60Q3N*1t7Qy9Y)ah0iK`|&Vch6 z{^x!dmT^b6{p=SZkGE7g!lnV_MO;`}neIgE5V*9euJD=#X2n@;u9(iB)mrdwG zfZh!Yn{tCtJz~&Mb*Z6Ij0((I{TWKa=Ab-6@By9>Y;CqcgQ-tG#?$>dlz{)J4)6pZ zSiLgn;swh$2D<^E!2qVY&076ja@D{%4m_QFx!6koAJ;Hk5a1Cw{kGzvr4)k=L_)v* z+m5w{m3I?oh^V;LWhZbKT~1hTb8dKGbX^(43Nr zLZfBxBmgokAk;&tEM|rZ5m%AjqDU=HIIOZAx@=2i^w`4#4IhdSDdyvt1-}4ro^THW zG%#q>5JMo1;Y;uPdGIf{StfVYR$cfxCT+1QcOdD%9c`fu1_AIf!W5zVJXG&3&n1(( ze==8t;YxvkE2e z;0@?TGwrY>U1k=2Ue2NO^E{%(mHHNsHbpjD@KEG_Y6cc>VB@aaXylGD$ zR}5=yxRwgy&4fZzKt+Q7OpE|Uz8zjud^pFMx@Tf>P$jgCV?d{gGeE+Jey|pcpQ?A3 zH1`G7_)Vbib`l`y5ZY4^jNuaj_a!jnTPxY_4>O@u1=F1i?a3G%3H{?L@H*ix3p%wk z!-XN}0l)jtxac0Z3p;Tvz+!ftfyn^O49r7(slCSmJZHl|#J?$>;J-zNwP410wM&x`W6(5Wxd1KDaN#q% zi$e{!O7gM{BH9TXjwzgrP= z5z8k1)A;x|4dg_CRtA1q!2Dw*JlD8X+!5}TS^(h~rgow284P(Gj>?~n;?AtzJ=v?; zY&sJhrtkmHCgZXHVIX3Nq+e|A<8hPk(1`24SIdmv)_KtWcmB?rWf`gyw!wyzByo2E z@q_-}H@&_8Rs3f@dHr$nbv;Vhlc%q;ApNNrf)y_l!P=c>N!rQGK;zO~mG6pUW5eNq zdM1eTRFs-G>e6tQ?yX{;J(F+m49Bxh0yhU5^Qab{MP9^9h}UMh#;S{DUkNuAA8L3I z^&?(>vHc=Zn%NWiqZb`V*bkmt(xh@iM z1&1$U7+-&R-?Sjnz+Wcl+NH7qcRhx2dZG^%#uBx*M*@dxGmO@^@cXF>waqPdaV)Go zM$K#x?Oh02-lT^n2H5(K!1o5fvs*?LO_n|AV zsykZzB1$@_@+A*E;yqGy#TPKzNA+E{w?*5$n)HABZJaM+yjoJsK*8nUOSX>*j+iAM z9`rz8Skjc3u$DA<`T_H6>1g z>)P&VtB^9>89${Gctr)y0{*70=~a}R)N}LFco%_ZCa#QKUAN)Re{nI~_2cOdeep2( z6b!dJEIvdV%KI_Y*4BNA|3x?o{x6w$@5bRdgDgRtG5dB94?O z(5iK#`18m4Rmj^HRFMcQ*R}wL9x*F)$#ZLqX*XxWAMZK4bZ0lG&u`0x&;5F5EOstf z)k3>4^=M?5WGIkzwr*~QvAzTG?ycTzdf05VpePIAfATCeU%dYtpGk?80vy$Cq{ zP0OGo#dUs*&?ZPGP|E(^XVTZ&?{x^HkX1JPwVFikZ}vL91(NMg*sAD4Tgr{43bN+7 z{+Qtt=r$^DyT83XQmO8&J^0Drnv@sFjb!(e3UhEvMkvS5H>=4j?4s<6c zJS${b3vgk&Gau~2O{jz`Eac@%@25N;_&}jn{29YmJW)PxN#ecU52d%H(@358m@96~Rb*Hcd5FOwwS z*}_tuS(UMaeme2V0+iW6Q~?wN*bxk25@T3I#nA*3h%|DXuklCLYS^ zZCuVm3@ z*gSut=jNg0RQDZ{DYc3MA;}wIQ9Ts6g`LyWH`iU53Z{N4cE6?D2%mfTH^z$YRk#x0 zCH;s#+R9iPr>Df??%&`X6Ei8#t9xlRu5)OUzsg9SBe#P0%3mP5Y>jBli5*sb+drSP zW(|lf5?)po_+hz#|6WHxLA|fPTt7@fvsjq&MQ$0zT; zK0E%M-?A*4rKxt1`W?7dfZRyJjiq>^OM5F#miB+ANOp)yj0tVCRU7OBVz&iQ`B zz4!S%&*%MlO$SLv#~k9;1jcee`tp+zC&;_9#-0yvpyhRca z;I_VdKOlew{4fD0YMt=IlTF+%whg6p+f#N*z}DYecQB1cC&K%1b9eVr`DPA2>SVQh zA$C;xpP=U6ap)sZ;sJ->b2}ivWn)lJ?B&$@EK;K|+;n;$z6BY|yjY|>uj+Q|-)d9d zfq(HE+`5ov*8vf1|5iPMnUP#b)Du-of!i{r1;fwDkD4FKCAD~Jqu;@B@?CR z@k=|8EL3naxdzgQn84=@LIY?8S=AD3&lAc0QU)-2)|Y#^YrgeJj9{dE;&U(>K^a4I zkfmsv1cY$IOrB;H#0V%jsoYV0)6vBSFt3o#aryI1TR=u51Ole$!U#NW`6F(QKe`Sq zMfgvi2S?8`{JfLWdwHqQocniNO5+~tivo#HaS2P{53#2ck=Z9w%u9D6sqa7gWnD;=!(S`kwX~pRJdkKjof-aw zT)R-@C=tWQpcfbX&`Xdz6r=@sQhc(BhCXd)>pSWwUX;(yspj9iKudjDnxb?%XZ-3vmT#|$0W%o zP{fv!YtCcs6UTZ&+pJGy4|GVA`w56Is;n<$+1pH1vg^c9w@#ss7()Hs{0GhSrX|_D zS3O2mI-SI>dZE+PP;5jrmi9;A!;ZAM2IlbOh@{1o1nrpCS;V^z{72JJ&tEL^zrQQk zIMd!@W{G4p2Xd^H$GIq~y) zG5ocx1Nz3VN%zSZ8l~1RJ;q+_#EU=i8sQbR#_{x3);YOkMkG>t-lgQj-9CE`#wcE9 zoIN7+qr|?u>IygHR2diIr0#zrzzeahhzQ;mKKr>uc1)8BH@dQ@PI=`2BlBu2JErj#)MG_XpGmGW1^|kD?-&$E&R;mZwT?r$iQZBPRc=_#;5atKpQ!~qq z*1-|Hwkt86@iG;U9*|wUWw5P)6Cz!e7-feM(RIS*D-`Q;xTd7gxbFD$LKolMemGO%+$7|6+Yz5G0*uGc>nkhJ?u%ZbkTa4n#xVY{om^gwwp39s*o0oF~A?a-uG(Ff}ISEXhd7|*{NbDtTlcCX4}@?u}RNrbD;oL+Ub$5QU}Xf1z7 zYb`ODBJ1plQE*e^o`!+%d8hJte#?89jr@n{Rbtm@-sA1tf4Qh``;X(M7COeb8AseX z#y*jd_LAD6IBA_pt2p9|=<6dz<}W131yDC&h~;3O@?J7mc6Nne7icSD&+F{yKwwT% z?PTqo`1HhMYy8_6fvNoF?AdzIbRY;}9~Ty1vU-wSMtOqIHnsWnrk)_p&NRQ(r@qMWFm)9s^3zu6z`U83t#>H1wMOkqjJBdD{z^3z8rEX>*zXg<+)+pEb&lXF|*2 zWdj-HU3cKa1_t@U;V6J)7-==5v6SkBshW5!*tZs<07>$XcBU0=XLP_G2eLpUaj?>< z-xg@hsiVogj}s_N3k1!QUWSGaQa_+Rv4CAcf42@mw*cFb)@&u^vZMN@c?<0G&L!Z6 zfnCI;xJ@Rr+aAS`+5nar*i``lMVMKrsp#$P9S`=H`1CkS)??=Di;I2sn%2Z>z2Z=QZ$!tczfMU^^xB?mgH|{Ef z={oq8gN1F{nkD}B^e~1)%5Nkk8j^iaSa!rdNCjtMxqm#+x_lX?O?VLiwyrmwDaXaf zd#z6@!KB_Oy0ZjxB~AFR;#@zt<9dz(MxGb0b;kAQF_~l4|h*ytd$JF zat#c%^y~GeB}H^1AhXB&68JPPK-KDbb{Yr{ zfO`W6u2DH+FaFELE+m+&$x`rnL!p?O0?d^#tK$2D+%dui2}}x@m&!#jd_=;Zf*5c~4%*)teo zk-TPDHxQYEsfX@d#2#Owi}e!Z#ms|Vz-&kgjP<|Dp#%<8w~)02*k&8NW;i6UsRYHq zdW?-FV>?3;Bp1|0L1^Uk@k4?WgSVX&7&2@`yz5}VYVRzkxP+u zeARetosJwUPL`<}yph9k~l;tEwnVuEB?Ou_TI zh$FgB>)cFOAyf6EzZ3&p(*rdJxjY2{(`mj2vl-8lF7NDq%P_)bXKRmlR@a}pe9^w& zqOuq|mB<{v>P|9qo;tUNWByLFo7}T|L9JF;ydx&_fp0kzCV@gWOY^JBU_UTltjVBT z6LGp~>FfM0dm%G4MfyUnYDB`INF>3aq^K??pUj^4z>O&PGvOd>l++X5VizIik%G7Q??Ti zt9*sp_zNPRasH}fNw;j-rzW&^1*QR}@#(!TtX5eTt?;vh7H)vreU_VHm zmV2_k(fsp_?QCm3yEFL2h}O|DGl80tFppA0@K!I^vmUbq%3tGhxiv$mc^mf+__0o6A~iuJWjDE*bF~xkNG&7Ki_D~9Hjr&GnjkkhM=IJtJ;7kIpC zCGK|Jylr<>I-V-z$7R0jca~*wdySdWmJjh`zqGhsta&n*Fx{8B6298K@7_FIQ&K@q z*^{;9B1L|ru}BjsL+C-*c|eUhak6fhlllEH(UsWy6LS*}hGZhhZ75Ok@Yd-NSI54}d;Pva`pVJ0!FL|)bUK#Z_WSCF6%QrlP;`{vyrb)qk0xVP zuznpCYBmdAjMP8;&JW2|0PKo5>cdPyVvH@=B>Rhh5MWbiz<@Qql#n$u_SD z?VW_LsH;+TW(pTWE6l0PiAqXgX|>)iDO-IR$ntU+?-fJTz!PX)9?*J8Y5T~LcHst{ zc&)KU{r8Smg5{63hYbIDLD1@Oq87~m&SYN8k&pGPj;eH8@O1QIJFsATaASSu^s|=S zul22?$jHT!_c}KpI^f*D$Muw5hN0t@!2ZBN(+-X9n8a|liBM637_QmpGltmNz_yC8 zWS4qT2cGE*Gv7O}sZBpnZEeJAi6uC5gs72Ize%ZF7W-^If&PCjz$3yBI7j(!FTCn% z$mT%hf9L#AM+-opC4Cgm77Hu>z{#&IfA;xV=NebOdnS>_6_+c&H6M<$b-2!U{iy`^ zvRZ9zbjKCapS7#$2{Xq>weQ%A_Kwz#?!8(VSwCu-;a8wy&T!z;6T#1v_ZK?%%0e{H zycDH?{bob|IWCgREKGcvs=IM#Zf?v3eD;l`ZhqSSJLjkE2%@<{9h zX~Pm5!sa;x%@UeRjAE(POHJP&ns$KFkb@D8xzgzD@9iz+WxyWu$Kyyu z53zORpjg7s;r$WxGuVR+gDL}T4A64Xe;N>J|JRG_)-Vu)tgrOCu-BAt{R=aW{6o%2 zv9}bupcW%F&-WdloHVrXE;l41RR6=4?DaZeUog(@^fqBADCQI&Z7;U{+g`;~<6o^D z(NuWR0lF}dTz+*}**mhxkk7$jmKh69*{fIT1t2z{yjr)G=zSAog}!0#z=z`*YUB8TY5 zJR1Jt>&ZfyL~0FpLWi{iaK{P6(}$m}ns7H>X~tYVy>L9Iw}95sQPB;*7YCm1XxEyt z)wX}hDx0A`{kGp4o_qc2IS2GK1iQg54KeR?Mo4$(^3Zv(I5?LYRlol7<%?!8bAxgL z$PWPu{8~$K%-FD&_nGE9_s`$f>|Cl$yalG{4XxokO=Wh^`+BE|qwy<|3}i{rB%1E;< z16?O-1MaOx;i3| z5Ofm0$ucZL%<%vw!^{M1>-Nz}+eh8OWY9~9G#ji~gE|6d19~|C4<{Nj!0xb4T`#^J zkg*J?9W=2aEp7JB ze_&Ai#sMqP#`MZPkJZ?h^C~u^EAK)CUn;dXi_Q#XdQ66-07@=F)=EJ~LzM^zatzbT zKd1)fU%hx!K|Opw^hzblf7Djxyv3EM#J`E7Smm}mVU54yeVZ=_D{(x$A5W!Ok0*2X z>9{_4jV8zS@mZ4-eK__*bI4sut>i%47dXkZl)CCsauqV_*_=TMIlr#ZRwnU=+LN-p z-V~&WDrmkhg7;HCrF(=2|1WJzBd@ShDg&jes>T}z6CKQDDr%Fq1g?8-Jf1ju7*bRf zZoVW5QD|xi*}O?^n39%ir2`KZFPoxgRyB4^p->~)N!G}199R3#Hr_RS(O;+gb0mjk zf)=^69%tHLig=n`YO1Mgy};o2eylf-azD^0O7pf3=L>h2%F;ZJ?oPt^V*Kv4>6yXP z+YU2!VcWPuBvij@-)S5X*)#pz6i^0HrmZ9EwH?iTx(A+E+BCovjn@|9w2-uS^$q(P=hMT1maZ}Nwt<$AuH>g=&bkb_@2bNF=`;)R zXuB=$q(?o*i{c!ltiXvOLgxyRa9lGaXRN@<%a}!JGYs4;xy{&Zoa{+VpEE&i#*M=B zk7^z~VB-xz4VC2#S>Ye%vKrAdX|Exqx7$#_5cS7`E=M<&q`-L_ikd|c zR)dbbI@WXjL?uRf^7Mq(_J6MnStTZ&l5=A4iqYCGzbp!>2B&IB+k#4}@s|Jo+O;4% zHUhUcWDwms_Hf9b5;+iPSDKCxOEHdXa*|W>x z-n{kguT!(o4;jC^$%+~Z8v@LBY3n0=-p-b`@hNo1d=YrBS|ox;@bSs=(Ar&h`LXsj z@d8Kjo4p^tO{(~vZ5>Z$^&h!6OKvOMv41&N?a)d=8}>`QRH9s?d0QjXgUG$Z`Q>8UGMSd)8(D-B~(rU`e2j7=OIK7u_Sz6qNANHRF!9lZJgIqc+j@quZ5{ zrFh2*dO1Z#mc8${w5d4apx;UP@Cy5g1=E2#aYi=wpF|AH+ZR?Ubup)b4S~{KuF+tSY2q5WXF&mxD6 zq&ej?+gJ{LyElogU|#t28GqN;+?a}0@>f|vmP-53{>|rmn) z)d}bBm*1SrkGU(F5y9ES-AYAUhDb!Qo=gp~Vvq%_#?pxtZo|$1eOAgl#YRZox6{{b zHOLr4jJjI!Y+x}!Les$R=^$SO;wf=b`8O)iGY)7DWcdR>ZRhNar~nZf4T4-id<4x5 z(SQCppzukxHm`vj0clhK-5BI5!=p84@i|2q^JESbo&Gi6<|iN_~a8^hNOl-Z#?ib$omF?Jt**7S5`z|a0DS7 zw9G@fNEp0YFdV?vXahXcO&8#nkmmc&c=p%E0vt)*(-}@V%^W?6An&1n&d4Hf31u*YWhXH;9+C*UTp!dV!<;}JLWLmtS9z4 z0zeiKQBifl$Kde*eItxt@3Vj_HhBP;5&ZW36(^NvmtTh>NiQS8aG8wC`@wGf8mcY! z_ZeWAL<(Rbv<_1UuZTeaq+CE8_NEYVii44-fELMefvE&$I7qUA`EeXFIzX}qk9Lw}8qJmIZ){FX1k5afxnzXwF<$1GptuTCdkwBIy*&bi-SdlWbrWi2<_>P|~10 z1kou7F?SuzU6Jp+{?6-+2mfX6*+Fin*l~*(QtqV&8bc%=r|ERLsRP8VKvsjYmEq&7 zWaOHFXUQxz@er{+LHpLvJ3#Ql7nonv!9X#@h1Nt`v|yEg^!vvJfGgOS)4PFOe4h(T z(h(0dbwr*_-HWksi+*1c?`5dCR0Gw=Zy>Zf!NeAv8E{7-_$t6?K(r%Gz3`cX7+|Ju zA*U5kTrgO9`S?TtLJHB@0Or|&W&jdif`W2RoS?%GJnNtcL^@M!AuR_$PzFZEW~7R( z7Kvjt1{=L-8l;yq$YsFD2{*H2W%qquEC~7;+q`1n+QC(@1|K@e0Mm1Gou+TVxgsN@ z8SbwcxsD7eCs-V?QhG}gk0q^9;h-;|-Gmz)g_$`})4Qz*uXQG|g;L(BC3)z$_u4$Z_(WsSv7f#=Z2qoiQv%IrwP(NFmkJF^>kP zhF$4V1n4ndf~KG+MHr%v+6(lcs+$&RQA3PtO}nm5k;t(8NC{bSj{YkCyCR6B6I|fH z;6k=F%1j(c9|q(ZL&m3q8^aPfX;= z2D3L9(&fD8Ns-k9O9xCu$Uz6(IDo-_gfwo%fP~%OhU){-^Mss!F?*dMz;*+a4A+G_ zt@j_x5~vK|bL>QJ26&?W9u7Vke%`;e2FBi{L=oOWvI+7ZJdQg&6jSPsiS&c_*2YlQJR&-G29ruiTf{kCUGhaW zT0hyvGbgv@+qER8d?j_U!kVP=WC#?DrG_Rgyi{et3q?`%aiOew1e*(A>CAWAQR|3D z{d#OzDtPZ}(-qXooCo`d^hG>Rd5A=wp}ITr#qEMGI`c5%R`JBG5E|+*lSmkVzlV6Rm&W6GdE-di!uBZ!l>Ya+7%P+|{R;l6aJSrVZ4-Rb8QkwOcnV?=UL&?sk0O6!D3f4<-PNBn@7fr>cz?^ z_bJhzd9sZ~eEb`uV#i!x&x@+vG^QZXiqM|EIxBa%!nkew2hW{qFU>1%q4x6_PD=0| zTs|W+FTKR_v;VcJh|QyW#NOX4MYVC0Jn%PERfRD^jBiah{M^ZaN|L_&O;Sp*loIP`ArweUfeT+ot7b{6={9-4ZUlb736}PLs-%vl{;5v9D7D`??ttMP9Av z+QnzA&~jv)WCiYosOa6z`al{-P$wP_KiIno=;9qK3O35 zb$eOSm8QP4U@2lGicZb(kxUQW;m)bzjlY)DP*=YBN2Gl$zF*3|s1gg)1+(nh^rHCXBC@tXmmWP7{a+f&m8;N~b(xPJ)KifeBaA=p z%=#_A*ekEAh?k=#bRZ66Nc9t)`}KU}dMRmj#(Mfen^|etsOCBK?JFKDFDKg=9-U}YOoSmV30tnizlYIlgvof!SP zW_W#XpJh7#?{vH?HEdI#V8inF2S-F^GaHQb@OMEbsI090%bbL`0bF9RgZS$u9<)1* zc}Ni%7$7vk_kGCvR4oJTI)aRTn$6&+4h;Jj_4T<) zPEUh$dH^Hzgv9p;u6ZNc`Kzf3EcO^QsdFg=S-;a2O0o5&L9CTVR;q>ij+*fNp=9dURNVH;4#b2fu*O#4B z40LH+lF)`T*-)Ypddm1qe2cN%> zCPN5GN)ddNetvSCH!tsIfT9iJ>gX-~LYp-}Wcbl{l}SqN3OjJwAaI0D-dQFK4jtf6 z>Q_Dzfl~yOxq!LF3m93%`)yRR?xXNxv9+imel(JY`R^XLF3<8_zGlt7jZ1l)Fl64q z+k&?WIzOQ4VHpDy2^I`n2M0X3hVkqw9SDtkyT0Q-obSM2ZCq?h?R()@hv`&=_HF?W z%o#v;cEuPR1StRBBCH}}DF1HF{%`eSQa8j9-BY^qB1zvCCd(xabo`&Khm_20w_iip z9yocwFKt{{%A&rV)FTvOm%@FsS1#`6*R*`Jj_62ju(~VFvmCK+dL`+mQ>uy2-3L4z zD{n%Sq$4TMhE46*pMN$3blnR{RidoHaGb*D190?glOp-W3S{-|&&xIuq5PIhYr*fF z`G(#06h10NK2lwDrx!8_A?pS?Gyux%DRjg+z0y&8Y4aAW1TU5?zci@F5uinIR5%wM zZ}rbYVD{`kA2>{c+*A(A*fu5~G;XotKTrY`8b%efTemczwiW)5}r1!t+KSq3--A%`kDBqs>YLh#vwpI$>l18h&);%7K=HVcq73F{A` ztsidjK@cX4mAO#N3nTACk>Kq`Dlk7m@DB{Z;*g>QL^()95r`Bt(G+mjiHEbOXjyXN z5$i~fN*XEzQEGx+?narVgYh)HHoZq^!`<|GS~zHTLgEq-^I!GL=ZxTf0}TNLR3XJd zaJ)dm;gO8+YV-Em#vLRjG?4atV5YL#(%EtN)TOk*N=(PbD^9$;)hQNn0_sq2Wq*zY z@~F@!BEMf>qaOBdzU|E;5hH({(jyB~B0Aj@W6yFtL~5uz&W?G=(pAYoTJ!LzFT8+W zvvBJ3J>sY7clM^mR&4X854SNV{7nySzTQ&x*?V>&K z2)nTtr^v18i55pQ-~E*M-X`=x@-Eek8D|{#DOloyerPmJX*3OM(PqecO+1L`x+wFM zyG>!<^{Q&_*$}x%(dQ1MZDHa(sdB8}|^d;4+vtwcXE%T!cUn2=tj-vGne>@@L zdG&iu&-GW|p~q^^>3NQr=v1H&@nI&ZMtgNj)AX|M(wYUnuz<&UyG(vS0j~I7E$Mz3eaDuoZ zkcC@;MxXgLPjhdE8hZEjzOuqw^IF=f+V-0dJpZ+nSqIMEsMu-_jv8$`Wg0v>3L!NP zUb`xHSZ9SRvK3Dkc8x6@+m(5{$&1YD>~OfEw%(m*!_g-hVcWa_J*B&BiU2DdiXOMr6i#4k$MLnNu+pe&F`5pA!GA|gfU1zu43!m}Fyo0}Tt7TvGu2n4UI`uoKw!pE)1hYj=DEsH_ibMu@{C5IxRY2vYd2C+u|piBN$!S82R1@i|5^IK?J z#HXExOw-kc&T)MiqqAVg?K5S^4V4`ZOYt)NYSXnR-i5DB*@M>+JM!(LL(o+P$Bp#J z8TSHP%^q>qj<@jwzPUj^W{t``nqDg(p5(CB$BbWTo4rnYPD|wWoa&TsNqp>CKK2EM z=zx0o)QsC*maF{H^t|m%@^Ibfy5#!AEV09qhq@WE+ph&?9ui>Y1j^r3XXsES7|GXf zkR^o^=6oTa?@eya)o_)qO|lsvZ2 zR-bU-*lL>04_3$P#vII_514(|A}+r7hh9}XPKttEwmdjV0j#{T_nyN5rEZi!RruUS5 zp`u+c=Wzb_54*+J91)SEA{8O{hbIhIXv62uSIS3k8q-xr3(eE>i%VR&r1E#V`GnwO z{imlBrQ`~w(x%C>ckY^SURP4}xgvm{p3T7eq;dN_|GCQ;G{D|u~Rm9c|Z~MGcR4(%@ zhvhssdY8nmne|Iys4aUQV-jWX!~gnl!0(ZjV1*w3_)_|6t&*PJ~*=eE)n( z&UqIwNgMSMvZDy8aGBEH_sw2asSb0qoIQ-K^*T8ek{LQ@%ATO`OtnyT-GDbqxYp)E z>}@4Aw7I(QEi1JcQznL7hL+985*80_@YjPk`0iSawd_V-ZXyx(x?{OU?GszH7# zxU}$iZ}pg)QiD4(souwRToSkwt$)WP!e$nV;SZ+jLYqz|ulbBpy;9Cg_IZI_Uq-Q9 z4U!~TyCicIqc6r5*rms!lIf#+s&ZLpWQUl5hena_yWaT_OyrA>LV<#ap>pbGI&5DB z?t}4P?kmFouLXz~E*F6`W74W6-+GvE01kpt2P#5{BHR^TIK~50pL_N4EPx(SXa~m1Ozk|GPdQ- z4EOr~+ymv8?WiC6{eTiOMb*?mryoX;7eZYC+Mp)AgM=+|;?BVMf#6sGL*@9dA-U8* zqXL0W2*=$v@bQM9_q6^tFmQYx&4qpI8J!m?*4KE3o zK{Tyb%{3NAE>M5gc%YNO0%OU*T4L3-ZmgoHsHh2p6L8e0r^?#+$tI=O^~Q6t(MvuG zSDyT5ldm{$5{Q{TRdv670)y_$iMzmDOX>Zr^IiabXS2Q+h+F>~^1vn!xD`k=LAD95 zrVm8`VZ#pq5U`K-g0ysUf=~Ww))&XRoUS-%^MetJ+F{v8fhcbj+!$3uNR)fGDSDHV z!N=P>serV&>8P;=N}~yHxPFnW#}(nd48Q!bz*EY|`PFOy-~jk*l)>4BWdP_XhOr=- zh~4NU_WdPmb|yO@Bla}Vd4(&l6c3(SmZhP_2kr-QFzg67QBd_Vk6eX(Z`w=z$9chI zi5Gd8!HpBWd@5cbO0)ulWuK}F`}m(DX{-dA+HW1kSOjE;=o3c7WK%R5zJjg2gg!B0 z=W(n9JR3%J2y=(Gy=yS>{$-sgEiv30@KX>8FwE<)%KO=)I5zFVapH%H(df}aKeRamA#_-BJ7<_fLE_h}HV z>X{7gxRme@Fz)2SF#){L&#er2ceHptc}=63P1<&uAXY_sF!k#Gu~=hdK|61y3{5+Sjy1Mq%K0sSLd0v;hl^rf z<9>8PqW4~Si>soReu&zpXp~uLWQ(b7bJ0%v6O25e_?GkH$;|FRNWTe(rx@ z`);duxlxp^4r=y1@15NE9epoE+y0aIDsoC<(R6AxoqHnN4<#}$$n*_l$u{*-gFWSU zI60rI3-#skUlf-NLyuDDx2tPBLoxAO5#*>6-}J4JS^ij2b1x+_nzYSuDE{WWiR!IY zHerwA3lTMv=@on!35h3Wn9%vtcf2E#)$gsdcvL^|zP z=YIYaTn)9~NUQBmyBb>USfJvajfo{%J*;j|{&!ORHNQ}vAeLm!>}+1TFu`cINbm>s z*S)KOCKI}ZFH62q>!qYLoa>2sS+06**$!{rdryApwtLgd8k+Yvm+Vy2zVaEKx{#`) zIOIjWbELg-GjXvgo%>zQy3~qXFS3Q}#uKO5Sx^McI~zTk%BcoJ!Xf^Q;YO7=eS^X+ z?Kv(>+B(@gN;17<@D!n<{LThMP=pbNt~&~Egr#Xd(r6T z{xGL6C(^VPk9rt%@u%Np4h@)R9#HY*8~f^~h%7vO^&xPq`pX45_E++ISeqe3L-$E! z5TPn6iaeN2G{nSF`5oFHdb$_{uNmGmZ{yQ&%~Scvld~baKt8uVQ4<(RP1o?c;C8S? zocy`SE_%r~rcyBCwTyUIGQ6ezwkGX$HmNawYXbZAIsp`{zVR3m&d04<)aYW9ln*V= zu*tTP4#da0B;+&E3OWn<8@qQB%_POjw-fcbrGB7GM&|&$~bq^dU**y6_*%piL`| zvmn%GNNkalIelswWDxgSWl|8)peek7{KD{7TtXqbXGqJNXFtcYCln^~%F2-@#K;zH zkB)Hx2CS}930l;{15TYF|UmdXn=ic}}DR+pJzXQrha#c)$lcIKUzDO~6UQjsuC&-(G7$CgRUK zYJ%=mNuHE7;S6J_4u&VR|6w1SeV}UoHk#nS^Nr`4id1FO2%lrqa>KI#gyr$5+WYqhauf~ z~Gjjp3bJ@6f_2twkCwu0$_<`A4v^WkGX%98j(Hl{nQVW9i#$)kEt`{8)W0a z+=o96N#d{ukScH})v;pO7Z7<5Y=T&{syhD5y?p^iV*|-wmzpP*?P&_g_ByZP8($aQuUt#v0GcvRCrnO;m;rRWw=FfMA{^4KCibIFdGU+*n@D z#}PM*-Wz`%dQ6fz7~a%dEw6Luu^FK%Rf4{xcpu(VgSxPU{24HFq)PPa;F+ik+C6x> z`FEs{^6NGuMGHw~k(!R7NFaX`P2}Rv`S%1{xq03ZPUM(X(TI1xXF=~*!aUN-^?s|; zlSYP2}65Fyn6!0ex4z2%^O?*tS5{44V>-+gyrSQ&PO4RJ4W~cVyBaiGI!*8l+ z?GBWbfweW-mA@cAmiA3e;yXi8)ApV);-rZ#f^Ykn#4+D{xlBxVmg?C{%^2U2fpC+H14Lvu1{v?viqH7TD%Jqu`p|3G~BS^+z1H2NQ&_yIpYi z4;#}dBKKRT`7Nd5^05w6`{D+lQo7b6&7K|<7hc=-AL=KXt<;_*B<O>}(8s`Z@haCh_Y{kDu=G9?V9&BG83(quLzx!s74-i{Yv zvj2|imX8m4VJg_A%AM7nXYuycRJ>RDuzFGHw{?^kZUheMT)j7qw~}msa(UtyI_g@) z^<{<=%c%y7(CHrsnZ0X*O#_krP3A$w_3v+(wD){=hz!_ea-1*nAKE8R63l(t zZe=kF4CcgoC@-N_ZbYDba0{e2+eIQHiM!@_;{N)>33zeud~HL5xLeQ=KQCXC(Ot2< zu=h1$>JR&=W~%6&@x`XkUpdh%Qqz7he{%Y4fZvL1_v;2*$qBuuvY?>f&d(dc^$__B z{sA~i_XSjb_<+XZDijqK4nXZ(LqlJvAy)h&(5#52rooR2>FQN@1SKV&duz8-KV@cT zx4~`&7zX4Q12t->J$volHOF_1AeNNLdi)p<(NX;`oEI{5!8vON0lpwai+u6~`qDz3 zavtJC1US%H;M%x^^tI&xV1R5GAOKtSWk#Y5hlc1tHF@)%a9S@C_Wb8lRO~yGVo#)o z?B8au7=%P4F^&i;3f_)P6ti&<*piW2F3`8ZI0c!|NccdXn$3y|$#yPT#{EuOcJeuTKMpDN@r=_LUZQtD!(`$#E zTW7+{KH<2RLU6mgqoo#nUMSqWnGt+icWf1CRobyv13FC*Ii=!3QgI9DM-dqy90ZUO zl8#$uW>{-+?B=E<#LFlj|E56FnWb_MND(})VSnZsU^Pf+9zrA{0g^^aJG3C7>~%da zDk`a`3**_r*22x4xygw?W-rr$T`d?TeBMTreW-{kc zh(a`|iK3t?U<^cbFvChHDSc7pOPn7c9SuWD_MV3-wfUv!^C66Nj6v&fN=OF5al%#R zu%@mUf`}j~8nZeJgzHs4JLsPU#V8_K^OUpSt(~2*M^8LZ@@kSH8#!s%KwN0R_xeYJC%1O6nB1HMFtQQ zsPy6(OQLuegsl#UVJP1C;t@nc!KMi9f1P`cdrAmp4m7AE?zF~cWw(7|0kg_hMn4k$ z3_LB8{>Y~27xILH-4^s@BXw>gW@rbYf{hQDG)77I9W=&+jhfVdcDfim49{;a5JpKuoc@1a zDKyAmepAC(D@X>$(7eGTq=zF*J-}ZMS@cWcgyu4&5LieBCtsT;hKt0IU37OXT zUf@6a{F>#B2{GJ)4CGG`LE{EoqRVB&&sb>Gt$~q-C{(y2@GObyoCPq}?{KNe%hMCp z=>_yPaKybOR=8~z!2H#Yf$SCpx9wUghgXpC61aUeN^!p@gYXe#e&IV}|0FYl`7^S< zcfcgpbbOD;XmbiCMJNMQybhx)+;-rTt0emZ-s^A9)9}oJAoB5kC~fB^@sly;{JX zCmIzuyW7h*I$S0Dq!W|-e>8msR8(!a^~_L12t!DBgEWYM#1PUY7B(e_w1hM>grIat zh?IcHCz2A1z|buqDyftR2$D+2|IEGjUyH?Z0ZyFro;my7&kiQx*vEc|`bkbXf&FZ%VS&|d9s=fU9 zXo+2;+fV+p_xt7sYP_CzhDs0eTKZO;A1 z2PMuv)=S5o`?5h)iQ>Pg|La{>SrJ*B+I6Tg8y6Jdh&6m>5u$QExIWgnyJNXes!BQ0 zS&L$;`fu8q+jXYK^7-dw+iWS@CVhX-_b8>Ze9BEYgTjag%}>qDt{qYL9WQINPUalB zDQ)dHwQJZ(&qc%^<+x8u9p+My30y2f5xTthv*U}q4Gt-C_L-z^)gjyzY+i}q8#`Me zq&q>v8f$MZ5qzrs^EH`8Xam>FnJ-VUw$c zDCCpPre^nGq!sxkh$0tpD6Vf1yoj~L%wBj5pF79bsoei=Qq_S2#hfiPT z%N}j{UaNs$YfROC%iOusq=7e`(DZXGz@zc;noZOL9FEMgaYu^?W)#`{nIl)i-5xr` z6s|=zh!*A9N5^}J=%G^(?L*aRWvKezLeEopvoPqo4#|e$zg`OumkB2A8)R%eZyRES z@|Ve#K=)sX@s|GJfa|5cRHQ0*y{Y2Q^iNjnSOFjYgmffn(k-vWyJue~YKqc#FJYKU zoO#NkOmO?PE}64`=Uxr|E&VfL<0UVb#=o+7l}BkQq@&YB&1Yg&lrxi0Yln0^s%ZP6 zU{!^Y0L7xxW3e7tX@NBs)B}B+o7>E5q-H_uugblcq#@7ILj-q`??)}A+9a*=EakXV znrH(q>?1o-H8xLMf6gRY9?vXRn;O+u%l!7S*Ke@Pzo?INwo!b;T9NHo+>c54RZd#` z?i+;#mE_!m{YWF}B?3L|o4@5{R}pG7m`@X0e*X6A3R`}uI<>#>NF>7dm_hO7?Wvj! z^l*`U2Iukm-J|Y!$Bnx=@Aekyk7uQiXIXB?h)^oY1~**tN5ver7kLoU)nB!o?H#?- z8E-VVFd9OE_rKJdIRru=q7$m^bZ-rkp4`D*7WlA%c^|l&rNOZrNY_^8D1^O zDXIK7y_$94TV4@u-`aU!H1ALeAz8H2!4xi!^U||aztr;8iKRT)hpnP6y5T#O;;LHP zkTprzo!km@8rPBDBpcb-!g;nA=bN5ZS6`vg3!0qr1yAld^ReZZBVX@5x`&FJL-A6& z@V+>A(`omTAl=l|v2bwTnOoGOIqjonWPt_3v*}r9W@ZbwSWi)melLZOQ|rMIPrgVV za>P;BILV-={3)%C#ODd=8Imt8#kCA6z#!ec;Xz@jjHyw0eMRbd81~lub{svsV9?(MZOCFGDz~@zDN$NAXff!_U?2TLX=2xXj8Y?gEm!QXB)) zuw6`FaOidIpd%eNkGVT(=dxwM@nP>DyFWo!ZFaeMY=f^5?0l%!IDDJNWlCxvt>-0D z-mja|bz01L&)G9?z$9{MRAaPt)%4Wcee)e@%p1jf8??M~PA_|7zKV0oTfR#CFj!wq z?R0xqiFR#xaCG}e!J~5ndlw4tvrtYXa(Co4JP2A{vX#g07I^j5?R{D}k`rElyc;tx z2*Z4ivr`jp=HSo)sUcq>ac;+R*vtcN^jWBV3ALaCot8r?1C`h6+FGjzr+p7^>T6JV z1#TwiK(@7gcLj{COB}S&;2;569Jw+8eHib7fB|lzP&y)${xtM$hOuyq=luVeKM&eyE5x^P=}zs)kBw!=wm>HyC(c$;86 zXK$ziDTTTW16!u$-!P0f0Zzaxc$^P5CAj~CZRX(>#Q==#W6W^ReFd%jp=r6#|KJ8T zRlndz)52dYBPIkTb#Sxa0Ah{c!3hQ*qJ#VH;VcW$ROMPrJ>pHQP63V*rkY^lApRC& zZ`dsErn@%$e=R^kibU^)=xu=9usiUaxZB|W3@Hj`FbNUi@Kh_o?R-1AC-4X`eN5dH zSm(PPZ@CE@2i`&*{zRy5)>P$oDDHH~31S8tvP75)C#|fqayLU(TSq0BzFzFwG<{CbGB0IU^CNIV*0w9|)o)lEXyCl)TLRyl}Ds0A{_P{7arvX`mnL1jyU_ zL<%frfKQ3GWFj;I1VJn=?zUq99qjcsfJ7d19jA!E;qJlsh&vd~|HoMb4y^TWH{B`( zCxI*NEv>#GDOzY5x&dndg-9(k7ET5fM$D!8zlN2U;N`X`o?bg%U2})r9~yF!8UZn( z1v4u{1kvjOhaCbZp$-Q&0N1zWxZ}0OBH%Q^IVZe^De9)ZQa26Mya2%piw5>8#626t zT5kAq0x?#_3r7`>ON|N2c(*Ygju!0pz|&Lt#RgU_ zz&dx3U~WrJ9sWAE0dGZ?@jBEtLeY{HYt}hd8q2FG>3PHhxwZo;!#e3vjs=*{XD<)| z89Xn@4>UE}>PG(fu=VMy+bFOTdzcm2D;lWySQQM9PTO2n~v z6#gN=UtnH|LRxMx+Q4gqp*ZZnQt5<$6@x2?PynWrhcCg22TW)m|Akz}BwMfBED+rU zu}bzKB`GZcKy~x!K??%M4BU4%6|7;6#P|R08z?NHgeff}P#xJEC2M5ZEfERO5>{kq zECf`MClwAmqVt5*iYFoOyYNM~#=nCgxJsmW_H2@Bp}i9DvBpHy0qqh*yU+;N1Nm+D_m2G7%VW4QLF+1e5+p{*F@&8I36aau#2^=uawj z(QpQWQ9;1j4)RU#7Qqo@OVP7!24_t0-+UerL_iRK>rRmRLUB>1n@&}0MTYSkR36n1P`m~kOAFR{E1eCMX)vz`?kPi^bzWv zXv(Kx?+7mw3`s-_7(nXO!~$jVZkseiq3!54DNwbts_K3&$zG7%n*6ss0(;zeIJAey zYbWX>!w_mZ0|lS<_C#n6KNc-CmtdaxAT{uonC=D32$Z?7d8*=E2THahpg;=CjVie49zCz=Wsg{plulQ z>`4!YB!+@oEJ{r{@fSsn>T_!$7^QPq>8@ojWK7Wu#Bs4|?0MD6-D98nNkQ153D|0P zCcmIQ;o>4k*MSIA%#S}x$<@LjWs-u(gk=W2?f)?8;ml=nMKC0+IL1DkqEXy!5}TEy zFFCRJKGQ?>@mF4}zPBP;|INiB{^JqnN7CNU@1-iIKG=<~y198J^vys`XO!6UfLfmH zSN>PFchGBMD|F<>{3f_5M6cJNdg+ucb9&zsfnRl&;${491iR#r6Ef1TipTx)Csb48 zD$()N^`pC%j9KB~EM5rTSLq)bgYIfPQ@JiNd#UN40epN4iJBRqA8c!l>(CwiT+)=l z-wELwo7}l55q!G+vj%U@iIi~BF;Ab=Ay3!Swfw#53(ix=0|_4+A~KpzP@7XHC%K#y z5hIP1%A7BcR<@k;;gceBVq$kf`dG52hDTea#X02xo8<@be{_mYVhB_|0v*Uhg;fcP zvD-v)Po79l?pm|EO{QbTPfzdbjYqvlq-Zrwg=w%anMXYlO9&BOXORz!kfqrA+*x4V zKirAZCsTUmVjY+{YjXbqrIWKech+y+9LAsGm$zMG^<8=QNM(xK!8*;#IVShm zFh?LHv&PE)T;%T<6rTTMaa5C{4*@BUL_6M2d-2~{DMmy$`!K?2GahRbhfFYV{J}+n zljG$ec|EfwiO4vrT;_E)x>Pc_XL;`(&MvUGripXQdu{Pq*m?+RsCA)Yj81F4p})kD zq_bsX@{lY1;S0nmbn5pkPV<(UJgZU<2GS2z3!JI83lAt=+CI3Uo_Z+fTglm{upc$+f4PY{*da1QtE zQBEf#_KTyzbitJRe2K`v?PgP(m45@DejYt=5+AL5VXGuv$^1Og(=lFOEH9^j{dC|| z>mUbzw!3U?LTkGNv&XL$!6Y%OkPwP^ZkN2u3GAOyy;?HT?C=zix;PSjy6mYiMh+Wq zwdme~QmcP`DE}iV*YEz+L@*j$7#BREH%)??(T>+bw=tr&sFUmd_FaFW(G+K26&J9h z=)Sfpz`1fxmQz$oi}zQ@w2~}3+%qU3NYsio`)fDF!#W?+>mkQ9r)aY8zu2!F*A8D6 zRhJ?xlk)|Nl6Ki8iKZ2K9JjDP_$n~j)b!-HHAQ~j9S(yTR1f9IcxVsC)q)I1*R{isbmlyQ4?Sr!o_tJ+MDt*f;b`cq4-3XUE2K`>XBl$c8C-fN!|88s z$e*E)qF46gp;G@F=2@ig9D=x{w4-Y`MTsGgqz87-j@Q_ZXY-o9%tc|Tm5p(}cN;s$ z+-9NO9U5n9G;KV;=v8w`OPl3?RET&|5(b`8n~*ZRs~(B?g`auY%9CNL=CQ{C7<-;e zD&JbCi%cJz3HJ-WMYhH*^QZMcyydP$^K2z}`}g7XqhABkiAST~+sN-X4u8zxVdpsb z{rBko-Nv65xzB&5zk}cP1JZ66;d1DLVXk_`3Qg0^kj}T|bpg{AuyvG&V7@22vX2a^S!K7!2Cc zu}`xee^?E&hdemjY-EE)ia*S_N4eJaBH&vzk*9WbcH--3O6cHgl6av3!A-EVl5>)2sGj>vK91UMo?QhJIfEF z|6XhsXak74g+zS>g6PhOivv23wV?LhJ7R_5G&nw>Ns>q(?=+nR0hk6nEFU%CeLGc9 z@Y`#sh#A?4tsx#Hh(B; z%zp8?o%Wb>>O=(29n8-mIi^J!-4S-HFd+bVRdDWtjjV4rg_sbL*pq@E{_tOx1eOkx z;VX@;pIItt`~y}YMvnTb#({9-<#$(NQw=e$V)?^3+XpF#{$2;! ztUPaLs`1|-9yrX+N~E(8%MRy}-iq#P?An1p-WLB7AtMtr`V{^5Ih^jp@#TMjdNK;1 zVue5ja&Nois4PqW(;8r5kz_by$QTR5y3*d)&d~^W2M1A38P{d5F$;;n?&x2e{?tCiI>kbRL z*$M|Uot!scgz$gC$<8`zRHMi6pPioFImBq%S@zhjinXA%0N?E~hYeurFRb!$$Lk#n zf2#*E=ky(Ht=QfTL|xE<;z1Lv>cmr53?XS9dWbIII@?6Azr9Ky-R{2i>wm^saC!ka zMZ~rMm=lX)gLD<}P0EqzVSp^MkWsxbAn6di` z>B|2g=D*pp?JCs85&V6#Jo<##gp3nfTK32q}mDO`|g&;iD$O<_l5u#I9hUdP*%Cyt&wyUpb3Y0n*Dsf z4%XX76HYqVzeEDNf!0lARekJk8-sF~>7c<-GMML1&?a2hY}H2$q8@9CCRpTO3GH&g zW99##E$Oe^2tPxf9+Ar#P1(Mqy!-Qjul2E8+{CrKc3#QGXBV!U;EfAOQS^(1YB}6_ zYqE8E^+Ka&?WD1n4~O5PvAvk<&AnJk$@+UEVddMWNXc%6k9l4$UpC_1-?8k~trduP z?^gevKkc+FM_7xLg@Ty%pR;F9S({ra>)u{n7gPKfH?Q!g)7gW0IGs$wmN&xz+0*Ao zugX0pS)ETd>dsk(Hw?&4jin-a^$u_4BM^R2+mTIHcUK2#V(8}nhBxKuL&0#jiXnZ9 z&y>7Z5P2x2U&j#$ln{=f$a-H)L!eBAgw=-Sv4*=^+_kdmQ}?dzjQ$$lr5w6s9U4UA zp_F*tms^eA;Mz4?wwn`QZ96INYbh4yN;Fig*LBY+AhLd#h|t-MUub47L!aw6$@CC} z0WlB9)OhVqdj#uA9Kk8CtRUp`rtB@LWLjJ5-RQpyGt)PBC5|Nv-sFBk;Me%js-r3- zhGP0c=3Vm@mUlu)Si-CjNvT!!sTO=;;~PWtn`Hf^D}LjR{@>5|`ksUk+SsD~_?YHv54`HjD;x)&M8hUg4deaJ-n7HWG_tYI+PK3*d2v|o`b3=0` zRgGWOuZkyW#<0_QBcXx&M zc>f5nYTxVELg(7ew>NXDD62eTYvPZMf4WN8my^he;=VS+R%A?3_X&~yo_yX7=VYFM zepiw^$je`-Fl{1E5%+~4t4EIJBwVCwyqv&~6Y$Owoo~H}@=WNs14>F*tdA4RDwDkGM!kLl9{-9qERAw-o}o7#8T;OpCeB^K_iIvB3h9k%)<`l^3|8a5 z^{?)ytV>K}jwaXj?<5lvuQs-PaI>Zvrf2`Vgk4M<9HH=1`=G_2zz~PouX4wrUE&)D zJ4qJPFuK_B(&R4OiD1KsW1#A>!!OiLt%J_OyR%B;2kAee6@8O}&wd_gX7;7Ej(w{T zIe(U+|3cr3q_pp!akzi#9&+@ZhldK#b<^?NpT5NrEEaS-iro2kxblWkx9c-l@{q?KduU|&y ztTWAF2X$N9K`X0@LuTv;uITP-X475H65E0yiVRG`l_9)wK_RN(1Z-!CioNCxH z0&7KJ{I%I5M_;d>xKvWCclu7D#$x_=N9`ztt1&NgWa@{%#vDe)BiOkuC41rgk1icI z>whqf7+?@brCQTu_s`m-XZ2d!`_q2CajIdJ{zJA|Z&Zapt?{vl@EA`QQ?;g3yYVve z#|UYQ%IPKxTbZ%^yXsenKr zVtFHwDKxJsLvbMxO9XfCo{3M%IAUK~c+>Lj)jdZ!1Pnd(1sP~UD}=s8eT@wLeVLYzv})3ve_QdU#hdT0TT`Sy zfOG7HrKffvBpqzxfSnOIwy4EhBi_nUW`FLBP(5TEjsKmJEhCtrR?pdX193kg{1jZ3 zH!-Au<}SbpJ5v2GUtMW5-0ICj_J=tarJ=%vT-Vtse+Uh564=$r4m*lA;rRn~`OEZ- znadwAS~9P3&bS`kJ|DZCwp+Tn=p@GK>*b)O>=nGz6wC#H`&Jq3wsZj1d~w2%_Ni1u za4J!Q!o%Zv+v2_0P=k0OtGmvgq@*OIe1-inHhco{P}o!dh1ksV9|#lJ#>f$+)Y!1w z03kuhxbrMfou}eV{SSl;;XdSgLxZ-^T}W$hcfJDiWG%G4?efk6O}3zq=!bJRrIPjq zg*MZ?UaTU~L8rf-s~*_hVY*x}l_V{QJKep@4b3mWr7u2S`QE6TKV)Sv2$T6nmI*Tu z+_uem*xL)QrE2pIzwadoO`ASMxZdzb#>sSIIXE}o*l$&-5&r^W)&Nl@VkijQg8IimC! zO6cX4Vb&r4hIcH+MFe1a#zyQkzI zT4O1wUJVUI{3|8F&NVBdS#vvfe{cV6F%%88ece^dXW3rv_&UKc2B%LdVXIilD}yZ{ zptv(OaR{t`@`dX=B_s_AQy!wxC;*7sg*( zkEQbmLfxgR8+W)E@MHee)ajJ3scX|Gr`IOp=lg}!kJ7|9nfI;~G-7^9*Y)L{UTS3I zrr^0ofAcfj=*r_4Vp?<0%+X3RnjF7TXh)9f9nSgSgwb)h3yVoEhle3!X5 zWV}Fs?7r5d%`+jI_t;)OHg`0fUl}_W#;UqZF*@?HHM&!HJPb+HXsnKIG0<#ojkVx@1MdY zk&+78-$7*FGI{(iT@JCzPBy~%$@v6M9W(Wz8*A>^QMYfbw*AtJYMb)%kyh(jF`-6X zAzR-473(S}5h@SEm;Tn7m-7bl9>@AyzG=SVrOLX~rRwtJFnDEuZt6my1Nu%?nQPM} zF-bG`N>{62ay^;|vQDNxK14NR>fQKOlp(6rmi1T66^Vh8Di?gxg)iMq5v;gdd)pk;l^X4^;(p6-WJv2Etkv~pK7{1ZuL zBk6c;nOdw<(vehB(CB}I>d#Krfbs@Mc7E22`WPdL^QFinwvLK)#xQ}~T!;4*b#Cfj zlaVoD4Vm8?qL2zDM7nkGJQp#-3$Z#Eoic8a9uJ@MdTej-4dub=+kx~}CtEgV?$seZ6SeK4B*we*=W*^<>leeKvI!}0jzpV7Y& z-;+~)ld=o$8e52DFX@v*RV~y9c z?(;J7@)m@8kv=U{_*5cojsB=3wCVaRWN(tjlzd03}B z8<6$aKU3$Eg$@K7LeVVUbH^N7^e&_sb`m^=-*5@6yDjs!Q3Th)f%(5?%$I|bO z?3jVQ4|~%O$E|?&$P`p4)<%IzX|hZp?UAfx&Y{0)=b;ft((L9Yo&W3Hw5>Gl@X zYyZMDOd|p+5E^GGkERh~pUe*@esu0$G0-BEFY9KIg{XVRcB!bTjdWL$qMT4VQ2{r4zNmvfJ-uAl0Yd>kRhW>$ zD3Pc$%>1%;_-PFkFBHVI%uw9*d?1uyJPiB$^sJ`@XSiXL)WP5mW_565B(g=sAWc9@ zP(K&VA`Q#~ac~WP00a>6Z{M_uYcW{Ccur_j{cj$fHE>&ytg_+z;(7xy5xaLDl3a+X znltWQea2=QM+zXyyn6L2aTX3EQMm&;#EbKfXd%Z2oaL}Nr}+$nvObH4AUOqL7R*Rt ztR4vCwsx3}**iE8hfkniodaLcN45Z%qNNTIRbQZwbvxO1n}hhpW>EPNJv`tw3S2U} z+X60Quy?>ST8f*Z@sJ@{^^U81Oj1GuD+ca;Fm6D>_lS35?>q>_AW=w`lQv_IVlcN9 zpayZGFCih5$y%Wmw5ZLa1uP*jo-j=ZUJ!1w=QrTM!i*kBOqk2U5D~RNmuy`Ig zI1)qzMGT%4uo<{+L0Tff@4lz{iiVXr;K3oru>wuarfT3~vecI$Pi!Fi?a4_2Bkznu z07zlC(VVcCAZG7Cpd=`|CdH;tV0Z9WugLgr}G&@F``m1(}bwR{rccE z{01(L^cOFFJ``f0gjEXH7r=6u*@GUFJo;itFhoW|%Ts(rL_}23rROlHEgH5yF*ynZ zpEt1;N=2mw2{$_qs24OT4S z5|MBdYda9|_5L8q`uI-bvLhY<*evwI(3g(35 zJC8{PlYLyw&wVRLe~U^;FHYb?c>$uN;nQWAN^@bHm?*2W;?IuNQB=VwFDW%|dx)N9 zFuhguzn69=ilmY+Q0$z^GN&eF$B*Zv#{l1@Hly zpD&fW-+Ebywa$SJ?V@9NMuU%3k>^-MNp<)3$Ni^~8vADP8<|aGgh=%-&3!Qxd}n0} zrj}bcX#0;#J|{WqvYU`0Q+NoAt4k_09d~*VJbjN^0)PFv^wc)}2hV@^lfnhE1bA;t zI(8km?HcMM9R+31B6@J*FEDnRR&)Up&)Q;G?+-?wtz17EwLOi0?e{{Vs4Cj_d`;kw z;(!ePeS>Cw@;6OM101}$wdy981kc>pY(CXXecS0 zvgcS=Mc&B4V=6xdNy*)%x8`8bPW~bnEci%_E9pZDy`NTa_j5T;iNkt~WDi;1G+a7$sLr6Oh%`D)K1NDPqDa=aM;gwvGcTg9XL4yO zjcRQu+v?(8M~7i$z<&w>1x1bQJR+#dL)GJDFJ3MdiJ1gzD=~GBT$+my`?tx>W{9B1x7vvYY4MIEhNLUW)Ge ziO*^{_0eyRd3$?*@m;Qv>@#XH2F&M~J-)XKW=0>Gf_Z{0y<){mHk_PQt2FNwF)7J4 zF>_lm(i&cJG&Va8pR2^E!>m8rzS;7<-O92Oi@_3jL-enIj1a;tCZ8cz$Da8dgi@|+Y8A55t? z?bjHaW#~XCIIuIz=!qrxXoL7ei2H5@Z*`j~L~>uh5mRtLjOGSR3|hZc60Q3g zy(fR<;0mMrzEctN*85GZRI89NsZGh6gm}w{`3mJy?RcsX(l6<(*wyF|uBHDQ2m`bAdu@Z-&c;G&-&q{0@0e;A;lK$6w^!@hxfdn)GD-?{z4cq3p+;YM!9 zBL{b6ApVdE*@|}{5Z#04mAdxl$eJvMuJqBIjx9k*Zyx&}@g#s`(8?adXZwtqH_w`I z5D}Zl2mcj75Qrr?6<^ML2Pvn+O@4#xo7Lb4X~U5n?(PTAKf4COHXCLqf6eMbPSk<+ zs$07hqygh?;;0e^i%@RQMRY5Ht`H*pS^z(Qc#XIb+C>wfv66@wK$;2%6GqjN`hvMB#0Y*%A4TS9kG*FWeJI_jx22`9#hII!I#!(BQ0mpc3+o2r*kMxw zI6Q1l3C6Dg2q$+I78XFL+2*ZH*afmw>O2yfuWE^eGGH-SEzTKp7TIm0uuMGuFK`@A z1t2>R4(Pye6YO~^S*GC^;yTdJML@s^LQ*te%wfv**)MBo)gx0v6GZ%gW&!xY@+?s8 zeR)vLc+AfnJp+&o_DRGF21sswZ&O(XL9C!~fQY2E;GKG!JHbi8L7z|lT?^?i`A=n< zgZv>|n|07D-Zxyi_Jqic&h_L)@Bq z6h+!~Pmq<{RpkXY!eXW-`+FSLHzwGL_91AnR7vDX(e>OwBP(qAIVw6ZCd^axOFVj(t(2;nuJkap8 zaFZQ@q$hR%eTC$cyT{xoCg{N$u==?+GhTf{|9;ZeSJMhFf>JUhoR;F$z}u-3J22Rq zHf~Cj#97azGE`Wi>g!KKe*Fn8$IhCj5=x*fzI(|aa2qN-3!?|D6gVH4pC)QZMSJqOFJs}1VCumek#kKnqcRxoa1P#V_x0%+lE4kOWA1n!mkPB9 zbc^z6Bbh((p{-`P<+sB}NAcEkKXRsRrOzDJp8Qj<98*`lw9_-1x)5)E9{A$n(9NJD z_E?NB_hBMMh=P_3`vcrk*Kksv09|v}p&C0MtDkwc!;zYn3@7q&`)BIEtnwB}T|AvM zT4qx%20hA7x*kJQ71PdZD}_Rb71BT7==0{akt$f$Vx5j~x)Yb*d|J^q0h6b(qsEgz zgwdRqmx(9TDr86C9Ob_i58mlMc~VZT)4?;W{8l}{@Z{=KwrGA^muZfx`cv#TgM!D^ zR220({}2#AcYi1Pp<=j3)m0@NMhE_lE-1yNQl)PuAMo@N2wodPWwhM#PJ*&Wd zi-|sj9~1&u5oT>wZunZLHk|z02~reQT>{s&khshNa;x7TXi1E@*nW7T)8kQjUG$6x zx6qt4VR*jfd+5I+AtlD;bS>mu^S@Nru!AVfW37i!L z<)A9FHh(HsE*q=LtT!1eu-bu{+hLt`MU{HZ$m#c;wUT!HrOsEM5&p&U#*}M3rlj4I z{CQIk=5G(qG@Q_ndCkEpERXE$Ylef+=YhP?*x!2pHQR^C?20qCH??gYT8A*&A>sIi zj2(LNeE8yf`~w{}gKg3!@$I3|A+)7f6Ub$x+S!{{_F2+%&dkNSInNrP8jt^#%~j>> z#d!a07!6Q$sm2bs+%>b07Fqf(687x)Yy7zrtzlmc7F+3cc1hHokvF1BrD48(?JFxZ z-#+!*db?2Je_J^$V0M1|XqnOE_#Q{+CW<^A#u43|NUM8?&hW2n;%UoUpQdM@v8AL{ zVP){KwH&^_WpNGPRs0+1Q5tqNUoL!6*T_bE%Dzds#BxpcyawLiiKEuFDR$yq0P8j) z1TA_Op~--v)YsEA>{kpP&&tds4f`^+S2FChdAq}@luj~2A~nD&uq-TNEF#oP zH$5xf_Gl7bVTk~m6e6d?&e!h9{HDeV^)*mDcjRHfF#H{ju~1i-s|sHbtE1#G>UC5- zIP{Z9>An9*#rMy74Z`*ux$co5Mlg4p1YKuZ{Ke*w{Iu~8R08)4Upjee#@+bixp??p4#6UD>$5 ztXJn<73z9(BF}!FX)UchzYfR_-WYL*wE0{lAGl_VX5ovcvsQ%L0fatR=;QURlMEDc!kt!gr}K4Pti7 zh~y(66a7MBW5wLGGf3lvF*enFh)%GGhXNRus_+3jGC%=9ga~%@m-`A3c?Xmq;2xMC z0)NwGacyq%2{1H7JOO+JaAJTt${QN`W7L?!O(8qFbB>-_$maTWFonP`!@@!K2=vxe zCn&Z?@+_W)tv=Dwato#ejbk&-4Me)52y}aoIX`sw1vd&r=mBii0lzVDE}&~8>iCGN zKqBP>dNgp_0%HSQ2#ETNJD~6d&6ghAy%W?1ypn_{S%Sg1lME}?u)EnE2+M9eAS^S2 zp0Xyx7&+Y}HuSS#h7t&-AVeA1TtgOqx61=2r55s*Z#E0q?u;79B~1amty zAkJ|BrPlY_cH%644vvD+At3G4hek!i^p6YR|3jsrYygey6Cfh1d&mh$tH)9(b@LM- z@qng-;UjDuz^zNHWsw0>uwmi)uS_>$&LAiUfptR=uqvo=h%AS(BgpG)0|GLyzl%B* zhfn|qIuOhtlSDdRW`TdfUZ8Xt`d`vBdZUzMR~}<8gSN8GKYd^!!vnG?1)do~LyBy! zh2axeHi?{qKAOMplBNK6M>KuGdj@lix%e|;gEoY($Qs>(Y*TakibshtPDR5rDmhtM z^8su$Dg2@<$ar1+ zSzQPyT7hpAEga1m-FyTO3oF|8ge$(2jTd^+iFuE2ud+#uEqM_Q){v9W&;?qFrYY#m z0wjM>1{%=qVu%&gT|_51wZL(8l)@_Y$j65$odm>c)ele- zl(Lt_+mEvMX)8t=axBtn)_6PKLFDFYk)WiL#zo+dN8J!s?vg^Ad~JujK=~0J=|r}! z;f_NB(-@cRmA%FRf?ATL;9fuMWB~F1Uv>MZPcN^&Y4+eOb*Rh)E|(nP=H@oHGFDaR zF-M*qyzdC)qi=R32mwnHd*Va@rwnTjW(Y|ou#1C>aB=4V zxKg5Df9W?Y?x0jVNywlDS{DSn;B!v^`61MyVtvJg{#V9&V2e-H`7yl=Mf(d`V&N!MkKG#$kDDW2^_{^zTF)P znfaD=U6(D_fYpv9gynGsnpC@~8WqBPaG8MRrn>dK>B)N>{$4inQ~Dc9)Tf~{I12_X zQr%4pO>v}9^_L_JgW+#mt>^6xWg%}c>VsI#+syRlUXuOBufoPq;u!PKwA!IxDbAuF zKQOg?bFtmqRl2$J++_Q%$QcZ~qn>p&Yu1BtMU?PdU<)%{hNqRG|K~^g_x;YO8!aB} zC=V>^hW7s=qvoZrjJv+#$vkRK@%;~3Jr-kr{x?BP_81~ruUzoPEY^%P$#V1yBKcYr z&96Q=i|DpdwtmGFcPi2$6Cr`*OnRelOx{+d&twOCD5e?GlmrW2RvH5AT}!0S#v z7OClU@h*MK?*~P@-uHIiuA7{Df(*Rww=O2KDc6wc-O};L?7E(py|v#<-8Usp7kYH2 zGE>bl9xNzcwq>JCS1;DTp?Ii^zPIwNCNQgsiJA8j?!YYkG)11XV=hXR zv4HMe0a8dvx7{Eirn8U*e=;AU-qv&&cHwZH;)Ja9*3nvG|DOjp6*B#)RNQ%|^Cp~T zmQQxQ(R$O#Ir}CE?(jLQribCuAxm%SJl#lIE@JRtV6_-)ojN+2;!D(@J{;R(-KMx- z&8g~}j`gz+Uvk`9k8x}be>ykzZEM$l<4rnRSVsAU;uXi=I#i80yokrG$WNs?%^|zz zn_`>x&xM3#y}gYtp4WNL5Md>zz$b)Bw~C?~bd{PLY7L2S8X-L%IdP%r^HO)f;47xSXfR>e5CTCk9WkA(Cy-W}D2U2{Z>q>#+`>LHW{k8T=L7NgKY ze7T)C+>yxMrwx;f&EEEIlQ}ish8!_-VpO!%>f^yf?6?15*xG$Alj`$H1Ske=zq80R zJjGVt(!}O0K{*fxB!SW^mt8+DH5Y*s>rd8ThW>^ z&30P9eY~{?U-vKex>)^UWN&l)E|=@ zn7KqF(7B}jGi0-+IuH2cii`P~S)k!8OS5dGDR(qFK;<~#fs0t}n1Ir^!>ya0HRs(`9HzRJu%~FD9)cXLnX0ZiodS@ z4HFl)kRJNmylu#I=H)+zvYC=AL%UxVuUQ{Vc|&`eEa!uyG`cp)V)xau9RZw9i>6~` zlrKNtR6Fk?2hz~(5-C2|UCuak#QkvRAfe-$+_?AW;HINL6cgJT`rSX4-|YxmeYRO7w8li@;zrh}>%V{UcM76FOfA1y0CHXCLOwDC+V&A3V|1}62n=PAk zL5&+wfZ&|9hIGbzul30>2#VgN4`I!`n`#Zo$puBjV&#T=7Zb8jg*ft#Q7fg)exc0% zSuiTxBJWAtELi?`aHOBzrmlsh-OpSNJFXEE64U4jdl$Ww4IxCtCKOvp`2pcQ%)3r@ z<4?c>!(n~ClFb{vs5j5c%!CMh(KCIZK6U2huor?n?FShVqF3R0))MVivZ0>9MOWk6+jVy_m9W>%M#s?DGqTv1m3|7MN+Sj z+GZuMGB0&xtLZS4NRyU&`>N5lHw>VSdTGf?NjrqY=-vANO+!ZzAY3YI=d|&!19g%ME=>kj zaueImIi@?#74lpaIn_8bGND11Bdd4c8Owy1j*bCa0o#c%^Xd5u-lnHh>EiEhMI=!AgbvbO>$b z1wWJ0v(k%(vbL~Ju~lPsS?4%u*}mxUbwH9Q64z9m^IfJL@-v%jzeMKS(xY9n!Kp)} zfWepzG^`!AcEL}zqyD=T3>E5}0_L&5E#rKDDSkRxLI9KJ$#?jx@hY|Dt&0Qpe-^%Xs!~J}<8a zZ)wtLxTQU*_>lBiES8c?C}mGlD1{2WMdlLExP_K}Nab zb(N)#&5>l25hgJ)=iY?T*xqI>^j%q``1o*!q?ZIyEjh<@zyjhtT%_~C? z%cGAzfUuDEwUef%$bqBJ3o^=naOKMyn{LZ0v&lIzu6ISn5C*tU1U_0GQctSxiFQz2 z2v~U+U?!G30#1F#wDqx&&FhChPL2YUR8>M#uozK24NHe=mp52Sh2JdYjoZt+yPjl+ z(kEMxQCzy@xJhlfcUlWe@w`(V#qlj^)C(ozC0n87m_*my_h|gL^7w#%2KN8a^d8_; z{{R2@Ip)E!C1jJ8>`nG2q_WB0WRz^jCVNz5htxY2AtYP&OqrFvLiQ-@|2&`X|94&I zdS6}dxVz7N-{-s@ugCK-sLZ4aV|aAcQFYBGwHnK+##<@XcOK|@Ay^;iQrKO6qM>}P zSajgCoud2K!CPk9iY{*~ui`!`Exy<8lZziHJsq$farEmAb%>lID>Kkl)>w+Dra$3T3Tz`4#Q&H?1K(Vw=@tVedO;HTJGq-1FLKdK5kbyTu+#m4~Pc_Khqwzg%If8dPK3 zd_oZQZTk$NePnQ-(N=1Mo@j)D&tUA&{wpJ!UvbIz#+yjoHG4u86ld{i&(<}D{0Hq%sZ&?~c9oOnc$CVcKIS9VOlAm0vhle1 z7E+a8{M=YLu1K+FO*C;M(hO|99;_$hLD<~<*0Q|^@~XC;9wKZ$G{it+o2r@e@W$fot?4B+*9=k8fmcoeXn|DU zffks&8;(L$%7xI}JW&Tm26tu*l9V#T82YdgxWfM^=rD@v0?xe9?F&>C%inH|?Vnqr z&sya{kq@*L)>XQ70xk}9;P8NGfw&f^EhlOblD(SIgW7h1HgKS?U`7ajMf9gpGvB!D zJ|A#nm{hd`h#B#+QavCcZ^O&8b{d-n=ycI$I{znSNAU^Ud~ zSRcsU?*0me)iB=!=mWulUb45c1c)sm`~%1zEI#l6DhRStVk1lBz!eJ<M$=u%soBa*n^)FyT4OmpW5ToVw@m z5kOIa3{(EgZw;TD0V6j+tGSbw5{w5~*$}J_<$cF_Gk=+=sk)F{_2UN2fBe0VG7>d; z|IZbU8rqY}v;l=2K{-UpfLs%4;rf=NMVf&m6U3*5HJw1N8W|hcCq5uO2zh!_G zsmiZHqnF;<;XI+2zV*K#rCv-a5S|dIL`cqDaSC*lr|4U8_{U*@%tU0Yu?bKm20ZI< zBcRSS#q<=w8+(xkQI^hH##ykJY1)hKbahw zzcO=70M+YwwnB}*D`X(A0Hv!CBiYVuD{g)c2xqa8vODu?AU-ULpWc+fW>W$8`(fwy z>pR=qb1FccR(=NN8XLCN@vLe8DptF(zP^s_5(gD9_@W`1nDq0%-*5U0wH8+3vjZQ_ z|Iu%4_)R$K_Z>krEW`Bqbhi(yUZ$m`g^dwt8v_0SJG%0*OxjwAu7Wgkz|r(iTwc}q zx-bbxrB(Vbt^jV<18DJ<-%U$VbQ_Sk4T41Z0u8{GC)b!$_8Ng0$L>QwoBJ_x?D>gz zKma{JbC~MS_Q8rPoNxfz2`ZL*M zvsghsR;1$5(fSf)A`xgIeI)cIAjU>LHrZA6a%S}~fe9;K$*@6cOnoP9_J$nW)hH^P zv+j6LCMRu%P7WMlid9W#@ec;HPm^dL^@R73-7ITxJ^_U#`@b)i>=Xiw!|lbh5^?;j zb;;kHpCwBD-hXX}hx>u2{8i-8!{0JzT`i1+6q@Dq;rMB{UWs3dvdQKNW8+^{rk9X@ zD_-r?%jKa!*oIS=iO58?PW;iJKXR_?bMPE4Qz$!Ue>ddZ*u%?2Osv=r;2-rz1cvdD6+CE1W1#L4wE3IpeDgle#he2F{NT?EMiP>X%bhxJ zw&mhk=@`7yB=nf{iP14F#uvZUs;4c#3|{TKN4!AR>Tyzj*_xi+JF5KI4_tv z5s^RtAdBK+-=1F$Z-uz4H{dA>>Z;pU9X1o;TqkxibdWT%4fTNW!yMal$#oaeX4Vh)Rd1wpTZlFGEe3U-GLNl|jC=ju zr2FrEc--d z^j|w#K2hG%wn5r6D~x_QrLz?d;laM< zz4#GdW^TmRi@vZzU8cNwsS(}4al)pqHI;NtfkbI*mF@q$uJZ*;Z?crfu|#kp2nx)n zAGevCT`N#V|ML!S^M}yDaj&)b08Yb}!9NV3LaS^t(r73xjKMKrF1+Eaxn~$pT&Tvf zV~=^Ajq}bbrz`r47Mg&V{HbJR@cqlNLAd*}-p)%Z#ERA^R5a_V3IyS&6y4#owkdjC z?@LYhAEcuhZ*RB4mzl0}pXv`?$uWwG@3#-LCpQ9(2a4zV#TD?FuJSk`omns|azgFZ zHH8w!lx|O|C~n>0E5%$U^qHhd=VehE{?enxlqaz9*?HwIO33Hel;)JuSoYfFR6bQ4 zH>aTsOaA*2cP1M;bUXEC9h$!5Md-^B!qeeo@n?kE#nWpX%sTBE^y}tZDk@5J#D~L) zUq$-w-yzTa(8@SXo{XLr%1%-z%vtBoD(`2@xeiUFDK+0M#eRq2wX>B}P?qeQN_vs@ zk{i7cmwPLIKZhoHZB+3Gxua#%%(u-$MAoxGwExev92Qd_7Afm4iN+3MdtYIiK76Ph z+}L8Vy}yNuJ@G&jU@(M33GGM0ea>OD&bzU9SWbee-j(I$`?BEH&zSp+$N%hb%_yjp zm+FzraI?zr7wmx~^k!*bk$?n%U>34cKv5J4U;0&=Gqe5|qlTTwHj@(3t#Aovc_~#d zS3CkF2a`HRqs_%dJTo^yYI9hJ@i8wAF;;&CJ=fb2D*=rE{)3o|@2-I2d^E4Kq7T$; zmYr>4{uDrp2&XaRTln}yWMojo3QoXd(cqV)Vh9<71j*ng0E~f-Rl$-O20Rs2rrJI3 zo{Jq&hJtnnKQfHB(EWv}p)~*LX~%=}=8B}}>}bKcSbp%X77!sI#Q(hiRR>$O91kWG zctd~>U|a~`09xU&Suj_$%hjFB>A~^f2 zF$jxNfBj+xs1rLo4bWVo8d7}>U&D+&a%aaI7I5Y(U@@Wk?};IVJl2>ws5gPgZF6%o z?kg)RD*B}kS4LJ&PJ3G$PUyd~Fb1r#2-bLP>vr&p>`W{8X=rS6-h6kJbL>gOrkCI$ zf%VMZ;ZDZS6qT0;uXrRMP>3L1gcAUa zBZbG0AXvqQ41o4exTOXNGF#h-R^D$-a6D{QHO%m1i#ffRl6v6c!DHet$4ta6 z`yAc{j5fh03|CjX)DX|W==Ghf>=fD#s4W8f(zAGFCR|4<&ib-Sl^GBuEPep}VQy|N zrY&%JFMuq2HGmm@DwcNhAdvC~Dwn|i5H19n%iHWq*RZe)n$(1rX5iJ3(syWoo7>vC z)lR1!vd-?olY>hS_!X+HlVOni^nOcJI649WV`t#3!P?UAbsSm(n==w_Zf-EoV7nvP zLv-Em-tl9QL>x0n*87qnZ@G{a*S{WJn{ACG#EypH=3p;HId6?O><&7GaGrqO24Xf* z+lTO>1RsjM^%z_OMDYwZGPNu}kobMmKdk#%;9gTAd@z9DhU|2Z0ARDFuon#cTkGC| z6Q(fDhu|Q9rXbXfbVcG$Tz#qmmN{OLY~5WseO9@2UL38i1@F`Tp;NTz-p!jg=ddA< z5L-ksf+xmp`OCEi_Fe1WV8&hk_N_1qjNFMTx0xZ%6IgmM>M#=2L)edpN0Mo0x4Mt% z-7851RSN<6T`ii=AE7Gr*b+fLS_y{rmPh0H?2g~zI|)8-1PR<3T0cGqP{YmzzG3DJ z<~k^(L8p7~eCZx+WBg|pPrU!_XuhBMG;p8()1diY4r6|C!l#I%z4_uQR^3F#IUEA% zPu_gw;|+FWACxgMBxAR<%`sUYS};5q_sq1!THaHKj#gUlnH#$!7Ig_49B$fpG@^Rd z!=1iL;)|WdXA$q!@WiY`Ws`kZ%w;xNkSuk{M;cFlJ{|RV^hdf>NtS_} zzLr`1*1x%CvsEP3kC9Bsql6Q-G8b#4w33jjP<4TIH>;&1&+VAIkxOm(rQR%22{MZ` zS0^)^Dt<;C5Kmi+(N|pQDYPXlC-ExzP`PJJXmhNB!%A7q+{5f#=TgKkRz55zQFIgXQgubg+;De)YwfneM$j%$ zU5KywCC*s%56!oVIM*fo)BQc)tb7K#Lk^0pHaxx3!-q^qmt_*_@&ZUgq!qmlaLR8Z zzQ&M;W4Ldl2#7u(_FA3}=-e+H^-%6+i)1fUX?Z+`bC997@#ma4|D-$P__TRS!@JzB z&(5Tt)w<24Z9?oM$XrVLS1s#f3Psu&F)mA6`ry0AF(Fd-UU_|%DZHB=VoM_QwrrE| zbn{7*)_U>hw@*mj`seZD{GHE{OXzG`zleaY(#FWnq#(~q<^wY z0z=|#U-p7*iTse!);G!7$hbh%M|*qUr&myCm$gNN1t-frtls9*h-fW9s+wnDDe1(j5CZ?8Nkdk(gahRwP!3^6)h`j9`8LnLa;@ zSjiiv^>XN3<@~o9oy5W*J-F!P!TH=cx^c|v{<2h17+;lype4n07N_~>VZzu`@LEOT(33(DUUa$<>yvMlyqj=CkAVm6ytHg+WLqGS}rXn=2RLJ+}T z=z|$lT*d1z*Shr{d|*xF68%#Jh7d;fYoz#2a(A0!W7Aw;JAzogc9Nvg5tT< zv>ZVqg>#<~BVywpdX^hA^?(Y39hajQPRPA{

    +%j(gqgfd*wV z$4G3D{r>o8hG}(ko1UoZYcv_2$(d6;ggU)rzTv*a9zQv_Ql$=V*I|*w`}4eyE=Nn@ zc%Lbd78bqA(;V4O`!7;8`B8Bf*|kgDfQ(*mma1^(7+abC3FhZtQ^T%aZN|M+-7WU( z9p(|1wu}+nGy16Z7ez)Y+4DO)mag6OaBZ~yWzJ?#>C)4LOWD2X2RN&>2f2fP_J}d> zs?VKm?p5FCygBT6Smi0%W_9aj=J2DUX9v1y-iAltDOcX+gc55oEBhrd(zPF;K5ZNUvE-|K@ z`)N+zK(+c6LENi66IIcy3%^d6>qQQ1AF9fSxS8&kOJ3D*42KBcNH7R|H|!897+k4B_w-0xYHr*o`I@I=UwDYp1D z>j}CL>vxh8^qMdYreF}xD>si9-gj625=MvhDWroC)0?|W=>-nDn0{1|y!cE^RIy}{ zDP?~@WkxQ)KA*W{g&sHCXgkE39NO7d&7xv&m8`^XJ?QzvNs>ZevpSE<#0Q0(Y8>}f z>ijSc1WxpaWTiPB#j3^9`C`f~8z?g#le|gidc;3HOBh&q>&LoP4yw}Yl1}HZ6*VHn zi9={_;=6lR;?3y#h}QlwkV!~~D|X10(*$vt))ybOQY2^<5HG073?dKef4w18=6RDr zrjjY+J2_f+PkbMh*ps*RQyvf5al_)7@pl^K0*RTGGw}Mn=!;@nMy#oY4IfI_eZc0& z2uJk^#Gs|O3u7{~8~^%4^3IVS8CSjgy2GQ#W+GGcv9_aI#Tr)Mr&G!@S&G?LkJu<> z2g3q4)0~Y42+dJ{c;1a_NzlY@VnXG>ZcSYNqNFepVZrEfeMfzbHD->$exFW#J1o4@ zWsH4@+B>|2&}OT7+p5N)R--_lT4WI0k&;_o6gP*xOo*E}f@hg?-O3bC-##=Mi>4gd z!6anb6OLlwL56zRVMj6e!uMOEQ%7xO9?r`67bkZbg#_0i=%?cfGte$#(YWwKry+L- zLI!xUkB@zNizclCbL4|^$H&K6=J8b&sQYT*X;n8vRt!}HwxZLo76PDA?eBq018O0# zRCuJo_Y7TIr8Nb=40epl1@N+qe$0bd0dM`OLJM>!NM3Z`z*k0`m7iaNb$P_aRFU`* z7@r2JpezfvX)sa2KnbznB9nIu4FUj|kk(o(Q3?}ivJFPUav}V^791^L*8YI|5wtL5 z`viZ>e;qa(hLKO#l2%t zUJE-sm~BA2K?*2Xz-NIAy0RD{Mc}16za8b+F{hlfH93wUovkJ zZ?g`{0E9XxGSEme59U1IP2*9-PNBZCVY>P7nKfD?GXW!YHr>DHhCfZ_@ZOyNtjJq^J&w5JE(7c06K%lc1ZI(KBR&LBvIY#Ff^`TosK=+1&EMg8{wr96 z_0|t1z@e@)K;psk{-G^Q_&^k`t)Q#3^IuyRjDQD&z@Bag%MT{VfvX3sL7<|gT%G4# ziC*mmUFw0xhcIG*jQ+X@W&LL%0vQrRu?1dO>BHSWAo#)iSKMnXYkvsU7;bL6HI=AKa1uA4`PgcHYW#jtc#CSKopz zDz8$SFE^T(;lQ9o%?af%G7b(_9wcgQ;Pe3~?*0)B%3#Jp;1scvHTQK zZiLbY(>(yDAgD;9xwH$#`71Ik1lH=o+0{nSg&?HVLDU4z7HChXqbr7jIe-81jb+d{ zLvZpldh8&_m6_rChv`|84^~V7jo2Z>}Kz?yM=$o&HN;Gv^*+E#A$V`>B^bMT`2K6Cg?PvH0>iB zWoF1%8j4tf_hEGEB|&~hw~GRGd=p<}7B<7Z)v-kBc~ZQRVTK>$Fb3g?l<|k}y}9XP^kD|n3@c;;dCrO(JqD+n14nC^?r*24 zr(*GcQM)N(z0^$%aQNcnBj1KS8@pQKXh*KCKQ+YGUfC)ZL;3+X8kO%wn#GcO)F(z9 zvLTfQ|1vpM^yEbq!qC^Gsr+pJ)>D!Wi53ZP29l|oi(0Hpo)M5oU#pVSTa&+V!!ve} zmMwUtOGQ+`Rw_rFAI|DifV2g%xe&g^L!Q&vm;)6 z<{=YNQB*h(cB|Y~qgCTo56s2Fvf_?c>4@c`F*8kK_m@a0%}aJ{aXxiu&|~Vqi7)z$ z)mqxXw*ZB|@VCZEwl_~?4f~6*$82>ot#T?$WL`JZW$4hZI;QrE%6$X|?dxI$#PC$G zN_gHz@vnKJJRhDRh`p^Bphb$Kp@$(B&W;Yol>3rDV%Vy2s^jZ|<*MR-2ggfG=%Bjx zwbf#Ta6}z{!$`#^31P>7tz&IH({9~|VVa88FK1vpBO>$t4hp5{#mhg!9!bH;DU``y zTBWKdPNKa3?4@{~AIwsFrnN0)v>YqmkEu6BUDAD6rTV9pDq`|tkJ5fb()sFD>o<2r z^t^jihELFLyDf_B#W<^ra;om$!l1hJ*6_>bu?ycAs^w=pD>cIOL4kY#QR?GW>oVH zRNdkv%hUn%$VXcUM%-LiEm}qkGJn-9V@1p)ZVI{Dw-tl*d#SGunXmr%3$eFeRNGq<$EWa1dY=S zd5u(?8`0EXgGUx^CUjGOyR2%6Q86fwQ(Jn!L|Hr^s$RvGtC>{uK4X`;&lRoSAkK&D zeENqhBd)%N=9^@AY{a(mSHI}|;gZR}uo0{toMALYZbjPF(7cR5D>kI*uI{1Q{rv>f zWu|Q}z;9MyK$WceV|4jA&Wvl(7E5?UR-aM1ag{6fjK?DvE}Og8SQ9bkHb(z>CkP8` zhs%C5;{M&Ua*cU(IqTW1z$*u`<|&mQ5~=oN`)A)w$fg;#Pm8b!mL(PbxW8>NQFPfg zApA0p7rP>yiaEuX{4!o}K2?j{_L|!()ujAcM$3PLtcI%iet*3^>+X_p2xFL2{i&pSQ&n(}L?oSPZJ2B8npZ_iIY4CqsV~=kA2X z{2rQ9=-8==YO7N5XRPiFSZK9-Dc;Q}94~J6Tw9^zL5kwgbfpmhgku<(4nZ{k)3rDM z)xdt4yZEmq3rbpTs=vX5G;#GOp3w+v>Rl*^MT=6no4ewKGR|CPQO%RlB3v8>p}EGX zz|3?90r1N}C$OlJtE+4A&&+Z@PV*!*dPTd%Ct%|aY?im1AR3}u@AWL1{(WbeAz%*r znB!oyFo2I7T`v0)a?+uEn_z?a5-3tKo-!e%A1TDLh{2E$V4*BJyVtYJ{i$ z^MBQdHL+VzR}DKRyaR;tpwc^6qMIjt9(p!VhyEC#PCytl!SFG(UJ-19e}B|LNoRf@ znxnvD4!;4c1!xiAKrTui&S#PM@HRa-l-cU(Q>tzcU{>G>p?R)5_OH~+V<~WBd(zw~ z5qa{NK6l01EOp}ZMguObOsb1Sw7uE1#e1}Ddzj#bdpjwj6kJ++AA5<&*l)lrckuPM zNZh`Y{8qX!y&@Sj3rN4Y>9q;bmz{zAe0tvzgvaGT>^>Ke@%qj2gx&@c5fOROL)&cZ z()J28&hiNe>;h}Ei;Q9DtHB8kp1k+$6>vVp&spFF{P%~|z=(s?*1?ty#coLD*ivDf z9Mo&TaNiG8?ODzXbn6T*1cFl$2nIOq$K0Hn zW)JW+d4Z=qAMU<_S(iYy-KnrBnA|}6H=x-KRtfX~#sTZ)0gV#_=J%WY&Cqq=R>7i2 z-T@LSLeO!1a8p#YeQb;zOn8}p{wC?k4ZB`JjspM^NK8(YUqLDhWoAz5S#9!!ia#NI zuOKQ6R3#jES_0-s0pm3j9i1)I+Cg!L5CCroH>TPnZOtpb05U=P0_!_~<;Q@95dgV$ z@oNjQb;SXPg#-=Y0|s`g(ZADx=RD}uvR*er)5j}S^hqyx1RD9f{N&_s(r}hi;TAz2 z!7t*q4>(={y(LLbe%*H3l535v0WArS*Gmq_<|Y`wEtvPjiniakCpwiRU1ig26sw4Q zimevlBL21hXfyg7TiUBdOf4sihkL%txVl;Un#FTI5}9XQ8kK9^8EFxN@taB6_$4=a zpRrM%ECt~n8&DIyPExFO?G;RFYgJ7=xy@9(Fh26|aL zvM0+?l6l1fL=*8`TlvKw|K?ii@+lU+w#!taf9#)0WuO}KSlskiAjb^-0}W5!i!glW z7cXf4nr5Vtdz=YVM+p%q(fHB4>{p;;!|wYVCC$5dYAYw)TQWS$LB*4t88ur<5X&v= zL6lIj!G%(Tb+&JyHy%{`UUbHIK+~a~p<(2m7G?vR$c=~V_ij>E^GvT=Dn72D=iGc4 zO3wR`nM3)&CI3QQHqPt1z1{N2%gF$~>mpC2Tz;8`)-CDCU&l&~Fcnd`>s_}@_1v`n zm3;(BUpR(}-L$RG58^crf=m(0KesJjl~YxhCXG>l$Dr%{C5O4loO9ybK09XQj3NAX zK}>ScQ=~@E=9AzZx|2eo2dD27=ss}LWk~D&qmQ#vl>~dm{4SflX8cZ z_Y6<}feP7eq}4{*DB-n#x+P*N z_T7zE_=EvXA(ohjBY=ikC5oJdkW#AVw+D@yAxlf=QdB&;e{8&Qwd4Fy4F-exkQYW% zRKKp7;?J(c#Q` zBs9WkuKsT9-Ox%Du2f*P6Ipz9@@a@ok_895tH$&jW#IpL0TyT+F4v}dde|PQM76Zl z^DE6@v4?E0nX;(8?!k&Yc5A8QGuozqIr7@{dqP&8f<-oK_P}th=DuZQQ9Oa| zDjpM#M^Oh$?wwx8f2=sTI4{2Ql~Wr&STj?TDWPCZxhp<_xs6eWxk)laV7?!U75JlY z>j)>5IE!BDjnaew3m;eJm6=4Yjc@D+=7@YAjBioGWkjad!5qpi=-QNcirma~7$Nox zohSBW0r+;sSYNp+&pSq=aYmE0BNSDvKA_+%((s1ptsW!<60LbLZxdSwQ()nAb9nBB zXRwCYkA9%{pJ}b9k0%w}-fko`*}(ZY!@TNAa?g%z^t&BNC#k6}#}fXT)W$cN7D>HW8PI0HJV(TT2tAya3->h zuX<)?g5i>=f^XG$tnZp?AGV>&%uVy<|IzdnP*JVl+jOIpw9?%rAu)7FcS=Zz0s?{p z0@5Yj9nzwJh?Gi)fJh61N=X}Z$G6Y@egCztYYA7FnKNhJz4x=9m>N$z>h>5NbBch&Rvj@HD?(EnMv>d@G3Y%K6-! zH1RXK=S_PNp_H869^4cz1B+!(U%c8a-zW^~W;esAYjla5Elt%=xp%*v{DIX4+vJSHlQVSxQDou` zdsvP=`kx36%0#&?=e~uJ$YAI^Z7l%StY46I@qt?@;6W)LouF%_bJrx|JV{p z)`6I2a0GN5AlYXIeoDHG1J025j|m&I;DVCW>BmYnX25~4C>YDb$c5$9U<4Pinvk_n zhIL>TQl@}tOB|?+76x(f0Kjj44*+9$|$ zw&e`*y{ei7JAE}SF;hW23~)5v4k&>1R+#Cj^!Uz!DGqk?&Odl+^D&aS1WPwtq!QB1 z%#98xj(X~NiDS7l2KP<_plwmWgZ5FLByq?Qct_e<4?Zt@0?Y>4>%nZdOOtWbxq>1F ztg%T%Htl2!rrN7qZdP^J696c0s=AzGr(}Qn=PT$%geOYXq`4nkIWDG`%2U}_-_0wAu0 z_<7^1?d?8>U4%RX2pISj`kel0JVxLo;D#fj@uOVHIIrpq2&a&zupQ@9tT z4}CIVlIvdJmH=)BhLglzT!#Lg0Dp?=QJD&lp_%z$(F19*!dZ~$=xLoB$U(*Qmfywm;vB?AC=sSEf_NYmX5 zs17tjfZ4j<7t0w+?ze}?E14sz^zGCS0MA}|z-FT(=a%l7Lv_;DR^&0{R zpsPvPY?-Mqw`0Wo&u0vLCjg4|_lJ~NTUS@DoR(Iwsep?FT_JPnM38n5XXfBCgx4^q z^v|ElLO)!)VaCZgYuuRJ6x6(`l%- z9MT~_X>3TzIrt3EJ(a_maUQ-{6!d>eLhm4@hDO9Ll9gn@eCJ5tS%lIt@{GdqI?c7Y z1)t0#G083MjpgANGew#vsP=kx)wB=g1S=&TedIE*&ov#Vn}fGSlEQKBc8GTaI|JW>c-!O+q(Q`Oc(seb3n`Q6!_I10#pmLGHG$ zQ~Y)m+Annz9kbfV6j}PJif@A4ucGgDa>~Ulf7+UK@qFPp;WHQ2PU15brNOO&Lt?Pe zs@KEfJT6M@5*9spnGnj$}hbADhCRW^@5!j4TVzJ{^Xo&(Q)mA zkGFdrn-0BG^q%_5*#7RhR1u+h;Z`bithgP<#RrmWje;^#GJ!1ih6!T+c@yO+%c+qC zmm@pS=M)M3c0#w##a6>nGQz~e!fL=~4&B=g6Aq12jpyfQl1-L!k17mS9;ftj4R#_t z@wm%DGA&HYV4kgKIAq3KB8+x6c+a0Eo1a*Qj`qE5vDC9HcI^UVZ96uDKW!&XHlpL> zYoeD@5pkyX7ZEE^u_eC3z=%cC4*83jXnEk6ltuca+ zIrMOHSU3~f6T0FGeaLQq5;?4S`Mf^Pr@|}3LmE@;vH`Q?dTD+cDK9E2?h)o7#=FML#g{0{H5=MX0T`TI#<1t0XPl@QZqsn9QW9?t7 zoNUijP(cEi^e&c`ye>Ox^y}pFq-C<)F`fFh7D7u695Q}&TGOvpep_JFUjO}@x(JQy zwCM$^yZle?Cne<(k8#W z?p{a1E>(xNsMU#4Rri1vRos!^g;T?Pq{01l{IMn^#-w42b+}`==A`X95kh!1cuf+h zo2jNpdmG*-kw#$-cO!!sRA?W>?ABVWg0ay;e&|-ozZ*^AIib^WnKQmqi4IEN5*x zSq~2OJp;ow0zJC-z`KD(4p3ixK;{L>BT0^jdN~s@J%ip>oq`jLLfAJ9Vr>ZAmwj)< z$fy$AO|ri$qmPw0VGpPs>tjS|tq<->yVecbThLOZlxhSE7*dz5Yb|pWY9%@d)5L%y zH%DcD&TrFD&unMyARv$oW{o9~Vebk5!)L0;*I70ZDDyO2Rui)1N{m>NptURyGUR>@ zE=Qqnp|x;yH9*N49G3kBTS`WWaSCSEGW=`vgOHm!fEe$<@my`)rv1*`0ZIYDDd11# zm=5PLV&GJ24Ot;GHuc1`xU-0_2rM|yq2$Y@{P$C6n{nl}m48l{h z{R!i1vH9!!R$zVzluXf2RdfFk=pQf#sBqv#zB8)IAOu#OS_@n^--7N4VOG3`#>jF? zS)(6VFu=Jk@A+H|?g})d&CzzP`+w1c_3w@D!l)A1GHAC|@jt(e#hUZ^Cf4=va z!$HbONCcSU#LR~5R!p{%um=ODClJvKeAo)PDPOq}E360Jr_V`35EpfDPC#~Ytw+qr zAEb4v2t4XyxW8rhKYlIJCW4tcY=2&AU4Z@gHq^l#u!ph?jf0B2C7l2~-|f@3%Tp;g zP_zM61!7mtTstQlT%jpzhCvv$^@K8w= z0B{2yHbjDo0Jj(V4nXpN4K!GAKf~w((ZvHGf@%~86Qh26(afXmr9Q|*U=Cx%!x++? zz9)LLVbT`kI*Xuf5R|nj5&tCvB71hm3ocSM*^A}tb$HmHFTMSQ;4I*f1rjxYcfd;n za0OuRf**$pV$_7h&5Ovt^!$EL6p01Bi;a5t8;=Rz6KI@}-oW@pTd`bOf-1_9h!!{~Z+?VwE*kdK(efm5l-N0V`8zY!LcQ%@o2ag6OTclt14; zxypnEEF?&|`yosDyoc#g)9`YmDo$nlzWteI$}EQqdD+d^-6L<42X+0ycOu&D zce5wZrR=&Adx@!ci%+5WE^6q6IgF#HO`yb%?)rF4vk6CynB7jP zMBgv=r}{|;tL3#Cia|?_f6i^V<3c-roR}&~w^>~u8h&Rj7PljR7H5(oXunwH_o-`o6{}(c(xs`SnV-|ixR~E& zHn@@xM3sK7V@b>+x+{{=aQ$sDUf4DE6RQ67C}Ah+IC(77QRaY>>s@D6=o2Edm^^`U z*bS7OBZoHJI>{U+5<+7PStsh+<97@6mip^g^>T+2xRbpqy6^^n`+uIUI1mX;Kfz;c zdE`kRs3Lj#9_Q0|#Z<9qV(SwPJcX(ankBE9TLkUS^}7YmwSq6+JmVi;p5j$!IH+GX zU@QrL&M4p#^EjAUvMyh-AgIfy0 z2Chy~Cm#lWG2b4$o~Js`hy6*2$vgTdMijBaDv1)7rb3&5?)xoU>HAb_#3Z+e*~#)E zw`T|P(mZL7-PRkEn^8NJBmFN_2uZ8VXeZd0PBpBHzNWM@hh8gC4SJ2*eXsn?HWwp& zn?w!k3XLUJHQpN!y)u117sY?nGjaN4G4zy_{8un|Fk%;qzmgi_kwwR`@?g=_ZAY<= z-M$FZ!W(C;*r35=4dAZVV3Ub|^M*@L0WIJIH3j?PghIxZ8#fs3sPi;3+R6BvC91Qg zqmInFyAsZ^xH>cC1a=gUUGEQRMsmH3omO%XW-XBvkC&SgvE+1}`Nf5PC16ByoqVK7 z@t&&pVCM@|646b`LR5F`RMy{-+*eEH+P|t|W$oYIEi6kYj7v~XXU4WOahmv4qc^eg z2VnkhE(edU>I64Zps7XszMhr|G(zIZkPZ3{E;wr-=rN??joyC;!~ImwTw?9rI0*S2 zaumZ;4o;qkXtryE6tEfAk{OioD+>ZFQIJdnP``qg=98b%ax<%y(N2|{^0`F3NVlea zYw_7ufZTFsF5g$u(YRGZthqm)z2kP6fiTnh(z49qo8Hd?c z1XB#u7*~a_`hxdfs=CJTZbT4mOn5JrF&A1oMilJgiPb=2G83DJQB~O+0*noE5fIKSL-@=YMBuFsU;G{hr3r9-L!bQgjl2X=GwzV1K{*SN;!wz2$XXn~ zfQnKF^u$4dHci+)lpTW&B+@QSfuEmf6fY4HGxs%|`zeXgBZs%3+#x{4{Be8mfN-|K zV1>K9yj<*)LYfEU-%KmMNdnY@Sa>g>0N4tER@8q};VO09$;r&L0VV?sw7^{j8yuMH zv{d;@SpiTv1VSX&+hWwfYYh`9UC*8sK=IkA6Oxp~XGJ6H@h{bkeYx`vuzpyQIBq~d z;|k*Aay-=F3hWYhE0f6AnOL}5u~%X+?72sh@U!W#Ot}Go2Zr&czeYt%$|EBx-oY`= z&;$lK(0-e*5-Smz!fFUKM}Un(3><9Fz|{zefD|=-0G9|jsz3cUk;0BB!4UycJ0lYo zY*9dW4UN$k;8pluo*y>*Y%_~L{P_#`FW{Q}2+Z7J@J7<^yTOe77&Qz9!CEr|Kqx95qJ&AgMhOl7~6o!4wx|^tRyg$_Ig@0lVzO&i8dhQ0&9ARhXH!a z09+Sf-T>D{_Iz(VYU3u(CTwZ8+Aa?-wcp8s5~k=*%>$cXz&Zl68?emrba!tD@;Hp* zAlZjICo?zK{^?VToHyZE{uWh}O&~G?cbh3vhdW-tN`VEc4+p;dVmCnzl$GCn1oj4!s9;-fhET`A3Tx;Si^X}hb*;XBjyUS}bC z(l3?Fs`QQBe87r21qRa0_(Xrv3m&E%e zxkc6c9$)eDc9f<{J6s=%InwdAao|e1@Q*cJzS@bcDa(%HxR!3XA9ZPX3q|WvG>i9+ z-pO9MPQq#8@<`N58TUyquGzI=MwZ#Y~#(7f4 zC705+)g~;%-J+8{7jeL-gw4K(1-D&0`5FDd%p zaho`9j|DwdoLYZ;QgR_6X4)9 z)|>C@yNAC5{U<^KS|}@ow7jabn!R%F{xtY9e*UE&Q#I>CrZkx5RbzSoC&!EK$GV4Q z948{&^`ij|qh*}lxzfIZ#fcYM1skpQh9-V>x%4Z}`@f+iTQ^E;y|0*KnrUxTeD1QA z*eLw#710$+E38wsn@PV}Dw*z?jd-vHaJ0Y0#Ne6nY``NC?oLKmz!_aBzt+9NmojuR zZ1B1HSDO|oo^6k@Z*tMw4b?BnkH`Nw_pRm{4KKq(2*fJYmg#omQU=#<@evM_`2Z_| zwf-~u)Tf?)CnA}RM&8ORgt$DmT;$2|TNQ&>RO=<{{k#UQEcgT$CNh1RKEm_Ix{(}6 zbdzAefR(W%p+r?pPWEt#WkRHxDwuUS-)sL2Bk$k>yI3%-K1S2K5ojqiDI@^_S zBQ6S-3c_LbNfKexdfL77Z%I5lgSEB1ZlHgS zxN33AGW0#BLz7Zg-d{Ypxl%tVXz)c_6dmsX6%|zm5kLQxn~%@rMzhBXLqkJR^Q0u* zAKYS&KMQ|ncS?H7P#}9lM*74@NPPO|@$RIHZIY(@~&uDVD%){(I9 znDk~qjR1>cOPMqQBha6ZGqE`2Hsw|I$i$mW4Vx{Ob53sRvQA*b0XBkLFdUJ0Tq(%N z1vV+LUimYM0jB-)7%~93;rIY{0C5ab5>WNc&CS*?D=Q!#Tg&_}$Tru@3y_Fm2txqX zg+zSls&96`x|M){z_`mzF_uXC*?1;soYG`H+Selz_pie-R0rgCdMJ_mtfie^F zp&`D(Tf_m>FmO79#fO=tCE(2P&tM1szjRxb>;SQb!`?Ce6oEpL|{>bF5LbTn`4 zDtDaBD1n}U5Dj69w41$&9PJ<~J!;h{9-W7o6Q(mbYGJDT4rvmgl7=k=d>44Fups!K z5pYQ=2t(G=HH7R1{sdgCH?BEA00uHb{wkCfuW!05*An96 zp~-W4{Ma~$$q>~ArI7?{Msow&G!Wka8yQj>OVI&+vj&NAyBPKhIxJhREqb^$dl*YM zGGIr-i!G0;nOZtJGR6FZ(^17f4MvLa3Uci}JP@U&4Pp%&*|+FFJNtl>lDTd4TXExr zbvy#>tpoLXEHHSv2~7n6@rZ>W2xURX0~Z%@TigXk2qand!ixk1$_Ct~fmitm+*@Q% z)>tkeDKOz|D^jk+l(!D#!+`6<6+-wLa9I$FDj@i9qX3AqBw?D~1AcZlgTYS+p&Y<3 zW6T)z0FnV>Jp+9mxIn@eRyv0V2SAEJ5`KZM3K!zz;m;-5E7?G&l@s?7nBYKjK%(_P zGXxbJ$!fzvcY15)I%b?j9_=4peOjZsP`w12Odj)WidzmrlW7K+6SG0ipPSbR3jKNP9DP{$sB6ha2*u0Yy1J zXlxq-nyDkcfg=ZeMz*CBfZ5~r^Mg7V3SPb3y84c;r}_za9RaiUljB=R+D7&<|1SRi zyKhheT?GsRpjbvYG|N2JqwKZU2V8_Zs>IpL&m_fB?jbO*lf@a zrr=2DbiN8ojMHs=c8cAdQm8x&|gL8K<;KCvqedj6lHCj%y}5E5Q;)BAS| zKb$gfHS2&G1DqBx+kv;8919)6mjLAW%Gd*)Gf-9#@&>!;<&MB*vcK%*13tQ8!2B+E zF5BY%J;i)JW4ESDr{UN3=|ji7f@2*`&czMhkH=}|6_h1Y651Bj*WXdvxnUG|&3#vs z6^hjpUv4*0G%0^I7>l+0NzcM}#qpPWCX1XUCC8oErY8#7IHTMgZj13vN4$hn8onx> zqKwMi98S7hkMhv;ZWQS1097v zTdyCt`iJ*qisNKUWo~zhC6tpdk2`Ax`RbHue<84?e-|K$XGdeD8ga*0pJ9jBHB&H9 z_1C*&|1H0*JaX~-JrxE;IT2V}se2z=0tDYLH9h){>h4tfCELf~(`!r>W4#bxv*yFyn&2!G z%5(*1d)+4VQ#ZQ`C6~JaEf#yJQpEOK-Coq2>5r&?o;)?lXBq1^2hl`cKGtfc!lQVQ z8x2DeZnw1wYvU>{y?-5U-E5qyup|bzinK_$NtwN zOchF|5BY9eg~pmK^0MSdYnNPMA`m#HR#zbU@?3W1O&DrGP&kx1%+WhVcw+n7$H; z-}|9_%wEfDv8nsR#G~QWbgVWf`L5Wui0zt{21~Uuy|v=%$+wE_91K%ay@k{kD-G_4 zvIVP~b4Mp5@7v<)4%SGYfv@M`W_<4>UxGL2vl;ebT0di&M3gw4H4^UnP2g9u+%pe} z#|)s8#_en}Q%4^zMG+(_kP(n(y`LO%{#@vzAahIo!WFYyJGrA(in!#8qB=E>`qT20 z*TaH+0f5FdpEX2LOHnB-h9!Ss(BENGmMbB_qUa0?fiDzef^|Bsa^lGE@#1kEjqa|A z7tWttrUcip68b4mY4|+9K;y;3cKuEc#=^i5dl)=AXom>15 z@4gVZ8Ph6aptIp}gn2cV z1a~Or3d1_hd&VrYvM$lpZ!zb5qif%qYD!3-VPn|!2u&i39JJc=ltHzVck6!hD=gWh>9-7K*B_Au<-4QX$uN+ zLlCdDX9j{FPoqAXm;nV^cY|xEAlL$r|2q^r(hOFIXx7$$54ON5Y@ASZogTsI5lyQIlH8cVN|x_LD{HOer654C3hHG2`y%!O^yVPg9KDBR2fzj$(0`C{ zRvOaU-G$yO+f}Paj7SlPt`VJR^;~iQPQtTmubBIHRS3mpTqj6WIklOsr?C!1Io+Bm zh+@hSGdO-3q!#n%l_{@2P#O6u#nVyADGV}DggSqdEb0Td3_frg7y;17tl|D z?<;K~Iw^U99l3!U!k2?*k8H6KR$dT$&wTl3y=-20?wVEc?z$ z9#lrt08NnA4F&MWIZ}Ni&81iNi{g1!OpdUmua{RzM-ahu1=_P1d9AEPgP(7QG@}i8Qf$BonY#;O2-C(p)!6>jQ!* zwLmPu)2Ux@znvOBE$nXillo1@TZiuk_qkL&B+=isv%{G37W=e^qzZe{rNg!x2mv`m zNcIE3D@d()1|pYXfPsJyaTolAk;n;v#i6Z143?pgltIuM&|d+NXou>KRIz{nklO-s zKM#E%sH&j00Z0PaJ+v2~pn{nhjJ3gD#tyIr*gAj#j5~cKjMV@UKu2fU>=_O{1blG> zPIRKRkKtbd&(kUbENDRL1|vLZYT(zPuD!G1h1I&H> zm`s8-!$|;dAg&eN47O{1X~+$OJaG`P6}r5wtPUwevbhCdQ_{90JDKX)tVx0e@CFbI z)F4op*B)tNca{f{1_u%M=*S)`<$Q3vnFEd@&ss`W&Z2$ z=AfB^IECz!w=5!C)(x?g0N2mMN=C336qV_t!n!>g&T&lK~zA1_s3Gj(omj zOYI3=hV(GR`7WKdI?96G3N7AKXeI#sfF)RBx$7*v80f`e)dMZUj}`C^a_wvZ7A_|R zq`5HSc{Kx{1}gf&!3D$9e+R7n9&?9*buUkT%KQ)+mytRAmSy$(cbcgU6&8w&Dk-vr zZMLo}M%Of>_F6IvAQ=S`9yh*3??xW|APszEs#C`nshFxv%8ac}fg&Na3CWQE z?B5S>$*WdbX+~Buw+Mq68NWPiEPJ_gGWgm0;wAU)Y}*_mZP( zfs6sb)_`Q@V9$48&)wB_`s7mEO#gj}_4Q<%Iwob=U}g8PHWn2*k1hsXbC05gGF{TJ zy9MDd71{XaZQ2K7G!K_De{3R`PoB@)*|iR( zTv+Ktn@jB~8TNQ6>Vc}Zuh}{vl#Y=SnX?8CQ(674(~SBJw5*>4^baqL1~y{D{IMMNq;$BCeqGDx-RNsxQEc*DF4s8U4+tuTCXR+zPv*YQ>n7TpS*vcuxaJ$DQ#YsY8op2960F6i_I1KDb4?w_ zyslJMaNZ(jlYr%juY|@vermFrkGiqn%xEZS%TpG3>{H~Hd`8!ahq6=P{CVx(5N?<9 zc-#|T+CY=-Z5O7h9fGZ8%qrG-^@E~%?$A}Ptt`Q?0ReBf-==gp5kmBmCb%gy5&x1! zE9CB3GfwFz5Ma!w*Y8ncr{FVmJJ7O6*uDt8n2^r6H0(RI5x{2Oo$#yOlv1qCq53pV zf<}oG+24A#-5w{x*^)@JtWkXIUjbpJX8e0BJ+ie>P4)nM_T6eO{E_`A51%)g!-ILY;rJ#0(RT`)}X zXG7%`7h}sv-zmpl?@SNN70Zm5oBEHf2J#0#e_FVwN^)o4(os6$<*MGcwBuRvqHpT* zf}i2{h34NanoqBcS9hf@3H@nL#l)s!zaGie=Qt+B1wx8^i_WG1Y$u0^z|O+p$T)fG zdI#o`_wti=_>n@Rd=~0QiD4AjRTT>IDVDAfCx>TdQ#6G-;%C`^;zpsPu+;u+@i=mQ zHT4S~n-|B?CTWAf%28xho=n`_7G3+1qBZ8&;34x=@p1jXprrR(IgwTSPQRX;@2l(; zTpYZ}U|5+QS=0@xVN^y-8$XV&5}1kK@=XoVeW=;oh8J`2mb4`q)!WW?pSqf(&8oz5 z1Er9~Pb*NWe?xIA^9H4ws{6He5v>O#ii-PyK{v;xJSSWF&Kqc)TnNLq7|bEQkX;I9=tenXWcKXNZf^18;|7}J_JY)$ zHfgrh1QlqCg3%6U08Kk*zswu+8?q5B1ivd@%4=INPKKYDSo0=M+!JjAbOkKBU@pR@ zPdwf^_K&*i%%&WYZvQQRH7@8z$-a1i!AGFobEi=xUWu6J2QR9e9Eea5p(ZkvtaGjV zlg!Gfc`yk>Z-eXG`g*0dIg@$1b#A?{vwt2N1%T^6VD0TlJ-bsAX-f^BSim>~UKju& z1mOywUYGw>(2bAYY=Kb{_8!qnAz)bx?7%rBt9}RsqF|lX<3W$jjAU+RW@gT>t>H0Y z!7ND~A+)Gq_|=&j2QVD;mtMkJ2HU=X0m11HI$~HOp$+fC&l>q}GV=8o*VnNxD-GDO zr*w#FLGTt-5J+C<*&;0DomWTGl*(g=uV{jqrY9h_frA5_=`>oQeONy{HLNniwoCo1 zTN*BeZ=Uie?Q6&{{|sTijzqG|($JR0ziiWbxOdmxEZNqyF=|R&KJ|!Lv6sf)&U2i- zselJ{H(JTg{%8Moim(}6_b9^~aKZe!hEL8iyp@(M9#-+z7;=wp?oUkn<@bR~;XJSa z24v{-04V}x3KCrf9=Vg!;A97)&AVol0ACsYMPD|3=;BiGIJ2xD5O$y_)CBx_@V&_+ z^zr}_I^jnVeGiZs{$~X;K$}{RchG^$ASfZSN1`pQ|1imO8_9iG5{C_ z@J>O;0lYw1-ou*#LL8&EJSa@4TrBS&O&*xk7+Tigg!|KX^*UU^w8<9m%Ei_luos5K z1%xk{nwx{cT+I3TImz@BaJ?I%k#r+VRJL6QL|k&(i}};C&#G5&%&Ev;ti$(1I7i(hWjOu=CSTzKJ3v-a@Ydct^nn1^I60 z+2Q5IoV7Xo>9rEUOrjTr?TfiNTTWS2bX4b3gaOsjqk?8%kA|g)E6BQ>rP~6XJxTAx zme7|;t=`tZR5DgBY?Q(|XS=JwBQG!Y?%FG3RBtH%FNJ!HR9_(yVu7OyA~BUepToZq zEmPJdglV|{6mA^3wIGtX2$4xI6WVONie&4fYQ~NU4_ApxG%Bsu*TY{WC3)JLG8%g< zhtU=trTAAmTqzn%`ieoy_tbD~ze8_cmKANlnsprAUMN&j|K(50fN`}jNursua8(Bm zvT_sBnX}1_s2_<_$`Z8Vb@=4t1;sBNONQ)N!vn8lCp$-VNqj6bqFW>U=E!$vUx$%p z)URvz!3XKc_k3=OJfD}w8>(OEA7(YSc#V#uB1WZT&K+5w`78)H`Ureh`fgl)rI#k} zR!714C@g#7XA)+ZdH?CXVhL%d;uFm|Q%XMvDIMmu zM^;YGlgBOU-Lk_WhxqFUQwGB2f$eMetAnpe^zF;*RbLe)l;a68|1grc;lcfVe1;$0 zT2^4dJahBqW6t?&7}DOQ=1jBP=!y{n@5x5kx@)z#^M>Cu5vB33^<>IsoU{7hwuzZy zn!jy65EIf*M8kmotY0?6l{n!!S!9yfB1xvExfEe=eVA9kq;U3yu-N7&B44)`BYKVAXVPYV#&5STyUL#OC;gmxSM8Xn z-M&{%?pd{s@G$XafCoPN_2wv6CRA^qV5!<7#UW)IYNeU6Uzmg$G)pA zKi$)`b)BJ=*!I}y+Q#nub3U|p{VYL0!_d`}6PWIO9zofM1=)waD#x~|@QA$e&pDE= zIb(aFW_627|0qY6^XXnCMNr|FC80W6I`tZ3+Ik*zT2bzqNU3K@HCdUSN^91&GmHuj zq>m1ta|rF|g!E~4ex$}NCQLWRsK~q0F+P}p(I26!8eF>A`M4K@#9X(n-iLBR@`T_h z4K1a)`gW;4Q=T>)x{r#a8(a$rHwKnH@24C%v+`wsB3^(E#Xx$_x8z}KibSG_zx)Q3 z6o~Z9#f5Xwa!h%CeZA5%dU|soKy!ln7npavYSTVsxQTqt*^jnWl2;=$+$~IleVi5KT8+-{5h!eKmQX z>w$%*o|3uD_^D~jK?)-Ses9VSQ?MQ&wHno|nd&WHUrlWiOt5TjdP%*!GuvR42h|5$ z!vp^v1|}4M8|8o$ar@|K(xO$1;B%Hd0ZAMw@Mn5;sn&e|W)1)gNKi8{|DQg+g*A|} z-&{QiFD9Ah8%NzUHfp6E#@CzbXc@onX5BGwN}J8M^r*f!cxWCxdJ_zMc@#L3`C*RQdR_?Js zAoapwopmsEhp)^2hU6V!!C}sqX54u(_iq=laq#duMzoNVH>nRU!Pfx96G&1c7<+=@ z2VOfOEQA>wY+{i*Q8RU1bGhHP0|O_bp*&hj_%<_xq%wUt{rmpEKbIG$1H?u33S!hm z2&i%G=pGa}@O1~>BY1cs`PxY0kKX(cVx0-)`r@M1vw*V;ZTYY6S0*dQRuF!G$S_Hx z6hdua6(W0agqT(Ra5FK}{ysa4q)CJ8;|7W}C<8ziQEprXS_|L|z!L_?tWN0LB5a|I9&L491&4n2BsEBo z9ER@Thg${|NhrQR6ojXj2@N7(IFlk(G^&3&rR@~K%}Dx za=@CU2|x!z+J$Wqtl&zi!1e^8I>1BLOsSXZ!$42eW%KlD4hX6>$H6f57#~O^mq!ej zOKh3HO%fw)gy~ddtyMB^6}N{6E#~LEneDw;sl@wHpxWVNgVj*_Fet`-V6;w|^T!s2 z_4cs@E7N7)xIwVJ63ToPy}#b@r&=!|pFE*ZGGFqondG(3&*KA^zZrgw>MV?eDA@}Z z=Y-L+=wK&>ms;=yV#zS7EG5z{$eS{ndkkK?&tZu9UKxu6gHu1KrEo{WZP?k`Ctgiz z*r)`LgMNVzYnm+Sm>xSN+~*2Pv6zl~^fA%t&4VAeu+V5(E@e@uRpm*x%NRkYB8nti zngsF~+?vYwq>>}7vv^|!Dm8t>#rF#O%JF@+26yToOTP>9Xqo3Ki8Ilil3Y$ePwv@& zz}PSKiRXL1?Oe~Gzoo_E=H$);R9!`B`DpF}o4JF!dWPP|+%*xMfry*?n7(ARB>htn zv};_iR+xo3I(v#EpWka@;9*`Rm3_w(H|%r$`fPVnOR?+NgDYv9Pri(^K6({Tm*U~# zYkpbP%!3yfd4oZ=Z!fR_;4drL<6o@W7ORa`ywYj zlCl$ZJfgeQtG?A&?RU`is4!A!@P@ECu;gCFB{Rj63VtIwWAo2Q%61U`CMz(qq>nq` zxp&Bb&n}`lj@w6koGNEbg!Z{8x;$T;0BfZsu@y-v zS<26HPcbYnYr}19f?NfqEkc5s+_5?iibfjm@2_S*`-g4ZPh=MP%hvv7znGuNdgSm@ z&Q_JShu?agHPlW1^Y7bm_h z&fe}gA(!bBPiP@pY7lQCdNNV45M$fB(6+HShuW94)7;}lHk4$REI+LM27bJ_Qifln z6>q*w@Qg=QuDf_$i8F6xEJm&M9*u|7d6YTJuEKFwb9DE*>&P=H$`Tq}cE!ObvX=|8 z&kq#Vh&jFDJ+J>sxo0V1rEC7{_B^4a%F`!?)tz@KOAaQOnC~jEUf4Z25Y|b2LJ>r5 z^0?guWsNULLnJp+11v5uuaWbnNp}cG=~JO6qYpTwUO7qJQ@+?yFz-D1`=o8~KLfx} zhO?mm#k~Q^4HlC;Bt~s>P5`LFiWT6o2wV66h4{hgGtfB#0b+HYlK_)KI#>i{Aq<(& zdJk}evnF90z9M5gu#zD)&J0y$T-9FN_NbZuKcx1w@!9Qn=A~1cZ(wqTGaWXke1{y*hpBJi~+2Re8< zH?MpE90J-XgfquUkxDoXbiDt?Njf}ycr^&v5nNj{pqYcR^gsC;tbvJeFyW%X01WO6 zBQ7_=a{GR@x^8xAGhpN2zR{cq%3-lWY`0zzuk%NMvjM_LeefMh2ip`(ZUCe^FzFn` z)&Fg*twqCPH0BD`=jcC$xfy79upcq5D*ZJpss&eoThTlU^qdC!usat!1P%^pOZCpC z8(v%LgVptNU5$QaZ9{{Ka2As92qg-xEfh7xP8{BN_#)k5TlLwV>IditG}768bj@Wg z@7ytV1;84KhhBsQ0pj)fU#2wTD^=!)w24-7us)A>AG1+!v0&k~&B?Xvy zLqZ+gp6~{P{&Bf_t55Di2-z;c0vj=mIQuboejO5P0Po>3gG5d?ILVMWY*35@X(-^q zuR!j8Z~$|H-wjj-z&z4;x)E(jO2JteeCXg3Kw*9O>~t0$2s;)SwJ>Az4tCb@0-A4T zW>#d%i>#mE9s}K@{@0h5QwVDY7%SR3Id|UQv{y))u66jV;1oG(}S(Lq(C>H zv^D)u=IZ!l=@vfYI==Kc}W>% z;CJC}rf{19r)d2i$-B`&H=bU;X{ATfiX1(q{xeDvS2fE#1Yd}JNh)u8=zN_OeH%sk zFjLUnKv4WH+Oy(8L8TedmU;3GBT|}_ij$c5%Ew{6JUx~PpG!$z@O37Qj48dqylp`G z6N5dv)aO?g<-hlM<7n*L!x6jek1a2I+39Ig+^Yr{xv_nEYRhlnDeSG`u%r%0mA4fIYI zU6Q?XaXUgdYLtpaTIi&I#d|_8IdsR-=R9_e?k&`5t;TPv5z#V8U0ujMF^<;G=is~D zf6AGtiJOR?Uxkv^NbtMJyVxiiTXW-Aj8V7Z-pVKtKuh%1=u>e}Y)kiuAc;AwO{>#u z&%APw>_8N3s(%$XAu4fFl!>HuR%3YIe<~?>R^7nt3Y{DO`rp}zed6PZO~O}EzH4># z7%|QKjPeE%bvO|Py(xD&I$_(1vhc7G9>+~l-@KzZXy1wZLAm5ho7mZESY+g;PjJp{ zohOghxfwH8gEx;4|Bg5(k}%h5;xxsR6EJu`qA_*AT$qwfE!Q=>!`Q_<7DD!%a>MPAtLly{nCHCr3C&PE>K$gp%#c+#bCR^b(yrr-W6JJn=GE9X>P{t z82=(exe1@1Y&w&u)?J;2%$b)b)R|Q%&g+b6j9P_u{F4nejb>7Zy-&lLVmMug?eQ^R z5;M~nt5OV>vp%y{j3_(46t&kF<&Q~>*H54C-Dy&|Td8C~O`ysCI+XY|hgs_nA(AFj zA5Dz6O`lu%u@{niSk~pfMLf*kVIWXjc}aqLgyB4&)XlO~(9yF!n8Yu{mN_%lYRas$ zM$$jciN;sUto$o++pnKle`ZaHz~XmBx6e+xBy7x^ z61sSNRs*!2k66(Mc;Ma0TkMU9`hZid99gZQy40!}2}Gr~+*W^;YzRw53>Oo?2T;y{ zhK%~ah#mhW2%dmE&BY@EhS4x8LS&X;ebAW8&1+~5x!9SUX6fN13c*rOr zM6!rLPN&J9=3QpV5BjcwlXPveC}#2VrB|l?$}eD}`tYpxVJ%SHpIr=Jngz3f!E!P> zHUF5}lQ?UNkC5L6EWI77XWLX77y03E{sZR=BFE4i*t9tCj|8uL}GuJN)XP{{G{+>Rcmbj4u6J$@$dZbFcJc^lX|HVv1$+2Q=Euhe0*udIGF!=5+M73>+?x#At)oDe1KpKX11F9tWR5M{g{{cS^QFHLKFD&^V z0TX_2uO0&f!d773MzcPhnL2{Nl$X3F8iNMWN*IH6Fw%mtH>?U$pBt`wib9W4_!pi4 zQ2C(1B3Ww?D2R;wNIcx{-v}e$A=n*~?O?bSyIf}e3pD}alVP!e2KwHYUdgaF)Y~A( zCxZq>|L)Gi%Rg-nfHBKm?#i`AMV;%fTc16DCJ&r9T)883NRtJ8Ud;^p!<;3+!EM1k zG`JENYMwf|+U04=ov;CbDvAWsAzVX1{7Yv4Ao>un5f{`lXukR5`*+|Fa+BPDZG0EX zH?p{4r?Ok4G}+*?`q$|mueO!<{tf+h@0D@KX9ikt2$(n~PoM2B3O$$js5jvf2ymFM_YCBEnOQJjq3A-^)UmrRw_ zx{$n>Ey$XXnA3SLzwj?7HJiS+rH;B_7CTMx>~431jCP~4L{ut^!a2#Lw=HVemw^4V zqQ7g>&bvqcCr8aCn{k4}@@n+CYK=tKvd2B7evU7ReyR7HFjetAR52Gi(B8PJ6PIIM z{Sco!UL4<$)|@Zq!IIi|m+v*_+|6A^{(oxEdPcDGMe-k}aha>=s_q?MM|1i0E;hwM znHz6&6z^$~3E7|PDg%wAGmMJCQ$%5P)1p{>SNUwYYLgzjo}jTSHj|5{ig7At5}e(o z4xa6{&0NO}&?M@@f<~0M!&Ctymk5KcT~q7)tflRy%Fhkme}*2 zR#f9P7S+nM5k-NzPTA}vpYr{#;7>^O*D}f3WR}&nvsnpfOvR@=+nKM7+zMKFQ0+i|bD9 z?F}B+al7anw5SzcZ>v3DOc$%qT#@2GXt!3R#2BO<$cT)*d#mffFaLgmZRY*!N&`_O zT@qoJEE*h%c_fKCm_@k8BN2u2Kgi^W_{QNgaxn*k6-`!3Tg)DOxE}>Bi3gr%4E5GX z<5O=4;-M@r-Z5Nj$!HE+eW}mrGjO55KRZGT$=YQ%|{SQt@=@geh?Vqt3^k#+>27(kKp2AotZS9dT(4 zs(qq3@j%t&LSz6?ga2DIK z8(vbCn$A1gtJ`{BRzVct49hwpYNAxJd>xC3`tITsx1v=ub@THRW}uS^fwmgle?fGd zs=?L+K0WwwpeZqv=9rk@80P}|m59irqQ{?yhAO4~u4iegxEcf9XKY;*$}Dw@d1}t4 zpqCK$Fc}&eC!xNF!{0xD!v7Z2{eWhFgMR7&*!f8SuTqzthbeqpuM*oDX1^4dGRwdVw5Dqiq z%lD-1)XHI>Gh?uF2e1!-Z@K@j4CNFF_vyiga)&G+cx?3*ugMq;)W9AyIXw24HEt#D z0>-)eB&q7M=kfO=fe@lDy#8ob$;dDgKr3=BA{@-1wh@GPhI<=R_&o9Vm)3XW&!FQn zFuztcdH+6<#q0FsWtiJwP(p<7>t5NQ%|k{q#5(%5F`(6N>*~Oi2_}2QK>%^nKA*b` zKqU8`K)M22*7487R#omaJ0K!}=P*<r+``v=I(LIPv`|2>^U3fAPL(NCWxVr=7- zpzQnaG?z=&8S4RQeZgyAJZIsYU1FveE*({ahRK%s|#gQ zK632*jip+KVa=4{A!KNP`uIr~$m2lSgBUL)DA;!)oC?@?&{`m` z9M-*HT5Xs^tp636r@dH+_;BvD1zw->hBq8+1g_3DqLq}FT+t=U~_9JtBgK1llv z?I7?OVBfA^sRVsf%Uzh5fo;A62ocy<)?rPrd%+&L6XB&JvPEzvga&0AAo)D)M=&Ns zfrh#~;JpHqHT+7%T?($=J9DF;MHt+<=NXB-9|4gerN5&29Yoc?5|fJWf({9g3|Q)b zQ9xO~^4Le!^6?`5N_W5)kZBYG_qM~^#x2J(Qa;!`vxul*scWQdm2~Rz(bU@Zz1vn0 z_V`LW={Blvl>Uu!&s+LSwm)-EXEJO!&HqvBw8d@)57!xz{Gg`a4SpRGx=avI$&44} zwr3qA(jmgj8msbJr9HPynw2ih4V;c;2t`>)C z`CsRykn$oyv085P&=t~p-kFR4*F-|y+jgkZD~>mX&Z2R%erSsXZIQXEhN+a)Dm&)3 ztfO1S3Fc454@&6j1%2j&*x64=qfPEJ28#U^sohPT>9QgxAl!7*SwAHGK4`EPB&#DU zW~CIXFxe+-Sf3(ZR-;Nssr|ycbB*E{V~x49XdO>xFIU$8plJJ)9bz2<7p{A0e}5}i zeIe1G))F^T6iCijKc`w{AM7@nT2|K8HQ<*U-sj|}9hdfpQSgR4m!akF>5BHG@~*9s zpM27<{~t|P0aeAqt?6!Q>F#dn5G15iq(MMhKtQ^clJ1fck(Ll?q*D+PQ32@^qy!}1 zKKH%1)?MrW@AWKa&YYRqdw=_j!mk*j&Q_T&(S^@0RF1Fy2I5%oN1om%O78pQhT?{>aQZp54FZCb6z?#DmWcbe3+3Q_xKUu{tj z&r;ML@NcCQBuHxocPv?){dHa`u##%K>*0sthqBguXlnPf4-eD4JDatzG%|G=&)@?s+cn6@=H%Fd)=jwRR z^=}I;X_qc351C#Pl}-{>))!OS>q5HWS)kqDv!UNdLt97nGaI%olYJiyS%4c;FI>GE$~AC!?FOG{w$HsThT-}dnfv&1rR->8^_ez#*vOHD^Ba?-W(_F}p^nhbor^f*! zR|u7@et6~ON9N}$)DffvR2QpMI=$twTF99+e4OT*C%iN!qH$7a@xf-wnIY1@c(tSG zlLP!M;>jB0Xch0o4F!ov2Yl>L`m*fgBqvk2LBBF`(%BFbE18s9ET8e}v595p3irx7 zi4|bVJyzYz%gYsfC5!umOlfQUl?Cat)lD^%itqvefD$1b0^5%Cer{}EXA$bwnyR;V z&>doQzl3?G7#Z79Um5#Oze>Io%^a)ELw%D@Z3Xl5$=zAeQ@5-6qESg8W zX3Y14j9yHEaiS$(CT^4N;SV5ZwZC(o-TzBw0$w?sa}_JA-AB>@Sp9ILfHxRA`_^53 zx5H7(qmuxc{)(UUhndfWI$>|ytT4hY;1%2-)C>s&x&f_`qQY z)mf2I73W-N+r5DKpD#!sJg)nx5*pbmdy z8Ppt6Fz8(67Y3LaJnSJ_lS4dnTD0yoDM|02{dF5^v+7zTY*Ni&uFe&u#)p~%+W^>e z)-^UlHgHsm}r zf=Iu*|?f&%kQN_d^il{67_agG@w|GYKbvu%J_W>T5K9Ta06Zp5O>nm!1id$3 z2MwLRC)`MY4}ir1B%i7iYHMrHzvmWppI$4wTvyZcy(KRTwPOo3tI; zN*A0Xz4f-Rmiz9};PH5CI|awhR)ehOt=Ta~oflvJFnh5IC*D$~I*7MQJ~GHaao*&V zmXYrL+Zyn0nebRk(n6PvQzgu7T?lyYhABG zLp;-xfF!x`TAdRA*4ghj$^xUvC;u4SOQnB2{Bth-y5jlrhl$VYEi96?3?7!;k;R|) z%X}ITpzKAj+Mwi_$o9n{Ju3c!V5B)daUbg7+S|pAuUpfaI9xk(uYa1ce-KdBl5i>b z;y>-8)3-K7<+1vWX2r|u@BGteG;OE^9mqb?&KP-qbfS~XlrhYc>#<7`1LXuFcnY)< zUKlh1VycPb^|nuTrSe({eB8S$H}zXCb`1ma9=1?QTlRK%M*Zw%+Ox|hp!!yNpk`&A za{Pd-JA)Vm>i94BDJ+RCgsO-SDAP_-w=~BpHM_< z-)gKwdM9I;FNNQ4PF~&o;P)R+|G*1kbn~E#>$3)$Po9(%a2fy@LS3nN+8xB?*$yaIrW!%+Pe zLToDyVDSZPT6k~3wn%dZFN_f2u$mo^-O_ulv4%-cGi91fyv!(cSpWhn#^h1jhZa~; z+7mm$S_hhRD2D$<^TK))_CN?W>JqHW*xotuJ@kdZAjpnJr1!w<51>CNGqAZ@UR_m2 z?tl}Ac?ovRNL0`d0MLgRg6zv`Af!l8uy`A|w?L_ZC8+>j1iXD=ZJd7}bL-Syfb!+! z1{u=Gkuuu-OIK5_)s$ik+#EWAZ&d%BWz^tyH>=Ha>_xg0ll=9Tw4+1VNLT7BA9>XG)EN zPj|7m25f#|@+yv!&9)qw0?)dL9(iO>;2JCX+sVK_^nL|YYn@AtgCeIKE*Hm%MV%s+ z8Jac&APRu$AH-__ULxjnIoe1`8JTJ%Uq}!F;~%J^z>0@o5wLm~NntHNJ)PoJ$$?zq z<#zHf2n^!kIzX+dl5$xvGO9(m)}VW*g^Ea8O!r4__^VS4$$HVm^z|XOjWD;FWT=4q z{j9O&8bYKEFa|;`4aDoGokz4ZgD{gpwTF?m1fX8%qzW&G3t^>e-hk*Up@#OfO3-=D{MgOlDzv{fobl2 z1)F%F8jN?uAr*t3yznwLq!)f|2-2F+pSgL(d0`FrAza~&!VtPaPlPxT9y5R{)~*dk z-dj_GK#g;09WDgo>R8mSwDAFf5gIzkD+0U-krfT491(m5csXG5a4W&X3)m1Wu~UXi z8w}VYi}Wgyl&ro2VnKz6F(PCMFbLfifu^wS7!?!cV+WLcfTx|uth!fka7>ln) zh6WzT4(xtZ6+c-?RgqI^q9jh$Q$9kAi7ihIFJM5DeQve;D$bKRW}ok|c_5Z|nR~Pl z8(|NX3_X)$iOrohwbvWZ_n&rvpB)xSl3m<@)9rqo*DU{Z6O^)Q8DtyIygb9=%Hr1J z69+3ewIXjEttnO%-AIy}B?mgp@uqgo2QGzX&pzfGemgLUIvjY%-t6;7|M0s|Xei^>3-_PWhgZ2imi@>4a&Ii(VZ55~n^nW-d)i{aNwJ?yy!YZG_g;{Jp1Z z+T4XO$H!%rRRJE2$x!wWI-i&u$Qg_A?XqlphSpv)wNcVD&c}}gzxB?y%!(a)iA7e6 z#H|>Gt0jKBN0{Z+e$3jYOi^F|UCPt4$*#7zg0<`Tn(;Den)sK zo{X!p7TdDq6EW{5x`p2>GNIHVSG-k(I`-~_lu&t7*5=MEZV$R0x{||*gkU>GZ*9-a zlwHAOBg!*$MXDgaH|6K{_mD`EMQLa?%R`N*zj8S87Z>Z%jEd9{(#?Fy!80tl6K`Bp zUd&48v#*XweCiAqWlC0TBNjbqUwZaKBxdcs#aFFzv?rWM1yh)_nB~u{YVIM$IGN%s zkrT2-6hCL0m+85aPCzizW4DbN=fU?Zl%}a49_8&y8aly0dw159F zUpqL0vePYPtMh_ou@F^a3Mq-4?@@2hM7c?8)BW>rTz8$qQx%e~d~=0q+7-jxq=vJR zeaxxZ-tnZmaYdz0THn{QNv|MERl#@<$a?Ae`_B(E_07L!MCFbrXXSj%NzO6y{C_S$ zfifxX*Ll4B$o_2PM}Bz$d|Hf~toUQYcm_fu8R!+pG6CXG{2o`e&KPe}&v*|{F~+IB zV8O_6&(@S3?Cv?}vD?XN-!wHynyka5O>sh<3vXt1WU3QXLvcbwm*#36`z82Xf%3mJhw8Z?NTE$eJA&7&T`N8`&a1)A%XshwWL`**_sV)Z6lyUjpDtK=4K_q zwjbYo^?A=1Jmr})tR|{fW=s@PKW}*>R9J}kx|`j?D`A*PzyJ=JnMFd?OgV*tJl}G7 z2iVmOL+A{V46v*`NF!j0I~1VALvYMs+VvokhoSsS9&9^-EDVB|wF#|5R$hx?seq0G zlruG4-IUd!#(8D4l(25EbRvX%jJyXpjRge2%c;`2>g@)g-3H}omufr4Brh4Njq>yI zICe~+cmfhzF{6N0jC4o$X=noJ-{1= zGdDH<_Vp{0PR)@O7TUJA6i|quh{C!PD97+=7`KoEpql~^U~R|u!;1}=3oouZ+va$g zwp^3FY)p-YP;yJ*$Sn&HcL$3`h!CQK@fJD&xG-?qzP{0}3s3@P+*;D}5WC1NZ=jq( zg%!$<&tC!L8YbLrNUOwo&8`rTQtAQ|cZzx$?0gYQX}6ZDkxV{Z*M)MhDS>(k4Grjp z-h2o49DJ@7z7^CL7+u#$J~z99Q%L#*%z)if9j{j;;CldKpD_tJqOgCJ&CJY%zT=%) z^%PA?4K56cvnZAoGrHs(EKLip>8fV!DfSxYZY_ua=XJ$uBiwYzYLiMV*#=nO`TOL= z#OH83v0QsEuM{x-g(?K|D*U#v072XeAkp3^cy>RG84dzVXn+l%u}pg~3K%jXSO;nu z*;frS9#rT-Y+;6mz6sb*5F$tny`weQ1cM(N{1j00|0A8%BAN|QDgpfbUn{YAIlc&l zYTyh4$r>8Yo2#yyr$E#~49Qwr;GhGFxOGroJA{N-hW&#N^xF`RHh@UM*==`k4;*O0 zQ<)grHRxXu89>l@!u)?*+zn{tK#@Xt6)UuNojmC3f41LI@wOA25m0Qv!W-M$$Kdm2 zNU=a~Oi*D<#oj7*ZW>t`O!B1J&^IMdZEIWDi{{C@5>lHuQ7i@$D|BE$ro3L&zK(=% zga~o863}r1QaJRLCK*xora+7bTO&lNh1^T%t)V&te+&R`V5I|510DtYGEZp2fe;9X zN&gA#&%nz+gCqI7uq~huK4XLv2hBhHY~4TMf4R~jr3v~;u-^xYBed&E&;diX;&6hu zFsDKXJX|9I<@Tl!VgMHS@f-euhr{duW&lJ7?l{1HgQm;yAM00>wq@XM!rBGwY$`*2 zfk_8ARl$4EM>aK)HGBqbAn?yX_{ObcBb5&H=3tiASR`Jtj5b^!(!me{*NUX15zZCNHaljo1W{|aw8RCjAepR*=!!vCt~ z_fi`}MFGRikXUnEz;cS5czbfmY|wOAYiO$2mFD%cu5RK3<4EE3Q}rg`Og;m}H7TM-u?aV%mJneF(@DlhPvrx01{u~S^x8#BrE zZTbC=OFDtL^KCE3%+m(gWGK|gU7u>M6BViNxU-@Lv|g4(JY=>lieS1se|s`5L-k`+ z(vT(tdwo$V(PaH6+d4bJHuw1ZG^&gzeESBuF@b}_*|A#@em^MmGuz)|<$AfO;z$(U zH918l=#i;E8kxD?t{~|j!;+^lCQCL z?iVLaZgzc@77W}DZ4y{e6xFprmm&T)O@xx~UyQx&-g~buXRMaQzcYZ8c#4Y4JmXb_ zUw9{WsBwe)tD?H)jzzIP9eGhF)3FnU+7c@v{?b=>Kj<8;M0^Sq$VOAyS`wI{G@JW# zc`X>IQ~GY&$6A1jM7qp$feFdrUY*fPIV8KvN0Ey+UbY4&Wrgf@nqu$V9I%wCA4PWC zT^vQng$+y3ojk0%kSCMNM`=HIz3t{4faB+Yh3z;qN}rh8U{N}9wDFQ>lrphvV{rM% z*)g{VC|{F>d_8vmAq#B;a!e8I?FL&+QCO2eIZft!EXsWW3@FpIaPXjocg8~EO#FE-p>-jkZCK>c=Phn`UuLXc&(lZ z*GzVpk$-4?8hb}wqNHbjjc%E0fvo=lZz`(*>Dh?xeMZ-YZXArcI<>jSB3n#eu9r-;(#)={PLB?L=-2#f(6T;$gqS#B!xw} zXUXi175P3dO*V5mglv-epX^Bu(O%+b3KPVVmvO}M=1ejpB`0Wz|HhhQRNOc^3&@aa zC#nee{iwpTJ%redp(fGM#DL&e5`V3sP>(U5<`)++fRQ2oL<^Z+7C(J-t^W3(=gPnI z-&aEdOIEog`Kp+tWM#KxVKc!!pvt;pg}~bc$k?z4t@w^Nl5hm1U&IJgWC%0rNdVM< zwcwhCJt$>$Jh+3NAgF==g#P-a6O{b|aqoVPQPeaQ!S@nN5(H~rRC7LpcuJvPgRPvB zHo2j+b$H(1K>lU_uhV})y2nuk6QprmZj$ zV?#fjqKpT~-=h00lvpWv8TYzMjLJT-yJc`?TSL#c0i%evKIm=flVRWs0}?q{yTB*F zw_x&@G83$~N_9Bu>gyFiTJc}B!RN+j0+dtEO$hBeBsb~&mURE#+5>%|nTQ$V#P-=>`+3~!poaA=aygo1rdU@K8?o4Z5RB;q; zLagMA zj=(B#?PF-GSl+U|mAbvfkhPf+w`z%d>!a^|j@3NhShaS7=G4CdZOO-GIYnKf7K2}; z3)&9~<(XCoQrKdgJst7_6Oa|qe=#Zwei9^Hd!9eJk?Nx0y{){v5^1wqdso%?QTU(C zBN-8+Pa`VI6n@rJv|osq`{MXcocdMHu-sHQ?vHDvi`{2WI222aB&SUY(n?C4V0}1< zffSwGU>nN(1}#WGMEY6D?&BrW{7JQ=rauQLuNj_%GbPQ!ghr05PaKSmQ$QjJhNA)hDo)@?!x?NV-CIBt_Fi` zW~H=DuuniSV>qn>*}i_P<$4|CilxU#01ZPODF-cn%V=WNZ^T0~xIk>mnIIvtRqXGp zqG4-4De!Sg^~PrV=cSVuO#eJ>)#;7Nvmg467D<>7@jp&bozNIf1{D8{i9VWOO&w3U zU*<_mv2c^TOQcE8xkIAqdoR=bo+T0bKKb;I-vZLd6TNbD9ji_+ehQ=2APqk8jEqUw z6lf6`9N8v=n>(x8D4Th{^iBr?1!ekBjsuo?0&z0^EzZw9Hfvx z8&vhfj%doAJ70flu`w~qZ>8z*)%VoNF4vAiW0hiGaaqb$P^l0bqx67?g|f{OZ8_q- zIT`^5pCp%EvfN*%#zo-BVhXZ|txqX*R#Ackab|F>5j(oc5`qP$cs8VU#N&ulNacCR{HZmgT&B8A%N%kTZA^oMgM-=~dve^~ACK-u_ zmXx)RWl1^Q=Ce)sVl>AMqyDCB>%F#~os$3@0sTq?aN>qBY#^gD7`=kmXy`i4sbtHi z>T%5uS9ikd1A53ZT$PYWEV)oIvz`8db$3BpRJ0$U04{MHy3fcCLfQ~O1FzJT6 zKEk&4t-lw3TP$me^j)t{Y-E}OCt^I*fb?-b` z+K7t`a0Y`wriKxl?C+97nuOSBC_++d|)R0TB|&;^8DS$%zRXo`S0ed~u0qhK5lb@TGL zLT+uZWf3S^K-;V3`IbIv4>KT)@=Nev*LQdEW<>m9$Kn6`{l?jh+?758ZU>q8v=gkC zXlQ6S=1R--?!8w^cf*kbwVlfX9FOy{@2oS~peNYM0V@Q7aXd3zXa<-a;gh!vfIQ6X z|Hlu90k#-L>FQ>;W9tdau>a!C@SB>>+wvuz1Q=O8d3VeSKtL7KYNq#!a~ek_w)mx8 zS7RSP&2q?a?d1S5!5urvV7;vJla-_%G8HfXx4ut*+ivs*q5g0@{$Y6jOgG)sbas}K zr-`)5TsrpdQ)7F3*=+FEH_TqVmW4e5^(AMS9WV|X&ma}&3HZPj>sUcM0$VEButTSb z(4m2n5`2o9I$nE9f;n=~)jgGjDj3c!+WkC#?Z|RN9^pEe#vxI+zLpOGu0#99b`=6A z2av(ZV+)`HMC7?S-_BIm3qy@CB{Kbous4Eg4U;y=>fjhK)+$8=) z%Hr|=#Cm}%|LS&EugOa>v1rVKg4w&ytE)@Q&6VoCQUT%7*hP5E%S*NO3HaZ?vIalI z#8FEN`*$-$x2rJ`bayiLxm82hfZ8V3$>LD=^zGHY5p}Bw3FH)xW)(LY`erIhbJ5-2 zVzHc;Y#9av`X6_0)#vuSBlacp;Sq2N`*gSd?^#^f6YC#Z>A%jx{b++-1#zAy^)3&W z%w-jpNKt8u_54*ES^07=1=G*N$E(m;KIV}3LPlyri}%$PUrEFwn(n;lYEB1gU=R{)R+A-!kBmuLgd}d-)5VD<>bhG88lUHGq`V^ z^%(y{UcYKL`pLmz)Ab^-I+uuXCPiQ!>D3d{kAHU_3npeqz43~#O>WESG>LQ*mg0%$ z8L!gBy-9n!d^xqcoH z#}Hp?B>#_2_(Aar>Ddymc0|vsB?0u8hlTa_Xq)Ja2O8(N_!+i3pV!OH+;s;Ht{oow zP${r;)lu}&yb-^L`mBzpUo%4y`P=1TppihBy(3AkyD~`@k2!_c!#Tpo6rl_4NSeQL zBSOX+@T~HZwOfmK#MQq}+xX!~Z43~mmP*hN%!w8WH z^*!hy)OjWL(}=`WY^~palbqjoB#g9{>jtalYHKh)LZQr-+b0$(qa@#R@X+H^^zC~D~ZFa28mT1{Fds5Kot3BsOu%j^5rKXGbH zT$*Z@{5ZhePsw?RWzOo^+rT6XPQ1=0qE+#)4W2p$0*UOieV+$hl3DgJMU&P^ z-5(!yKCa7O+2Fyuo}1j&o)y1%+Rz{$c-?IWWGMt_y)jvM^UeQKzsLOEF9`x>W@cis zH<{_#;|^dU-sRg`j{r##cGOT(LDdrj6TY_g4koy+Pr?)>Qxt(+V`gq1U)NsQk3@Fg z-Pe~qG&z}=Iw9KPOn`kCNC&h7x@+zz!I~a3AUQ^eXkTz@BHL)@r_r&g*#N$5RxNhG zt^Pzopou!{xDcoDU2s1-o<+I(#Auj*9yt@ZZ5-CY-!@2^nwI0wqW&D7>Lz`Ig% z=)Pcz3ftv7utcUM@B%tI(96bOh)YURVT->}o>i)U$cp^vS5Ohl^}{kz*STibi9)&B zzK}Nuo;a&bb#+CP`EW=mBxXdx=lSmB?SF(4)Q3C zHdvWTkv;}XUf1$n)}MSpw+5;J%+bw@ez)&!#dsL*hOgUHqy@JwAmm^hu>D840vvDY z;~z>rJLQ3L0d)h&@`&jYdIkp|g~G3i6BX`oO%2)eupW@RUXfb|n%(zye?$fXV%|ig zN#d4_tOYwGn>vAOl0N z6=cXePn&8H-UOW|)$Yswbd!a06=1YdX^>S=@I~_xj%I17B;0CJXjUJ7eCaL%r&L%G zl$4Ypxcq=1{qjfH_yNL>$S6G3cm0RZxC3kiAd(^$;)?b>4>^4lGB7lRg)oO*?u(H! z-^><%M5HJnD?4#<5rFoNBXTO}+==c*BoXw6z}P^-=&mb_dTptkYwPamsT*Suczr1e zLQ2H%m*Qkf4vDphbI5H|=OJyN?hIEELXO9x;K%oGrJrqmw%a){~wwE-8RixAFwi15vqdQeRc z7Yed{fq(;l1Z@yR4#M6Cap?fYs0SGVkS-l~?!X-Y>P7Ppz6sD;!-u^sxOo0Ty8w3= zB1YNT&Mp$L9f-{Wp=O8zTk83k>x#j({U~AZl5lE2MIk2ZchZDb`li^ukg3|2?^(`n zeZoxEX8p5@t=(hR63OBmVOS`m`=>sDO>NaeX@EW^^(2ymfpsf*ZAQKKdW#6@-f>ne z8^NetF~P-8oF-k#vuWp#1u4w948=?wcSsce?TjAVSh1wWzWFr%Z&hk=LHXnMeq4O> z^Xx89OL45`U8_c$kO=QMYq8V}3Y&J6^-wkhAe)-3A!OymxE#MngFG*8Q zof1V|rJG42NiM_L`<7%us0Sr_+x;`s^{%8&{U#Y|hUij!N&t^01wG;OtJ_^tJ=eF? zW9f_>348+89yp$)ZquNK<(ZHiPWR_N_7x1(_a-yOvq(LbIW%PJP&roLUhLT|!w3wO z7@)IZ!l=s1QtQZ;)tP@MRefc#8IsnaDr5IuA&0(qC0Q)x6Z7y15$fQ(TI1m1yqhS= zj9Gt-pUl4e@$Hz@yR4^dC6*ZEUbl9Gx(lgSnA#ufUNO8|cs{0~?po5QX({5dZ+li_ zZHTpzxoNNa1G6i8bVbP5Ziy>s|5Xis<`AcK!j&sqrxVf%o@27pGN88 z$r3so$X0JPZV(X5KuaX#Lp7m@{DpMLGKrU1D78}ONrt^G=3A@a4>7Kck%GU&gCz(w z*Qu<8`Zevo^zkoFpBDA7XM}urv8DgGA)H~FvG&i*_6I-OXq3G0Z2C5h!fn+G+L;@b z99ij14@pC^jl6;GiuXkqudQ{t; zIo|jz?{z`1bfA$4t{QrEhN6`%`u_FbB~ENAkJp?s<2weDY;{`c4&gubh&Bg86N9OV zC2N19Dt@JSjoI~eQ`1j{*PPOLc!=s|SD;S+JNmb>FnYax=qlh%4;~!7z^;N__Gp911C12eKj4o63kxuKM5xVh zhXvuFr}t((@Czt35piuWHbIRri-Ca+b^#c#5WYFiO~)*Y|Clp`O4O zs_@a(v~rH14=gH1A?MT`Q)zZhRWJL`SzQ5SZ1Cy@H2TDd$NB{=Pv+=W=lB1lSdTqG z+YtNt2nKNjt}@e~kOxdK_+`tR$=b&7bq841_x%H~9iIR~dx4ndd|CmkUsLp1(Gjs< zU=goSZ8YO51ZyAD5KW?Z92F^GkRsnLkbL66U`gg>INy?{7ZYrV=k8Fzl~-Xi2R1S@ zq1CXG2s0|r+QWCe10HB3ztHRtc`^T+yt3p^hcJFsXC3GB0dsl~ zihFyf!6XaJ1Q?M)h4A=b2}-$kfiwbx0D&K*=gYPn0L3`+Z7;u7h%f= z2Zovoh4bt%vug~z`26-e{sJlmO1oSr#qbAUK?mr0X&P+pgHNg~5$qA*CxB%iLgNPs zGqmB}uvdZufsh3bgy>wLQ#w17P{aaV-!SyHK7Re+a{xRPhByf=ZG6#?a5C|a`iU7(lw4KnY!hJ0Dy$r=M zprAq_A(VhSci0Y`r3#&YC+i)80Reb8G$rKNTohZX!tMkVfbo&wl12;LrG~mXpx=Op zco=X<5TQ<>t^d^@2R9`!2>XF{0O1LU%LE!k_}Y+62(1c2uL%G072=P8b3AG7+zylz z$ay5#X=`lkgI}j+=k7PduuqNiJn&uM&k&|hmX-+5L1^DVcQ^`<7POwwSs+A+8zpdP z1mhDl3OXE1ZG6D|z+yy1074oPKwEItfH$)>%?gh>Sm*$^0eF=E$ykA{xd!3AaJ7KU zoCG$#>a0MW0QzEQF|yaZi%|?4AUWWqguU8&M?JHQsXVvA!bx@tW>?TT)PF{S)2x6{IuPdV{jZb{k>}woL(~ay~TV z_Esxbb}7fBW0BtzWC@XJ9A*fOl<+>8-o37Bjtk9Ap_b2kYrGObs3kpC$;z5gns71U z_m|_JXb+8bI8l}$o*Fr(DL!gH9v4-oinM`CK`d$>#+at1w~&Y_i62kSveg^Av+?0= zCo}EoyV0?1(swoa^WNTDJ=0j9jit@AV#wL6zN$Z57)I_*K{yd z+d@YYP2c!qC3FkV0eucu7oDl_cAZ;9%gkOJkESN*)W%4q9n~yXe2QV)Z^w4aAxi_^ z#!)qy_S_B)ueDSLOb-gs*q%HjoV-J)S)M)Y!ab&nd=oirQvUTzxNpmNT_K}wwm^-- z2*XE5JV%VXj#D1ytcmy~1;c-(!!`Lv>GQ&eL-hsbHw-aaY=fRlFMKSpynms|%~adn z1)lZRzi+_2CMs-L5hHzSP_-~yJ2)K1Gc!_umJ&mq6)oz-Kd@}#h@~*Vg;BtT51~7wE-@dJ}!lt}UW$hb~^V}dbfXkhu~NeYjC z-J~p-tC)AxlL5hyi|6m}l8AB3t^Jz1**2AabVak`^#(!xqeBVd4bLZy-W<;IdN@g> zu6pn4Q5dqd3TaY^r_=5|NhFOcRTJHL7w|C8oP6%yOdaj^*W+O(;?JQz(rMfuwy~tJ28i=8$?GH|v~Km_&~bau50p`tHrC%u?d>73k~czXAVE&e`G`ytc#wXJ zhH!CKBL&C87l}z9sa8acO0N{(Dl1@DPhN;3j3RH+Dz%3xDk>u3R-jQRy9cs3hIFF` zQT@AR(N0;Mw|A%59X;}@cX(_LUI`G|$LTU;zYnhpkGvaZ#~5Pr@mmCq^3-@qwuoJ*^zh>F2$J%Zo_{jDfnRWdxXd||#y0oE2`q-%6AEEiC}d&H}1pxwCT<`Km`&8-;(+0IEG#Pu@_a%8<;K;w^TLG_N6V||gX8C4DpviQVAz1lg^ z2NPps@eZTIc0w>-;|nypJ`m=b-SGj8U_!gT5L^gcDfHA~8cw*2y3hOX0> zrsrFxEV$Dzu4M46>hUb4pppW}?xr0@DCz0h)79ZCXhGYtR|C}b$IsNu^q~K9rGQ4Q zQO(ueU7sr*m<1Q@@5A;b2+jj77IvY4*X(Sc>Mq?AF0I<||K^+C!QK6^-XtDr7?kX_ zb8+u1q2B`F1FZi+oDcCapkIK~gB}99m~kRM=tpwK%N>?L@IuY=1mb?eY`H!c0S8o5 z6CpZ4v;wVaWWT`_KOTBK4@C12po7%|dP%C=w`Z0Gfn@=RL8CqnBMjrzEX|;z064@a z_M-t8WHtk>6QOE>Y-4WAa~wcHHXsg%+OKNB712NvK<@{a9quJSm7q)l4?^|5`4?-p z$4%6T>_s_yAu4E=e0&UJ%Bl^x5V?6t)lj4HUl~3DXvD$IjbNb}RH+EZ!xf+pP-0D1 zedPh_f5ApQI6Vl!8ODVY_7Hvu05WPPxYZrX-E7>@P~OVcbg<&dS5A|00}tWJ4JsWqR~pa7fKgaE316*8op{ks@a2yJjss&gFtRR2A28lw%~9dJRj z3JWX1jA{R;48E_Siz9+;2~Z9^Njc+euyBK39%eph9oJ6x79e?Yizw%Zn>Y%?ghOLM zuuM9CL0+1<{p;5imeIQ_1i!Hf=MOZcxG?30&-|M_Sx%H}(3F{36mf`zywn*;gz&}R z1>Hq&q+1r>Q-Y569q+ABJB$O>t!gpKq|}~kq1z^R6S>AlM=!oEe%A_kOOdSfY5ZwN z8kzr{=Xh>PEIjO#D!G0#$uBL2Yi&oF4u?07pjYtI{+9Q=;(7Qp67Ph-Qwrl!ysk=g z>!WAKM^@3EMDs}9nz`@gIRrwJ`*mC+6r+-LMjS_3XK{(;IGC{$_xSTazfPrmYip8$ zLWdoBa4W`Xmg(UV?$~32Ly^mvZ?TD8JFoE95>l89GqI{OZzdJdOH-Lz@4pdr{-&q% zu<{ZWJ3saF1EEt>JQ}SGfjy1>y8J13Jm(BM>=EQz!%a^+? zxWhn_NXy^19#yx0YbJ<#Fa9Drfb&LVH}Cz|e z;S+N-#cw^HLKLj?=WKt7=XnI+Z|Ic;MJ6jW z*|sAybuy2Me^bV8F7()xsEdp|xEA;mtVQsh4u5nU)8zKwnt|Mc;*-0T)PMi@bMt77 zY?=^vF}#OmjbjHApouJwS_QOj5;pxTp}QTc5W$$mNtb0m#S`tad|7exQaiTN+}ijNbCgNuh*~eV!|%m z=IO?FyT0h4%lFOotx^F$js4T0x-Ryu=7rWDbo1UhhnpOVy>|BD_0zEfD6JiIZnZJq z4|kE;n?E$EbQmeA$u$@in^-wGl5F%sb(B3lN;WGgiVSL>@DKI7i-`=- zrHTT32}Nh0RDYyQjkUt(3M}vpBM2u?VdJAU4^T5F&C-0?_bOIp!Y}0jS=(A(Rr`V( zyPKR7|DzW&VUq0Bpb|9_YZq%tk2Lz9JC6**QCg#{C9X23mbi}Am^?i_6Fx^gUCq#q zE*sTdV$(pae>Ev>txmf1G?jN{etI!6j*qUk8W#0@$XE?TN9;*zb{ZNQdI4RA z*Z6(AoQq5@z%GOd>)*pxzAv8^g36$VK;r=NM(Uz669-Zbb>s-p`Ge*Ai#m^f(~MtZ zqBvvkT3TRtA{7J;fRAvP1d$LMCs7|Dydbl%g_;?Yh(?cBDlZDJF)03}X&{sY8f7H! zBYS(5Im?G7y&gI7?!brGDf2d1tK3P$_b*U|{81Md&6snMJ&h*8A|*F229P=imcE6} zHNvGgUz4pQOcY81uJ~l#!7i&dtUf>Z#+?Kr4_#T=U5hWbaME zSHbj*kq+W|NTqHqaYTv{vJ8Pky8fI3FPw4FC8{8&&rlQD!XOvO5KsoZEdWV|^ZXfd z69le;4-o|hTu;v-D2~ZT?4QYeL;#UKo|1!_+JS;Cmu3m)`qSCM7swiGm0A6y2kIxa z!)Imkyg<9O%=~CRx958zID4&5s*&43XkV!QbY=pW?;uY|7F?AefGzy>xYf%fl*ZRW zWG}TIQt+b|8E`qtSGg{LY~Q&lhal{H|K_S|gZ_G%9*_V)M-V=@(3*gk{OWw;BUsl! zX#h=Qh!QLukY2&u4oJIpq3o=S21M7R{vmy^$RGR%m-cs)Sv3$O0bz$~n_hUe`v_sV zppnUkyg8K!1OQZiGLF;bzLkLu#-fzldn#4A^^xJ$O@aVLV(gh^W%A2!Pt09BdRi z4qexgsOhLC)qu$tM-d3n`89cSIeEU*b^SQVd>p&*E-5#|nXO7xtijvx7gx25`>CUA zA~V!QruzsW4!SA?*&*5Be0*YpscaSEoI~XZ$cFsw?9djP;X6p>?ZYMkKmuyY*UIXZ z3dxBp0uU%XGJ*q9KX*$2in4{>7+mE&en`=S=DMzESlJOpgggDkgld?O>%x~#Hc<75 zi&IRgXL_5M90WbL*?e}oO9iS7@Nklzv;~9+3OGnV10z663X}|>a)M;1n3B-4-LGeJ zljFrb-6mMl@qjNAY>XiGxLk=}gA>t;BKRzbjtI_L>bnQ5t-#-^f|0N5^`U9CJKJ6Z z`|gTLimKRGOx8b+zrtNwV#b-%GLVG{kTP1NX>-u|iY2Qt%96!1B_EM!v zZdZ{1ady9%ABrnc?eePk#|giGd9*%PyBScSuGDm2xku#| zTBPXXxAYuqAvJBfHaB=aRLTMUFAsUa@e}=SA!ID4odlAk&`R}ItNBh#GGr4i(H0>3 zW(5q@<&$lyMLyB{Jkn>T!9*_lm2X{{ZQKiwSUvO1oMc?%OzlHtoMkXayAMgvmDwh4 z%#VG%?-lsB`grkLlFoi;f6cMJh5x<%KGOL$s2yfkaX7E>x%~5$9_0%u-^C+zA%*_H9dP zF~Z;MS!BYQ|GlFgZLMabqPQ#UKan(++%ogIgW$n9mwrDsPN~xf-?#d)B?{E`wo7p!pPkfH3sHx&m7y8p_Uj|KQXi24_b4SH}JY}JBN#r>sWpHwN9Q3=RwE#5Y}3?&f6+m!=6E5WoFgm9S;8{|`e# z6fbJCJ);LN?k=gR^f$E&jK?PQNp!S47p0*tNJ?q)gsGXlZ8~HPiBTjE@rCDmytVO4 z#q{aeKRxQ~!R|3{BKqiq-GwU~VzHJY`}*M;6=8(0dFuq+RpZkTq>lofTj_NJcb>#*lSl(2TiRXLBA% zx6q7mLYKQ-COn7Te@%7_1DZ(oiLO5wvjR&2BZK2h0ZhR=I_~%Who^oErd2xc z<#RHon~}pWegvS(v|H(O#KgW!0~)60iuF;fW^D1l9^>DMX=!5!QKUaW`sedEKv#>N zG~aSYLIj{z1hWY;j2_J-!BLe6tE25@{rpPb#`7x(jR1(!5x&SB#D8L-?`)zT3$JQ1*EO}rVXsr=} zg*}Py-QH|7TIv(Gzy*F`ud8IR0f3Sf7Ad5kujUqvB-OSHm;k&(g${@r!4Qh1a+u11 z#zMyCLH0uln?kwYLpHV@kONqqLva!uef2_3h-Wf`R6p1>gH!@Wi?1qac7Xc;GYK>U zQZRtbucx^_>4euqz2euLQ|VdaQj-TZAnP32Yyt1gqGTD^k<;c|p6O3ze`*Gybn92? zS^s$Dem*&~>~#@&{S=^=3^^4XMs;3icx~hxf())JW$q`|*4B2gaR+(=P_AKIHvss# z&H8uXqh9qjp7LG%*1L?w#JXBbyJETCY`o-y;qCB5gSQ;^+JchM= z%eyD;(Ob=8fC+2?&jK(8&e+Hya@7W+#W@v;xkRg348{}qf?5SQq91q=T>wE6;=qKM zm|%=KLimI+Bpa7I=bd|lCiMU6o?-4wjNPq;o(a*b-AKU5ASYQO=)yra4q6Br_F{{X z>HLW+8jN>8|oX09)1-cr?0v&XUP8p6qj`wPsv zr=yh(?Zuvl51_rU+GY+FXpl64)k_VL`}Dm^{R6@q8Fuuv6HU2u@=Vt8?Y!&s+S9vj zH+pFeyH+HvJ~jz-hLi@m?_m@ZklfiWKKcCp1_Fl$kL+78$L(Mg#XxrNG%*9OG#!6$ zA6cr8#lakHl*jsPVHRD@t~6Md^ag0Oi&mV&YZv~fCh^j)3_PCUhE&gL@IREg2wjlP zD2kMn3L%sgS)X=9GP3ELGn%q}H{~G3Lb0>>m9X6wL1xyLo+3SROMWqI@JGmRi66xV z5;*w=>_NfKwfDj{BpXRSM`tZ@4Eo+mUp ztyvUrkfUE_k8sG7(?je_S}21T@tU`w# z_ zlb^-ycUyCK3Q2Hc?pombQO_h6DsEiu z9gWF%NOJLC^**yMYfWIuGIWz5_2ydgyXZsExqHVK=if$j3TJ&s6H5p%krVD|`6%L- zuyk60@RaQ&Em8E2diuKMhDDjh|7!vC1Yfj1s7ZZbnC9OQRO(+`>{U$8rMK4BTznB! z`PJ}{YsG+!v+2`eUE)k;Hkm-@I#-*3lv-fI8!yUVLjCb^97YsQ>0-L_q8W|~>>_oM zzveQs!aVP<8)Ye48*JVS;Bg=b5e!JG6Cd!Qmo*MtCT`ZD;cCWz*D4wCtB&;GaF$Wqsq_9eGMetH|34nxj*9Rs4#TJ=CxOB_GG1&OKICu z=v|h9ff2c{{QoKq3}g0MC>^vNypGiC{1}Fdr1E%v{yL>CAr+uE3sG+W=UObPoi@nz_`6Nc0H%0t|HH*xBE1!E!WlgAWUdrAS z)~02fR7onek+D1At}tcCPutXx>xh(NqhPU=ozPli<0WHcp$*4!ShFSBsmNZ7et#}v z)1&$HiAO(wJN+{K>Oy%yH8cKq5syFEu34*dPERa_{Kk$~M=5x2}=Og4+g8D;Xn zNBgOTg`RDV|2qMcY8zAu9ykGcMPK@vCpuUuyWd2z}^a@ngEmu+IxpHjC-1{DLw zDA{jZd3N#r@Z|1&7^pJpcfBwp`d*()>|M?S-kh0=__=?Iu<7HEAUOPouff8WEMOl9PuNsZFJ-`_ffNRm7*@7ec`0tg+(8?h82vyCjk%fm4D{RfO4(`| zkh@^X3pTmmVJfV`@u-T3SE4&Fy^#%e|C#a2%?2RWB5%Lfw4B_AS45;}!V*+~_zF4k z)f!~*qUHV&W(+Y26PBP71W6>6qSQ|3jBRj&@(=6}o{bQ30G$Vrs0)iGL>NKA8%PR} zY&fv!u%+Y_66yhAf9i@YH2U`0Q~<*ci3CXC;3U8C>;Ys2zPnm}7Z3kYgSE7*OdNds zYPqxg5vJVG%8>QC7&gkt^h2On5H-pld{%(r7Ni6{2*hxeRab|sxPUYd=yFG`0cfA~ zfdZ#kh~>c}_yeVOASDDTUY}`JygA&CklYj&76yHHFQMKRgs@-|fM6*2erVCy9g?8| z9KdJA1-@lxzWwHZuQ&{Ji?oc4W0eF3uR7hG1v;TISeFK_Peu1P-+6&uu?IHp$bGUZ zGp+w%Ivd6)U^d85<@)-<)|U2r_~z;r`Ig1ME#3^q6OB1ejE^_jQbLT!Xt@>}gdhUF zLtX#~4#VjKm$QR6jBLp!FKgR5%)?PgrPBcFNN(!$4>Gbp%=rJ^~q_S02p5+YFIg#bZWDO2mtj zhGu1Q=889UWmoU2$7{$_9vdkU0n8spIcaI>6J%&~wGQTNAK%R4_0`OE&qi@$#6}G^ z9dJ!6D%S@pr`;-^Ey&Odqz={&t_K(Z-_`A6!UqEEqTwL>(b|z9Oo$K{Ez1IWXu&Ci z;xWk4LZ*ZQ1OX;ZWMdT)A%Z#8qG@8R;plM#gk=F++X{oB-ql{53usfEmttSQ*n~{4 zhD~2dNs0FYIHV*RXTA=Zubx7|B%Gjd0$(^9eOo3!A?GSfRMhQAG3emm@i|Q4n;R&Q zJppkXp(oo5i%4j%@4q28G3H@)L;om`^K(Q1wR6isr@mp z%Q2W|;aY-21M{P_-_MxBI_F(qxXtz;-4kjdT9GMSNb0F^W(8TfMdQAMf)u|(VHm(y z5YgR@#Fok?3QXN8fhd~UmeFd3-Y?`GGGS@AJ1+%{q%9>@PZ@o$Cs=m@){5#jMh@G^ z%o%`@&a;Z$mmUBOV>{P^0pAO_sJMJL2xe1PAnv2uVT}k55%t2t0(sqoY-5<&CY!*) z3*4t`KRDKNep?`EZa4rui0W5`TwGk@Fr+s8nB24w1w0M(FCekufa47&Wf+77(YIj4 z74W(eM&f5<8~V?lXS^q(8{D z_kAsr(+mo17Kxp)jowvSTV)!KdYtG#eZFYCi??h;JmuUZ$9zrdh{f1YNFMYEqOUF0 zExMLBn>e!_h|c>J?v%8It1=wK3f_IY<9wd4>TFTor}63=p4tzxTs3B~P|8(&U2o62 zCpVhr%CEY=mhRHr^5J7Uo&9m2rE{j6FKvLxCs5Euoaz(8NFt0C|IhBdBf0H&Ns*_v zO&U9LoYys+K>7K;3~@eFe2*d;46)J3Xx?Qj27pYO2!BA(rS_{ zOSiQi2rq-OVkg(W^|NVU!k<#zbQ{K#1@%*=H)Tf{2ohrE&ph}JUBY5PD?G#U?f6FK z9$fn;k2~z<(Fy-7r`LzBI-1hc8O;h13cPdGYR#uJN(%~Wi8ttJ!vEr_lDM3+?!fj| z!%(g}7b|(|#y)m~xqeA-e=NN@A0Ef36~WD1QiE>6wW<%EUSub3v&lZ`p=`Q|XISKG zu7>_|3gq@Ev{I)ODbole?Yc+)bDttU(LMQwAJi{NgFkYT!rdg#G)Py`TCGi1LFU9U z>ckYROe6Bw`OCtS=E}|nh0RBq3!1ZZx;`cuKH5xOvhrm9?dWSR&Y#2aWG8W23cO7w z|4iOcp!aXv(@-VyIS_ulbn773Lb-7U6;xoFC1e>zBP;$Ew!zb?Oy7rZNdLgy9Ee%i ziqsfa$Q_aMaIfOEnqyGa+zVHFf0U?Er{$S^lrxddU&{^7U$$aL-UNx$sbq8Y1JJp@e>3sd99S7h zaHPQHR&>m>cZv$qLs(w=X{hb2=O_V4hI@Tz`xxkakSlQUYMQ#5CaQ>>`U9s>mVgU; zTL1+<_ARd-yTWq?84Q%1u)H3d&tvlGaEfcKK&p1)OJk$*<h;hknn{+#xxxnG^D2rP%7rP(9n@(awXvu1WUcOp_6P)(cVpdeJ{` z3>Ro?Y0Bjys_+o6C~QErVUIOi z5r1RN{z&vJxb_y!{Kpn~GXj>Ul{48R8?(IH2kUso`4V{xAGdrKe5g2LSU3_)CJ*fK z?RXR#qncx>4=+9HUZ+{Uh}!gBz&T4GapIJ5G6?*8igOskCQ}wvVzrk|U;mRo!9AjA za^;(6+gvk>_192yho~T>WX&`~3TYwzF`@6r76*BbH7WSHhWJ8h46y@IEVt!um#OxC zB!8e5_hdcgj!YrurE*+>*|R8?$7R2>6aZTtVq;p2d-1!-yh`KF>JQuTqVZ+0WnE zYrKuVjh|o`;eb5UHufSENhEWuiJ@(usKs5oUPpRnVr){E{rxhuI_St1TqN^V^J{f^ z&g4@1wNj$$pQO1%sO%oE3I+RG1vN9#JbWC=9BQd_23mWvcctx| z18_C}>>k5jvWMGVOF=^>lHWeovE}&?`b<2B;uw+%Xu{41F6Ac;D5v{=5N8Y>dB^tZsw_A4y#P6gc4kOXhM17Y z1XkdMgbIVQ+S>e)$%?{54TG5&P#8%4fn;g;2FL5ju&`A;*BvZKBRB9*F!S=F>9pk` zeTL$MM6EbL!~$yuz2gg*5@BXR;xavYS06$B0fJrFD8Xd$v*rr z;_JtNMnP$HA7l2}FWhohXJ_Ys{2wOEP#xlppx{!6n}W3@92}yIDX4MZDtN5~sGWY1 zlBAtBFPwbT4PWHV!54Q7d5Gw~&`6pZ&4o$-q9SG_!tN zJj?$LqIL+z0C)_7S-=4c1GozmXgtP7iax;rz8|BuZj%N|*s7u);C22taT^945Ug~T zvB4PDjrpuTuqxlmbysWj$&G2uNXs#3XsndK)>zgD@B(+d!FY?!7!+ z`+nl@-_bd45ELV2^$?{E2P9X+5Mr^>2OCcEfyVmd70*3lM4xm{$2ZgjcAz9jg*t743`EYRpx=f47}Dj_jD)rzwH7J&h0O>+wDUFW zfJK6;3lOfCIy&Hp-Umz%fKiB5TLw^+T(;n%ylg`KbiTW3G;y~C1>K**qLp)MF@)eR zuJ$*j@i^X|P`{rCl_wpCB>|<_%5x?Zik->aH)9Q4B=SuV-SlthUA;bsx=2ej;?B?- zrg`10HRYNcu_c;0q5052AlDiB$ViLWJ+WPraFX`-5i`9EmZViq(DFSjMQs}Oq(dh9 z7GaqS9pNu!@BV36pOc`STA-GcLH z*vm!D@Fmg2aYDEM!3FQfJD->4<|l(p&Kn6Tv%*UlQ}42;D`3YfT)zHI%endKcBpnq z*265*BBB$gmGWN!D?ITE!9E-h(F#c_x4WvsY7?q{pIY5tq}4bZ`FnnX$N4RSU2&pJ zgy5Xbmy;PaB}U~%AnO-$yw&_1p3P6$n1vK0y4YM2C0s|+U4?3oUKh_D*onbb(?`)cPB3Fh%n{0pMMo+Cvq=} zx;XiCv8T7MJjLVSCb*it)zAzZlc(8S&DHiIE*+3r_)=H*H#!$GqR`k_Qbye3vAgPc z@4I!epRafo%Q@}b957wmia6lM!&vQj8UJ-;93!|>SKA(<={%WxjC3SCXhG! zjaoxMSn!Kxq1xNW--?RWr}AbO6^zM)epx?R)b|KwxUX>aO=7{Ao{b63z$Sy6$Ldk~%6tvA zhl;+7z6;%s?DV&zkvo?bIFF3Z8A^Vm4rGqq6*J%3z)l z*{foHtJQ;RBWo@WZiD}B{!_kHIni$Q-saq+EgDT3XKs8vf#>rl zaZ|Nm%S3kSqDhG(x54d^m^%;OP?cYp6?A8-Yn@W2D%s3X*J-1^$u;^6>iZGa+q9eh zr?`?RH^_PpetZ_ovXuOZ*||5_ggRiqTPIRQZT&T9a%+V6j!cAKtP_DU&YG6&fpiton(N@k`R4fAf|IVrXS|}Iv9+h=;gj}ns+(=pFB8kmm$|hjcr-=ApLfxh zy%E-Noo0XiHFVNm-~e6bbNIjW=n5OQuAHbfl9meh&*l21hVf>1P)pbf6!D|GY1Q!Q zljxTCu?@(of@iBKqo%3LMxGwkG^EsQ&7SGFU-qxQreiB`r+&s3I1uBS!dUnE&1E(E zCm$MDYXbv1RFPAwRoZOfJA+39&B+z;oQ9r7(Tkw#rb6vX9`4XTHZN$g+J9xWbh5~O z9U&(r!lIAQ;OZMpU>)FhE*LTg?}DSO$PQU0XgheuHz8dDv<=8O>nITWcDQ8@4JM64 zSP8^YCV+>Te9hsN*S3QoWO^nfk(lSg4p;Y+w@jXJ`{yhNP0mbc*~H)fQC-~)3p21n zK%yWe#$dky8H)+Xgt$jxsR4S~@ik~iD|2tmKHL1}5c#O&Zm5)pN8`*G?W21jLjiCO z)J2n4u*Sg_+d1`aZsUZ?u4<4x&F_BLgG1yf;&8pz4~bJnVbHb4{S?CIN2j+mTdx5f z3SOX^7|-wfIiAQJJ5WGldR{5^EB#2r#>Su@Q_n{WzI#89U|xV!GPDe#+xsajIF?@z z_`!+_dk-`^dssT5Y6G;#7UvDXp@6jN`}eF7<_;c5+`(QKNN+74hvsJU~HcXs8s7e30r1(*(Ug6oN+p(gvE}3Oo}Pz&JoelkgGJQ9w}LQ3w8NC?xr8vNq^< zmtAM}&yTkNhR@ydl7(|6Rt&_{$fncdlOac4D!b7#Hc-EUi5KW0aMvRHo1t_1=-*3Z zu?~=0098hALU`MM{bu{;jo0Tec&$0Hk>J2;3(em}5EJtIUpN4$$jVN?CUCjkG6wo~ z8G;Tj{%&7V!x00=3t# z1*F21L)|!NqzoR!&S)wc!U=om*qNw8E zQ-EqgvD$Fc41~Ht;;v~2cRTuag5lZIPd|EN;0iz2Lum){4YG;h;)CA+=n2t#y8vxc z8QO!L2XH7j^3XdgpACL!@{>DQRS;vQ%>5R?G`>|+@WjVy3J|GMuhfg}jo zC2DC2xT7*?yur`~gAR-_a4RC*PkZ#1?>3%bfS4YpDk#bUJvv;#aA|_Q>Q~cmWC+~< zR?R_BjH!_k8p}NZ?Go?pgS!e0X#gERj^A}C-3Vp5!lY~C8wFbIIW@5P-bJMaP+$Q=WEA?vWVy@-{B7)H*o3!|*h8W6usdDF>EBoEStcx-0_$hC>) z3xoslnfx>i>qHI(D64Q0x{=YcUglA8JY_r-{U!g<-9A3eASCcpO~=m^RpN@2{(FKFx3;HcGWVE=_Iy2No0RlnS9Ed7pyhMa^qr~oT1oR;l*1d zMD5wTPiJtkK4GR*=}}((FzcYzS$0xd{xIoHV`Lve5HclD#$3C|kj^fE3bV*0G&%}sxx2x03aU~d%eY7(lB zavHIh)EoS!+$#G;xq4ig>pAYk^=ieRMff89cBJ=p%UKX@6$fqvc^ZA9CZFQ>8tHPp z{Fp2DQ>DMesYv~hXl17J*88BWj-hBfZp1HGdLK zX38T!k`E;~2>D;P*VDs|@+Gb+%NF-k=tWDC%|%OBNmD?I-j zlqVefT=xlrS)Hd{Ah^Zh`I6n|HrV^FxVmu{rLisypAhH&x?7 zu_TZ2`_*klb%HQ|?~-a6@pnqNg9Zq}UY7!ufT0ytg!u>N=P8<}~G9B`DEMl7cX*%kWu^;v!YLO8X#M!GH-7XBn%Ct&N=m$k|E>Ej}OQS#=q zdN=dGSJ;zl$3x0lLk+GsFKcNG%5^(;GVvsX(2Va7ufBWdyZs_VACZ>h!-<*pc;zwG zt;FqBT<^7|alvQ&xNl!ua)f3V+!~qrqM@7ElKy5{F91!xG14FxBlCt$^Lb`crz%R- zTJ=y}2L$oeN(31q0v*F`n>rDFST-X521E@{w-IO?9#NAD?~k~<T8^%|D4Va=$Ka}n`zq7Q8?eA4%EUr`Q&)j0(0$s2bo5n>;b?vag23^M zz9fpD+iDBqY&QCXW$fFjnt(6j$5`HC1UskRVu;>tEOio6_Hi{>#E+7#nBbpc>Iu?7F#-#oSNUi9e zB``8e7vY&ih5qYbYLxHD?j~*h^(*GSGakoNMZL4(IAkkW^58&%B4(edJzG!GC0A2- zeNva+^XFM=xr9!v2!I_9j6dwjH>xs2dL{~zQE51?-=2f*cYJ(&6B0kLyIa%Pc-_?d zP+SzHS0L(G@Iltads1RTOg}z{ zj*VYJHn|w5(T~)^`0yDw;dn=vi2F9v!XJ5*TKkgtZo~sm2l86)NA7bsPj*^wJ!6l1 zGQwYAIsZ4{=G{Sao}DTCfeh&Ufam>5kk<(o_>91c!_ff}m1a_L;-}XCuLWp@)-iqPz=YHtj%qs;G2=kHDOhlJfq5YZJuNyTPaLih*SQr%2)XLFmB4Yxk8EQ z?x^;===}Le2Dp%#3_zm@qIL;pk`|bfq4nfO{5tgm$tO5ud>uEA6E~eGVC1O+cl6=8 zX8w{so3JGtk(XaH?Uy0uA1;Up-n=|k0PYapq}$4AB1!`t#P^lchsY2^IaZa!)!-&zWTjr>3fQ` zX~hG9&d{R1U$b@W`P?`|0+!m*ybq=k=rW0#F?eC*DV)3w!HKCzvgc9OQ+$K4Vs?IhHqc)TDlSfoP9&TjreK|#oBoiAD4*(K~fLaa*L z%Z-f^qmCbwIq33~G-;|)c&l{aRM^hR$|bD)<;P@O6A$U0ttTQ?e?l_#oWFNtv8I;a z{!r@Veky%PCR$WYVsofO_gd-0=cR-vlhE#nzUX5`gEcPmESOQ-AJ_5@;ReiR(>w7R7U8 zga_|~;qv2OL8=9I+#I+;Xsdw+6SB50<@z}rq^*dRoF^Je0bj-s({owfJw-ia3z%`- z6K{#6&7ASeqIe+Y%_(_LtiNrL9$+2NrDaf%;+~P>V!{`2RKt4C!LuCcd8|Br1?3q< zLjN+~kXt#&)6m&-1Uwz-739NJrn!$cWpOK~hqCo-=aY7=kf}@Gd&@KPUUFi}f?#7W zGXW_*5R_mt63bl_UteCk9;6PWUCghDcD`sllS!)}m$74{(dJ({u&s8+40&9k@>3yd zO!$vGdf3)&Dvtse#k~3$x<*3D*XT&?j@uEgs1abU$zdR|&z{+5V<83%qo6Z)<~IjAqg zjk$bOIeb0e1xx3LT$Nz8cM?R(5FWfW=c5>(W^es!d-50~?=aPnBI$~IC3~u5Cer{l zgdfcTbM+2F?oI$2E0%`e(-ATrKd1(o#5(XW{n=v0WX6=o!U>i3&o?K&ru zX89|~G?zSQyF*ok0ev7!X`K^n)nt%$_I)V1X9?;m2*af_m~mhi3MZIw(Z_eR(snM!~AiOyMRU&vW2ud{bpC$S>GgIPAjPT$FN#yxKviPG| z$Xsci8*KJxjPIAe``3!FR};3pq@BhgoeTJ%v&1tHtsF2vpgeyb;=@i9qVMTR4cNta z7*x}P772d67^Tn9Cnm@53lL5lIH-iw-T>3`5P(_WM}T+(P9|Mk&m6dqT0orcr`F`1%dkwSd54{n_yLDNnE7?k#n{SPf;)|b#10<>7Xm-(_x_n0fHA^@}E#TjvPi#KClg zjgE>uun+?W#W7G?4qu?y0T_le6$2F|S0VUxI*CaAWC}0m5>#%q{{5yN#m6q&)6A~Wb!T^uGN$Z93;Sl&OGdgv=s}`KWQ-%HN(7D+P+p30cRJkc4S6P{X=$k2%R->btP93 zz2t$z`#W-ArPV0%31-?r5S%x-1VHZ7va%1dIJ%_1VTI3MnBiyfbcagP!{Gz#e>Qk;^Rn|%!Od+=N&_(oH-GvgE zfi5WS!uVBJTr3TUkIf!bM|uKx`J!;Q+>VJW!*vdO@o#SYRBB-#e`Z|!48z6yILm4A z(6K&I6jG&h#LuVmBx zqTe19VsXs*NRoGMQK*sk3cpHI_#~k&pp!PV;HQ^r`+~>(Tp>Ee|W#&W9t>8 z$>-aBfsADkkaR27E_-tZbF2?=c+s%Z;|(TYG!eXCBl5fMvoMj1B-~w z`+kjh7g5~N>QC?EYDHbRAw)1cz#2-|q&F(`#7Oh(&WS?I^wds8&$~%EjvKb}3c?KC zq2A8^oVE2~p1<_RLciT9-W4Rkoj+Y^?jntATLozxN^+Wj$56wkDhzz0A4JUbj`R*%nOm*5_h>46v*ARa^5uGVYDse41(o zOt}2LeTf6RYJcmmey}D=*GB{%K68VK}|HykoJs63ye7*PgVH^}5(E>SxFAjewVjQuAT^XGGw*ras+ zJ_Jwy95?O>E`HyFsz8v14fE7RA?dOJ@h9g~4*qyYmB;)%)57kfbCvjM8-pk24KXwY zjXH?BUi)zSlY-WPLWk;vG}b+GyA!;Pn&vrsO0g#BhMp?@#Y40C#nNMDaM6Z z>{qRNLc+#IuhiVe$h%GvjtS}-csTpiNG7&OrRC+BS5Cqga&1D=4nc067C%0~vJDaC zTLc*1VfM-hh731;$_{-FvBnub4?b-@md`yVFxOnUB*`UnrCc)=^fo*eK2*qr-|)0N#f!UZB`(2)w1B~xdd9UPSSuqNhu)=U?n zIY7mpYX0wZW*nG9z%|V|gZ;v`Y)48shyO8w^oN8879K~!S_|6H2aQ!{UQ&BmXxx(cl%-ma}!%x{t$!=&#S4V zpWJdgCE2>}2pN>{p7+-lH!$lLKrXg`qHTdi!BgxTY$CEZv>+# zKxP>0&Efp!z=cFQNb@0dWBDMySv|G^!Gv=#+Bq*Ln8CQQ`{!*jw80T4+vka*%o2Na z9Bll}yy_vPFhGzvvQDjP=07JVMrW2o(32T~5*WJUngN&c*38FH8UgjIAFR-DQUMaa z_2U&DU@XXa0+hPK)c0RR!k7c9K^T|e1i&>1?+8#h?|~HtvA+}XKV;wcwPrvnGn*-?*5LB1BDkr%qSVE*fZyU zk7xH!VYdK}0Bo)CHHRG}cIS0o=@km2kv>N-3>s4n9u$EF`oL6;x1dXC(-NegK|Rs< z^z^-R5cI>uPtJfc^6)KOT<;UgPTWP3gvR7(0prURv0JR>Sow`-sbj<4M= z>lAwBq!sy#Z8+>ON+aJV2xvMqJ4m6{%E&!eGatD(06jh2FAzEh=>|8N$nb;Us^g@@ z?{0wYEo2>lAqGYm)#tZ?`k75OGBd-1X&hORSToH|YJ@Ir5(Z`k!tp~G`{3??(u7tp z4ixFu27;U@Q!_tfaucZxhuIKrV@U96Qv_OU_pjSFVJ6K=GU)*_7~xyqhg+f-1Td3I z^HWN*$4OM{FqN2Rt34G-gJ!^HWJNQ&Uvuf^j_ei3l3DRp{@V+Kqw7(xh;a2V>jS~| zAB3J=ueKymx);M=)|hVp`;+ve;&s@sD88spRt6Tg6Z&Kdt>r(u@2%r&`26K)Oy8+0 zWS4FBCg;S=cPCBE=hU3wYMfhqM8sk*2l>xzN6iHK!J+Ju#K5ygZlu2Vw%7yj~CWlJZHEpx-EKXq7(ZoGT# zbMtChkB7~K58mtAc^3wde4Jl4aTl~$B2HS|Kf36j(hwf#r(wXoCG(I76nAHR6bWc>{h zQoPkeBJ*k8j}_Q|GF16!R~r3rXr2?V?rK zyEz6WPjrXjetVM32?n#APvclYwpl#No^}sC+*}LDO!sXtEg;ksk zwQilOG4q~L>^Yv2Uk=DNMnYsSnU#HNYoS{|10D+g=Uz^yI|yd(v>`D&bpoS+K_x_b zQ=tv?Vp)ez;`9|#9+MCbVET18v3JC0(uA%=4@NW@T5}}8qhn(V_34dz{uQPwMVx`^ zr-+InWkbJoQc~Pj)0?*5BWyO5Mwz%LUxH2da7ca|`x$+HLh?Mo6y;|;22Xjj32OY3 zg`TFK(Puo|R^v_10z7itq78|+9utNNkNF)W?&~MyR$jV4=C6!z>#b2IAwKB9^Bbl{ z`6OrZd^L4CN8bmdk4qajb!w}H$4{fp@27x-P2(+WLQA`5F~mTl4LTEAM3b@1UJz}V zh;sHy(|uIN{luPE@2MR=zGsx#)1zOQ{Ni!_w1}$POucRt4P7W@PT&49uA5hkp_V;o z=_89k&fraKf_)9^fq)RI&y)X}brMxx?Mu&X5sF}@&SUp})3?R{fw!8C;@gU_BOZxQ zc`3=2Dke-MO;04vMJ*$kAkLH^&6Vn}G6av0XSt&sq~!X&SUG1+BzU+V9-BQ*7xUrb zX$qwLaN_OV>fmSY!I5Euk@zKX_0cqfyQ=BlQ$9p%iJrGcPCWZVJhZ72gpo4ar|!1) zhjEemOr*WLh7am#{%~u43q&8*5c7%y%>fy$BGy;8Z6BkYeH;mL)Jo^VBv#G&z(0i< zbc$!z;Mt0vK&YyOnwH=~k(D+ut6Kfkps$RSeJ4Sd#)%9UUo^-?%jrN}3k7#%t{h>A zuPY!t@>POQu_WbCn__+Er9RILT~OTE&_EdA9ia90{A1z1PEQ(x{z;ZTS}a2qp>O?1 zhMo|?OCT|*g}U5|+`f~CqjDtp8w2^1W7Be(5Z4t-0~(HRk5TMD%~0Jzl!ofoITIoX zLL{-<7WPj;qk?VB5FZLlvd=4cIct27(Kd;L^LUuR0E)>_4gTX>^2z)@%rR{-#5e&!JFwh(wlc31qx4;-va8@lSv_*&jclw1Cs^mr zM|IxNfr~$3IZF6mCy|SS6oJ|kM%?U+<-LBN6j#lohkk>Wv;+NSa+k!xy&|Vhi&QXcG{o*SP4Y0F1!<0*`hFXf~Et zl+u49QIi*X9=Bnz0S+V3fRq$J2!6x#S^TM<5Gig~_Fu5X0ELA#!J)78r(|B;#R&ig zON{-N6tb&v!Q|!lc34WyQe7~M>-KPU$48_glG1mifkFd{4r#c7`Qqf#6X2MOSuD~2 zSV3qTxC`?OEXP?3kn7tNzqWn={<@RHVz2NQuU!I~GQ=e*j?XV)v3~Og3`+Q*poSw2 z7X^rgWf_SgJT;5Q0Iu{QGGVzB8lT2Daby2fSmU`A+Z_o&0r@EdXSO@RN$v}-d>An} zIslW9>A3k4;4jd>08GL8__0)x0D#=Mt==#`38r+wghYrF0AgRf4pNYDVgF;&F)`&L zLtaU3xYYoF8kS-!jhH8s6xio#-~<}Xp6o8DK97xOfOuUPKY&m}X5lpr0ICV6hBOce zJlUhAWN@(E2CORC9#w-P5IHr%cq&jl70LBbNm-cRxZ^L0mp+jE@83MR9k8bpFc)?FD|nBOqrY-EC+F7 z2M!}g?`MTu-iV<$;$x=Vbga3#h&fZmo2F|LS9x!fqh-`EbJ($KmTnyUBW2Cp-$~{Z z#td3?z3RyiC9EEBQ2f=ewB4>b5RTiAZPqR$Vz`@S=lpNRZDV^2?QhNak#Xjmm-$9h zXAf(e?HAd6<|IkaHoWs~U!?w}AB&x>MKS5iZna_+DyV(nI-v-cWpu6#*^^-#L?%9Q zY1GCqwc!^(Kh^5KlT#EeqgphlFBp5rE=8~w{%qvsz_6n=3YMgYs}qxu%GS@;H?L}w zWA3h0tj{tC3jO5&_-NMpS-)+|2Fl{^zxC%yV~;(%+MhMedMv8PzY6c!o6B*rcKgt{ zKy1ryG??A8h-gKHU%pnS*qY<=HTMI;)F7cMFQQpFFWC_biYOJ=& zHz&O_+ja3^Jg;|G+)_rMQ#k?U$hquASq|k&}C;@kec0 zdUlr)9DnVnzDA@_HD6wLUC0wI#VmJ3Y|(ej?$!ud+pt79^V$l9553`d|Ks6CvRiai8)>Y46t|z5ZJp+{Q0}JK_dQ$iq#ystAn=jlv_7=@9j#c+hb21*W>47bR;-&E zuzL5oAO2BA)0nb$?0jlfaob?!T4rxXd$Bq;o(64CDDmHi*Hw~1k7Y;@o>I@cC_WB+ zZC)AajlA2GE^GUEqZQ+~T~h8F@(Yp1HQkVx{?rookt*sQJ6OJ|k7=qHY2Z{r4u zd70~*lX5uV8+CF1qgXu-Ts^{EJvdu+a9cfcT|KN>#XIL{$}ndoQ9?6Y?tFmKNRyZ+ zX5jr3ficBa*3wLdMS{Rd|Aza4Rph%qN0qfv~%~B{2Do7I8-A0_}Rs{S|)qJi(8~$D-VNF#X1ccUh!d zJMx}F_vrs?0a`ZwQ1qvkwe9QVxJH(7nbhN3@R+BJPl$H2Di!T+%ds=Oc`PS_%R#C? z<&D~Eyimg>kfj*&K~3@8E^o@ zETT0>K`KG85X06s2I+dnd!L~VdzoAfJK7?Q^z@l+cv=|(O#)8q_Fun9KrR3~Fc7y6 zxj6|^p?<+8EZ__@7<`8!0(+(i;eglTKor2*UiuTD0@S!0m>kW2?@irZ-gkj@0XBuu z6^o^%?9DRe$UK&$PYB8PS&@iocq=yjAUxq7;;PFSl{8=Yys+zCCYOJR_CbJhc z(S=@{P?9#)C|Q$iUlt;(9;42owYjx5A1y=O40dLaNWkXN7HN$px?%W%*h7MYJ_UBE zUT0suKEQq%gpx>V2+0^Q5+OH?6BEr)X#k(!CkP!;GPVKU*@dsrx5@1L} z4-YEuZdPn>9l8P770+QfJ8TL#S-641zcmf#g|$J^+&vQsx4L1iUCn zOag$>0_ztDc7dxC-fbg>;gL_z_rfz-#Dg4sL-(Sd*T24h-0#^)Q~7R2I&-KAE)%%q z0WEz7d;GoacL5#xl7B#civ3OTYlss z5c008e)|qxfuajHLW=zlt)U^q;9q0nwF!Ne6$8JHf08nls8X+bcjG*JT&s*C|Lt=j za8t<;{@Eo17&ZDlzICT7iYne!$;F`uNt`QEr%`NH@6zRxvi1TK9kzVB5O++^QJ~P0)MOT?X8lhf_V?G8`7{_Tw$+?#FYx1IU89^@I3dpGygnbB42=~QFkgJJF#PW)O8dxy82 zMS^F(U)7H5`G`g{wJohU>Sv1daH~MNtCp39qk&7LpwppxXVv2HCjoo=$h>|VUabzH2z$ky zf`?<6F)xBXeva2|zDK%t(r>;ZgR#=T(s)=$XUd%`bVJo!HgUX(wpMs?^u)TBo8pvK zn*4fmPNlTJP&12v;ek;<-dm%#O_A^plr8cHjGrml#cpx%tsu@@C8X?X1zJj&QbNN; zZBca#3Sd#a9hw`)Szq%rEYQU`cO2yxC%kSFLEQ>4*@}S;pKpU zoAo(kuhuBI@5YwvsYQ;I$J{J_b+J?N?QXs|(Hg2AU1f8LN0as|+soFK9zA98a`~l_ zQ$eTc%i<*AyJb~nN*R?ei%a%79o@TCD&@w`>o&r4`%qNo**J&VztiV86kf?s z2D5tz4&0_6k+Y!;D58{cyb(7N%Om|`$VBz~R<)+zMI*jD^O$tBJZ@dKqP$MO{`2(5 zjbHCIIQ7M03dN*^}-Hxnc(`H`eIG-u8lxn?me;9PKah zm>TC_uOyu&Gr#+h&w6}Hak}*2anq3 z=6~`u<*eSX_Wd5hOy#>Wp2ZqfM+PU3qaXM$&~FSNlnT$X57|UoO3{?}Yf!RK1l89Y zfGWVKhFFtBA`cH8An}o6?i!eK*crr}#p&MU$d2g`3_bXC)EdlWU@v+fPESv7Pi|q4 zxy$er$B<@L8-+c?<4jgA!x0N{j*oYfYy!|(U>RIkb~Xh0H3$ynvL|{IjMWtFNxnn$ z;J>2}SDH)e_<1yA-l21TU??`YxJsXwex8TiMc2C3CjS`yWyh)yHibRjL60$u<1ppW z5nl8TvlU7-vRCA@yKn(%DqC?jV?G3`faLg@)pY#6>w(b$cGKXox)v>a=|`9|9WI@nNZGx&9HtI4#WXP5bO%dJeDOwAn>>% z67n5ijHEMAF@&A^w%Mlw;u*+_+Omx8-Q1XAS?$%-O*1_OIH@1&UJ!9ZD2?Mt=d!c! z-$e)sCRG3rgyIK#VNlWTpw-|+@Xgl(m^$ui0F?UHi4>3Lfh|dDcMx6Rd42U~S`=Kv z>_F^CzCZGcbdWQcHrFXvzC6u`td3jbcfBGZ8&REaKe{)QKE)Iu`@jTRuQyH5J3-Rp zzdm`U4ys_H-9Yex>grSh(VRgB0UQca3FM_{8d@P`*msItmj~sCp%@it5GZ!Nt*~++ zhmOSs=snr81~eLqJlVc(rv0dKD%7*+8)lXpbsn5q8`=g920Y^Q#X& zxaQ)*h)5IMe7Fm72Z5;AY4k+%xw%%Eb=~u$S-=215bO`76a=y??nhrcRa~ljqA!Z; zjgX@|;9Nk(;WJBx$O*UmDQOXbs9}8UM3Vx`@GUT1aD(B?2e6(?(PxSa;Vh8Jv`)^; zK>TAOPJOxys%eke5rdjx4~Rqtc>9-V?jES}9*4LVe4T*b2NwI7%ZDC1KCX?^3y}&Rx zFa2-T!nPTKLxPS`ZXDYk7W-&#?_Q+;@vv|%{^OH>O0S|qV%rMeWRRO*Ox=5sGW2mc z=SAPuw<J*6r@dQ2sav z+E59FXQq2)6?<;ZJ+C^oe(|-i!1a1(CCV6ZBnG|18U2EqLIZ-U!jpoxeaX2Jw@Wi; zHDhZ2gIId&#p4VepL++n=OBDAtX|NI?(%Pi;ApSX3=e%xDN!x*}cI_9vItA?q%TDN|9n;Qnysu?`(cAo@#oh_Vzbk4#?WXHVG)#`}LA<14 zo7?LLZqu_3MJ|dyW;)7clp;?N!lo(rhki@W9l1NVB086!gsV+Q3M{Vf{4#Kx(V1s) zdbuJ+Xxz8;b!nBawYq4Iho9*|AB}+r0lpK}0*1`FaW;FVJt9t(8!wOV{v@(a+Z>!L z%YHCZhHG(mIk!>J6rHovywxA+OTOzG)b}E)`v0-0)z~md@iAS?bUKO323*$n*PAYN z7mGkAQ;V&SGnFjK0=fWLuUmp-MF#tI0SEW0;6tKp!ah&>b)W--SixOUbpOMA%%wzd z6mg`2T-WZ>PGzA`Ahm@i*>a(X`1{&AUtRbBsaRpMhC9u-5>5@K4S z?1l|CTAAH-9N+{tr)8;WMA8*z4u3f;%7!HXwIWffH(+mqR?`;F!BNlU>vK>h+CcIO!ArNm* z=(z1Gcf~0io(IH^_=!NonLP3G{CxaHM}?9eiqDGwf*xZ4(y%T#pHE!#s0at-w5$;eTf{SRUPD3C0#<=-NVH~E;gECwP<>G4qF0XI3 zZ#`$lG~0qp^*2T*j{hNteS%6v@G`l5LN50H^NT*%VRM4Fjx*fWgJ12wzo@^69bj{SkF zE;6<5(CMThJ=r=P$W?wC1t}pCg;O*TUP4}-_H}G z%~B+gK*WI09*P%SZ^&WsUXyZV`{efT4@a8-{Rci3ye?>95bxsp2<#CW8lr3DyNW`2 z2(XC|=N(&+7eG_KPQYeT!Bq{O0gyUi52Y&CxI-DBy&z?9$NydYw$=c2%|`(CV5uFx z_Fl>8&SZZ!xAJubn1BWrS53t^+?Qw1lEj3RK^pY}*%#7CJzmf)di*K+%@OrtNQ;L` zZ9>2Y5g;12-pHt_-Nia(D(DZ80-_BmCOUO|NFX4H6$+Glp(S4Xo29X1+Xubb<>-IQ z|JInH>xjC0ymfoV&U=lUeH5SQ1lj1mQaP>7w{b|0vXo7us7os>Lonv=gJFY&=OUW< ztfU)!dYk3*y+=(Vq_138J127byG`uTnf&Me6J+iwQ$>}c*Z{q!k(}RtG1W8bl7C5l z@V-9P`z^jQp0V+|3oUKlZH4m0EA)wRhn;R8cH6j56A{m2>LFTjCoAXIF3*y}$%c-% zT)b~?y_7HP3$3@2?b(`=6U$#~bwR!~y(H(Q%KkcITc_!FAN2xDR*;42q!N38<;Na{ zw@pz6`^Lx4?fjoD3e%va_eytOWEcDA`P#TJH_v5rbaKbP439QPNwz`NprS8xR?@Lo8*RQ^ z6PX{9{vjM?+ogT_OTe1t*~ux{f85-$Wyw~q3U#tgwHc{bHAkBja}Rl_zB>Ps+?-Co z)&3DLKV2;E585nM_fA?GBRFjl{!GwuD_W6?0Fx zb=Yx?&4ryL8!k)35H5D~{q`?oeASgKH2dioGIM1MgoV)Bl@>t(? zGhU7HoK z6mAnVN?HH%+Ufm2?d?1A!>c!XUus)eq*zv{RLj`>RF;wwq-dfRYLS^5d!^PlEE0Y$ zd0}6{S`}aYLCSyq|NfPisx*%o2L72#9>$}dW_E@3*FM-B5muWx8B0; zAP=vNmZx9sd4$R};@Iz*K1wC3s1jR+fC@?W7@bYIQsECXeXr@~C*};vbvF8|!n3Ek zA`Zw%xyRXX?MS(qx1RQI<}3} zZ?02}D6p9@%<5k!@rn z#jw?t0ui*nIEeuFCT9y2pPIgGG<-R6Eu-x`NsNS*awHNF#E7YyRDm(GkC~d1)X3;j zX|`jCN{l@wJNuF}S99|nFi?SZ1ZG&1{iw+id^UEU>D_U{F@;rXmI>5~ znmeM4l9OeDLKOVlBmvIjw zFK`(cpD(ZjRp`n+U43n>?i!KgSwk3Cf$k0$k0ptyQEy3L`TYJv8LEz^oTbGJ{uk6fplS|4|`ev3*fAa(l+HF=E87WE@1VFNQ}hw zyjAalDU+}?5aKPI{1`;AL7fqpLbN{KPp~Wz!0wqE+vGSnxBSrudIPBOs)5i#WJVYA zG+PoK!<#0Ir^<4*s&ySeowr&0QV>di@ZR510M`}@%Rj&v`7B_IDM#o^D>l7w*|+QB za~%~?c!7_(_z|_C$s_j`O9&*@ZYiiMDbd$*!DodM0c4p&rxG#&0RCi4dNJ{4CHz=o zSi>L$&_34s3Vn7qVYKO*WYs=~t^ue-s!586C)682WgS#9UB)ESr&hO-J82EtR5X1a3U4VVm(it4g$ zyEGX3q%OgO@V~-%Dt+d?VTID4UiRS<+&_dR6cZ_VM7EY#(Z{C|$oDuCMjF^XP{I#%dE;$~#5ULh zu-a4hmrda6lq><^gPMSV;kqUXdJB;S`Oh>TmLxPk5q{xWcrPO-^3R*laE6ce&fe{ussA-uZV&iJ!JQP_Ts zI0i5sVysza~&?^Wk4dly@ec6^eg2 z5xh5e^?kR24aK(aqk~_Ti>hi1xh@xd_M(u>>&c)J-PHZweQm)o`LSGDzkNsa<8}S* zPop9v9u`gX`qS)=@EjKykqK(&8JyA=(9HO(u8>*o5p|JSQqZ33uj`rNxwqG4*-}DP z_UAgt+$WK^!)$M;{>(dVfA7xr$$PKvsyw07YB|ujLwdMq!s+$BUX^=YaoeLRMf~1f zdC+BFJGngIEB%djTjGPLJHtQE=dOK_?_7`Y=;h~smGLueB1%x!`N+X=pKVP_Vu}q@ z&!0@5;<1m-}Y}5N%Asg~-__mdlEc2s@t0Q@KhsGi=Cq(_3QYDCc<1=&)7s+M| zs{t*{10PENGV3VrKNrwLFTPqWIR+a-^xFFxB~~`Ut2|*8GBi!wOKshoj0H7oka*|j zK~iQwQ~^VVfqZb4`CJ;SP6qSH*7JeQw#9hF`pgcUkolzF{P(~c`9x%ErAI#(F0fZT zwmI_0J-ykhF~)zEUCSCg;sWlg^Q=mh6m#5fa!ftX1C@;WK7M2ZjvZ%V78$xz7`01I z+xSIC6=*eobwNDo5g=@pZ}0gE+gqtQ}Mza?5J-$UDvtxeSPA9SlbhM8iH58q*hEA2S63 zcdpK+$ve4|Bavo#CAZ|Dy8#l2W7%iYr{wSPpa&s6idOx{Ug#{aI$sR4P3igdwC7EE z3IxfRDh8ggCq%!@a^3y$O^*u!<{H}$gF%EfbX&GL`TuJHmb)(O(_8OEqrwY*5!CvK z@{yu#9A_tdN*+A=Skg8QCDqZ#IB#JXe3#2Er1Mqh=Z;U?zp$Qv*K_|I`)qMuLS6=p zTfmjS8(UZq#}O#haKK&PzC9k^blCrZMBxG9s)gx=-OV~l+ar4Qde49KmRt#W5_V3W zbkoYXD5e(y-k8aVLm8_u5nBTd^cJ`G%VPKlFf~HGgu@wPD`16$C{N0$ivOAWuk7bJ#xH$*^9zvTd><|nWKJORJ=3rp&v@7x&OfXa&l847ja-Bp-Si&Z#=0mtA9A+-`SA8>ns zs+epE#(kvMZzXFrOd=~=?|4x&WDDL^p5 zKvuzu<3|zi3yl@JsgCHM@=p`xYN3C0$66A=#CWCmH@2VpPu=kJt<`_xHV;%6yE`$X z2e^3a>VZ*HkbalWF`Z@)vZWY;76UI1s01BNFcfM~ctOA3d+B!IJ`Bf)GV)4F4r^K+ zX+w~M$#e6MO!&tj`yl%KGGtPdS8n+q&S1mi0nHddaM^0eEL0c1+7n7JTwDAt;XMRH zf4b`rz*8Fx<>-qpUc89+1}Fp(MaY8kFL^LxgQW8dvDrr-dogMy3MNb-Ymk z4#dT-%r$#%1BihHJT?k?4{4o#^gF8m*5-(;4B|~fVu6ZHbSpc4Q~@I}Re5>r1%mJ4 z>eB@RUEW^@>Ht7K)OG|3P5AHhT%|R_XA6?w-yXD~yBd7-W{gB#rJeo8jOyivk33mp z@5yC;em`pkyuuc)Ocr`*G@jglUZkEv?7nM#!g<5nKi7K#9LMb47^1>1$(&ZY@ipPo zuvBF&zlg?E+2KDu0TG$bTPiQ6A2IvZIQNA=?N#Zeevy~4z6Cr1{>A;evN7{^Uy9FZ zn5ijme53dMc0bb#{1W$nMI@(AEmeGU!O{~uDNt~-podCnId8>qcmf~ zHTcOBg#wqM*L}~1eBR|xi|nfzxqAQ8eTu~4{H2S*hYl{Ey=*+Ywka}SbMx=%I|8G# z*<1ZyM*raP`Q}_>lrL>g!>TJ;nmBc?Sl`Kj)~SbY-;0w=!i(Yp?7|r@!Vh}>JtM8l z^n1fqexSI}RK|m zRqYV#Hd!P8vg7))!nNOOKcjZgIs<$A&g@eB24Nr&g9=L2e|>I!}yzwxVfPj#B~j+v(`Mbp2kYWLy| zyFl929kf5(LW7x_70X_=()oUEXyW?g>%uQM&>Doeg=>~tYJFF(S?uN?n8EG=vWRJ{dwZ<5125S%dBb#vG8S;Ge`8OK0{owE2LsthBioccbRU ztyAxv6(()2dXB-qQm>P0W5=^Ubt~@*L?n+hZP9>&K}0{Q2-FUm6+l-v{SK$^xU{W` ztGcm~0S5x;E#&)eFoFt&DX22WSlz(c?8cE@iAL->>Lfe%m;=^9^sXixp%n+Rv!RP& z)BX%)3WX5$j6u!TMs4)I&hds~@X8a~*t0Cm7n+qYrEuAg+&52`u#BwPmWtE-0 z?Jc?v>biX8MR`?y%ublGZbl!Hxm2u^Cq=KjGybd;7ei!(gtd)v@g6_&mQVAd>7c@T zewhhic;{Cj{Z}6LL)v_#$ROtN^m9M4dw*pb!90j?K34 z`h%>-*9B*16B4HrC#q1oJg~X}9xja8D0JJ|ZXpOENHz=s5`+mHHz0liz>iX$rNdwh z3f`R{Pk9(+YHyCpz)cWSPj~{*-1ILuU!IBjw-i-`LPl%=qc>LlLyg8leQAISw}%%`HA)9b4;C`BYhb3}2nM#zy@_K)>Upl?>MuiGuQJh0X))*?Q6rS!zzo^eRo0kshQ18ny4*RkEy4v!F= ze0AW0_ZYn}w4lCl#Y_pbGVan12-Di;RLK*j&pI!>`P6s@vCBFN2|8p;hkuyxuvJFU z{380!p`q=IX;^j-#u)Ryrcgz|p4bLtLsb1<97eiQhd??+ULkpwt@xf`LGg9I8!ycz zp{cJ%7S&9XTOd2ug4E#RU<=6x73w;$;s2U8tOdcRNW@V7?|vNfyKN~F`{)t0Gk%Te zP)?Nx^5X&Rt_Qeqh8NoKhEa4EikBSGTLI`GHprej@Og|%Dy*8 z{ypf|rjOj#;vmAQ^Rvfo{n;Sn6jw%Q)8N4K>;<1ElZULwSf-CwXO#56wojs?3H_;= zFFX)aB_;c^#ZA~aj+G)L>^tA3J3V5bC_7k=a$l3Qp*YLlfAN69g=ER$his1ZmD`mh zqF%mIX6bWLG#6I1p|0f3XkF0YY zAGN&Qq%G#j%_Mg3LF;*L*G=j*4=>T!7W==Nn11rZbe%lJdnrwPk*&HyR=T6W<8*&n z_MuEuo@&{IHi5MskGyxk_fd}xld7FrBIE@B>}x%6KHE*;OCRU+C+1_mnjXA+1^I_H zUQeDoeRE@KAMg2VCtlhs?21>asIVT+SE#=FvnRq~J+NiIyDsH-`uhbaQYM<8k=MrIdQrPl|FX)2Q4_^|#*??AN{q*I-#Y zE5SDE7vFiaH;W=Jm?HS&>)7$vs=cuWs}HDUNHRezRCM;Fo9aRDy^V^y6hwv6^ZqfY zosm!<`S5`paaKz3VEW3-Jx#_m@>YnHz%YaJaGyd>e+Hxm0II%!-B2`mbK>m1I$)2G zfns+f{KTk)VVA_jWGVfCSTY6c50Y+KU3|cDm?48PR11C-!oK7n$5YKXYT&Gkq?Br( zM766#YAQ}xQiUeh=0rcN^@i+|@UdV7`M-P+Ora*?9B~2X5MgiMntkjA!?Am2+j;KF ziEoeAM`?k!6{-fWukDTn^yU36DK8+d!sMwb6y&SgJa4ii-cW9mhvcY8^)k;H69^U! zQ8@nfF#s!9e5!NyHh9ghNwo9`d_nnhzL?K!L(z$217#BjC#ICFzMdW`8!|oOPB8Cz z3Ap+QQ&O;Q?vr7_aex$>ob_jF^aI*%b+|B&v#D|tBTr63qXgq_>oOERIHEL#WZI28 zN-6RfF$IRO6kYqLJ`M3GB*DblK!oAr3PUV}YY4pt*E20Gg{(lWvnC~2Es}cdh3wCU zErtq8O3%rc&lXr=N~p1ujmx|hboWOx3M$?QmTC190Widz5A7^=Dw6&;)nNlt6|h@b zC8b+Eg>HoKqsVVgtY8aPT@L&z?03{;C67Wj45=AJz)vA^PG~~>&eOJWnV8QA!p9|u zy37+^<4kMWcm(0R70~k#RwG~En*^h#@o%|>`$77G;QmR$d5o}>)iOnQpGQCmjVNOp zQ?{d43JIfs4rspA7p)SO#G)kh5typNeIA&}shp6GtxnU6!pUrsb4)md2qM8h7s$Yv zjJF427^KL=hwKYv+zz7`L~nplqxGqiS9`~bqA>B|65vf$?>&M)!vsbcqoV{hbj3Mt z*m4n4qhCFRggFQI0ZPQ>{(#s@EICnkVEGGOFDo7O4AM5Y;V)|77K5P-miU>87q1BE z^Z!YUv38W^6_L58%uhoZrX>tBx#Rn%8#wL1`XDAK=h&U@DKN?5Hln;+u}hq`q_~(K zF7zi3GCoXi*rfg`H?wNUhG!rJ$chI(gq1Y_319K&$WYrON=%5G{ zH7E}(a)`iNhDL|jLDjT@RZHPm6$dmJUOAwlcbGcIw2_g6#t_Y`uMxJweW(s+MyH7` zCdiKbag>>c3I<0^qPVCunvbyg&3}mnoe9C7J~yudzERMMQ5iQ4eoakH$tb#^+d)H& zrxId4D26_#>EVF_CB77+vCO{Pe8N(le>O(&AJ_W()udzHzGe!0-xSy_l}JyB-49Xu z{7lDKA}2t|+m-u-xVopv$8Jr>_2<&1$9Mi3cHL2W%%WX~{kLbhvnKET*Ys0lHG_o3 zm9RWYYR@sZ$zM6-n56xjr~CU}$cp@GsSsM_iK6V|{WmdtKR3>-gw@*%?{_G1HCpa9 zdD2Ylw@PkPz?Z|VS?{}l&W|~-DX-sHO*m2N;!ks2BKgrLK?m=~$;Y8FW&`!?AwF0U-a)@3mrYA`-~r0S4pxOBdT#mvK} z58L+ZP97RJ@9TYE%^2Y^F?8xxpycuMSMEAqY+apnw@!=V-;>5uJ@-Ok_qj%00Uz_# zdoSvkGEAA@wJ|OphWxAUEDNB>b<#kpH1k$LMOoeOm?@7|4hw{(BHICVwx z+Ks&{>3gfLJ+nR_9>(!5K=XaVM2=)CRlRxe<`1qS3@_u)d`L|Hg5}bIeY64^dVL9BJc8ru z>6RR;X1Ldeq(fQRc&^4@I6fv&DMKBupP{_UAm|^cBE=#l0}E;JpuA8>rCLkIRw0`X z(@(;VauP@4sM?s6E_jyZv}PRRH}tZZbdZs0QFfb@bgmT&stnER39}yZ{94E7D3_nJ zGE~sxWMD9O(Pa>Cu1f$rRQA z-CFQ$+-W9mUb=7p=l2HU9Cn`65=WYxBF{?MbKjAkc$}Me=8H*k{mZQ^lk96lH{aFT zE^}!w7E`h)a2oQkRnZEG3+GdXaQbU{lDcI+EB~xgrEaD4571Z(NN(Dz`y!H!bD%Mh z^Uax>yy9@%3cDTbq;z-J#~CNC|5ry0?VNjYY)1!a_WX*RYz!a=TH_#Z$U^B9#kP8=6?|!ZpIrva? z!1jXagQd-Qd$f&=F*<7~Sxfq0jRl6r(1;%cWDCzOPM?_>7R;5Ha;gn@!YUj0VdzD4 z`=r)O>%H{Gh-pi1nfn9E5HPQ9TBSm!eNBq4lqTwHxAQUk3#h92UX5{Be1b8?hKmLV zCHS`RV_Rr~6`|H45&Fj`wB!`ilMp(h3C79f_?}fu<|;Qmd5L9`n_R+5+L34^Z@D8{ zpA=NLAU`)^A#(_8ZFDO`GpE$iyDid}IK`jH}i%n$^G+{@Fw2T(iUXemdUT~a`#EthH}UBtn_X~^3F zs^B#+%!smZci*i=+Q>lQQ6v|lH3a(ls*AA8{$3=sUaE7A^3XOR9Y>Jzo%(Z>CUj0~ zScIIb@6Izx-p}yg+i-?K8k3X! zHnvrJg#@CeVXSKMQBzdZMC)Nvhj#_0eyT*GeFAcKh<-uphJR-Y)xwXrvH1>m1UDtd zM0&>R3Lr4puyp&wc7|$A$hGj~6+A-A=g0vII`K`Cfe~X-6=dC9s(wJLX(q#}Z3%i2 zRlDBd{@5pd(Hkhd`}_UbiP*gGYGCKXAF{~eLo(({1KZZ8J}1Pu3ULP<>T-Kn7G&ue z7Ox&|8S>z`J3kF|hN?^TW0IQWHp(tL%aFR{EJfZA&4Gp04}wf%XEPtYzb~UVpE!yr=49~l*&psjrTsHIEaMo$ceCNGy_)D#9$C1AH;|e5xmg`5o zoa8qQ)?x}Op9z|7oZ`LToLr{q7@_>i?Zk}ZjN(vGl@GRG40V8Cif)X^M4*cd6-$&UUqjl z;NuyIn95r&G{0Ym7^OH#Y%NNO2v|2hr+#34jwVAOE#?Gso!{iJA-VS6hRBCM1%IDY zCY*C+%RT&8;?D?gwVu}Jko$L9y`L&o{pt4MNiu%YYtedhwXNaIi(k*0x9z=lmEu@$ zSFw|yQ5N^1=d2G$H!gLb_dV#hS{)PDPtMV^>q^%bB~{NwJF0S?t(pCoxmn#VQ!bI* zxc5lh`uir$&Tyrlm3)8q(a3w*6vRAda9VhCFEg-3%eqo6vSY))QPp+Fap&w}oyqVk zXFhElQVukjKkgtrCUE;m#?pcM<%`2D`?|=yGo>vSJypBSB#xG4UDNvPCbgCI%J#GJ zCV$NCefm3PL-ux*o4jYo_j~-4MBDds4i#}~3k<@qr6-rHtL+V=P@0xc(=qOOn9)jc zdBe4)czspKXnJ^$mgQuEdO35@z)v0~axm5R)%0&RsA3JYtn*2Aem~v@IoPD!d{Zd# z^5VuEE;qka=FN$no;!#k6B%BHQ-uO<^IzulX`PF^pYpc9 z@7F8o`=M+g!L6^ef2!uO_Lh@>4Z7fTl@4~+S7wv9D(pF1EA^!qyIlNY?$Vna82tXs z6)RsF?wdVDUMk$O9T&)IbX>HSJq4@#&4E+SoN+R3n;;S-3vAVkWn@B~)ug~XFtdY9! zM2pu2rU?Tn=r>662fUC3(o@=T!B&P#CXJKidU8Tf^nzf<%=0tLpN`Kgw_FoI-5@Y5 zqF~|s*281{TJpnLu3_mcpf^h?|iD5-iRn_4P zd`*d)Tr4#eBn#Wdg_2wB{ruu9pF*ocAe8TyKI{Q#JEYRT%(Q{5b6NyJF$<^?J3>&U zFcKC_oAMrg4;68pJrbH4_LO6LAtPQACJ>;R=Qi$X>Sf<^6Fmv3CXFHMoCR7XfQcIm zZvQwn)&`l49p=(TkdUtm5*B(`Kj&||j^_>xR);fuJA^qT!%V@uWHbtK69iZ%#Yskl z1d2D_J5AEBsVN&^ujng)0>JY@U=HwPAVJf8W6ckas8o13IPb`MjRNT)Zc=DnasL8e zz)%VN4v4_;%*?%YBFFy^YB`NNTlEf#>(3e4Z&3r~L*b48;{t;YX37@TIR<1?aHn6z z)?>tO#8#{R27L;Al;O2=VGkj?CT=Wu_lm{~+5PV@r~`k%i-tMngL6RU`5|I_2XsI; zk_hiD;#KuU@sW~YC4yphZS>4WhLhza**|}@PGckb4y*Z@8H@ea?M(`dbfe$Q&Gwh> zU358PRHy#&M%Fv}5%2YxgjVAd73^X^RwhgCX$vu44R0VPY!+bulp*r=d+5U8ige1J zEd8#rnZSW_ZBb!`c|O)xBzcF;_so|p&^xVK7hUj3r>pa^UNC8!2`rQO+vI*$KE7Og zopCho;;>cQ*ODD1(wA@Mmla~@r-mxj+dWbo)24Rr(ipfv^J<4$VZ_0YPZY!Lb@*5R z_El?;CVUm&wMVae{-t;O;QoY}W#ymr)r)0UM}l5omF-$zdO!8O5jui_<^%s<3y{@Q zU*8{Ky{X7IcJz%$R_r+Gd~e+)wGMK{y!TzkPa6kwrmFTT&fQ5P`R(niiwN7{aYCi3 z^-b=j3s*AS-^k<$RQvI_y(*=NGpSprwcJquwr`R)@}u>peM;;46G=zrq8?b!r;dbK zWNq?2`RQt;$}Qv8vWL@G`_k?PC_a>2O4*{hmw}_LnfK7?)FeT~ihqg!N1bq@?bJW> z0?*|(){LULw#~=hUmRtg_lV+C$~k>JDpKmv61;jD-Ps;Lo;sef z&#q6?u$qOzGG!rVs+wdse&3||;sDLyPf;mHxi*>?+*R&zpVFJ|*wCF_lT`2Ar}6oY zAxTkmCx1+4wV~tJ`BXWnvWH17ljpuJ%64WZ1r5$s{+>I)rQWKW+~OqrNOq}X_|d(U z;s;#yhMk37is|R`tsBi8Uj;myZ|h9nN+Wmv#NvT3G)i1y%vwR!X=d`gxA_gn?Zo6m zI^Di{m8`tBm-BA-?XB)!SK?zD&e#)3VgJ7gYa6AyRe#POC$b#naLzwwG1YD2sR{F~ zN6ivc2%IwF16x;tGJTGLgmkwI^^MAu0A{B?+WWs#XWl*7+4sR9Vet4>u^Ec(qC)v% zRa*juK8JTxpI8lu(;*$H=whzWnCa;xzUO6qzi7$ zgcHp*oMS{P?suE4{AUbyCF4FN1h0XfUoJj^Cfz+;JiXP&mBfDJ{)ICAn;8)ksnRK} zSu8gu4V~>JeS@`(-k#V^(~Cpxt%}-zsx};>j{`H$!)6!Lu&KiKFV3$bET&{8TN)Mw zJU1Vbxp*O<&s+3|g0ikq5_}DnHWgQnp0>Cr-0cfRJ-{ozi7le-*5+eSNU8>|SsqTK z^!~{cPOh>0-1GHotF!i%dn|3-BqHo5$d-#RyAjdPM05aj7yz06tG}pg)b7+vunjrv{0^2jCN7Bak`5zU(gmR1Bt7`~l0bs3wUF2509P zH%cut{Tf2K2VqetB9IX{Ozb2j)^+p-O7d{$ zC=e)OU>=tyj+fsiK4aBd*in>JN1-bWVSx$IcP#O;qQiM0fq60KAH(@Uv$1&XUu>NZ z<_@SxF+30%l*HAjTYSH$hKhopL__(UbP_-yCKyzi&JT#8EU?1gV>kRT6eSGXMFo@e zMFEzxFonaiqTnFt%|O946Io$QV7SDdt+nptb?%Lg-~YbLk4(kr1L4JRV|;C;&Az8e zhM{!%N5WFD#u62Q%Mm=Zs%psj$G8z4eBR=!5jZG5Mtr(5M`EmsZjvvaJsa9RcCK0E z-|O=7SIgkG?;vGLH;p2>rOqpng%W{Id_zlr$J>aEtOxh4q|Sf8{lU(6W`KeaBVkk8 z&FXKu+fi@`W)UIp!fdx>#F_HePJr=(WN2{?njoOg5Rc0I^Z*hFXDx$x`ttR2zp!Ei zdRNPST4n)a2b}i)Gw&|Z6Y`i>UD{A1p}{a2C2q*lm5CRPuH##qFH0rsM&J9g>0n+L zv#4kYf3m)0LW|@M<@Kyr+$wHQ&r4B%+c&W-RiK?ybEMTOc7g5P^iI|zw+25v>OW!b z-p3+z<0b9YxfX*oitXtOmHkn<6XJ*IU&urqrK~!U!foniaAl&T`^2pY*GO@*cJHPc-SfgpWLYevl&CV7xnWg4OAc1qJ07OKzT> zTmo4lmqycGi|HjaW+)cihnWB0k5;DDv4z?kNI>TlN`N#3J%Oug)T zL->}fS#z{DKO6DY+dpzStWN4GW6^!jVu7RISu^-gJ3aqLoBxO9y?r}P%81n^B&{@- zREH)Rp0UlTQOU9umyZtLo!(xe!OT{YEU`${`8LQbDK^Gq|D%(aZ9Ce`Oud~cwZzqL zyz>6m_4s1DIxz8PfdMttss0uLWIdzllQiR|DffH=L=zg9UthW`7*mxmK@p#RpSGLw z#%}@L?^Ug`>jF)OdoPPkyb)R1qwn;_EQp?-ic-vwEAzu)O*=Z9l$T1`UQZ_^GnhN0 zuIE+hYH2>E(m#~)(o}Kf@U(U5Ad|bkZcyZlgo~R^?nPC`?+R}mZp^y>t+~guc~5Sd zo?e#Q+x%wLA@9Pm4&Uiz4xf{L{a*Z`4UX%t-yVw`XO}MxR9am4LX+OzZ>x1^M`M=7 z#nsZBxK6>B{bnpSCd$WWdc~aGh8u5v*Z%H3EJt%1j8?h)pJfI>U%y7(Nlem9)Qcwe z+?*HXxA7hOYL#~RM?U#<9Z|B_yxk)GLq}uJ|2mKYS78O^hIZNUMHUI__Ac#^0KuIU zbi%?6^umVvw&bMq@AT&tR)hOu?w0j|a4Xq5c6Rs5I=!tJ)yt+X=->eA&|LBF4f&cJ zn0y~({`i+2csQ?9aMrZKZ4Ow6%N<7kdxm1RkHvtGAzK8Ndg#mn-jH^^hQ4_?&jw;f z_}=Rs*urf2=#}Am_+JJfo^JnMsIh^fp#$gp@e7N#<$zrXsQLy0Gr>tm(k!zMe{f8{ z0CEMSwW65@%7))@5D~b(9mLdxSOy4jrD6;2L4XnyfyE-5pDaPv-iheg!*b^y?>lr^vDrJ3Tu!*OtK zkOo1rI3z(?6!@NorXSX7zE69>)C)v;{VafU49D|ZtZS@BrVPL;^t*`7$3+OI0$EQ4 z2%#V1=1k%Lh<~e*2<}aSDyykJR^ASOudQRyeeH3(ahvS7W=p%DNQl0Kqx< z{Lkke9Poay^SYsge;*2TAhr_{x&stfV&^u#b@)WY2Rmp;QP)96j+z8>NMgT+T!kcr z76MTs(fT$J&ZBL|CjdoyB@d`4!lZy5mm#>kOnxV%I6bga3S?VQ_1q3NdV=*QEN77B zQA_LqX*n}9sErt#X(|+W^b(lpK<;QSr1WEhG?5bn8j6@AiNs?

    +Y9;d+Zq<^FkkGeDPO_O=OAy}n$ZU?}Z=Csm zT7U^+u?4`Af}}gDuSAlPlCRiNwd1x_+vEAj>Dk%FTLe0N#D7v!QXgoXky+f&jg3uA zaP$;HfPIZ65!~{~VzZVl2zmdTQ%Kd|e7 ze**&vlsQ#P)u94;VqI7h5PkO)flm)%FcC~pIba8CX!v!VVaE_Uh(>$g{~Ko`(g=m^$r|#hS%1Abc0S$Nx&Ct#5{IOeyNv)(sim7gfd{4uYlke!)Jpbtp(q{hUl8g%k2 zZigqLN6d@&VviHh7`}vtW3;N9yWLM8J&rbDGC7*l+ubn_P?@%tMIe4Lp`!)A>ADgh zH9ti5Pfg|UXkvVYEw4}3Vo(JiC;oaP5eeXfv0)IbNd{GUE3z3YUoluTcCQBp_X2Qp zh8J$VbW$k15O%|N#Ptq@QspkslQ7=dbe^u`l`c498*8JrD@Pg1`mC_}|Ga&{_>2Zb+GEX?p-uYcECR{|y{H6FDMR zwo@R}d%zLUvFP)X!&c1T{3rOx%-_;zz2L7UMo$1{kWXM{`;nL!3;<#Shy#&zP;p@9 zayH5OfuCY1?N}Z=K`ICsVI2FyL6{-B7oT*moaax)Vs1ksPDTFG*;j-VY0?nrCxP}P z zMRc^(DDFFZ=n3GWTd=93Y(395MWa8I1AXEL5VpC#Rg|Ak%<^OJYPnd6s(VR^{`14N zcIjx1iJzbAw+QTJ!@3q1$PQP9AGn=0AQRfGgzM1MFZ`?KSDVY;CFx%P*i$sblGZT8;+-!YrYj*d}|Hy`sW(L&Q=As{k|9>C^RiBtp=6gwq)~NV65y_+LQ35V`k^VzvUxNSA^JMX2|8 zA2_GnqTISsiL@8NAq~{(=e2@JR@cQ51l@4_@Q*%MH~?QC?cEp|(3z4R4u35LP3PHC z>I`v16M6m89*q{dRI%0C>WY4F7H*M*(%9H=Tmv=7XLq4*t$NkvhU9vlBbJbD<1*9y zB};=hdsf)&T^t7wR;X%yin_~MCC*gJ?Kx98IYgyX4ca>1$OfLz48WIzx=Wx z+t#_5kZ?Aij#6j<3d(1`hQ)PPDhw2(qn!RS@A{qm>4X-5-U(aH3`UfvltjH!iISt* zLWZq^(G`6};wfldSuy{L%#QXasheO9kMKX3;KfuLM8bPn^Iq@@Xy0J5Ya;8OaKcx} zjk^78E#~?>vxO^dzD&xlIG#EqP8pZOrDdWI1zbCSLqoI3^F5C2Cj3%-WC}=?4#lBr zWwGBo1PPRDqGd60M&ZTHnd-P666Ye22&HzuWIpcopwv_#dWL5vncXI2*gXh%Cz~iJ zbfJo|cY9t#IPE&#^ve<59M&$|?2dD_o%~TGH7;h3@VY>DBVbXo*805fsz_knEn{dg zujKqmz3QmhDMh$0mlQpNcKjDzu$agqH!s7ESyq@dw3TE&I~VL5```6ca^JUba1m!K z%J%BBsVA%d$*U;!T3JDDfWBb;z}XkDh$iUo#% zUW!?*o#kdHce2&n`+Gxx)<)I<0yR%G0!zKY8s~VqxtE36f*to2T6tx`K?>aWMAd}U zE-D8p5ggc&|Ku&}aREuw3tA8R>qCvPYLEzn_Wpek7K5h#!EAZt8pz?a zWe%4IFOjXxs+5#2V6#LxYG{C{79J7tN_ZYFHO5T-2P8035X=l4o16aN zz5{#3^9(^>LSUGB=j}1!_q!JO_h6oAWHD`>~)L zkET)?COvRK~q_4P3?@)7^8wPXNyJq(AD!^ zn9}WJRa99SQ?tQ3Y^HPwE_5i4DzCg^TONW=ts;(Gsftx}; zRYX6eXfqB1&=v&@65WFW{YDP@5&AT$hTBpVFjkl5`j20q+aPX^(cI=y2$F5X9C^@k z&gv2M^bF4?OfF2bMG;ALTb)9z2&Tq8H*SVwY4LTm2?eHqzl??~!!=~Av{$x%%j zjVs!xduU{0ihf`pfknQU$~aZzq?6`i(71K!>?j})%y8O>hcl&pEk4@_wQY6r`AKEJ z;&K(y&PK~L{#pew`aZ)~y(#oKyCm1+93J-T@E+nfi0YiM{AM)x>j^+-|5mip-~awo zHMn+Yy;ajnSgZ!m?GEW;(&y};9oYQKc{?}NBRg;c1vfl9D z$-FSFyLQjN2l6s9DuVh^t_v+3@N3!9mb5f4ry}SsEF1~yLrnjVz4!j-@_+xvwM#`- zGAk4zLfNAsl9?^5NK!^9d$g3T%rYyHy|Q0G-k_v3yXhw;%%tWm=0Io^DFRdIjhxn8{JxlQ%0_$Ezhmoslu#zKX0@7n*I^H`jl?#)gIQ?uVy=RV;>Y zz7M|duY7SNSHIYtH8I_tg){TuS!*iWv)spcYN}nc3C6{3X)KCMLuc1O82J%t)<&&8 zy792#i507KH=R$|*PlNaRJBC6#a8gg3C){{AMRf?^bKjJygHk5RX0E4cWFzS3XfkN zkE?`hpxT6W{az*g74Z>0WEw@oZXeKymm64_hhNAZ?71%bX8$Xz`84Hc)X7FGoe$nDIlXkYXX_L7jFn+iwiBFg;FneU5bMC; z+n0Ce*goniUj1BerT)e7AIoi_p-J(Sc2gckDj7h^-PuKVVmG~a z(Q)y}F^$WY$;Z3pC)+bC1U<*T*4q8~OpCbGW9^j4*`C+uNqeTdZAkOaBjj7mCVO_3 zPH&#MuaW9gsAGK5z+Lz2knAT2a1)NQeI>Wmd#x6`?=b~Sz4zn6@82uESvlyA9Xs}` zw?rf(tN-jKCuiqZ0EV~i?9RHlh_gyMRYqO5K@$Twg%?Krr}8cbppWKvAkESW2{Ezv z&CQv!jA*(1D%AXFq9*qYbWx1{`?o*+b{jP|1HDg5N+dRK+4AH2_j~C5!*OJW$!$9Y zvo{=#J;}rp8G(R@;=dh;Z%uUXb$zRi5yBsQE{Dd&QR-|uSO$6Fz5{h9+mLBsj*-|s z7fZ2o=joItOJ@kqo(r0hn@a(yq7KV;s{$F7OKY;m4tOH84ddcUn!T>gMN0(F7}!W8 zUhO0gPmGW6qoUdbRe@5pC>6VW@HalpOFkgu;Wq4|qM`z={L#w=)&cYL^YybB_JcVD zXXC#hrM3fYLcf3G7Zp9gsTwPb**!0Bv2EiHBPZ0p_CE&EteSb|Ic;-F-shWnOVb}H zXCAUfoI{1~(#py?e89|Lt&2tibj^R5XSkUHht{hfyP)VrhbI} zX3p=ffAW{>mT;csAdq!5vo&ML_wQE_`kz6?0OZg?P6p~>7muK8sO zHLymu1Pt~0i9w%hztm2PFvdK5XsaWqczc%PbLPRyuYCKMl}s{koh0Ra97##jq#pBr zF7v(r0)HFU0(Q-1ENp8 z`}PD>96542{qpH@74f&#e)p3#_O@p}U=VuF*Yxb!V|Kyc)GW#dOgw5_k7{44ULcD+ zc{LomwQ|<1BKs%0uV zQzUxheYb8tp=kW&HC4(k$zQX)0C|Y!@$T*r=@-Yhd(CsnwXHmG z!#Zwgt@q6DovQQ)JGwj1CGeexUiw_9`u&(H3VS(Tp##VFkWmjPxap`k@ce7=sW4BDY!Q$=3s{VIH!iNnf z6Z)!FDoUG>qy(u5;^MaL?ekYHHmTbMJ58Oj>Mzz6xGLn#X5_b>dOxmqUvmPq zSL7)gdWJ^Eua}aY|C(KC=ld|`wss1=T^a@RB6sp`tcH}7htTZXFSneX#>*CK`u6cQ z@25A~`6_E`heq}HBsT_-K|(3O-r|Di*i#9Pge}V|W zbX?a%b$npJgyZPZ0VFD%mZlG9?&Ljrk`_H5PH}T=@m8CHdEQA$IkFla5%Gjc#QOW} za6{=?L9es-o26Iw=;vDsaC4-JhVvnVCQsGh?Xeid5Aan>K20YSj-^4L|^}>an>wiZMKKfOtfY#SL zN19^JL6(;Jl$V!x4>8+JdDllWJE_iR*^k(&5nfyqWZ2JV;ElFrw_iJLIt_n{`MAEQ zi|kt*n3xDa0w?~g;62%;WwiA_akXk|T}Se}`EOR>h#+dX|M20%FAIO2(0Rvp{?{c8 zD|j%c507Z3|C1&dgY z*D60eEV8QnY`y3JS#}{tM4_x>EH2B@uja1yO;KOY<*DbJbRPj z%FT_=8~smLcq5Xv3gaA@9M!20urU`I+|QQkul?r1G47ih&-B=V`9tUWrJwGkUNNuS zp4#Ysq8=@1`|*1rWm&(<)5q?TMn87%`$cEsX2v5_-hPLRuEuJ=C9R!=o0!|Kn)&Bd zo#l80RE7@LKNOX`Q1QWn#_k34T35NRnT>q+8>pGs#vH3!W;{pf=6=xx|1E5-suJ-K zcy98A(W)>}t-WGXn^NC>lx{xV&wck;@H=YTFQgsGvc#e2?6-I5k3_cHp(Equ{ny&Yxd6Id<>iNTfV> zJ@e{^CH5kVyrEd5V%bLa;q^XR3UbjJ&WDBeT2PS6awHvO^B zmV<-P1F&?iNutnpa65X_?2x$c^8>RhNV)}ug$E!Te=w#;lLW;n1pH5sGox>EdzZH{ zI6Uk{{G~m^@WZ`LTeus{1R2m9H^5_U*_I?h?p1ZgHFc*h0~OW%RGmx{3`?07IFUN@ z=T9w$13$vIUKbsX;NcNOK8N>m?oR9Rj){%hPoI>h?uHNO%(`gE!~+xo(l&5hA&Tu_%58GN{9=LjNjT(7L?F<)!Kuw3~7wcT&Y{ zezVuO)QPHMeVGTvvDdOxgBymu{ryQOUbmh5sZ5BuA2g>wfH_4*R_mbPHNh8$1o+OI zu(93qqgOEas}fU~{S7naeR#%N5;#mkKRf&wl6|cb13N&w&A;O5M{lO3mIP7@$5F$p z=eNGnO1;qN#y-fud5cd&e*hE5`IyR?2-73dwhs#Dq!i{Sc9UwT{elnA+$wXa{L>%e z+LLri%lY<+Y&Ur*(rxdYw0xD8^-^ATpU#gLLVNY;*47jP{Ze)ImPqP{ER6YNsmFPJ z>aVO-x(4=zZ(hDRRull4ZW2ey2@BVx>{9j7 zXv1I|*@M!tE1K;J9g8yxr74`l985r6(k#m?ZK}ObBG{f(HMB0#?`ODn!|3fPX(wks z;ZLFu^7lSEAGG}*QRF@E|KYjV64S}luf8FP&jNz{x;@IA`TZk$=|^YzESV?T zR=3p@Czu@(bv9Jx&|r-oH_Td{xFM-gz%n%@Soi%?vG$_F;?m5gyU)99!q2?-R(~bi ze%(FGp`OowY(aXkK!LxBbgQ}SlfukSGCqn`W4G;h4|x4zcrxQsppZ1E6IT)w&qJs} z_LtA_gsXOFzR1Xo4&$RE8&}$AqvyLFgvFqK#o@XV;i)N5-_R~iuOAKhNOY&zCpEZp zdoI%^8=Wmbs86?)FIt@1SyACh7PogT_Rn%R^{3I?s<^L|Kh`!GzdmzC%cV$@Y{Uo78>(UY5h|JK1!L z;_6vuLj%M6htJiG{Rw2@=nC1leXohih@YQ=xNLT=jp`#k#qg(^A&+;Gv#krXXV}JX znh`Lkpo(E2zifDwqBFMiDm+`TWz#iHEfyerh`za^byD^FGg};?+ne zuCO<81LuyiTL{olUl=`q?kL4Q*#^c_zTR1F8N-Pkxu@O;ifpbV`3&g_nG1HSZkwFs zXz85nl~ua@q-SzW}$#JmFn z&fmPr-SYM8EA3Q*@kOEfNvkeeG=Qh2P4EtamSQiHh<3v6UtM`Tfy`ni;V#{b5N(UP zF7je5o)0K(Wa5{WmR>>(extWI?-G>}ihGeq+7=+Ug_4pIQ*-H6#1C%mwBQ2;pq4nM zvX$+pnCH4ACQd)bba~iggzE9I+=L)eS*~v&J}YbATh%!9Mi)eO4n|(Bz}oPV)g@o^ z)<^=3!c-9@#MiGM1;Xp;>Djk`|6`EdhwA+KY*5a4K~eD`G}vfqKJUAq6Im}p2*w9X z$pWr;zq_PE+*UFq%BKJPkw+%($An?oycpEDL^&2u1d1U_}Wx8t+ehzC%()PLg^?UH!k`i14a^sAkeH#XDD z&v~Dn^_$zbG0m1kE{FylJ_ySLFPbkEt;A<|Zuz#DZaypN&{pGUJ8jasVv_2@l4VkL z{maT>s;|^)>e_pB*v?ek zj0#E#eAR2Y-CURGK74%7uqpQaZF}lPx&mM{y=@F!+H~(fePKa_S=v5bSsnAdESq~O z(jcSKXPcvPd0+V1_+#>CTj(U~ODO}iw}{A7E)^4Zc&?*+*9u!o>rGpUVR2To9(k3k z`^hiP{uuqW9koW^7I&R@x}p&!VIy#DD1q(pZ}Obof=~5B_o9Z6xa~`7_K(^I$oF_% z`6O(h@p&S|e)l^y&C6TmUFDsMo!GzeGoy;=1+8Io^bp8EHdO#ZVxTj5V@16>tXaA$=vDm)hAE4)Kz6T=dGWJgPYxUii=DeE*qglPTo$C z>K=%l*U#waL+Z?|txr#Mal9-lQo2$+68h|n`bBYxkoMl103VyD$qypijo6>XbN}iJ z^A1QkXD7JJKPFr*kt{H9Xu06#5zG2lL9TyNl<3Z%mu05gFXy(jdCOj#)Gzx&E?z%c z-@7%OiJWlJeusYNxSo+CM#koBBR zein_i6QsueIT)AlIziyiG4dVx&y`-O-BuS?=W2Un(_h|E;%GBGi-vw#7}U+v=G_3P z+&)%TihxA!$SMp4MGyO{s;=Y-HPB2$jG%dZWrb$!N#60uQ&hw!eXnVLt9Fx-ac_3` z*c;Q@mW0aCV>Jc0I-bgkrCw>{Ws{9pi#=q`VOY&1BkV`$W zr2pYS`1P{oK<^S=B2J92WL&6sQ`1}2Znikkf2)}8*7;Y@b@HaY^4gb^h4X6{tB>i{m0dd-;LCPQ9^t5EIizgZ^$KP!_1rdKJV^B;U&*@icT#3{`_>f{< z#YiYJ@0n%v<*P*UH{C#p+)MoobRkfcZRt(x0)5RqLwArdV7sx~%(nQ(_I7#%A_A^b zsUHv!kS^?%a9g?^MN@i->$+JB$CXy@@1t5dt4jj5?uj#<$3i2Uzrn+p zyT46T@LBcCqb+YKzmHowl?*rB?=DCU|4?=B_sMN^!yk`;X560363AlyF@pMd?$WWJ zJgbtneqpz?rQkw;+Pt{`gy9c&!{poEv(4daubwiA$Ye<5(juso(*w9{G*ZPr7@BMU zy#S+MVTUG2TiIioGCjADCp@O1I`hDLqhFRHegD$;EweXOu?YFTO4~~p_TL`U*6Lgs zgCdl=;-qO~T=Rkz%gMUZyJ>v?iQ~ixt@qjFFTA>0WRPKpH9&#=!6nk#?`$^1gNF~r zj#;#)>1iC>+$s;X3!z^L;Zzl@?{^+y5fvAYEQ?LdLHX%8CNkM|0sukZlWP*dMY~Il z3oZL!WHk4?@8ICj%~ZiVl$@VxRx;a7HdVTXRKwWE$G!!980wm?hkH)n|1rTTy|sKb zSTEmX+m&;sQeGyzjxM~|W$d_7KkWCX$pj1|Pg|Yje1Mx*wj2M#{+~8~_l?@+#U9^T z(ri`r*tGHQ8ThWx92`~ScZp3U3`)aWyw0C?{m09{Sq1i4>bNNjJmP18XM-IA_af_# z(fX#()i5;&3F1=M@;b~91z7LuHnZZ=alXT?U*z48r`uO>s6JGi7+RFl23E({r zsl)@5ePw=NsV=%SPEX%{5tTND&)c&#T&D?ECL}k0=v43vSnGICNb`KQy)ej>A z_zn*CX@dosoT=_*CAbcej~YR&{}OhN;q%W;mS!9H1>^_r+%|S!pp!<|Z-t=b1~jES zfq~&SPBMn%Q|{bZNjOUMNgw1$%*Wo1hGGT4Y*jE1cap51|GkiOasvdnUb?z+cQSMR7q+MQ|+u|_!CS0pt zqjrd1MsDSCvld@1C`&rmihPrR6jfmH)n)5Fk&kj|%dAjZ;SrnV#m)hUL2GJI>bSpQ zQTx2|;+>iIj;3wuhZ%;G2cv8*+{q!QIJiB@C;IHG4nZm^*&D6-=}T50s=WWc4}Wy+ zpJ9&WxIw`P10;I|sQ@(oB1#$x9VQsbu3*>&=1ht~u4FpgCDn^D9*0GByEKneP~=yeOo)629pf5%>MYj?)l_JY+Xp+|IW zNnjotywS7Q>!TrR7TWVi**Mbrp5IBn*~H|+P{M=Fr{fPNPpHJOSv%5>{TSJCL9(r~ zZRL!MGD*Px==AbfWwQ*;k6#O8T4MHho_)M07jTc>h^)_@KFPR$+GDDJ$KySlxcfFS zv)pHqxaYFa=s^zK8~?QX>Uv$6lWX91>{;XddTjIQ(#0 z-83GsvOBvVFkV-yt|a5#L!Qfz@@xFkpS(10SXZn2s~pA`m@#cnnRPACImn`+gJ=9m z#Ze0s8Nvs6`szM*QtNwgQ= z6pK7!wyV$aGhEFTX{fiDa&33+G&}C+>ezkW?{49-v3)th`qalRDZEw-4Ne?X`f8Dg z3O|qKu)jwAf16$%>z@1TH1G6$%)T^Z$~?pQxski{h|GcXDDmzfLscUqQr$DEGFSQ4 z3gc(BhK^S2{q_}X=H_3st}blwFRM)R%=+JK&saClS($8=FcP2Wwvk@?{&$3()&0&~ zps$zL?=j&U`)o;6R3kA3VzS`{G)Gugi?=K}4n9}>-d{gZ?Kjw)P7#Jl0xD>2bY(}= zjS&&g_0{L#7Q-`deM_Qx8{^PL5lvO%3nx;8GHhndC-XtOTvR(cU>-NeVuxwajc$jL zwS*~5Rc6I}RQ>Wvw9?46_y%iX83luy6LB>~-w8Q%>`+#3$C6_Za=wrv%J}HSy%N+ z?aFv+km-!CmwvhRmn5w_9q;DwK;uq+^zxPqJhMp}oK=~1_osX{xlQ^?y|?XV)6VQ$ zwdr6K>0@>q`+Rjos<=H<;-05S)iorp|MMS7C9-$hfB*7Qd{@Y(|NiBW()Ry;dG7?n zf4?L<{J+0_dguTC>3#pd&wTX%e*FKf%>PB3Kvou0+lT`)egg#OC5(*APea_*Dj5|+ z6v2HpYHn!ogOEpO&N7L2jD`5g3&9~56VxSKsPT0cJKFv89950Quf2SEC4xc;XqJzd zbDW<>6yo0<{dO~!D$J~G3-Ox@g&=qqZG^#{%HaQ5GPNJj^ z1#|~i#^0$jyG_5htvmcg76hZ?eCWT^eUJCwF@O5y!M5EdOVd9D?1t)|OE_8=b+Ovj z9k%`X!n_8uu6TuzqumydiEEOb*4lRzS3i`F`Bc?=MSAvm{%tURU07In)?Fz|_&5Z{ z`yG31Xew34iT92_2$^J;V~%tWmF_4a#=*Xa)k+Gx6$7>qCzT-29ew0|go;o@ff{iCwTm z%Y|~hYaPE!!iYMD`IGr2hQrdtirpKHD2V687nOk`7-;P@|3#jr0fU_mqJw`Rl7?oz zBfsCq0pZVkL-I#Lk)C2$L}(~!%5!7I2_O7!H1o|H4n)QKrpi~WiAxd7pT|>FQR6IVkgA9-BO1bkJ0 z&UFg$UoQn$Fs1wqCVZMUw0o`&9{k#-pL0#2bZNk^+o0PtNQ!7As`tqm@)H4v@ecf$ z+|bBKZH`$3(um?;@F&{zDl=nie?ib%_vzE8l#1Duj1~V5X7b+4=zvY+C}(PzY)GZf zb0!mAd0&7PI$Wp9Oe^ngvTYQol|{4bdRvhMIy$=QN4sbSFvBwl8&M7!5?VUC^Oy?~ zj}!F;RN;Y>H`H>`b3uJjQ~PfELxk0}yZKA^0h{_)`_b1zokHX#va!H5m*iRK-bUM9 zJbClm4aGG87(%(&RZbx>o^=C7G(|Q1e0+hJ6T(>&z(kKr_@S;3<%Z4}8p4TD>HDF% zM4Jp3S;$7>v3tS_zs_QmkP?zNp~ZbETB)KK5MEFu4B@*IG%kbaafyL(^fd_8UZW-; z8?(`CaY6y?%R2K!%)0I?H7NZVJd?-5N*SPyCGeQJqs-@?VF6!*?Q8SVG&O_hv&suTya&sHxp6Xzg-6(Rma&SXWp^W0CLDPJ46<==0U z?{C==E;fZuTM4naAM$21L}JNbRb|Q=n{SRSNL;DB_YFyZo|Aoep&B@m#y25+ZC-x& z5lVuX+f}>tHvIqQKX~xqn^i$?_)Qq9wp%}{>5bDq>k@{jsahZcf0h)YPOO?(7u~*0 z2p_7l_YrQ1 z*Rc3x>c1`YE$Nc&uUAiM&QVHf{&0?vhwOI`gCGa7H=m!ldRE(t*k>pb`2rP0;b=-~ z%Vgo))D<{^f4>FGItZ4yskpb>rhEH0^aT!Y= zW*npRTsj9~$YEBPQnZFT_hLaKS+jI`H1!J{d?C~z4X3ovYmJCQD0hjO@Yu~#e`JZt z&BeIwz_E-HzQ=nQsH>~1!I}+_ic2Q)^|c54p$PeBK42VK5ZmZALv`F~`+gg}EYxcS zE7{ekP`=8zxNqU`lF6 zy-Nla6=C2&{?+n(%=kfBuBUAUyugAANZ)r&;yk!i+`@l0g#7b8WMo(9|1?QVS^jNU zy2FQX{$h~rr&H}Dp=L=M0{%d5!ed?hJ5hADj-4F~o&6~_vz)P(#nGUq$Seo)@In~= z!H=AAX}@yc1;@o5gj6T!ZJbB(*$ENknXy2Q(Rdy`ubbtHan z<2l^XTGtPHEM0{zP^iy&B!)b119s}QafQbW#!%|aH0D>pOv=fU!gP%ECKud3>=hxw zj6c=tP0c9gCO&~Y{SS;nAqF}PU=a5)$L`srrn^}%We8bMyUl*&9A-4dE}dyGUKb4K zH;&aEiE2KnfR}6FHdAd|O{XJ^JzG@M-xV!p{}0!I(bp*q%Hh~H=~hsX1f090SF4?h)HCF$e*N5J5f>nTLI7Y zzk01KVs_UMMIQ?1)l+|!Ef>hl0O|aGE*RE(Qzxzp;t#_fk`E0{0}7`Y@wQUt4`B45 zO|(Oo#TQh6rH%6I<#04f{psmI50kE0@U?_j8ASbfkZGXUQ55h-87QD{ijn}Vr49o#Q6X|hUR@}aSQtR~LrJIGyat6QtekOY1O7ry-q;7?sB~b2JHDuIgAp~hH4Nq? z;K}@vJE;Z$7lXzd%Q`*46m&N|ktzx=TKQtUJ{wVphoWgf-&e+szi}H3u#I=4T}G3A zHobM*cma| zD!>ec!6DF#;7Y3Zn;Ab}-vM8qjE?I&(xaoJ!DuZ73|c7%NQZlSgn*hN|bW12YQUSC6C@TCF{aXjn8Yk+v4yKznf zKB!W2s+l1!EIL&>NB!^$f{ei3e1(THihf2e{h;(b0D4VH-v(f5#&~1Fn4xwv;Xh3z z=ASAPU)+xuV*IZbpzz@O^pj-o3oGW|EALBOQz6!6AR0tV=rWE&esUcC!vHd4lc>10 zadU>+G0ayt>4vcSf!__F;-ld_@R$0I&gY;31IR+n;3^Wf91 z)&P&q)(m)BYJqQQM!JATNe*cCX<|}>p|}aL*r-;cHdrDoZx%@yZ;|Iz4S<+BQhZ7Q z%wmEIb?iYL`BGSh{BJ8io3VBm7aV_h(H~v39q{2y4Cgbvobm~WLLGiysrzU7%4Ea5 z?X~ojDItq8!n3vlmmN1g2rHbdZ&P+^0VN%8ad0!f0fB|tPRPlQ;s7a^24TRZs8)e> zZ|(#Uw7DRDx|sJDW={j@vpZeF=$)cWw|~F(N1?vUcQYQswI|rw+tbvh0?LoJSFGP1 zMf}s(a-DFXKppXo&1`Jy=*+Fk>SQlJK9EHArSgTIA6~Ls)14GmU}g6|2Mi8cf2L9f_Za_Z6pXZEZaY@Yt|qfFR>uOb8KX zRr2v^oF1aDSUR8A{1&ag2^d2XQ+|HpuvG~_=F#oUUHMi~wvE1zJ|b?4x%v4eQQ5op zTh(XKj9eMxQx921Oah7~u z#Xh7E=gLD6L(2DD`f#u%{}#TTJbm6wYf)MwxpB;WtU2k;n>U)>{cDqs4BduKKfHVf z*OzK#R4o5s9xG=)4;R;kiFeJ?7TvvohkCvC`6;d}*Iej_hKCc@7cxDM1pax4?%<8h zwunS5x~;JvTl1~DNe&S5G&*IXHMC0#K$OqK20rv?etJ?)+XSoY__ND}x36~P13V{# zs6Uc#1xIgEHwsIvG(0rKkze-rXOvJ=N!sTb;L4W#71)>;`O4_$S?{JzoEKs`m(>aZ zC9R^c%}(0JV)nFc%}nrFd*EZc7xo0H=O7(egy6WN+D!a$7NCBs$g_=+8%>a@1dPSc=@Rt>rB1kZ{dC<>Ml$<6i4aj=?P$BrrJJ78}SGAQcq zbs#36wZ-ntZwm+%h_rl)Wnk-YP6MAGPJuLnhP7M7z>;dX>FAEd7{@+^f0!f|CM?$s zXWS1Mi!-|!E~1ujZ~5cTYxtZ1^~C% zrC19*vm~Gl!_)%Axq%p0CzicBSu&NeXlis2=M1v3yInarXVq{B?WBAHP$7a4v+87V z?4iO*vFfb6zh&?-lXabFCMGQk2VzWat{MJ;Fbuh73Nr7|SNyqcsW*|*tSuUeWkN39 z2Vl9zi{1#MvOV2bf2(@>Vk?PQMd2WcOe`Qus>$?NNcA7=1*EX(r$=)=AB4l?GKh8ZL8wqo#Ed~wi@G)WJ6N5r zm~`Ua^%CY9X-$fNXN2<83341~KYJA%O8RuE!*+x^Gs6+aHK5N;QR+Q|F7E##)r1Hm zU&7{?9(XM-^C2DGCb%aSdL6ot6Y$R8%HGayAnje#Mg2t_5*-)o)?}D9TWk@tv=9q- zPaq46%nEF%Y;5jaGs3F8m=j-{{|Z=!H;-_Wgl%1K8J9k4KvY2b3&Bj;R&o8Ltk|`mZTbloV-R@E z2mPyRHtk?mOPRzNszDqT%hmzSm_xV83ACuY?RI@TkI13 z{U!tngXK%O){W0E--mBx08@s2x+|aj%U!eGyfBX-0l=ok=BI%yxrF*a!4(3Yc8!7X zNcq;2(k(U;t#SS7FJf1t1$Z^q>|z+a4#BB_g|W6@OE2iVIGzc@!>lP4RDvxYxfXQA z#V`W2z(p8bKWLUbdG`c%AIXD4a=J3j;W2Sk1`)pm0<#K^dBi6rae=Q1){Rvz;$k(Nz2MQfx>;G(Uq5=K`d655y}ocHx2Y54&N6DFY7*j{CJb%h34XlkjY$^YC#hx z0uvZL3$GC(IiV@@A1G>2-0M;P?AVQbp=F1AX15?VP0O(*2vsNAK6v%0)(mNa3q{Z+ zttI@{lfHF)Y zsGfqXJ=?WtcMevy9q%ZVhhwYHwU3y ziA1nI@YBN9JqG|Mz-=?bWwi>vg}FbOt#q2V3={|nkpLmGBEn7GY?Je}`}c=0?+FP! z+Y<{hY^d(yXlkY$dOmQsZZy6SB3Qk!(fHzPB_DLaX3#XKCu=6(dJ#JV!}^X^PKnV3QsQ;X6;mLtoxXu3k8>saoDrpzk1U1Z2G0KY9p6g zo4JoEg-`13Wt9}g0iYxJMUyxp^ubBA5{u0PRq>C5?62^QhBMKdiVnA!=y#j@q<3)S zMH7(^#J*{~X)g26=>E%oW%+f(P}4ZFbQ;x?UpEE8XS*^{P#d?gI-*;A=Ql-^yf~VP zU*K)HqcoWD3y#RAfAyz`Pl@it9zpk5t*i1L2g7u5Kyy-b`g(&9>+3!HeJvp+*5+>J zL#3;|v&?h)eU2*XPNHn}We<%K7lJLKQ^N0X3>BEUXk)#6flFoaV)G5UpEchs=ymV| z=fFmIoHWN>y&wikL3{k;-i{aaP!l_R^_RR1qKQJb!N3>Y_7mtNQHulwjpKfTB6pBJ zf;^oR(DosL>A4W(sNgu~|mW z7?ZJCU4KV%&a>q8MT!ykctqh0LAAY?^_oY!OY|pynYSWRSwe7U^y5$)PTc@pt2c(s za}w~L5FwkYd4RBjKRa zprcR_nD9wji8xCTgz~CapD03HgvPW^!(lptZ4F?`5nG%`tYlKLw&+LXCKloNZblAo z=-`_ZT^kv!ZjU*6rla4?F!nffTZN5QAb1G7xnUTA9(EvO6%9P$mM?;`FRohiT#-_{ z)LKR%$Re>c!IC3*Y$`*Y$nyl-vI|yd2$pfCw!qVwLW9Zh(72y#Y;AR-`I@=2Hh#vB zK=8IBF^)B$*azUq0|~4G!1`=q3DAkJY`*0eLd4{K&WU-RfQmH;cOn-=e~+UDOxR6I zESe_&|Bw!ztF@l8_{gu5k---eOi12TGpWXFDe9)BV0H;M2o(iyRbmEK=bD3vC^dT| z*40|W1~kD85e+WRH3~J8FupZT*U0cp26!%x@Z(0Mg_nO$2Ut!OB_$>G{CMJ9jL)KJ zARKccSW@bSR0)6jXMg7iS5VWtQm29=P5t2{0_eVDv9>tN7_f09{8OBa%$Ns)0F4Y= zp>1!1ACxK}FQ@j(Hl>U3Dli@mDMrD7mSN(2_U5kIz%t$h$JHc0mge12szNvk^fI_e zP#_p%!iWTnswMEiav>h!;)EKkm56nZ)7zzW;tZz*neqX0IM@;&gG`2S_9{UeCTvkh zBB^_}AACe0VW++z7WsF6;qLm>g^}eT#eXPvoQf5=u%BwUD~Ht{&?-?S_GS+ zz^hoW#XQkG>~~*-e#Pr%jBIzX1&*vG_)3B$B)k!*rPrX)eXQ2k|5QX2FB<-LG5)3S zY(E}};0RAQC=%o=8Va^!d0UuAaOh~EwxHgQ!BzvH9DKl1SQZh?*O5hywk9q(H6kNO z{wceZ04OB(*4eqacjS&r2uTsmGdVju6NDBK7u>;vV&zy1dh8UFmkB63ehaVLEbvc{ zeRG)JTW*xW$=Ifk1N57*j)ebqYMe*_+EnutQ|%z|!fzRc5g8COEgR$^e9V4J z2PyqQx$ql2It+h!4EtCObtOt&Dd*DeU0?)w?~0OZO(?tnAX)aaZ-OMgexz9Dc$aoNtM+kT=xDI|~-SO0bbp83}r?BBn?255Q!maD$-T~`}%DILSRS|)!% z#peHA26v>oM?LVMOu6RTouAEd2je`~or@fL{yAoq|D<`5x?jb<4gxzy68Bu`?jHcu ztH0SENo3uLz7M9x1QiD{QiKH12|UJxJYk!=Ms^gU_5n`7RNXM9FGLSJ&9sj8tz(N z(c^ZFlc>k)Fd;Ey-jxGAZv?|P5XG18O!kN^;;C*p!D5y`ZR#V3d{-yay0j?1YTwC=q@F_2Yfji}nF>2!%(q z6J*2j%efcy^MS(&lDB2@Gcn~EALy|Ubt@{}4xnojVije7n$`h~G7wpoW|@uBZwqKB zE3>{>P=SLxeNkMi=$3wB^KF20i*t0qaz2EcLZlp$J*5YEVCp^A*_(a`05nPSU?UBFn326A_Y}dplKwiujsP$mMBJ^cUrr?8;XDjS zUEt77SC?iIJTjz^Z?f>D@X$v>V`ZuW!9D!lSJtm?on{e779Ej*y4JJF9+77DwU5Ea zjp=D=Nys`e+LSG5*BGk)BS$qRRzyo`uF+OGcCOp7AFRl6 z1k86r26yn~Lke!KaOBNgC-QV^VoH#;WsqmNt2qwFW(LxRT1XrS6$BO4KgAKTqO1*V z7!ye{Z6vUS6Rk1sjmYCCWK03t`MiJW?TwbnBp=S$0|XHTTU?7Xko&300_>?jk$u!8 zas^Jviw%Nq^2OKcai-8Tm?FPwQ44vEH3mcR633Q!&qy58Yvjli-ATiu($Lk-R4LlF);M z3PcazU3Z|zFK}N3JKE(yoOU9cw|y@oEg^0IQ&&UegDX~gr%XVhS#%Rvnqi9(-KE~K zmly~sU^_taw}(TxG!9dljR**%sQSWh>w#1ofWcB)X@Vp|%>H`U9|h9SL*KydMHUVk z6OB^|>V*(NIN(hXku~N@i-DSbcHpF62eV}HV%II9KGpLa>D@@Mfh+L=O@s7M0C6Z) zz{eiHbpy%l8RTTHOKx8za5q>`>Fm-pM|UFjL6|~B#2}o`xFJlKY4%(fB69sC$6N5a zrU;!Zg6!FrxQj{-e(7)&;ZXwz1N$$|Rmb4u;tW0lOs9C||=5BBeyP-Z0X?vHs^0ase|- zdB8z(XU@DAe*d8U(XD^iBM2q(PmZ^U`5}1OqJt`sO5C|5iKHams4I@~43s05oe7q= zh-^84{!y!LK$YK)c^2r=)varqV`ClJ@UOIT!JRZsgd@mpZ9@NH#MX0w&`i*OZ>2S8?&Dfx`oXz zSSgI&V7y?G|CKw1JZ|Pr4j&YijAdhq>*F#p3v*I zO&NS%b3+_ONn70Rqk$s!HRr78*BX=>33v? z^WaMh7uxg(ah~`byRqVCEZfVm%Tuq>mlB-o7D~yd2&=NioZL}|q3u#?LjWEkR53R& zC&FM0Tu~nkBm>?0Wylbu z1_Q756VR4;V7-aJdF2g!#zHtt2|<$;4h1W6OZLyEAkdJ+fto4lU*iKp)0|ucw(%nZ z06t`R1jmG-bSHM4zx;jc;|LWp(0`-w$73coHtL{Go@2+7KWAJ}K=SsV_zzrzdGAkx zkwx=5d3ak)z2=-mP;3|E3jL*~3uhdN<{Av1U?#xsH(=eKi9fgLWj~onDkyk&NB!*9YCxq4s*R! zMLNOj5uPr$_V{%|5h?&ENaVD`wm)r%2MIBiSrJ%tX+&m&0YbOt6c20>!XOhO zSMn$66jJk_iJNP?|CyjqkcrE_fu@FDHGUndQuaVAwa5v*Xl)L}>#ZitIw5ZO?9{)~ z_s0Yj=ND{6^1K}cyptpt2{LL-&^jFJvHW`p+{^&pL=Yi%OU*is%Mx#&Sl;KSZfQ&6 zh1!0w0S3kI;U4O4_HVr}sJceZ8C;E%TCXHcm5lYgv>*G#?oe(=^N& z>yEZ#s<+Y42chhC-=TP<4@&*>12LOT;KU~3a_ud-Mhhr_NG8gSL3~o%nSz3XdYn(5 z2VgUUCv0_;d_B+&aAvHF3AJ|QKgX(){s?v5mMtXM!U5A^5`Cn)+SPp`r`D%3d?B8g zHrGa^?^+9AvM4@#<{Lrqia8P+m8w!B*0cSM*dElgH_dyhrW_8FvUt=7D&^&)uik3w z6A;)TgfiunbYSmMP9!D1mufoaj*lo^LND{|Zlt9EY>CqShI^1&{KAS(qc5)1jkJTq z8B3baRUlcwZi@&DL%E3KIx^;Sl)GAP_UM%`2}!t|&NzZA*=W&FmGb^RS6hv%(213f zMvuX#;7&f^Y8&#dl&n#Vd_b+_;G>Dn^RO!QRKCC1Fq>Z_w*Xt9#g@2BV{PX%XJ0rY zhm{O4{}^10P0{j*I`~HjY@rx#r28i;613NLvqXQ*o1R&iFZCzq9%{85Cv{a)IQ1w6 zPR#Xmu!2Ovv>m>JC`jh#CC68=@m8TN@bp=5U-YZISQr7gEaSQ%f2V@r>QmB!XzS_^ z+^b9YO0&2dPgdMaikv8ZWfb@o;A$baUO;6Mi>RsxgF?sHrCrqvbY%VjNtre!GgfIP zffgze1u8;O+_JU6s!Ts7jZ`3X;{Yw{A^hTSXKm1x^gX;i(!B}$Pav2Ec-ZQ};oU^L zO2x8!RQlaepNtv-n6dI>k*m8wqBMZnB>M!UG?MsN^(w3ZT8afENKNHFphbMK_zwG* zOn*5D+3ivuJy6C3hb5EAjWfg|BvEMz zg`zdz@{az3;t(;WqEgI-~38??$J;%L8B4@7M=q4d0yV!zwpxrvl5 z40R{1{8e6X$JhLb2;)0R*WhAcCoa;U!Ar1uYuoSFbpTxf-=+24C&3p zD6E>G`~-q{N_EJyX$3|}zm*e8t1QYZdY)l(4M6F95jiGp#>%1#QpsLIn3pH>?47|_ zu)d`FpmE1mzoMka`P77FT%Lo zi2}YH`9b%6-BteQt9LAt=(B0NQfhGQVCU}*p8$yny|ZIz+=C0@j~yMDZPvWx!l>6} zud&vJ+u+mo=Ih1X^ao{(jLQ=EYQqMA_%Qko!G~0UIhCT!-%3ql(Pfjl(Zgz=t} zc?8a{Rp(HX-*C?G28O45ZG)oOy-b-5{KRaXcc089Q(yzgzTCTd94{cQwzi`FUqL#3 zGwVce+x7xhJ7a6aRMpa5y)KVx|y$iM<&BF6(hRrLr z=IRwlHtkcx{NgJz-Qyz}fB*JY`126lB$N#80k4WW!RwPp$A~+I7GM9 zZbs`aHs>OiN}cHAOD*?2=Zd;EX~>LHqL$rReZ9zK4Y?7@=pdLvb_l@q9aJHR?fphh z)cBY(F-Vu-nihXpVSS8;<)C_0Qu)DQfJ_u8TCthOi^!z>g|Cj$a pW~OZ27T`|>Oz@gncUJJC@u>&Dy%G9S+-o&_c0`dF+Y+7e!QZsfw%Y&z literal 0 HcmV?d00001 diff --git a/localization/ar_tag_based_localizer/doc_image/sample_result.png b/localization/ar_tag_based_localizer/doc_image/sample_result.png new file mode 100644 index 0000000000000000000000000000000000000000..3ced77f592f5d2748ccb6ba5f6be65b9ff508b94 GIT binary patch literal 45098 zcmZ_$by!tf*f$CF#b75G9qC6iMmsQcAkJySw|`Yd_ET zopY{py??m3!di39G3FTe{j0IQ%1Vo2V-RB?5D4ry;;-cqh#SHP1WMIyH26vV-S4*W zzgPAm@9Y(<4DFqCYz+`nI`-D)R`%v5x{n=Cz=rbKJ(HlXIBTdHt?c=vIw7 z2I+=WyH;V+hZk}J0z`8U@dfX>+(Yjg=JlL&E%-@ITPXNF@{>76u{m|>0}RsezMB4} zi>uo=_1cRq2#=R5ZP{EB_Twhrh;1eOmXo0Ixhr&=VoO%-E&5~RUv=JuV%?$exjPq3 z+4}9jUm5?uexR6yMb zH$+3oq~@E0Y#be%dwahxb;j;5#ahYB%Dz`-XJ!udygZxT-VVvhq37e{JJ_0xo%XuE ztejizPsf$v*==;F3vO?1Yx~>T8MN3QrJ@=yG(r95v(MdM{&Cz+!IqPiHX9>MwdY&h zo|lIz{s952qeWCUHa5db!vxyye|G0v=y=nI;ii}@##kd?sQ&fGrz_vCJ&$HF!fE)7 z%|hpPb>R}jVb#?_?$uH0uzqs3o>x#>YS{Br@P$VCPK>TC7Hy_7ZR3W@T$pSbn)L^hI4!P*5j zs;g&(QOU#vFD@)lGcYi)nGR%_UZkfC|Uuj1fJ8FT({jO0{ox%@88dT zms?z{IGC%c?yx?z8MC(8ljKdz>w3TzQA1{8V$#;uCUJQ(AEKmHc6V4c&_gKUCWduX*$)~N!s`>eO@8smC^y;MxHOEuJdBd?0>oBqOYQ^t| zb2aVPhp^Gn(bopETB^2d1OB`(-x@w?XQ=C`urqo@N@`JrA)8oJnM_WFIHPyd$2wn zl2?1SR;iVKSE;LSH2Usbo0i9+(yffG7%x?-yVwg*t97ry zz{FG_4ide**zZoOY-nhZa^N`{(OV1Qzml!HJc^~Iqf;PZH<$h3dN`<(cftiPj}T3k z>ra=-v);PC+P;49b8c=f_srA%e6y@=a8T(v6;-U(_@dfpEHv-F^+Q@JDzVGm7V@_4 zZkZq=mbAXY#l=O5yy2{c1^vS|x;$z#Gcy?5T2?cQQP-o?{#8XSt%U!cB`lV~{cire zp&a$}tMln=+IZ>o=0Kw4v0{_tDffLT{CoG33_GHe5QnpVb=Q}9eWoRF!|Ry^ zx8*dS5#67obYdbpTSk9lY@BgppfB~URLg;D&ECJ6|3cpm6%119wJA3 zV_>`PT5EM*>tg5P>U=vwI$hz%j~{7v$OrXdtimpRl&v#{P2uwVxNd1UGCVvbJ3D)T zrJG03k%xgn=JfRRhXcJ-G@~HO8f>U6S=^r*nwp)uiW0x2va@@RijJcw6~p@5 z`eM%QsC#>o_jn>1ao8(H{(}@3)~v-?@o!m~*ROqU48Wqak=ng2N175V`9-~P=8tzL z8HdH#gCNm{`j4nmEig#qo}Vb`((%ls>NT!x@Uf3sS;Ju@{W(w|pkA?CP8idYkdU{*${yQf zXk;W7LdM&nTeSi$Agefcs>W@8Ys=DALsquFE1sK(N%tmHpR{?d_+Xp)W}Bss9~j;- zbXisKuJDM6U06pN{bqf}tQ__@Ghe9^9zT2LBS!9V5R;Gv_qQ=t5|EKWJ>|MikL(;C z$CD~1DvQgBUefmVtaQrRKjAeK(5zml6|ZD=e-91)6cW;H(5-T0cZU(ijnP7PK3e|H z$<}sHN$=jTN{yO^ceia6c6N3c-OTm$yuH0q9UUFr+ohV!~t zdXu3oiumq|Vw145PLgxkQ^TUs-&<%!P6z(favdEl?cd?y%gUBvy;p6xe1P7r0M87zS|=J}d$OubO%GM?$6g3Wt8@$J7Z(jAmNFZfDz8s# z?*5{D!~Cq#!g6QkPxa-|xU;LPe3|8Bdt_DgZD?09!8EBSaKSA4(yPmJJp%&~A)&tp zRdtr(&@f549raiHQr&m{ppT4?qrPV(d{=Hw;jlK4B$q6zbQT8f#)_b2GJhCa97omqGq)@R?>Mt6^0wr8Owq9@S&)H0OHoITjo>MKcEW40ZNFbujVu# zVH6S)x{Zz9)ZZT#9{ymdJF#2a>#_;(pUvRvA+Ouf0xYt5s3uAYJU2E*3Q%QaWYkK{ zRTmvFZE}#+o_%>`Zm%S0+S=RmOfH`Ruwl2F>cC{EuJ^fvM@>hUY`5HHK2iRiQYt1o zqGpKAkG8+i;H`3=Rwq1^)_?y1&iH@ECfQ58zVHJS_2W4wEat_sY0r6NYyH>R*#vkQ zwrl}x2n_EyIu@9uxVX4?0A`^B*Ud)LC5P)SwnYSzavy0s$YJbSnS{%?^$Fgl@F{oU z-S1$@)~-ts_QO#!=_~ZSbp8AHFQ@&AtgpV@mzZZrI`D;#%kAhz5HXwXRJBVWA=9t6 zwavjS0&HT|j3FBnAq~t`N<1OOfW1B2+=IGE(PY8&{=xUJ=R{A>&i3X*_?1^r3bM0b zxE`$hQIO$PGH}4KNlq~kzb!`(h$OEZF~9gw>4DIf7)p9!p)aNd07vL7?bkLoG`xFn zQ#3BVY5!kFQpoY+f2c{Hl%qE+ZyFjJPHyh@GeV#;jr2k^B3fExS65eQ9;eTUDh1)U zX^Tg`@D3ZZR~~1quq{#G=Q;%FUI~02XN6V9m`K926dD`*RzTpx=rf!*pDlZua+wGS z2#}NmV1CE6U-`fYVhw;aE3uUC_(E$~@A_d!G?RBEz53kB%9px2ekkKq&!0DC2mAQk z{ESN;Tvo>M^5x4wVmALGqwbi9uV23+w@lh(G`ZUb)877mXB*UdCjEbR0XpyQ?acvP zOf4=h9-BsmyAhgjH+?|_K!f1-@84%PkxB=;)YMcgBId^8kGc{P7#`>zgoSZHvsut?sfi31PRf7*x=~MoL8uJIUfq$lUT`e;qRzyNbaIo?R zE{C;nd5Pcr*B1&VC2A32VS2P-KYsj1AOTjm{Mve6oib3m%C*&f%UK0Q?S-;mtkN`>t;cI}Pg*XHT}n(vuo3WDjN{ z#OjFW9=4wtACGMcAlP3Bli7pClQd{b1Qi`{8q+1mP_>KQ!x!)BVG5&P*--)xGD`G# zsI9GCbUi|QE}R-(IY*xVgT)A0%=+g86!vM8!=JFR;m1ph!4^<`8*z8;C^`HWtha*$ zdjxDmgV`@WcZZXk!;*la+#@1th5khs*S~&wVm_sy_!t<71sG8B z+IKKVeOS>DYA+O=NZ1C*ts4ZC%{WOIdOjS z^eLdpYI9N`Sis-z;p2k;67X`R`cmO?}i_-S|)72FW+5-xbwBnHQ7_YITzALjN zEiElA2AU(GrRU=E3c=3Kt|XrbA8WmvNM565H7kxByr?>m6jbs{^_F9HoaW0))_IH$a>J(yWoTxNX~5f>NkF{~zkff#g_+ssQYJ8+Sj4Q0;)m;7ZmoC^?!#c|^u z-^q-3rq`eU3c>3C^oa?7TRS^Y8Gy8<3kAsA*f2p^8^}>7;O6GW6ruLXFxjhOXza`@ z?6&%`^el70EU!j6$ssSZBawf4U=pb{DdLZ2C?TtK-aBn+%kN~cvy*dh+|1$wXYUV7 zhEnLHrKI?PSg;RNE({8CmE-0KNFFBBwY>Yw-OGS(o^o@KD|(*pEn<=LJxYB5Kjom8 zblDA&b#~?iZR&M$FQe0z2Fyq+%r`8uc~CO+7XE!lARDVzjqCS_2m{m0(JCi~9Q86v zCZ_M8(d+?7|1o$8qew6m4zI{uar^18K><7qE`bX+ohfIP27MQ_Zkt(kK1yB(QNc^qrsx)Pn2GLtck-(DFhK7@aK3t_xxap2Xu`D(+rK8g=qs0NI3(={{62r*}paPw2jVK4=J)M$SE8&Qg6KxXI8}XKUidS zTa*dlIi7uWX_H@3YGnrv1%!y_Fug`I^&b&Py8in0YeuUnp6Z&KJm(rHv_P@msjAK{ zFRRR6fcoUJ@LdeyJRijI<;#~Dczhh{CKtAVGp!xiu6i@GEh!o||GbyoknGSm=^*+Q zoMu;B@9x#YwROaL?3CnNM<-=gF|)4g7wgTIi!;Qjd7`eOp)BqBhRCJKAg+~mPG1y7 ztbgx|RNIp+^MqA)C%qeoHKatNFF*8dqFUR1E1BI=1f?98W5-`&$#1=?3NhcFu8+KWf$BGonnCqaiMw?p3RTc}WaveUS(-Q}Zu)XoU1o1S_!-&8gU0?E5)Fm9=a#skSc8ZlQM*n}rO1Jw zf~fEqMhXou^;&{&1>R`|rOyS3!p_kVB?ChUNVNb#P-u%cMn*=WOP`*m1D!#NVMQ&l zL(mvYxKh*7=C-yxCmk>;EJ=UdO1-E&XXW4GF&M%aDEUbBbR4axu7doCeXy=9wkV!0 znfs=#*Exc{#fZ^q-o`QR-$GT+SL94*SH&_HYLXHu*rS)9@+XM|+1T4Jv{EJNpB=11 z*}O|g_zzS{F&!NWT>cA22^tXnPP)CW8bB}+2I`I6=~+)XIisQ79Boa$jpuRz-H_eF zy2^Q17obv$rqg5-=uqOw*DiIU27Y}9#38Tdh}f$3lyY}>*ZpMH4}YzzyW0pJ6{ek9-?-g}KiQp!EuX;H$`~qNtdHL(Z2Cto_B^ z(K-eAXM)QT5y)AofMAqBPgSzFFJ8R>>a7TTHatE)o|wlu{|t!8z_eE&Xxf7yJ)}=e zOg#Acx1k|IUIJw;fT30v?p*=86)iQjI0!5MHY&=@M}GmY`3;ar5eVzRTvGt3$#{5D z1_{n{cNSMyeObXRbWpo zq)2i)$)S?Xuv}AO<6g#g4?#jlFRXUTl52N23B@uJdy5!0nSOKVrTJS<-1^JS8_pi@ z>^5@sUZj>0K0_v))7+O95z~=_36EEciPH`&#K#{yC0y9xR>>GJ&1G%Ah#nA3o0%2`9?2%;s^?pNN&2SK zU@Y&PGc*RXo;T^Ln!WsvrHQ&uC%Lsdul{po&w{YL0(@~JR4%igwV%(({fj90N!$D% zU*_+YUK`D`1y9M=;j)tBV4o4@Wl=h@9n6(cRWdU1#LTar2A-L6*YWkL-v2f310u?8 zimQl1ThwWDzCSJZT6&`BCP=eSsXOAeeCrxGa0M*)Qva&a-QK`*sPa~Mx|5B&NuzxABbA>rtrQOvg*k8a#|HBD~~Fes6E8VnP&BvRiqd2lu#0&R-QRw7%pysf&;M zM?Le=%4w&4K7Kc%rpwZW`NJ7nE5ekbk$>`Q-8og);{L^)MmS17M1WN(lCNaMz>)u=8uEN?Of!T8eaD;L`DF$#?t zd1ZE7MPEc~rC+!dVs<$W4%0r*R5nPQ4#k>$jHF-J_EeW!Bv}62Wr+)uC1Nx~QFdjU zC{sHpsNLBfQ5b{kcPyHP=LO$u25pPE5XFt$u38qHAde2sZ*~&SQ=J+9)t0ztZ%A?M zQ4w@deczS+$Z*Q%Xr;K2b3RAFFbuq|li@CX{JlA=^U(zBV8%@{En6)S%}bkqH?lW= zcHUe$NU^E6lj>0wY^ZG>KfO6}ac|@N&YUL)rPwCfr`o)a@n#Xc1|R%TuVZ_HziV3< z=}o+vQg;jg;lz>Vh&1Hc>-s7*!U1!dkw~yeL!xpi0-72|$neP8Y&xzy9V*O;4ZS z+>`xCV6BwH5 zgyh?2^_s0per~6Wdz%r+GYAJ}JTK)c zzT#0SkFYnlwD^JGy9?z`jglI(wT({qYM8u7{|(`GMt4S@RO-YK_F46(r3%!Zd69gl zBKv3+BMaQirFzu5k2UBiTi(})Y|{OCH`tZcrbv1*;*}d>P=9B0hbuon^pAm3Ql8z{ z*T=o)Vx}f1cMp2Z{C6?33Ui{=2L=WPY=jXN+>35D^kl9p6rLBmVugi;FGwXy=osjp z8g`cHdyE8s{cY7F5Gzy=fw@?tCCYJ#uy?C9O=}r0{(L#}wR2{;uUxeELeSb=GeU84 zVmhLwav1gfk-zr>{(4r5mK+Pz8cL+B1rom@xEjtbF1?`SA)v{0fSeWtgaSxrAPGk> z@UMOcH1ChsSI2d%#ytpib@dyls4nX{Ws=Ldk2nRkr)mny%346rY9VtA1TxTn8gTu! zZoiBBLWUp+!S!UfR*%vKnkq({m>H!uy2vL z7>NO_t$!M{M}ivvFFUyX5({a>u$m71Q*<(zbR93XNOn8kg7@Oxy<1<@&G!~8xK(#o zS1#etSbsq51Me59OlcinPJ`G2y|tme9aBX`1vDx_$-q;ueI$PP`0*nsz;oN%-EalB zCN3DEl)Jk-ppPY30JEu4T2EM62NZ`t-NHmlZNx!nV1)qtKrtRIeD3M#`9i&PBhzL& zQ^Fr}q+$WDs~TS@R+B+Cgk@n?Ty1>0z-{(!C0YNUuEjO{$qtS6`o`%bEruR~zukHi zmKG6;ys0w6pLj_*W7Yo-d&Osja*1G9)CO%giGYucAq)S(@50B&{|zE@)~{br=25%_ ze}}raPhfpE^OQn5QGnA;0b;FzcCZFGo%Z>25f>Mi-$4H}K~%~BMQIS$(I8B2zXJ%u zzigeHRA85@07X%W<*-r)k01vGA9(tU+uM0tHOE>GGxaDXAP_2nk<13BV*eo?rR0B~ zGf{4{28PfY7(ulB{Ms&VZdo9QXp{0d%jT$+NWh24pwNOUM3b6JQ%aTSEDN=jNV7!ScC&qx*v$pl^ZHy}$o0odO(so`99OM$M} zm&Z!x=GhYB;gvwwZthKGltS+FBw*2p-mf139G@*OL+h#jkOD_iSJ4Ja%tQvs80*I@ekaD6z7 z-19_`l+XPg@(=IDP6J$3WpQbVHZ@$W+PT2i#zwC0`l<>k%Z-8Mhy;)?)u;dZVnzU@ zJlm?;R@Bgla|KC0A|N0DrHcj;r-Hu!Q(i$q$<#EHmWGB&lizfJx@h=7 z2H*48>R!dN!eG}ai(+#YibT!YuYs(Ww9A8PrtQ_MnbaKpeX~j-h4QJM@$cPh?5e~4 zLoz~5hsh+B1X+}`M2kFCT2+0ORezOK<2YWof*HtylW?ioS${%!c zR$g{OthSaGG31MfA1ycCT-Kel?#qJfc7I=HBY%121I zSg$z{W{pj+84Kyf7VQ@qc4i*9TyMeTDuZ5Hy=r5?j|zsgqEsxq(&xJ8Lm&?_X1O6Z zLqQ7}OO++`3W==2OxT|I1O(}bqQ-UDh#2L%%m*^CwAw~TRgt>`R8l{3&kSNV(-cUV zZ(Kr}(*X8!TXUzDnZK;5KQUnCsS)U$@ zC}nNzt5>%A`~dIZ2k#W9q~JW&x3;$0gVS^eap%q*AkjXcnL-&+F!2xzenj!?*-h|+ z`U`S3t8^I&zXSxZkeWfYgPF(AwFBFd^xVyXtYe(latv3bP(uU!Gf^?C2oVJi~d3qh^;-$=`^JBObqe8GN)k z9y{2ZB#d6v0t~A9a7ew_bPxj^9i+Vh`W-l2Q65_Xc?BR(8nZ?z59e&SF?n6N7oD6P zZ-;>Y0zwZIJ7_)z%1)r0SwkLV&MiD4p$kujM=)75$QrUUgM&zAOrZlQwP$2}fkw2u zk{nV9Dl=Vh0o+#BPVL41ZUl4_g?I0qI~T1aBy0?~U2!~E36Hlc`zSqVj$-8Jim^v} z&voy;4w7s*_iq2M+^*k?KsVs=jS%N6+_vo!boSWZ4}JR zxs&Ddi|!G=iydLUs}nsyZFoQ-zk;y+Um!@ZkK?Sy`C_+)jx-OCkkDAdo#D91`W47) z3lkM~?t86NH*ek2F*AFMY~)PnH*el0AP@tS0s<{OhXV@L*H`BkAZ_ECsZwQv#tu$1*DcEIjJ7B~xIRVb zv%|ZLt1|h8HM6wiXf8cTx#+!Le_UAEJt;!x$ol(1#NnHM2Bk6U`+4U>TaF}li?MuY z2LK2Q3NugUZEfne&JNe<;_(NwRapQv2p~JZu;cnrj&X@vzrbo6(!7Jx`Vlte#^xpp z$onl0O+z4-KwN0FKo1?dJ_1ZpWY7%IfX$}WUwnWPw-Y>XxC0`yfc^% z0C}nx3|@(KQ1@tHZEj4}j1Sz$BOq`Zbnr)dgD~9{=UY`MoE~SzqX-wq(joAB!jpvk zm?02=)Nntdq8s<8N%@{ZWIz&>4@lgxke)A}>+9($%(^-Bf+-8xxMh63+R=sh5fR%) zf}5#V(h3p?YI*k8RR;~p-HKzrrF9b6P6%!S!hII^No;xD+3xH5pX;&ayD~C|*)sOJ zlmWlOoGVpOCrB-FJ-_EibMH(eYb5s-ej>KOnPYW$@8Fw8(dwS)~7~( z1Ec!xy?cM40dU$b+y+gF)5JtY8+Q?z6@iO@^?Hwhpaq;?{mk=U;JV~{oIAp7bU+T} zYev601+xb^I+)8HfYu$6D34LI|N#EdW;gXq^{7 zD8c&r`ag$B(#0WySZLHu2G(uvS%RvD35p3x?NWyq_soTdc1+64hJ^d~Ga4%EP2#+C z`FRtrzea}M)|`8YIKIN|AtW%Is5{YC8czPs(Rry!{es@;sx(aL{;v$tNWyA+?($re zfwC{qxfQwcPhh*4p6txFb#_XPj*n*{A=Pq%TNmrk(&}oB8nDxm0u?d>33mD+U0AyR7 zpHJ5EJT+iLs-eeMw%eVVN?DQ)PU}Nbpv^hq&jo@ZiWKAkVz>47$^k8ssDa*;why+g zDTGPehK7`Hp`m3$S*YzhKHk>V)l~#bBOE@^bR<6siQh)qKt@vl$yE{TV&p}@pME1E zDymh=ml`;Y3Bgg26H{P*QxZImQ~@qi^`C+%*T0S!fG7Ysv6nEsOxQyz+2eh6=VuF- zYYWFR8J~tPBvF3_Xz$9dPd~~Wx-5{yf4EM6f0*9jGPe16Ym-aDAn{5?DQ7Gy`;%d| zGDY6?Z-0sQOlpB$E2X2;9Jw`ZEZ1^xfSGe^Yv9@9ynMN|Zux+KAS^ms9HMp%+yctC z8FQ!i0V-QVVuseD;D$30%oCvAP^;`ChTN*4i<1NU0mO={@?sczH)w^gnuAH*MwuU; zP7V`ZgjaUkm&y3Pg}L;mOvCB4M+L-@r?E$8~8ww zjtWUnr-CT&;^p!5GEnE-U*cA{zP`Th5KuhWo+gi%Zuun=@Fg(t*^?)8{=*<#u;@14 z26Cw&{9Vg?|Bn8}A^wq{XY+3!0xE$#d-H+fW%qvcRWe70QNwa=CwK&TACP>JHbK2|EUx&?3r z;w7FGEG%KLQGkWCK+=PbRKqi!mX=l*dVgbMqpZBV5G-F80Id~3kh4;*Os^*yh7}z3 zu~lPh|8jd&t?m#lHlg{UlskAtdy)$07Y!+0+D)63y5IPo_bC~dr)c@J%9L~`&9C(; zIl>38d8fTyr=*og(#tLX7oI~N;t)8brVYVfduQPNIor%lC;oF*U+!ArP1O&{S3C%` zRGnmu#dr1MW5=W-vF{mHF|s5KQW?we^eF{~mw!&Lb7%~voK}6|is_o?U1PGFi7>MA zU!wwD_aX?)qGvpFO9s?_^Xsjndu&~A=uchQ0Cz76ATu?3?Zgh6hBb05DwHqS|+%N}D}vwHM8KA&u;^D`6wq%2!a zjPty?nTVPt69~G!Nn51(mB;j=p-HAc`-!f_AqA)9K#C8J)%=_?X_WfqSz-96Fm>vw zUHYMxq4%k6`8Nt9p1#HAQ8Z%w=ctdZs3Rt)izU;jV59Tb1b>${ptI+Ui< zPb3^KaI50*G&Xkp*;wDF9wMr_f(;dyMV+~)PloQ!Y42HLZIUs+Y&;qEvZ5xsLHI~M z;5n1g$)x~s9*#+{bY+_*En6hkEp&9dwSnIlEs3scG)SvJZku$XG3aWCL1- z(Z>x8br+#j3C_PHw6a8#lK`teqohjs0M0PMC4$v-AYF!k38LV(Q2 z*Z1E2`$7=n|6gr1}6c|g}>)APc{pVUBQBm@ZA7KeymP0#x!*nvTV%~ zuYlM1);Xv-VZU-%L?Hjl>9F$z$}d2C7jwI`>Z_qJLP`_%N67l)!q z+2^T|cP6hKYQLQvsGG?RkH?Fk$uely#%*kvLk{ZQ>M10kwOm)9Lu)c?8v`BX{}k|P zewYY>e(1WNi;7s(a*%nNp>D1b=%?%j@nPf)puqq^}1(r+$jurl|!i}^d?fZ&mBB5j$Zma z&3b%ZY?FSzK4WYqGJKX`{)Jntakhwc&mlKWpy{wsoI~~c>aw7qKnFxF{I1nQSJB`{ z$XEyohb8O!CpBQjGJL1cAfW;C5B;oRw!v?8q~IxJ3`J;~U`cpuHd8{4Uj9q?2Y3! z=8DtbSxVpIGq>65{?yS?$xlzX$ZFrli8@?7+M9G zOzY%d=&x#Gb#JZxpA$vTh(H>8_UzfW@83U0L`0Y@i30RM`Qq=d3uxbP-XBt@Z-I6K zoSy*^Hj@=XE?nPZW7|iIj5-a|{x?q)e|HW?IoI#x_Q?6uwGlPe&&;d>Ukji7?TKt! z~jA%NG$hPbuZ*TahUf zNVj1Tv;NySX?jh~$Cm(+o0(OY)9**Hct0?mzLAkJTIoruPrcQBRgoK_oK-Uy{S#;h z*s~p#eQ<*5Q<2~MZJGRQ0%}h54`?Gs87)?elV1lMl4Zu5t0!JXf9|_w>t;GYKH*KV z{_K&OX`F#0>BZ!R$;P_m#3&DYlMy3psGxk!fut1{Nlx)v#P^5w3G^2q9tN&Mpg}h>(rG0r~F;M;0O z9UE_S4#!I8ua3OJLVHe9Hg)qwX;)8<^bj&o9PU^jjUatzzJ`X%X?)wz#syb7(y4iB z(2t4qMn#6!*_JncVfhK4#RMfbPN_z8<7%wxcCZ+s3O?GwJ3JlZhPlEm zbLQf|oxKTifLBX}AES^BbC`)wEPbl_D8~Db2gOfCU>!YoeJ>%%(zF%kJAZ zDxUOJ0XLOMjMVA2*5CQTx-u|$Z(||UT>rUjW-ETdLFQLEPHqW!FXHd49yw2+@2PVsrHScT1*a|Us>D4Lj-;$R75XwR)@(CBCFe#U z=oz!RW8#3tVMYDh#XL`iLnnXHyXU-Z>;u;KNNew)>y}O!s>m{ zU~PS;*y|*QVbey(|FV{4RR3Z490goa=)WtjYQ)*FkJKi1mNx&}HEpnU-4(QD+1uMh z*|9C0y*fe(T)it!>ICyRkRM=%lM`#8VYk8+np7uKF#Q59BKqG&k~xRVn*=w6IE&it zM`mU^`SPkx8EbgeyPTtgoidmIc*lRbZMNhW6ft!F9;VK~n&%hy!EzU~Gr1iT+s>#X z^NohyVjlKKQc?QxKSU2 zg*4e}H;S`K{uzyEpG)6{7VN7F`KhqQMJJn=e>xR;QiADl?J)Ru>wwy%9 z6PcJ#R43Z(hnfq7$FI9Nw>F8xC_Y$X*C0vd(g_yXwp<;t_k#%JzLw+lFKivZWPzF8 zY2`MT_|O;5?X}`6H{j07%jKl&N>8AATW*3+h@6p97;3yA8mFsfzriFial1%jN6I_x z;P?{zTf@(g<5g;T|C4o=q01u1@AwD5jdCg{YN~`-xanKn`Wn`CN8EXm(^g`Exub>g zj`A&8i5DB!_+0!BQc;5t3XIGm{r#%xHI-ps&G+L$hWkqYt)jX#+pcfbHe^WIporBs zAk2Fn%VA`V`R*_dZeN*)9ok5{=leOFyJyHJa{kobwXYnfR|%r+l@R+Go-`VHK1pyosKa#h<%Sr@9 z1UQt-g^SK;$ECj&P(NZImxK*b+xr>k4%fX>-~MMTp-bTi*|g%<>Sa`Uql9Y5WUY5O zRBx$$!B{)I5jFNL7R$y6fWV66~b> zzWgogSn1N;Z|qHa>ObAXu)*wE3pB&AIQ>^Xy2C~#tmR(8^s%#rMOLD<5RVPHp>9_A zifja^1x|iUG}f%f^9r(Iv`;Er{Ge`S&Lx>*(BgShwRMb2NTcXmZ?pc2^UZ}smMv{Z zd<*Z1g0dl-mw7(rMJ}wncE3Lg_`-BgBpocGIc|=MOdXvTcU^c}#=MxngWagk@jQLi z7(j)97=cqe8f{}vTNTqu*~f4~&hndFyf%Yx&2#MSvzPxgm)n{1MN+iNV#8Yh!u>_w z|B|X-d?f$d&y-aA+5BA}v_iI*aoM~#ueCz@@;%Lv*V=rd9|+5-Y$Ya?g0YKsoX{y) zYIoVW*saDCNA?5qrtV26GQ3}3y8Q^}>b1-zr4XwKB0PD~=dGAIx8&oW{WU&X4S@uZ z5j3_Tzj%cwe=Kx%Z^y)S@GT@CKeLH_kq*y!W$KT-P?{~qVfMIP^u-GKYWO~Pa!Gm+ z73()0&46mkW4xa8d&HIK@7QH2ERBK_dh+=jbC_^awvNw~7)(~?eewe6jqKizcrXW4 z5o?WK8O}BTcj_)BB|8pVtm}T6#dGYiC?>@s5_Kse^9eWrf1lb1Tx#7B*9vr6pC zg(irEL`lMuF6)F6RRUQ$L38P~RzbCjY$PmO0z>Ewc{zG%8WBnPhjQFUGxiGvpEIzr zdi3jkHJ0P-@XW_#8cQyXZ)_Sc7T;ydmGjEC^R9j%K5_HVP4h5xE2tV!4pB$;)$MI( z$XD3}NOVxYAKbcWs~g#qMg3{H#IM)%f$>lAWg)pRx83q}oocg^Li-G%iP3EHAU!|F zZWhM~O<`up#TKxwSew3F-jmpIjNEk}L@rcI3JA|;PepYkt%wUT4>8J>p%O^l(=c}E zK3f0uHtNj?2kEDpk`1$GjZ#mM50k6#z69URaeulpBmD5fBU$22?@5!HdC4NRmye`7 z4b+9u8idT$AFpuxA)m^E|KVabe`wcdO}AYsjjo!pI>J0Dw#%c3oCALiir!zqM3afnl1OGi~~U(R;|KLxu{d&$tGHDnRu zpzs#F=fNB{=q4@eZp`N0&atDt>1nTwfv6b@E=+64x8f&jsek#{JIS}a!i2SXC<)t& zc=%D~Ga}-?%!g)2>4mOdv<%qhLS<-E?w7-N*jp0Aa$aTrK;HH1;PmC97fY;SdhGql z)}#z8rL$=?j1J!TgKJ+r&TZat)S;WH8zJwyoG(X|C@iV5Ze|(%{XvLfx*Pk^pI%Wh zTgQ7$Z$^tT9b1MZ-nwet*c z5CG*G+Sl(durud!g!*iXJQDX%R#C01vcV)f@YPo-p=ZaY9QSi410qUnya#M^=vhev zb3469hBj>m9o_)i`@)x3-3q2LW$YbLKj7af727LwmECrZm0f5nCQ_ zvC7t=M}tV9WGY@ESTNt{64^u<=4_4b6lFETJNb|&XJ69bpkz#U@<`CWbNiMXNBb>! ztYn>^H6=b@xe`>$piicT%vBLP&zo9F!JL3`YHzl1tF9p!Z<&UM4rc0#DHDf{eT|uu zlQ2kBVU`{2M99rUZUGsl;^g8&rk&tGHu&mHS;#XzARa)VF9^PJ0nGBbjnN`Q14t({ zgTcA8xA(WH$rpkEg*pvrMa=LPIC_Rm2f$fh=c7?08hZMiqho=IAAqCxy2!-{Pr5LM ze7kk#KJLEgt^U`b>^1YdHM!#tdZqNo*4}sgWVbdc-#mHNxY^cqD+Z_Hfb&YGs2?JE zXspMm?+33Q5TA3+Z<@a?n5s_*Q)MGsB~5J(O@hS#_m~*dO86261f%VOIDGK{P*@%K z{ti&k^WmEikar8m&83D39z3}F@Zo3CWC~hZf5_s5puilJw!ZcP8fKJpS2tULdeYINS_WSg{e^N*QhNqFZJ02 zU>}Gp&TkSw1ba9C-Uy5hF&cPn@ANE4UP5*5Ya*B?Z~_z=I7{un<@A5h1%2VcAmGF| zGDm;!p5Sz?2lBWmoDc)S4SAp(0pB9=e+z@i93G?d&U?t*1l85;qHiGwG}rhwB|SZM ztu|(2LIb`x0OB7NOJ~oE(6>g)OULIW7`NXgnCLn5o*CV z(Q%OrFh6dO*|}lAZ=U8n$UBRHnvSDqHU1DFX5o8zbY@J6=(Bb{wE;(+Lzc-GcXu{Z z;h0ds3u)y1Lt5zvt4W{1u++cSR)|K-EG?l4ym@m6qIBxxZ{LQFkB-9mwoy33fPgQ+ zV6_+v2S+Ud5^3Ehl!?AQDWfxD=sCY$EI_(qk)q+AONxW;Q>|HSuM*NSyO7-m8yz%iV4_nRt z*`OCi*7Aap+ak4}IbVbxp}hH)$)eMS@m19R>2tP+OYx0QT6^{u+grQ3knFsEhbfYbt8iW%}luqp;ncFHM=-*a!q~9CBYwa0ZL* zxe}ZbJb|1OZzAL;Ay$)?TijL+Qet^!WsD^X3d;3W(A}~WTW{U*T`a8&3v$wFwU!Y6 z&gCt=qLDPWPi5J4PZeW7^sW5dowU9VF;3*iK%GLVdl-qMdE2JQ_|;zD<%(63hLz)) zuF7blU!QeJS=!e`8@0yf+GU>*;%Tbu9U`EufK{%?NEprSl)G9E2ipP& z7z{xkf&)lDV#+~f@s>7vq?s2!2ZzZ1wzT*mk8YEac0zq1gi{SPIyY!7f-1+>5~-Ket}zcZdY3WQ(efl4?C z>I28T!Ov&S;-I6$tkKd=YFgQb2w`XCN@M)&!08R;4Jn<|DSg|nRL0k3@m3D8CI+#_ zw8&;cXtR# zw+hmH*R%Kkd%yS0yyu*mZ_n&KvmIQlb+7xr))l{?#LTCWP-7Xb+OEf!(g~44qs=hv zk!|m&ZSY%dQOYjY!tv7@Gn$Wm2>Z+M;f&Dh(v54{k>;K7F-QgKC9n!13Xt+zM1$f< zh|25NB1o9l$jEPQKA*U_;wxSVXvop|K-?2F8qJ6r zW?(9saFX7@!!vL8$JEf&_1J`-zf3r(B(RtBUKC~lMVQyCqooCng2MQLG;~%WShYdS z0unusX*VHsbLE%Y+wXTJ3%j<176o)U_d&V?P!R)wI9340?EMosPZ`h-M53O7OP2yb zBc#{>^_xGcpNL#AdN}Sc5BMQNSM&Jtnngw=w|wQNrV3$)AwoUo^#ydP_Ebv;4gn8M zb_3`M4pa*M(`JD8(PG#*lQjYaIn4c{H7B!M+PAsa@wb~|m&ssvL0(RjH)O&DLzXXJ z=wUK%;&Kkn$!|K<1U^Viqa(bPQ~=E*THD&V99I>A%87}KYX+@$V1bT38}I1}1N133 zkTOBZC_=9=+x_?IH;v-A(b4z_r~e%jbJKHiDeKu&_5LhlvTu`#ia+0#9>-?d7usUk zY1!OUIji(?j}yXwC0<63Gatc9QUnCvktMO-#@N?6b+D$Fa^_i%)ak84RE+Og4dvB_J^E-GnzKeep$IDD(>o*Iw6>f3X zw#bWUcsAHRRb}nfX>nuordC)lA5hhIOO%_lY2&CDelz$-@`;K7V{$IVrX9MF%|XK4 zn_D{qlk1ab@}&Igzg#zDkZd2%n2;GgNNjixMDqS-|LX94_6sX)Ju_kja+}l1HX~^= zgnY&$wT1`&;atjLl@3MrKcVmT*|W&OZ0eIP^1SdU1SX8X%BruV!(6*5kgORT7lT7~ zlG#dcI`nmZrDHsF3kla}Bf}1z9MOdAts8*+Nj)rC<*Nc}&f26eE72aX+eC)yD_HQ6 zEA`y^v29+R8i4Pb6-&p#AZ_j&4<jP2^2RSA2%A^@I*Bvn9*s!P0a@cEjbn9{KqmB?!!yPIVjPB@2+=WG6bZGEKr9 zUlJq3fUfTe9~E|9w$w>Lgof)Ij2&wJd<*d}AI10bBaF{Neq&p%JVA~poRySo8KwPSR5*lq&~KGnQR8Z z+Thz{*GK=x?p}E-0F_3KX*{lU(L#vjC<~t`PTBGkif1Un2!iBsFrl=8}N0y#Qg)qDAEVJ1oJr9c@rdL0@rHDY!ym)KFAX4OLLvt?o=+W{Hu zLlkIVwJ~MFv#d_&W}jS0FuOCDT5t_&dIn?m3$I&FhA6qGaiO5*%=O13y6O$!481G= z?yx;r|ERrVg`u5Is73_MC#sYxdCRlp@EG`45#FQ^I#P_K;ta5^zdnNw&1hBlIYDfD z(jv5_1U`SplQ32ySf;Avc~*;Keo?J}8Lb`7h4Ru_+>NhDXHe>f>TRvast?${4!_5h zW0a&3fq}=RaN%E}5j6JB&*HrISZgmOlr zz2t2apsF_{)tJ)ax2N?lx|aOW;nAk zJx_e%!PB5O21P*R*y8g1t2@ z<|u7UL8N*W7esOCBPytqwbEy@X)PJUME5`|Asu-=R|4{KpM0}wczO?y18Uqo!~N2!>QZNTVPI%Y$wpNG-xs0R ziGHqX0{@6%>Y_H9v_CU4sciPE>e?l_I;7`Ec9nhB$qUP=J*sD>Q3&l*)hZ=3JV zyJ~l%&Ls*EXTyw*v;lSZ3T4)hl`0o5bUKR~L7|cn9yWy9dXDf|o~DPhxwPVBsZ1g@IY)p( z2Q8Ipq{^2ib>t=Kd8Ootr?Tlg?Qex&2pss}edcwujPqDtvU^RvNl>vt-AYZ!7 zP}sf<;QZsbL2z3tcysWadT^?-Is<>O$<2D=N-_It{<*rXigm<5&LYANnC2lY%;Ryt z_utN0M-CYH9E!zGHbm%J5+9epWrSZy8;h$7{73zx-FCLnMghS`RybX?v<$>P{JyrM zE~O8M;tEPAkRNMSKgk1NltMF|yWi!uzSbL`g1Q@7?APFIq?-kVb9srDVM7~p54et`*wFY7yvTR9 zn1j5cAdX(T8HjLkvD?{o^eF+jG=}=IXyr3a-xuDhn{VvHBJ>kZl8I3G)HhbW_>_-j z!q6PTga`~6=O+?PO6b|>l~Q=*p#X!xcum4L34I4-y=5oYuYM6O*AN?fp;KTe1i?MH zvPYn6iCffp+han;How4!=Ogh118^CMp|aHP#?!WFyP`R}SeaIK7NQ0v9sM1q#Un6+ zyl|E0V{sHgs>cB}Oa{X|o%Wc0x!Bl>Rv6RAQz|oWTL!-TiuF(rXv(3aOzLY4=Jj36 zS?DQ|1ePu5tD^uJwD7+%E)sLpsn|s`Rr*t@>T&PWb{P9(bTwYW3y_0`E8f7P%+Qr!NRU-R#Fhll-_D)BJWM%X{uQb7B9 zCGx@SE0Z0PNed18`US7|AvMkdPfc`2^FpjkL6YbJRWgykUc6a@>#Z`+PB-yWZNw@6 zAs^8N%+{fmz(=*n294dO@ny0Pgz$S0wU&K%IegT;c;P)|jh;%q&}{aw7@QCoyHw=; zvfDB*)A8NgifYix(rs%GkiKxla)@fY@$9jHmbo*NJ$wklkwF)QN*1a8UX-!9|ZItQn%{w zUvto-{PN{X{Mftb=te;89~>RELpKm~?;MV{GXpX~>QQ6E5wD>rLC zG*Q0yE9>s~&NYeKqeMC{H3ja%a=$RO@wR-lIrlsDg0B5+XyI*B<9JSUD)o^KiCQs)WkAZ8szg_!=OuXDwX^%pMun7b0mZ~8AW}JK!JGAS zJsl}r2O6x=A3i(;iYyY23>sp{uFsOu`Msc^pykCyNx&Zh5VNhl9bH^pT#X7=8X#G} z0NtH&(qX%0Yiny}y7%nBQm|~ior30?OUb{tm2CbdX97#v+UKHywBwe|mH6ZdQG(2c zd%ZrLShxUsV_?P_>8QNcB}d0y<3OO5X@W8#5TJ6Szvz63iSd)kXzJ_3@d0iZ(1wuA zJMRAi>^-%l0`4t60NIf2YJtCSC!m=4=L57**~YnQ^4T zF5kWq<^1n^WGwkeUIbvZQ+#|7rOS482k6jzx(DSqw4{CmIQ2L13-q~G;Tb@lsL!^t zCj2b{IeB=)odhk~)Y1z3hsf8bkb%;^6LWJwdh=4jGwzYMbZR!5%XoX#iD-5S6Vtnb zlAhwn+`OP~gN{oH(o^06j{m2g*W$mZcu?Dt%+3=aLe~H1fcg^wusc!z_w!#pfU5cg z&4AC|m+l}G*aDbG@3!~__cbc$tSVJ{-_xi}uUq1N%iF#(&G#9HjWPlb{#I7$+lt!} ze_b!|gv4y?8vZge^_z~*DJeag=+QHcd%oN?2%3%nRR^UV>aX_7g%dnL*aWGMkl z@|(JZpp_^kg}Sk^0c;Q?fh0O9Nf8ipETcekjm*x@p1QN$voZShHnJDWGjeGOcLt!% zc-!nJ3#S>se~0$uWOQ+g+2j4YwQLm=589vSJlR9Ya_qmv&O9ml%ZPqu!+3@_(Wc4S znW!DXC=F)@0IUC35iXAaf7$zwpu+UPHG?c?LbAhlOIlh58z zg>9~scHsNH*3|D71SjL9i`1@wfzi1I$spN?zZnhfbMv8ho?sx9lR4=1Yr2`A|91$S zfvL0QU2RQGGCG-X1E64?gK!jxasdiX1_anZ5ijc%+%9xv{Q%pG6qo}J<|m*AMNmB8 z_xub!e^^PDox9rQFNu%{IKUOt!{FoUV$ZubfiDcG^1asfN6B{zHKOR++A;VeV{v4l zGKr`ai1t|EXm9Ntzs~(cqS-@_dbIbM^^W9JS3Nf$e>wG?|6hHg^5)-2#t(>H4uXi= z%{2gue-d_O2dY<#0jEl#o+xrxK@7=TeKc=G$wv}H%h-dC%#qr!yQ1x7+3((<)Oo2B z?a-k!dBP{!asHB--?+<5rYzsMNy1K}r?yY(o~kuQ{2RHBIkk zf1h{Vcq1CALYO1^+i;A~9?KsiuIZ{AjZox!5Js#yvM4|tH4q1e%_R$aRzVwoDsdZk z)gq%M6pP~6(yHv83M5?5t(?UtJtbV;7YF1R#vdFP*nJY*fBK}$u696!sWA}}9am0I z3aXPy3YrhA+We#tI<6wiFETBUgzIZ~`^1i96Fl{_ez^5-w(!x+D8a-{I6fnS$bD0a z``PO)j=LZy=2~|YMXG)J#0CZ9$-ecCOm~Z;i{6VJ_WYO>}72~9* zDRD8Dixx=PvJmAb)$bfCE%CK4HC$y7RM|gB~GoOZ&df|kxMO%Nmu6*`ROczHkX8@D1 za3WxJuf2FNk*D|VpB{QT49~RQ-X1F)9l|R~6WJPH(0d5G?RxTO{{@$(0(VZs%;Fwa zFRH6g`^-H?5s&WTrkF}#iTAX-$K*JP9RdLz6pyO2Zi42}CuW?-qpW^boF;xsdhau( zk+<|b0r$GOcc+5yhwtrk+ff(3f7A95%L%WbwqxxYyiQcpg^k|A$0&sWhSn(bYUTY1 z_&TO%j=wvyD^}Rk!z$*6_n!_^o6a=&^gkin+q(!kjbuQ8P}lqK-R#jQqpkuAh~;|Q z$Uq&Y?ted^xymyk20J&*@g%CL&$T2qZ(U8erF`uyA=UJ`RbXgW0t(+1wsZ2J&4BLL zv^@(_3)(imAqhiw8lxP$uiGiHo04H_TrVqkdW`(-Z~ZXJ$nb<4{B2Ss*Rl<#jCtiw z$*iVRJ3^;eaJdQ`i!$lTt61(K0~FW^+y)7Y9~&E%NpGBdWilXv;#cXI`)q-_zlu-B zXmk(*P!w8Qn&gzX>vlg{W!6P0lFkQzW*^-2vvPX7a=2EBQ1@%sk~GE&*wQeR{Ks_)qtCKhtB#jDZ&pc z7Nz~`;lO3x1b6Y=!-9BhB4T20k3SY=T4Y*I!YqF+aeeqNq66rV?`Wk)Z@o>h414o0 zx)p}g1_tTUdqm^AQ62dn>=!vdj$GSV*MKT%cCggOM-*0sKT%_Y*k=z$V+gaygoa65 zA;ah%S~tSe`|V&cqE6c?=4ej9Hy z`&(aw#?SR`1uY2$iR1so&1~DIdRSGqC`jhu4=UYsj^~vp_7$^n$#u=c#J-{a9RC zWb_-+BqPzgHhC%N^qSJ=mT7}=goAeEKzgJ$vrt%#(F0B3>Z+=$A{ie5T7E$)@!e@- z_$7|=XcF<^CcZ3wpMYHVCC+I57K%a;Jyeak0b&S>g@A3WL`UJ1w7w_CMJ~cU*mK9A zJ~wj8S7IGbY~L133rriNJ_qoXedFRtz*oTRfx}r*`LIK~AfeB8hPUQFVRo#g9Ysjg zu&&_(Ys9R8!}Fno!>x86%>d$?{jUmYsDi2-Ew)?&(0UvcW^6Z9kgE}Q6xAI2g!Y27 zN(5^h*KM_9NY2xrD$q=%#NdHd%9ia0lhp@SHa11n8Jtud%N*U_YDj<|ELTmSfjyL>9$s2eypI`##%h0YJMR)K$FM|I8 zrPo{$PSxL#(cb^8Yw^(`yu^6Ru+ik-l@t;J6e}Q3~T!9=>SWE|C*yaHIKK zo^K2fqL^tM2=iITJ|&Y9g2SD*dQ0(1k(6mo;U*Pat>k~ICRM5$5iG6+>2o2{eSLu= zjKA7;t1Tt(OqLZ5Ey-~CUr=hjp2^u~zJ2?4VeNY%=iQ|30~eCv;s=6>lnx9jWpp$9 zR`Y%TZdBaQhiOxy_7?Y(rmlPC7s<^GXv}%6#xAr7H_)s^cxq_~b(5>ol7TTr$wSJe zdyA_-8PZ`zU zDil*W6Go~MCjn%%9nn>b(ErO3xcV2dA3V0_V>Dgp$wu@%0{RTkRAvf^&upYn1il{v zPKOTms>gNb0Oa@XTDL;ewD0P)n$tM7+0~~cVWZ#b(D=+O@jFHPkyJI_{0@2vIqGm! z-P_%+_HSA^a3Erw+8eF_0inTMLhcBs3<9e)SPx_w-FooOr=O0C38yKugGtPFcz6-{ zmz5(hd=;peMDQZ#5irB}p>VITuh~&EX@&k&s$G zEPwUqE%9Hny|wHN>m?^yjwJRYrAQ&?R8u<$CI2#HAwVH;4Y78-@=p@{@bI@C zj#qwTDn@wM6Yn{8rw@*IGa5^ZpJ%{zky=r}^=4pV3SM8gaM_#h1IZ2F($dneiojn& z8nbNP27+S7kOlKBkm$pKl>}@hG5!omjb5?)G)wYy*q0bPR;w!3#xeSp0G zR6_$qVe<}&NmQ&Ajn(K)qDg^>p*O>w@n6=EAyEO zB&BPQm6TSXjH3lU3$#X1RP^-vK?wpxqYZ!$ehyVFt7eHm;Bqb#=8J@t{C?E5YE+`% zv0VQ9pS@uvh{`MUcrK{DR17g!jxp(SUKfCtCq{0XrrZcj{78^m0?i4q(fMlc1uNsU zKIn@?L4e36fExhTaR<;s;Ch3I{_k|cN-1R90Vr_$Q0()75G~^Jco`2JkGdB$d7;~b z@#BAw6taD8<$d}Ar9+RlFPGn|6qk%-9ob+yJ9VIMEkqkYx4#td#5t_a{)2-|4~E}e zSRqM-Cf7IrBliswJj_b|2oMBE_DtBT{;w^Ggh-ozCB6af!|8JP@xzBAn7VskE!j#( zc!Xy?p8D}3R?$|fEVBifP0b}>^Lw#%p``}gyTy3(KGXeD1C_Ck|AOuCD?Gg{07rs2 zJ&zDj0!b*T04~`g7zBX6Hxn!C7kHnr1OR}6_m*Gw8AkR)4c^|UsHln^pb58sc*w`{ z-_^aVLB<%0tJ0a|bUhn=muV-|JI-NFACZY!;emt%+KKs)m37fDsYQ0gGK};x>GFt) z9BEFnMW# zP0|I`zRseKX}+rb*Pe=}DF1~N@_tgZd+j752<=DWA7Rq&|9nnYexf;t8{6c6ba<;u z*GJaBO03PD`%>-y)L_WrBxZzg3Z?V#$OwSTet=Zb9f*&xo78hyL_{b-jHgs`5&?{V zA}t_ymOz*!(h9${{clYM%`p6mO)n13Zp;VL_XK6fwf{Ya`3DlEK}`vzfE3eUir<7j z$A8i6OvG+%8QmoW@e~sidVqe#U~r)U}Oi$28rq(KULzBH zMGwadNvJa$xDCSNz(dZ|H39k}Qf3DJ^cJ|?fF8~NtLeR0b#2Y#BOed@$ZiS&%IRG! zS>%UPYwRYf?=FyT1LKQKAX#UD!rhGG3dns|!J$X0$N+28 z5TGVVxx~Qy0h{+0ZC8!-4*u)6VoqWQP`r!Oyg!I43G*B>I^+D4)@4 zo{j$}GGw$)yPd;uedM7;EKgz)+#$I2jwFFLFCA;qW1!7dJ5;L@f^`9o!%ayUg?X)*-T{D%} z0Y~AyF)uuo+vo9A3Jf@!+6^WV3n9yxD@HB2k)n!mbM={QP=&dJM+ ze@k*3-ne0Z$0~yL4T~m&+$fl-)l>^ae0R`l#t~}v9p2CVmz6~Z^kYa&fHb8|zQBsztbYGdCjloZE9E;_!`zCieaVrF>AqSm&i9)P@N9;@ z$-4|Mrk1rlh+Dqeyl9Ysi?Pv_rV!?=Whv0vPCe+c5K45hZcR7z zfLwmH9I1s@Oj~$-E3FruAVr0RZZI&cO&d^C3Zu-UU9vZdM~d*+NRiZ9SAX)g%SLKg!wPCH3ar0(n^rbMWs^N(R#{fkA@ZMJ?T~R( zp~vksTLYEPoP)~xEE;~67WuRJy4lo}JfrPeAJfIFn*aIjRg$G~G)rzCV&Ym2Z#E1T zCRmA|D7}Llu%g=ZAh4W6^O;>w`FD3w8~{-Y)E1<9`s7f{*1|EY0(`zFK3dMjL|$7d zZ%k#}`Wj+)L-@{vw&q(oHC@s( zc!Mo;_)QqwKU>`@^}|vhpDeQQLPTw;>kCbpa8_Yx-z!4$b#e#*Gd5*1gXNPx7xwQR z<$+@D@AJa5_)3ObKKu#BbtV_TGf}0*%2iDGp1h}3WkB}bY5%6b5YlmslsHxWr$|}i z22EP-r92zf2qkoYqQp+uyL@fjFKim>;cn6dHb;8*ADfBrh(LUVypeakyd`8au|*7G zezYleiw3XQ5&eX}f_B0cu9F`HssGhx66ygg$FooOyx1QKAEKmM?-izg`1duudm0)w z-gfY#F4=@=6QwBg!y|sXrF^b?G8Xwi>aTodjGG=?eTLsB?_NeNQ(w|j%tWTVS9f|H zSrzC?%8@;}AZ;;M?NI8_=`^q2$txTDT=#7Mlc>Sk)88ms@yNf3W33h?jV?yLZxpVJ-lN{HP7~oBV2p8i@lL6{}q(=kE#PuQU&X< zyXD!CCuFwzE?$c1&KAR*pVCS z*}wWjm3#vzQ|aWhR0NH=zxok`9i88}k-ZLdzojO3VR!p^We@?6{-D`uys$@0*UTd_fAL<#!tDdRmtGLlp*HKJtV^v|oWHeU?phrR9PtgpB8i?h8 z{d4GN#gt75k?quPW#soSNBVUpP+g@*75m=t3yWbt%xgP)V zUWf_<@&Z`i4?H8!aQuHa7`}PQ^E3InxxPXW1Jp=$VLUD5$3mYX4_|J#^t?fHnA)e2 z(X!!gXv`K2zaX1Mwc_s84lTnDc{x(xtZjsiGic=Fr|{25W|sJJiu<7?dN0=UVxQ|L z1}TQ_P@06-m``kC9R=Fbu8r<@cQJ{J?B#PpoWknnvqP3| z$5-JkwY=;n)D7xySZ}Sef!49A&AHCb<0G2KpN5SbU1&^NwUJY-s?5wJ;Q@@-&2qKH z$NALeUc*gT)MsJgB*U5?Ev+$MlKiywWwH~6pz?Ao-&u{HLW`Vc`)aJD2^peu&)2ow z`aTNjkDC|S2Ay>A-wsF1&{srUsko%{UQ2yfczZXJpE&qvoDMDLQ91eKa8%{^>?4jj zvF@Xbx6cc&W*us2v1nUyy2NFh(u3?3=few1e&3#u*w-b(m1Q(T85En$@K~;mKq8Vp z0(@%<<$~$)1x=)2_K#lM8y0pOMeq$+HQ@yGjuquZ!!@5}ab+6&y`bIC1D3?kwo0CF z*9>xxrWMdjBgf{dJEsBT#=5VB1Gg%gFZE#|rGmW&v#GMS&u&eU+*4WMDc0m#M*Myy2jJThLlDoN-owhxmm^1b-huo?cwuw-iEyE6@)qt?yw zLbJiNjyu)`?{A=3hlmGBO4>Z|1mT1{mR~c<5#`t*eu#9Y8d(NT2hsu!sg?m=128u3 z{VbXY;9JO9-M|)s6nyP!UH8ya|1IG_O8^GQs0Kg?0a}Ycq-I? zpago#s`3t?>U8tKKPZUDpb;@*46Xdl*C(#L9E{rCexC0fR$1yod1wvMcyE?EX#ghS zR<-PdAAfq@SUeZhyAp66uNOOMAyH{iRgfx7E7)#+dN=AzDe!(O7?T(UYi~remux*Z z?uxFgtejc~znC~kB}X!3@!;D5gK)DoFk^BA$vX*9{{XodWW5QlCIl1|kn>_0C|ZDw zE<8iJ-9kNB>u>?I8tE`Y?R9LZrW--=V)oqxjDW?(8(z9)rgNi7Zx)?CW4x!8?}yeP zkEG>id>}D-cd#{b{8=kPfnhDm$t@_*FlyN3qG9?cTMe|BIi~ppKcDDyWG8uLE*;1T^ZP)E3NtJIm{-Qtutx^CQnDsgbUpOA6prYB_Y}|r z*p`>dZfQ-i@Sd1c?wVZf9al;lQ-S@%l1|}@f5+C~YipFb2CMo%4zB0D&TKwB1>Hk5 zzb1*7FPRaH%1MYH5J(|v5c)-qvSZ%8 zYXVE%*HcL88?e0P672`iztGC1$i-a?KjZJpNg^u>_EVa{XH;4dCCHtmx)M5&a@TH% z&dvPci**p5;JcHQ8rkyI5vM1d@WY2&4#%uLfA5tFiut|rLv0+A=@=ZG1}eNn&vZeY zjRyWiJCwlx5_5CgmA?gCqJr#ODQpjUN0ys;u^&M@ed3{8xvtBR>f6qhT3H{5RYUUc&v{awkadCxLA z9ux^)QuY|D1q-~6y?c>)Pyq;D(mC2_Nj57vEES^M1J_@pU)8`trv!?fn`=O11CrWZ zkbH%qu3FyUqyJS!X7&l}9F&~rJyp9>pl6~u0UPisOjJRFgq;G4xMYwVS^d1TE^cZb@6qNtpzJr`hOg! zgNiliCV|lJ{x5ER5t&Di-hpN<@Yql+W-8bKuK^qbhY4NRPn)8k*e@v=H_&EmY+MZb zL=jJN!$D?n%8kL{LWk7pn>v63AftW>dpk0z0Jpf(>rk84CrS=Q+~ z`9d7?Rn&yIq9XDI74{nu(WsT;`$*o`M(^Db2M$IG^vYjrpU2BFztYVajOEM3(84~4 zp+4w&Hg<0gtAR2V7ii}}>8k;@ub|Tl+A%0U78iXZA{^{K{!gA*W4zkEfEEJXu(uHO zKLWnvEm$Oh#5M{k6x0Z4cie^350HXQv@9Y0f2)V*S@b)2Fyl}qiswHFx5sf zm_V)%%nrb=s}1&DUv~ot-hvep(z^@nUe-Zm3A%n&wG^(q|^)l5{ zvhB++*O+J>1s{2gQ!ARfTi+BW7{~};PAwjOxjxjHXqay`QuvkQi2viR)VS1OAL?xBIGdDAtWtnL^u||Xm?2diMd-vo8@Tb z+1i-_YDUBWTEUYXMd=dYfw*o+^s>& zL2F3gI7r_%;Q#}zy0U8}vGo!L9)us2qPo`qlIbN=H!8TEMD+t}Z7t+C&{&%HFx0wO z*m;tzer~lE4Nha@956Pvq>=0SR;fa6MLq#Q%t)*cO9QgB2LP=`yC23w~ZJj-%akPfU|_t6RJq zGgk~=7ZmX{0lE^{U1lfqguq%(jI5p1y*H@=2P9Go=eiMxD z{xxX=aYCuX=3Chxo6QzjlRwtmpdxrKTKf_5J=S#B+ccLMR!Xt2nnkZz=`XJzdV)0% zG#O;>_isluuKdlmA45?3afack_f-zNXlc*d=(5s*nz(HhKW8=~rBsDPc1UNidF z$RbA^P3w5k$XvINL*^OM>++GnwARpfIh%3HjZQ!Ht%w;%_?7-ScdxI-$myM+M<}zU zD>JN>PAj#2A0XV`o?`*}o2^050k(SUz0%!%&6^4wHX%cxsRKccjC?67s^??&XqdJi zU|Nj;Mc(F$QTr=(%wzQ3a|`r0*Z8?xkQkq5)t~+Q8ioy))dZvh)KhgTvnHdC3ATjt zzp`HEwheiAakVq&uJd8#^6Fqh6b)OrvmWbZHP%~@$hKn7R8KHXSeyLS=fd+Ods(nS zBtKi(tKoD1-!GFB@_np2j*nP~TvcX?G)+i+Q6$X_RxdBOgyapvZnpe#7o!&O=yle2 z9N>F%ZC=N5?r+=l7gm1ip2c5E+D88Ff;?i(!NsagWd|{ATnXfu(#>Y*6^F~u&yGxT z#r#RJer*38+@RIQQ@AnIsnahY*Hz>GkZ?O)iLFB+urA0ms>7kuHTUpj?RQ}j|NXFX zxhWIESnZkbx|F0N4ABm{ejDVQ_g}o_Gb9M~?-LNTAR85nuDbokt>2c7Qk%{2@r{GT zXU}yOXU7LDynnLQ`KIidX%Y$%4jk;IyHyrAb2;hBUEhi_yB+tT?cf`QwvmAT0s$R! zaJ|iI6NPXyspjaSuUxvQ?pN^)*k9Kw(>{>AEse{E63im_*~i`(&*GWmyC^H>7WxWt zdAE%mHhE)-%V$Z8zoftK>#F`Hn$R}?VN=`aPwhmUgQ_I<&X1^4zw?*YwqKT-vrZSb zdK8Y>1PyKFWQW;=rxqTJi~~ZK_s+_x!WY|PpU5?_e7HY{>5n1F z*&M~N5LDTDb|FLgrdaLH<<=pK4BAG#R**7Gm(y`}oT_vlbUhtnP@AYYgv+M_9w&V?eMiYbS3_CWTX-{`h~ z2im)aGPG)QbCY`S8|psg--GThTIKRJc0JZxZgcS!^gZg z-b^2-3b>bKf!jzWcy_GxF8$fqZW#@^a-||T4YP(9#ILdvAdwV9LbvX+s zF|WWbBPGCTk7t(@ab^l7(6Q&}3;ZLBKQw^cyyv*9x$?>vRS6a1mn5H` zEuNGvuh`xa5c|Wy%jUV{GE&p{LE(i);)gy65yKn{lLReWr?I4}O%H>*VoB3&AH$Vp z3diTG1cXb6CX;1%T(n$D;yCFaW<`mJy~hkeI>D9V9sJ|c<;#`hR+n{-Jsh(aB>WppHVsMv9fv+C=duRhne}*QnQBXYEWrhutKlV*;f(l2R0$Ms8+jVZYLkJ@pG`3Ra@n-OY0&t+7|<@mHK9#r_2U@F}L{JmSEhAZr2daZ%WozWz4WGG*GVam@|J38`Ku2o%9)bR54$G#9)d zI*pSc1I6Cq&HlgQVSc3~i0adu<1~G%wXLkms~C< zn21f@#^UgKVZ%ZMu*kb-jg>jI^K@0`gt}IOwv@-jxO3(|wtt2cclQ>=xVJKx7GFFQ zYfmJWS|FK!>!2DNFvzAuxw(gP!+`|3mxtp!?}$Bl%qY2|NVAe->SFPOqJlaWUrB!4 zSK#dfQO%6GA0z>`qf!=A6v9NfUq}vgjkpuvI}Yl9FUGHlNZBe67?kw)=#sJ+azh@v zr-~X_sIyd>&MRK00+az?hz75m2Rr*F{Hy4m%LtU-!eyrw*vWnwq=>efv2#Q(^g_RX z_2aL(Se|crrnF^n79i>-;9^RrOAcEQ$~fcx>=B)-%5`XxOL4G)HlvLwFD-fY61Kp( zAmxcTQ%_~teewbs?6%@HH71)t`;*XjRdkxK`b+7t*sh$USI2YZ0}MH)obwLG{SUh0MyutmJZCPM$gUo34>og@M$BLAw)X>xd?? zRM@H{Y@{N>M~2VV5SPEzwArUH7Oi>%)wXDV-O|QW3J#QgPHR(XO1wVm!KtskzP*mA zs+Kkr^K&}rmyOZA1?%~q00qlUj|M$@MJJXx+li?mr0rfk$cF-+Jy7!=B*``f7%xF9`_KxBkPGn zCw!fo>z=<}e%(-~(4C=hY2q1$XK$`3!PQ1p`9+>n z<5C{?9n0yHKlyL^pa{cng73Qm_l{IvRvmC@{I%z}*Y3|*;)t+~JmM#>!^a7O_mg@* zw7II&Kx|sCT~3#t3R`w@Qhxn!Zhp|chZj7tlD{6r;(v&7%9txeb4rwS>2Y}NDK(H# zSn`;yvxFM=$Z07p9-lfCH!HL9TlMXwHRMy<={&=yu@UbXX8C^HcsVT^wCjES=jFZh z>P~SRObOW+Zzb(4M}#DT4xT+!TJwBExi%wn>KcSP;nDJ z`g(An5CIJhUL(>d13X6>!6SZ9XQuQew40GoexzhIXnsF? z&LAi_by{;TCIpBi%UfGLV2oS+`h@$5$icPT+!BkS^wZM?S}#WZ2UL*a6rJgK$~&P{ zQM_90y|?}+8a80-4vS*Bb=14#wg@(EMERIRzrV7PoR={FrCZ3WjFl*{N51p<-#?Mw zZr+bX5fJYDSPm!3NjH#1g<)K~}UU=V??)_QO%?6!YruGW=NR5Tf2Lx6+s26DoE zX6EL(IVvA`NNA5wR@hL0Yh7AyF4A5cDMkXM6RS6KNF^LD<97RlrAN>_L1FL2b%`5pTA76<}A+lD~4klN;%ztuy!bJMw<{l?d3i5bKqviP$w9? zG=V0HQx8?tp@(Q_I)JP(eVPm;R0*AglFOsOPzbF5;K6u+c@;@1D5b7W41WMzs`sEJ z4TL9}*ZU~YQon|@RRO?_rXN0%L9_A+XQk~_GVh3g+%sk{WXNXX z>PEX6t<m-(l2G}sbpQ$G%R~M9& zyqBeRzg9Zc3(mj!JKzC{1QkO+c^TZqlb1pxBW3c+&l@=t*@U?VQp8h&s6B$g^UuiG zSd}mUP-5Bx&u8>Ca&s@2^!2>2&K3^#_lvv&0=ucAZ46&O<3#kZcxaQqSNE|I+aOvR zXU}e|5N{EmZrR+JcpELHIf+=>eG})^{%F?w*h@?}?Ww9|*2hAu!U&6=`3a2T*JgO_ zkFG1=6Qom*o%N~!xPPY7ZViSe`3~RU#=+byCLuu{B1}ZN07&c8F)##xsuO5s@BjHj zf9H-5$nGFe(b#C>0Ke9BN|~%I3q8Tk&Z6yEN-%W1yg18Ct^}(tkbxrSk$C{-8q^%$ z|GYnRkdq6!c9&w^yO4ug`RE(#R=ZA|sRc)J$!y4joIKb$3AM~ewc>Rhtz?vU|=V23_)>hx)37`_DQkh znlhjf?c8x893sGaqzk;IfnS6G$+6Ut4FShhY#3&ge|`Wx%vd&U)IqRVM9v5R;`VLP z5>P4YPD0QuwLM7?N-mi8U@)Y>bs>lR#-zm5&3_vZM@Xb)@?1n* zL2j-QAZd{S4||pH1Hs~?$y8u(#dYmoE+v*T$#OohM)gh*G9mCwzUu(NCL@)s|TWOEp@D){w>PHuG=5N~6H< z-a)lQxDH<_1TJAAN=Vflq&-ly{*<04X-D-{l%y^9HK&Th!H32MtU#_-#;b({B0rTfBt?Pllzj<=y4q(~{rVNeA1qwarwq zHhAslEs%)fXxjcN*Gw&JGMG~D@DI$-B2|w^FP@nt!|)UibiRp9y-(+t{l2S@qhJnw zfU_4d{nIvWTf{NsiTtiPm++5CX3`pjlPz+Y9%H}w(OL=Fr}O0WYt=*JM`IG|iKnWm zWvQ-KcJo{0@X^1l66_YbLz{pF#fvJ%>^uzz2?oDzbrAQ$4IOzkwg-mWM_=G%kiP|M z?mBF~6AD7(`-qPgQ%0NZH%IOqB?u4mH~M84n*XPN=1A%^M*iC+&+qzUrV!`@%BV*!eAPs z`%SaI#V&H0_73zGS*K#UYpaJumeQqTJh9oSeTt~z*>X5?Z%)a=?tC7LW}vb&X;dFY zlqE?&<80&x1w%M)mN|=E898Q;)D7g54PpIuF|!x;u1I zrJ7J)CJ|Yu$kN!d?{i!jYP8L!e!xq>ZkgO3&!q#!omMG<&@3SSRV}_I30(R9d#1Ed+AVU z`r4hrFLWQVry@r~=p1M3UFM$MpO`zZ_C~uy7G)bwwAwc$|ln zHgnPhVpdAnKsDI~Mo+BSC~vZHU-@KK5qW9)JExaxS9h+CqrbqX%4tN+L_|K+3qlTy|Z=IIw+(1z!+b|6z?)Rv$ovvL1mO-n*<48 za|nmS*|2BGf{$zyD7w|#lWS`~lobe$1PUdppHw%9S4>md2ngF%`dLtE6ozvsNmAmR zZO`NS3(TiJL>-oA2pmWiX|N-40lf_%6*=q;2ou}6wMKbE$wcb3TUiaRiLa(o${;R&e%zLDAlC;T9Pk~ zv6}m>)UY)dj@_iM%-*lP@uwsymq|`uBsp3!#BKALgVf=L^OM5M&2?`$hZj%dPw)G% z+Z9_UW{krb@qg4?OwTH7{EfAHdE*hmf;(nd*Yw@WK^69p_~LPtBI*T)7T^qq!>NL+ zFSpE5ly3*FmbAIOKHzeBzVz2H??_8|jBVAE_Iqg*u171U_&cWy=GXl_#XL@iY`Gll ztH{jX4UoI|lI)1!XMp*2ECRu$n5N~+a*Yv2KZ$azV z{_}xHS3c*O@49SWp6ay_B^Jm#zY){iZ7&^hL~A(xmVsDuno$#~Ze4?E{7?DPcWca{ z6&rjNoe^Qu?@FL{Fofq$I6C6<3H>;t@ws2S^BcUh6`T0O>jFlmV|sYZn!b?Do?+jo zAk}dUxwCO6>}#bb)_=XvZ2s;VnjrXX&l=rxty%gPa|P`eZ?sgnq_0R$T>Zi^mFXgv zIxoKHj63_@a=XZBpXEY-Vkec=kU7?Q448W(k&~roh;ME+b*FYoeQoq|DehHHvA8z# zk|1d?!OZ3*-)JLip0qaEDay96bNgkPJ5T11H`)>rM9T)3^6xR;JS*VV#&@m_e+hi9c!F zvI1?oA>8!#+T5a)J-_GA?LEoTaj!-?!i7QLsaE^-J3A4_Tu)Vs!`uFzmA>`2_S6ywm^lLQyL(asN*M2X+UdP(ce7Y^RA|?eAZj$ZL>p|yNwO|Lg8DPg3HT`wu7S1O|8La za<}fwjs{mrSu&cKqV@J`9Fy;oyWqTlA7f+{)Zvds-#ntvL*P9xB^lsDlQlC!efEy< zV>bK4bUxMeY(0~m0I}bX+JFjEy^FHKR9Gac(s3qB02qw0oJ=w|H`W@nSgdT zjPHXaNhbCm;dLw@ofU?qa!aC$O5hznM*jLRK0(jnE6-F}(9vw=s~>r_bv3VJ-^uOn zcPsl~qtD!XL;s&EG<+;3zq2v5*LQxnWmlKW%_`r}w35U89;mGy6KnR8bv+m7(zm^x zSA0|7y0p#QGV_w|vyAJ+&#Q$K*ldOv89$A6bB5Iz>{~rPcEFlhke8W7+b@>%EPMWn zqw>xNU(OsShhGmqN_N;K-tI_G^F;j;GD<@+)Y8ZNf5Q<$7ylSe@k+u@v*y;BoeS-f z-ACX$ny=roHM+*&!Fq>n>ZHKky=O@Pie#n=6o)?me)7Bp##S)KbRo^`w*vc>LYx}~y%G}~!J)tG(kGgm>p?KTZ zMZvn_)q5oN4!8stdjBRR)IaOuxWN4A!X!wx`NjPm+nfyaj9p%wr=8R)qr*0_{z=jw zA1_nc+{DKVUQOFG&#^expNe{RZ3RffKO+sB5#|dBcwj~;0pE_Qfj9H^?;Q2w>wRL< zwpECi6Cgm7X@28^;@{tJqXD`@c3wbFIR-?b$b-U{%J2uFi>q->1-7SO;kaTo3xbsi zy(n}m3b2ZuZ>z$N=lY*gJwye($0Z7#MV-1;@0q2BXK!-)h6^ctJAcTVn|ELjTetX% z^rtV3_64ug?|U-e1Cq>2Z9;2#tA_;mC(OHIVzQ^ zbn`n01Na&v9278l`rCFFKskM1Uqz6S(e|E~`37i;b9ZVxcsS)3eVv_ske8Q7E6xxH zZ5%o1B_gK4JsTM{2FDpeRS`ImQy0e;+-vE9o(>KZ1TrG10!C+sKqLe(0~DZfstx#F zp&GvhqqArCLE9I!aYdAsDS)y^!Ci86bSr4DuC4h46YolJVM@v|&{1wwLKz$PILrh8 zMk_MAM~s!@&$Ge~w-)z;7J4pCSc(CbG8y9jfq}a&qj^jY?M*Xsfj+|Tkw7>Ejgf(L zaA#fsS1m&Tv)miE6whWBzgb5#y8+XvT4>l<10o%uNEkX$jW{x9@+y;_r2zh9YHQp1 zd!~gt zcXl(ep+Ttz^rP1S+szN&Ua4%91>z={p@T0k6Ie0If%?(rjB#kqKR8r#^o0~?DE#?r z=MD!vMc!R0wuXwpr3A3*Qe#MPv=g|i86+#*2RA_=BjQ}K-Gc=-0rZ(1eGs3?gbiyZ z*=y;GKJdz$0AwNt7hs5kXwT0&Kui9$QW)Iag>*JHZqtgs)95xa>oTG1Q9cFlyRLRU zgsdRp zJ+Gk8oT*1H91OuSgK}^T{2uo@%=D_QjVTPqerb96sH*ReQyW0p+{MAevlbN$N>&AP zafHmi8ESzg&|(C2`b_?B2nA5Sy{~|b#>CVS{siP~z_<_vAUY=}C(`33)37E4@wgWO zHUVFe_4uR#UARgB^CF*sNR{Zxll#K}rHca~w8*~R!^`UmxTzx;hWh3tJEt!aj?TIN zZxp0=)H0{9m@ps-?;HTKh^jvVeGl0Ob&a+`zbR0fm)~EIaa2sXK0xIT-I{X<0IB}D zZ-%T$oNC6+E4jsexCzRAB>XMjmR$t+SFOl!o!7{K3MOOzei=#lK@sTQgyXH^(2!Q) zg1f|m;xK!MWM0Q%frz9P`DTi~FrOlmoru1f0^(DQKwB$cJO`gJF9w0j>gUNx#=nBY z-BLzwh^eX`gP!0+y2Ue>pf4B>{0gDw)swkTW48C@IV|tt7kbU_`R1NcB|*vuDj3gt zFIlj*cfNCdk5?d(NW+0V168%Pr&B^Zqi^?TI>rVnoHQecXH^eO(f@qsQxXRAB#EOd znFNM099l@zNiqY_rfuBo?-}Kk(oFWi!Ds*TnMrg|pp<5W}DRzWf4(QGyNodaVMTBnfz*G$ccfp{yLUmy7 z>ug}1WKz zgh4eH78c2;>1x5&u%-Q2c0G>Ti|^0RKS`u;OIhTqq!|s&(fk(q71ex9<5EDajS6Pw zn9(e;^1Qh~Tc9v3ynqoIY%?Q|4p?Hro-j}HK?ZO1SsX44RcV$;8-_EE7TT%OTJCd6 zK7}M?p*k2pD=4q6cvXRS{d1HI^jC-blv)Cw524`?F4bV#IaQRN3BD9yBPk>#1g{2? zRv6jY*&!i2&JUHk7(;FuuJtP_H--VCif)5j2T+xjZms?Lcq=9PyxqW;%7@AQ<`f!` za{U7WtOPD#3DlxM5DZ%a`|04ueV9|^%B7xN-Wg2${&uCfU0#gvK7HAk>7_k?c8LAJBH zxLp8x>yKMnbP(wRAa8ZrX<1_oCFt_L4g6i6%drzq+_gwHH#$YqO)ih@wr!jYcd=d+Hr z#@~}GVZDLN?9By{g24(1v~##ax&wsrK^ct!yaEAU9`^w0yG>73R8{jFf@zN-_G+%S zKe8Tr4hbRmLZUQ89c}`gmCNDhftVwQ4^zW<1q4E;-CrK0b|ioJVL=RkE;cZrhXuY$ zf6zj`Wg5J21i7StF4$p0V92h{-*j((eb6eEDoI-a05rX=s%@_ig1N9w}LP-cL9~MF6uLK^X!x;*d3T_n)VD)^@zGxZ< z>Vs1os|$KXLwyi9L<$sVj%GqJTQ!&_3pv?Sxyk0 zOa(CD;%W)tDW=-$@0+^d+Ls-z0+nQpy!^$k_V(fs zyA!mkXN7acp*tZyy&1ZH|F?vM>^E&~d9Vn;0Vln{!rVL;hNa3Xc(bm?ia;Pl=d~wW zV@39lyn-5$xds*p+(j!}>*`-1=lFd2E0#*3PzdhsMd2h;E+pGxd%4h$@Ny1-6d)Bu zA*m@TDInNjUY?tqYfS`y-H;TET(GO- zIb4bb_7JZAx=%8)7SNFwCWa#udT%}exc|(V(7yWL=Gy=L0G(2JsNosn;t#-?yPu!3 zK(9W7#V)MbYDLlokrRc%@RY)WNmb1lm_tCrUrb{M13-6V>9OY%coJ1suJTh(96!#$ z&Q7jH3km831E5L5%Yk;Dj)n#U>k;X)ius8~0VXCUm=Wl;-5AIrZ^!~Yz}p8+i#E`0 zgJCwo;ac;G8Xkad62t;1iT-wLJRqopEiI)n0G-YaEM~6FywCbmKt0{DIlLD#I4bCe zEXb=J1zy5RZO;+VC^&bHS$%s=IB4aEBg{XbSMm;cW-AL5JycvC;!3U^!6vGpP{uYM z%aNh>S0^-^>mS7s4#BqR3fQwlwe1*4o{R@fr;VvV6d$47T4I6O_!=UI;yRW9@Rjo)d zr&nQ&<`xzfL{@P6sH$4?qY%Lc2s4UoQ!-DTIyLV{v0;YwArg8|{T9Y`bajj24^ +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +class ArTagBasedLocalizer : public rclcpp::Node +{ +public: + ArTagBasedLocalizer(); + bool setup(); + +private: + void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg); + void cam_info_callback(const sensor_msgs::msg::CameraInfo & msg); + void publish_pose_as_base_link(const geometry_msgs::msg::PoseStamped & msg); + + // Parameters + float marker_size_{}; + std::vector target_tag_ids_; + std::vector covariance_; + double distance_threshold_squared_{}; + std::string camera_frame_; + + // tf + std::unique_ptr tf_buffer_; + std::unique_ptr tf_listener_; + std::unique_ptr tf_broadcaster_; + + // image transport + std::unique_ptr it_; + + // Subscribers + image_transport::Subscriber image_sub_; + rclcpp::Subscription::SharedPtr cam_info_sub_; + + // Publishers + image_transport::Publisher image_pub_; + rclcpp::Publisher::SharedPtr pose_pub_; + + // Others + aruco::MarkerDetector detector_; + aruco::CameraParameters cam_param_; + bool cam_info_received_; +}; + +#endif // AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ diff --git a/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/tag_tf_caster_core.hpp b/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/tag_tf_caster_core.hpp new file mode 100644 index 0000000000000..5b10fe5b1dc0f --- /dev/null +++ b/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/tag_tf_caster_core.hpp @@ -0,0 +1,49 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AR_TAG_BASED_LOCALIZER__TAG_TF_CASTER_CORE_HPP_ +#define AR_TAG_BASED_LOCALIZER__TAG_TF_CASTER_CORE_HPP_ + +#include + +#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" +#include + +#include +#include +#include + +#include + +class TagTfCaster : public rclcpp::Node +{ +public: + TagTfCaster(); + +private: + void map_bin_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg); + void publish_tf(const lanelet::Polygon3d & poly); + + // Parameters + double volume_threshold_; + + // tf + std::unique_ptr tf_buffer_; + std::unique_ptr tf_broadcaster_; + + // Subscribers + rclcpp::Subscription::SharedPtr map_bin_sub_; +}; + +#endif // AR_TAG_BASED_LOCALIZER__TAG_TF_CASTER_CORE_HPP_ diff --git a/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/utils.hpp b/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/utils.hpp new file mode 100644 index 0000000000000..06401dad8fdd1 --- /dev/null +++ b/localization/ar_tag_based_localizer/include/ar_tag_based_localizer/utils.hpp @@ -0,0 +1,66 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// This source code is derived from the https://github.com/pal-robotics/aruco_ros. +// Here is the license statement. +/***************************** + Copyright 2011 Rafael Muñoz Salinas. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, are + permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this list of + conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, this list + of conditions and the following disclaimer in the documentation and/or other materials + provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED + WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + The views and conclusions contained in the software and documentation are those of the + authors and should not be interpreted as representing official policies, either expressed + or implied, of Rafael Muñoz Salinas. + ********************************/ + +#ifndef AR_TAG_BASED_LOCALIZER__UTILS_HPP_ +#define AR_TAG_BASED_LOCALIZER__UTILS_HPP_ + +#include + +#include +#include + +/** + * @brief ros_camera_info_to_aruco_cam_params gets the camera intrinsics from a CameraInfo message + * and copies them to aruco's data structure + * @param cam_info + * @param use_rectified_parameters if true, the intrinsics are taken from cam_info.P and the + * distortion parameters are set to 0. Otherwise, cam_info.K and cam_info.D are taken. + * @return + */ +aruco::CameraParameters ros_camera_info_to_aruco_cam_params( + const sensor_msgs::msg::CameraInfo & cam_info, bool use_rectified_parameters); + +tf2::Transform aruco_marker_to_tf2(const aruco::Marker & marker); + +#endif // AR_TAG_BASED_LOCALIZER__UTILS_HPP_ diff --git a/localization/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml b/localization/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml new file mode 100644 index 0000000000000..940f6ed53d8b8 --- /dev/null +++ b/localization/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/localization/ar_tag_based_localizer/launch/tag_tf_caster.launch.xml b/localization/ar_tag_based_localizer/launch/tag_tf_caster.launch.xml new file mode 100644 index 0000000000000..6a9c3dcd17e2e --- /dev/null +++ b/localization/ar_tag_based_localizer/launch/tag_tf_caster.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/localization/ar_tag_based_localizer/package.xml b/localization/ar_tag_based_localizer/package.xml new file mode 100644 index 0000000000000..4527d2ad9b086 --- /dev/null +++ b/localization/ar_tag_based_localizer/package.xml @@ -0,0 +1,30 @@ + + + + ar_tag_based_localizer + 0.0.0 + The ar_tag_based_localizer package + Shintaro Sakoda + Masahiro Sakamoto + Apache License 2.0 + + ament_cmake + autoware_cmake + + aruco + autoware_auto_mapping_msgs + cv_bridge + geometry_msgs + image_transport + lanelet2_extension + rclcpp + sensor_msgs + tf2_eigen + tf2_geometry_msgs + tf2_ros + visualization_msgs + + + ament_cmake + + diff --git a/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp b/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp new file mode 100644 index 0000000000000..ca3bfe2e4a6b0 --- /dev/null +++ b/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp @@ -0,0 +1,272 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// This source code is derived from the https://github.com/pal-robotics/aruco_ros. +// Here is the license statement. +/***************************** + Copyright 2011 Rafael Muñoz Salinas. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, are + permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this list of + conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, this list + of conditions and the following disclaimer in the documentation and/or other materials + provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED + WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + The views and conclusions contained in the software and documentation are those of the + authors and should not be interpreted as representing official policies, either expressed + or implied, of Rafael Muñoz Salinas. + ********************************/ + +#include "ar_tag_based_localizer/ar_tag_based_localizer_core.hpp" + +#include "ar_tag_based_localizer/utils.hpp" + +#include +#include + +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +ArTagBasedLocalizer::ArTagBasedLocalizer() +: Node("ar_tag_based_localizer"), cam_info_received_(false) +{ +} + +bool ArTagBasedLocalizer::setup() +{ + /* + Declare node parameters + */ + marker_size_ = static_cast(this->declare_parameter("marker_size")); + target_tag_ids_ = this->declare_parameter>("target_tag_ids"); + covariance_ = this->declare_parameter>("covariance"); + distance_threshold_squared_ = std::pow(this->declare_parameter("distance_threshold"), 2); + camera_frame_ = this->declare_parameter("camera_frame"); + std::string detection_mode = this->declare_parameter("detection_mode"); + float min_marker_size = static_cast(this->declare_parameter("min_marker_size")); + if (detection_mode == "DM_NORMAL") { + detector_.setDetectionMode(aruco::DM_NORMAL, min_marker_size); + } else if (detection_mode == "DM_FAST") { + detector_.setDetectionMode(aruco::DM_FAST, min_marker_size); + } else if (detection_mode == "DM_VIDEO_FAST") { + detector_.setDetectionMode(aruco::DM_VIDEO_FAST, min_marker_size); + } else { + // Error + RCLCPP_ERROR_STREAM(this->get_logger(), "Invalid detection_mode: " << detection_mode); + return false; + } + + /* + Log parameter info + */ + RCLCPP_INFO_STREAM(this->get_logger(), "min_marker_size: " << min_marker_size); + RCLCPP_INFO_STREAM(this->get_logger(), "detection_mode: " << detection_mode); + RCLCPP_INFO_STREAM(this->get_logger(), "thresMethod: " << detector_.getParameters().thresMethod); + RCLCPP_INFO_STREAM(this->get_logger(), "marker_size_: " << marker_size_); + + /* + tf + */ + tf_buffer_ = std::make_unique(this->get_clock()); + tf_listener_ = std::make_unique(*tf_buffer_); + tf_broadcaster_ = std::make_unique(this); + + /* + Initialize image transport + */ + it_ = std::make_unique(shared_from_this()); + + /* + Subscribers + */ + image_sub_ = it_->subscribe("~/input/image", 1, &ArTagBasedLocalizer::image_callback, this); + cam_info_sub_ = this->create_subscription( + "~/input/camera_info", 1, + std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1)); + + /* + Publishers + */ + auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); + qos.reliable(); + qos.transient_local(); + image_pub_ = it_->advertise("~/debug/result", 1); + pose_pub_ = this->create_publisher( + "~/output/pose_with_covariance", qos); + + RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!"); + return true; +} + +void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) +{ + if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { + RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); + return; + } + + if (!cam_info_received_) { + RCLCPP_DEBUG(this->get_logger(), "No cam_info has been received."); + return; + } + + builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; + cv_bridge::CvImagePtr cv_ptr; + try { + cv_ptr = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::RGB8); + } catch (cv_bridge::Exception & e) { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); + return; + } + + cv::Mat in_image = cv_ptr->image; + + // detection results will go into "markers" + std::vector markers; + + // ok, let's detect + detector_.detect(in_image, markers, cam_param_, marker_size_, false); + + // for each marker, draw info and its boundaries in the image + for (const aruco::Marker & marker : markers) { + tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); + + geometry_msgs::msg::TransformStamped tf_cam_to_marker_stamped; + tf2::toMsg(tf_cam_to_marker, tf_cam_to_marker_stamped.transform); + tf_cam_to_marker_stamped.header.stamp = curr_stamp; + tf_cam_to_marker_stamped.header.frame_id = camera_frame_; + tf_cam_to_marker_stamped.child_frame_id = "detected_marker_" + std::to_string(marker.id); + tf_broadcaster_->sendTransform(tf_cam_to_marker_stamped); + + geometry_msgs::msg::PoseStamped pose_cam_to_marker; + tf2::toMsg(tf_cam_to_marker, pose_cam_to_marker.pose); + pose_cam_to_marker.header.stamp = curr_stamp; + pose_cam_to_marker.header.frame_id = std::to_string(marker.id); + publish_pose_as_base_link(pose_cam_to_marker); + + // drawing the detected markers + marker.draw(in_image, cv::Scalar(0, 0, 255), 2); + } + + // draw a 3d cube in each marker if there is 3d info + if (cam_param_.isValid()) { + for (aruco::Marker & marker : markers) { + aruco::CvDrawingUtils::draw3dAxis(in_image, marker, cam_param_); + } + } + + if (image_pub_.getNumSubscribers() > 0) { + // show input with augmented information + cv_bridge::CvImage out_msg; + out_msg.header.stamp = curr_stamp; + out_msg.encoding = sensor_msgs::image_encodings::RGB8; + out_msg.image = in_image; + image_pub_.publish(out_msg.toImageMsg()); + } +} + +// wait for one camera info, then shut down that subscriber +void ArTagBasedLocalizer::cam_info_callback(const sensor_msgs::msg::CameraInfo & msg) +{ + if (cam_info_received_) { + return; + } + + cam_param_ = ros_camera_info_to_aruco_cam_params(msg, true); + cam_info_received_ = true; +} + +void ArTagBasedLocalizer::publish_pose_as_base_link(const geometry_msgs::msg::PoseStamped & msg) +{ + // Check if frame_id is in target_tag_ids + if ( + std::find(target_tag_ids_.begin(), target_tag_ids_.end(), msg.header.frame_id) == + target_tag_ids_.end()) { + RCLCPP_INFO_STREAM( + this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in target_tag_ids"); + return; + } + + // Range filter + const double distance_squared = msg.pose.position.x * msg.pose.position.x + + msg.pose.position.y * msg.pose.position.y + + msg.pose.position.z * msg.pose.position.z; + if (distance_threshold_squared_ < distance_squared) { + return; + } + + // Transform map to tag + geometry_msgs::msg::TransformStamped map_to_tag_tf; + try { + map_to_tag_tf = + tf_buffer_->lookupTransform("map", "tag_" + msg.header.frame_id, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_INFO( + this->get_logger(), "Could not transform map to tag_%s: %s", msg.header.frame_id.c_str(), + ex.what()); + return; + } + + // Transform camera to base_link + geometry_msgs::msg::TransformStamped camera_to_base_link_tf; + try { + camera_to_base_link_tf = + tf_buffer_->lookupTransform(camera_frame_, "base_link", tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what()); + return; + } + + // Convert ROS Transforms to Eigen matrices for easy matrix multiplication and inversion + Eigen::Affine3d map_to_tag = tf2::transformToEigen(map_to_tag_tf.transform); + Eigen::Affine3d camera_to_base_link = tf2::transformToEigen(camera_to_base_link_tf.transform); + Eigen::Affine3d camera_to_tag = Eigen::Affine3d( + Eigen::Translation3d(msg.pose.position.x, msg.pose.position.y, msg.pose.position.z) * + Eigen::Quaterniond( + msg.pose.orientation.w, msg.pose.orientation.x, msg.pose.orientation.y, + msg.pose.orientation.z)); + Eigen::Affine3d tag_to_camera = camera_to_tag.inverse(); + + // Final pose calculation + Eigen::Affine3d map_to_base_link = map_to_tag * tag_to_camera * camera_to_base_link; + + // Construct output message + geometry_msgs::msg::PoseWithCovarianceStamped pose_with_covariance_stamped; + pose_with_covariance_stamped.header.stamp = msg.header.stamp; + pose_with_covariance_stamped.header.frame_id = "map"; + pose_with_covariance_stamped.pose.pose = tf2::toMsg(map_to_base_link); + std::copy( + covariance_.begin(), covariance_.end(), pose_with_covariance_stamped.pose.covariance.begin()); + + pose_pub_->publish(pose_with_covariance_stamped); +} diff --git a/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp b/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp new file mode 100644 index 0000000000000..92d2e35ee3c1b --- /dev/null +++ b/localization/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp @@ -0,0 +1,54 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// This source code is derived from the https://github.com/pal-robotics/aruco_ros. +// Here is the license statement. +/***************************** + Copyright 2011 Rafael Muñoz Salinas. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, are + permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this list of + conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, this list + of conditions and the following disclaimer in the documentation and/or other materials + provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED + WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + The views and conclusions contained in the software and documentation are those of the + authors and should not be interpreted as representing official policies, either expressed + or implied, of Rafael Muñoz Salinas. + ********************************/ + +#include "ar_tag_based_localizer/ar_tag_based_localizer_core.hpp" + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + std::shared_ptr ptr = std::make_shared(); + ptr->setup(); + rclcpp::spin(ptr); + rclcpp::shutdown(); +} diff --git a/localization/ar_tag_based_localizer/src/tag_tf_caster_core.cpp b/localization/ar_tag_based_localizer/src/tag_tf_caster_core.cpp new file mode 100644 index 0000000000000..d0279caf88dda --- /dev/null +++ b/localization/ar_tag_based_localizer/src/tag_tf_caster_core.cpp @@ -0,0 +1,125 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ar_tag_based_localizer/tag_tf_caster_core.hpp" + +#include "lanelet2_extension/utility/message_conversion.hpp" + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +TagTfCaster::TagTfCaster() : Node("tag_tf_caster") +{ + // Parameters + volume_threshold_ = this->declare_parameter("volume_threshold", 1e-5); + + // tf + tf_buffer_ = std::make_unique(this->get_clock()); + tf_broadcaster_ = std::make_unique(this); + + // Subscribers + map_bin_sub_ = this->create_subscription( + "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), + std::bind(&TagTfCaster::map_bin_callback, this, std::placeholders::_1)); + RCLCPP_INFO(this->get_logger(), "finish setup"); +} + +void TagTfCaster::map_bin_callback( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg) +{ + RCLCPP_INFO_STREAM(this->get_logger(), "msg->format_version: " << msg->format_version); + RCLCPP_INFO_STREAM(this->get_logger(), "msg->map_format: " << msg->map_format); + RCLCPP_INFO_STREAM(this->get_logger(), "msg->map_version: " << msg->map_version); + RCLCPP_INFO_STREAM(this->get_logger(), "msg->data.size(): " << msg->data.size()); + lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; + lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); + for (const auto & poly : lanelet_map_ptr->polygonLayer) { + const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; + if (type != "pose_marker") { + continue; + } + publish_tf(poly); + } +} + +void TagTfCaster::publish_tf(const lanelet::Polygon3d & poly) +{ + // Get marker_id + const std::string marker_id = poly.attributeOr("marker_id", "none"); + + // Get 4 vertices + const auto & vertices = poly.basicPolygon(); + if (vertices.size() != 4) { + RCLCPP_WARN_STREAM(this->get_logger(), "vertices.size() (" << vertices.size() << ") != 4"); + return; + } + + // 4 vertices represent the marker vertices in counterclockwise order + // Calculate the volume by considering it as a tetrahedron + const auto & v0 = vertices[0]; + const auto & v1 = vertices[1]; + const auto & v2 = vertices[2]; + const auto & v3 = vertices[3]; + const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0; + RCLCPP_INFO_STREAM(this->get_logger(), "volume = " << volume); + if (volume > volume_threshold_) { + RCLCPP_WARN_STREAM( + this->get_logger(), + "volume (" << volume << ") > threshold (" << volume_threshold_ << "), This is not plane."); + return; + } + + // Calculate the center of the quadrilateral + const auto center = (v0 + v1 + v2 + v3) / 4.0; + + // Define axes + const auto x_axis = (v1 - v0).normalized(); + const auto y_axis = (v2 - v1).normalized(); + const auto z_axis = x_axis.cross(y_axis).normalized(); + + // Construct rotation matrix and convert it to quaternion + Eigen::Matrix3d rotation_matrix; + rotation_matrix << x_axis, y_axis, z_axis; + const Eigen::Quaterniond q{rotation_matrix}; + + // Create transform + geometry_msgs::msg::TransformStamped tf; + tf.header.stamp = this->now(); + tf.header.frame_id = "map"; + tf.child_frame_id = "tag_" + marker_id; + tf.transform.translation.x = center.x(); + tf.transform.translation.y = center.y(); + tf.transform.translation.z = center.z(); + tf.transform.rotation.x = q.x(); + tf.transform.rotation.y = q.y(); + tf.transform.rotation.z = q.z(); + tf.transform.rotation.w = q.w(); + + // Publish transform + tf_broadcaster_->sendTransform(tf); + RCLCPP_INFO_STREAM(this->get_logger(), "id: " << marker_id); + RCLCPP_INFO_STREAM( + this->get_logger(), "(x, y, z) = " << tf.transform.translation.x << ", " + << tf.transform.translation.y << ", " + << tf.transform.translation.z); + RCLCPP_INFO_STREAM( + this->get_logger(), "q = " << tf.transform.rotation.x << ", " << tf.transform.rotation.y << ", " + << tf.transform.rotation.z << ", " << tf.transform.rotation.w); +} diff --git a/localization/ar_tag_based_localizer/src/tag_tf_caster_node.cpp b/localization/ar_tag_based_localizer/src/tag_tf_caster_node.cpp new file mode 100644 index 0000000000000..ce83c572d6a6e --- /dev/null +++ b/localization/ar_tag_based_localizer/src/tag_tf_caster_node.cpp @@ -0,0 +1,22 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ar_tag_based_localizer/tag_tf_caster_core.hpp" + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); +} diff --git a/localization/ar_tag_based_localizer/src/utils.cpp b/localization/ar_tag_based_localizer/src/utils.cpp new file mode 100644 index 0000000000000..9f582830280d9 --- /dev/null +++ b/localization/ar_tag_based_localizer/src/utils.cpp @@ -0,0 +1,116 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// This source code is derived from the https://github.com/pal-robotics/aruco_ros. +// Here is the license statement. +/***************************** + Copyright 2011 Rafael Muñoz Salinas. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, are + permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this list of + conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, this list + of conditions and the following disclaimer in the documentation and/or other materials + provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED + WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + The views and conclusions contained in the software and documentation are those of the + authors and should not be interpreted as representing official policies, either expressed + or implied, of Rafael Muñoz Salinas. + ********************************/ + +#include "ar_tag_based_localizer/utils.hpp" + +#include +#include + +aruco::CameraParameters ros_camera_info_to_aruco_cam_params( + const sensor_msgs::msg::CameraInfo & cam_info, bool use_rectified_parameters) +{ + cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0); + cv::Mat distortion_coeff(4, 1, CV_64FC1); + cv::Size size(static_cast(cam_info.width), static_cast(cam_info.height)); + + if (use_rectified_parameters) { + camera_matrix.setTo(0); + camera_matrix.at(0, 0) = cam_info.p[0]; + camera_matrix.at(0, 1) = cam_info.p[1]; + camera_matrix.at(0, 2) = cam_info.p[2]; + camera_matrix.at(0, 3) = cam_info.p[3]; + camera_matrix.at(1, 0) = cam_info.p[4]; + camera_matrix.at(1, 1) = cam_info.p[5]; + camera_matrix.at(1, 2) = cam_info.p[6]; + camera_matrix.at(1, 3) = cam_info.p[7]; + camera_matrix.at(2, 0) = cam_info.p[8]; + camera_matrix.at(2, 1) = cam_info.p[9]; + camera_matrix.at(2, 2) = cam_info.p[10]; + camera_matrix.at(2, 3) = cam_info.p[11]; + + for (int i = 0; i < 4; ++i) { + distortion_coeff.at(i, 0) = 0; + } + } else { + cv::Mat camera_matrix_from_k(3, 3, CV_64FC1, 0.0); + for (int i = 0; i < 9; ++i) { + camera_matrix_from_k.at(i % 3, i - (i % 3) * 3) = cam_info.k[i]; + } + camera_matrix_from_k.copyTo(camera_matrix(cv::Rect(0, 0, 3, 3))); + + if (cam_info.d.size() == 4) { + for (int i = 0; i < 4; ++i) { + distortion_coeff.at(i, 0) = cam_info.d[i]; + } + } else { + RCLCPP_WARN( + rclcpp::get_logger("ar_tag_based_localizer"), + "length of camera_info D vector is not 4, assuming zero distortion..."); + for (int i = 0; i < 4; ++i) { + distortion_coeff.at(i, 0) = 0; + } + } + } + + return {camera_matrix, distortion_coeff, size}; +} + +tf2::Transform aruco_marker_to_tf2(const aruco::Marker & marker) +{ + cv::Mat rot(3, 3, CV_64FC1); + cv::Mat r_vec64; + marker.Rvec.convertTo(r_vec64, CV_64FC1); + cv::Rodrigues(r_vec64, rot); + cv::Mat tran64; + marker.Tvec.convertTo(tran64, CV_64FC1); + + tf2::Matrix3x3 tf_rot( + rot.at(0, 0), rot.at(0, 1), rot.at(0, 2), rot.at(1, 0), + rot.at(1, 1), rot.at(1, 2), rot.at(2, 0), rot.at(2, 1), + rot.at(2, 2)); + + tf2::Vector3 tf_orig(tran64.at(0, 0), tran64.at(1, 0), tran64.at(2, 0)); + + return tf2::Transform(tf_rot, tf_orig); +} From d82c81064e745960885ef83bf1e985d0c12914d1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 7 Aug 2023 17:43:46 +0900 Subject: [PATCH 111/266] fix(planner_manager): don't skip waiting approval module (#4542) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/planner_manager.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 4b5d36c56f268..6558bd7110f10 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -49,15 +49,18 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da manager_ptrs_.begin(), manager_ptrs_.end(), [&data](const auto & m) { m->setData(data); }); auto result_output = [&]() { - const bool is_any_approved_module_running = std::any_of( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), - [](const auto & m) { return m->getCurrentStatus() == ModuleStatus::RUNNING; }); + const bool is_any_approved_module_running = + std::any_of(approved_module_ptrs_.begin(), approved_module_ptrs_.end(), [](const auto & m) { + return m->getCurrentStatus() == ModuleStatus::RUNNING || + m->getCurrentStatus() == ModuleStatus::WAITING_APPROVAL; + }); // IDLE is a state in which an execution has been requested but not yet approved. // once approved, it basically turns to running. const bool is_any_candidate_module_running_or_idle = std::any_of(candidate_module_ptrs_.begin(), candidate_module_ptrs_.end(), [](const auto & m) { return m->getCurrentStatus() == ModuleStatus::RUNNING || + m->getCurrentStatus() == ModuleStatus::WAITING_APPROVAL || m->getCurrentStatus() == ModuleStatus::IDLE; }); From 135addc7ecbe325dbbf39221a464d72afe19591a Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 7 Aug 2023 18:38:47 +0900 Subject: [PATCH 112/266] fix(accel_brake_map_calibrator_button_panel): fix calibration service name (#4539) * fix(accel_brake_map_calibrator_button_panel): fix calibration service name Signed-off-by: tomoya.kimura * misc Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- ...ccel_brake_map_calibrator_button_panel.cpp | 43 ++++++++++--------- 1 file changed, 23 insertions(+), 20 deletions(-) diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp index 545bdac7b630d..5c1c98488b0f6 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( - "/accel_brake_map_calibrator/update_map_dir"); + "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); } void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( @@ -118,25 +118,28 @@ void AccelBrakeMapCalibratorButtonPanel::pushCalibrationButton() status_label_->setText("executing calibration..."); std::thread thread([this] { - auto req = std::make_shared(); - req->path = ""; - - client_->async_send_request( - req, - [this]( - [[maybe_unused]] rclcpp::Client::SharedFuture - result) { - status_label_->setStyleSheet("QLabel { background-color : lightgreen;}"); - status_label_->setText("OK!!!"); - - // wait 3 second - after_calib_ = true; - rclcpp::Rate(3.0).sleep(); - after_calib_ = false; - - // unlock button - calibration_button_->setEnabled(true); - }); + if (!client_->wait_for_service(std::chrono::seconds(1))) { + status_label_->setStyleSheet("QLabel { background-color : red;}"); + status_label_->setText("service server not found"); + + } else { + auto req = std::make_shared(); + req->path = ""; + client_->async_send_request( + req, [this]([[maybe_unused]] rclcpp::Client< + tier4_vehicle_msgs::srv::UpdateAccelBrakeMap>::SharedFuture result) {}); + + status_label_->setStyleSheet("QLabel { background-color : lightgreen;}"); + status_label_->setText("OK!!!"); + } + + // wait 3 second + after_calib_ = true; + rclcpp::Rate(1.0 / 3.0).sleep(); + after_calib_ = false; + + // unlock button + calibration_button_->setEnabled(true); }); thread.detach(); From 48129f1ee7985a20ddfa8d41b6549e007ebc6ff9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 7 Aug 2023 18:39:31 +0900 Subject: [PATCH 113/266] feat(avoidance): prevent smoother undershoot (#4541) feat(avoidance): prevent smoother under shoot Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 6dff21d26dee7..601badee6a9f9 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -2997,6 +2997,15 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed; // insert slow down speed. + const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk( + shift_length, helper_.getLateralMinJerkLimit(), distance_to_object); + if (current_target_velocity < getEgoSpeed() && decel_distance < remaining_distance) { + utils::avoidance::insertDecelPoint( + getEgoPosition(), decel_distance, parameters_->velocity_map.front(), shifted_path.path, + slow_pose_); + return; + } + const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { const auto distance_from_ego = calcSignedArcLength(shifted_path.path.points, start_idx, i); From eba0e278e60e97e6ec3ddbd76fcb650ee9317f52 Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Mon, 7 Aug 2023 12:57:37 +0300 Subject: [PATCH 114/266] refactor(detected_object_validation): add an option for filtering and validation (#4402) * init commit Signed-off-by: ismetatabay * update occupancy_grid_map path Signed-off-by: ismetatabay * update argument names Signed-off-by: ismetatabay * correct radar launch objects_filter_method name Signed-off-by: ismetatabay * remove radar option Signed-off-by: ismetatabay --------- Signed-off-by: ismetatabay --- ...ra_lidar_fusion_based_detection.launch.xml | 19 +++++++++++++++++-- .../lidar_based_detection.launch.xml | 19 +++++++++++++++++-- ...robabilistic_occupancy_grid_map.launch.xml | 4 ++++ .../launch/perception.launch.xml | 2 ++ .../detected_object_validation/CMakeLists.txt | 5 +++++ .../occupancy_grid_based_validator.launch.xml | 11 +++++------ ...serscan_based_occupancy_grid_map.launch.py | 2 ++ 7 files changed, 52 insertions(+), 10 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 2d983dc47545c..24b8a75506d2f 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -225,7 +225,7 @@ - + @@ -235,6 +235,13 @@ + + + + + + + @@ -262,11 +269,19 @@ - + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index bfb30e860f070..73d256a802340 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -105,7 +105,7 @@ - + @@ -115,6 +115,13 @@ + + + + + + + @@ -141,11 +148,19 @@ - + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml index 0f2712a03247e..751eeea66c7b6 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml @@ -12,6 +12,8 @@ + + @@ -42,6 +44,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 11630405a6336..6634c36ff3768 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -68,6 +68,8 @@ /> + + diff --git a/perception/detected_object_validation/CMakeLists.txt b/perception/detected_object_validation/CMakeLists.txt index d4fca5c61295e..f882c6dd165fe 100644 --- a/perception/detected_object_validation/CMakeLists.txt +++ b/perception/detected_object_validation/CMakeLists.txt @@ -80,6 +80,11 @@ rclcpp_components_register_node(object_position_filter EXECUTABLE object_position_filter_node ) +rclcpp_components_register_node(occupancy_grid_based_validator + PLUGIN "occupancy_grid_based_validator::OccupancyGridBasedValidator" + EXECUTABLE occupancy_grid_based_validator_node +) + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml b/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml index 8c9a28465038b..04bcbd87172b3 100644 --- a/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml +++ b/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml @@ -5,24 +5,23 @@ + + - - - - - + + + - diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py index 355cc4bd8b5bd..b99335b0e09ef 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py @@ -171,6 +171,8 @@ def add_launch_arg(name: str, default_value=None): get_package_share_directory("probabilistic_occupancy_grid_map") + "/config/updater.param.yaml", ), + add_launch_arg("input_obstacle_pointcloud", "false"), + add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), add_launch_arg("use_pointcloud_container", "false"), add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, From f211031643be9b278d258f7833240ff8e08f51fb Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Mon, 7 Aug 2023 13:04:04 +0300 Subject: [PATCH 115/266] feat(routing_no_drivable_lane_when_module_enabled): add solution for routing no_drivable_lane only when module enabled (#4308) * feat(routing_no_drivable_lane_when_module_enabled): add proposed solution Signed-off-by: AhmedEbrahim * feat(routing_no_drivable_lane_when_module_enabled): improving comments regarding new parameter Signed-off-by: AhmedEbrahim * style(pre-commit): autofix * style(pre-commit): autofix * feat(routing_no_drivable_lane_when_module_enabled): reverting file changed by mistake Signed-off-by: AhmedEbrahim --------- Signed-off-by: AhmedEbrahim Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/mission_planner/README.md | 21 +++++++++--------- .../config/mission_planner.param.yaml | 1 + .../src/lanelet2_plugins/default_planner.cpp | 3 ++- .../src/lanelet2_plugins/default_planner.hpp | 1 + .../include/route_handler/route_handler.hpp | 2 +- planning/route_handler/src/route_handler.cpp | 22 +++++++++++-------- 6 files changed, 29 insertions(+), 21 deletions(-) diff --git a/planning/mission_planner/README.md b/planning/mission_planner/README.md index 4eb91e423c01f..3b649168884e6 100644 --- a/planning/mission_planner/README.md +++ b/planning/mission_planner/README.md @@ -14,16 +14,17 @@ In current Autoware.universe, only Lanelet2 map format is supported. ### Parameters -| Name | Type | Description | -| -------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------- | -| `map_frame` | string | The frame name for map | -| `arrival_check_angle_deg` | double | Angle threshold for goal check | -| `arrival_check_distance` | double | Distance threshold for goal check | -| `arrival_check_duration` | double | Duration threshold for goal check | -| `goal_angle_threshold` | double | Max goal pose angle for goal approve | -| `enable_correct_goal_pose` | bool | Enabling correction of goal pose according to the closest lanelet orientation | -| `reroute_time_threshold` | double | If the time to the rerouting point at the current velocity is greater than this threshold, rerouting is possible | -| `minimum_reroute_length` | double | Minimum Length for publishing a new route | +| Name | Type | Description | +| ---------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------- | +| `map_frame` | string | The frame name for map | +| `arrival_check_angle_deg` | double | Angle threshold for goal check | +| `arrival_check_distance` | double | Distance threshold for goal check | +| `arrival_check_duration` | double | Duration threshold for goal check | +| `goal_angle_threshold` | double | Max goal pose angle for goal approve | +| `enable_correct_goal_pose` | bool | Enabling correction of goal pose according to the closest lanelet orientation | +| `reroute_time_threshold` | double | If the time to the rerouting point at the current velocity is greater than this threshold, rerouting is possible | +| `minimum_reroute_length` | double | Minimum Length for publishing a new route | +| `consider_no_drivable_lanes` | bool | This flag is for considering no_drivable_lanes in planning or not. | ### Services diff --git a/planning/mission_planner/config/mission_planner.param.yaml b/planning/mission_planner/config/mission_planner.param.yaml index d596eb9816f0a..98c28344ea25c 100644 --- a/planning/mission_planner/config/mission_planner.param.yaml +++ b/planning/mission_planner/config/mission_planner.param.yaml @@ -8,3 +8,4 @@ enable_correct_goal_pose: false reroute_time_threshold: 10.0 minimum_reroute_length: 30.0 + consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not. diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 95a4798e7db68..d8289824e517c 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -147,6 +147,7 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo(); param_.goal_angle_threshold_deg = node_->declare_parameter("goal_angle_threshold_deg"); param_.enable_correct_goal_pose = node_->declare_parameter("enable_correct_goal_pose"); + param_.consider_no_drivable_lanes = node_->declare_parameter("consider_no_drivable_lanes"); } void DefaultPlanner::initialize(rclcpp::Node * node) @@ -401,7 +402,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) const auto goal_check_point = points.at(i); lanelet::ConstLanelets path_lanelets; if (!route_handler_.planPathLaneletsBetweenCheckpoints( - start_check_point, goal_check_point, &path_lanelets)) { + start_check_point, goal_check_point, &path_lanelets, param_.consider_no_drivable_lanes)) { RCLCPP_WARN(logger, "Failed to plan route."); return route_msg; } diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 09b519267c962..cf5a19443dd82 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -37,6 +37,7 @@ struct DefaultPlannerParameters { double goal_angle_threshold_deg; bool enable_correct_goal_pose; + bool consider_no_drivable_lanes; }; class DefaultPlanner : public mission_planner::PlannerPlugin diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index e17895a2f5018..1818c460e407b 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -89,7 +89,7 @@ class RouteHandler // for routing bool planPathLaneletsBetweenCheckpoints( const Pose & start_checkpoint, const Pose & goal_checkpoint, - lanelet::ConstLanelets * path_lanelets) const; + lanelet::ConstLanelets * path_lanelets, const bool consider_no_drivable_lanes = false) const; std::vector createMapSegments(const lanelet::ConstLanelets & path_lanelets) const; static bool isRouteLooped(const RouteSections & route_sections); diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 4f50070ca64bb..f3270dac1d722 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1999,7 +1999,7 @@ lanelet::ConstLanelets RouteHandler::getNextLaneSequence( bool RouteHandler::planPathLaneletsBetweenCheckpoints( const Pose & start_checkpoint, const Pose & goal_checkpoint, - lanelet::ConstLanelets * path_lanelets) const + lanelet::ConstLanelets * path_lanelets, const bool consider_no_drivable_lanes) const { // Find lanelets for start point. First, find all lanelets containing the start point to calculate // all possible route later. It fails when the point is not located on any road_lanelet (e.g. the @@ -2063,15 +2063,19 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( } if (is_route_found) { - bool shortest_path_has_no_drivable_lane = hasNoDrivableLaneInPath(shortest_path); - if (shortest_path_has_no_drivable_lane) { - drivable_lane_path_found = - findDrivableLanePath(start_lanelet, goal_lanelet, drivable_lane_path); - } - lanelet::routing::LaneletPath path; - if (drivable_lane_path_found) { - path = drivable_lane_path; + if (consider_no_drivable_lanes) { + bool shortest_path_has_no_drivable_lane = hasNoDrivableLaneInPath(shortest_path); + if (shortest_path_has_no_drivable_lane) { + drivable_lane_path_found = + findDrivableLanePath(start_lanelet, goal_lanelet, drivable_lane_path); + } + + if (drivable_lane_path_found) { + path = drivable_lane_path; + } else { + path = shortest_path; + } } else { path = shortest_path; } From 9ad6493cec09221c06b8a881300a1d7fcab66131 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 8 Aug 2023 01:34:22 +0900 Subject: [PATCH 116/266] fix(behavior_path_planner): fix getExtendedCurrentLanes (#4532) --- .../behavior_path_planner/utils/utils.hpp | 2 +- .../goal_planner/goal_planner_module.cpp | 4 ++-- .../start_planner/start_planner_module.cpp | 4 ++-- .../goal_planner/geometric_pull_over.cpp | 2 +- .../src/utils/goal_planner/goal_searcher.cpp | 2 +- .../utils/goal_planner/shift_pull_over.cpp | 2 +- .../start_planner/geometric_pull_out.cpp | 2 +- .../utils/start_planner/shift_pull_out.cpp | 2 +- .../src/utils/start_planner/util.cpp | 2 +- .../behavior_path_planner/src/utils/utils.cpp | 21 ++++++++++--------- 10 files changed, 22 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index d1a69fa0e6cce..e56360922b56c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -383,7 +383,7 @@ lanelet::ConstLanelets getExtendedCurrentLanes( lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data, const double backward_length, - const double forward_length, const bool until_goal_lane); + const double forward_length, const bool forward_only_in_route); lanelet::ConstLanelets calcLaneAroundPose( const std::shared_ptr route_handler, const geometry_msgs::msg::Pose & pose, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index ec3efbdeb7bbb..7f8272e748233 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -154,7 +154,7 @@ void GoalPlannerModule::onTimer() const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, - /*until_goal_lane*/ false); + /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; double min_start_arc_length = std::numeric_limits::max(); @@ -592,7 +592,7 @@ void GoalPlannerModule::setLanes() status_.current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, - /*until_goal_lane*/ false); + /*forward_only_in_route*/ false); status_.pull_over_lanes = goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_); status_.lanes = diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 18e7c006e7ae4..7aa0fd2d690fc 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -116,7 +116,7 @@ bool StartPlannerModule::isExecutionRequested() const planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, backward_path_length, std::numeric_limits::max(), - /*until_goal_lane*/ true); + /*forward_only_in_route*/ true); const auto pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); auto lanes = current_lanes; @@ -328,7 +328,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, backward_path_length, std::numeric_limits::max(), - /*until_goal_lane*/ true); + /*forward_only_in_route*/ true); auto stop_path = status_.back_finished ? getCurrentPath() : status_.backward_path; const auto drivable_lanes = generateDrivableLanes(stop_path); diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp index ca251e625a5b0..6a5ccc827db29 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp @@ -46,7 +46,7 @@ boost::optional GeometricPullOver::plan(const Pose & goal_pose) // prepare road nad shoulder lanes const auto road_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, - /*until_goal_lane*/ false); + /*forward_only_in_route*/ false); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index d6b30b0ee0f74..9daee39433d97 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -57,7 +57,7 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose) goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); auto lanes = utils::getExtendedCurrentLanes( planner_data_, backward_length, forward_length, - /*until_goal_lane*/ false); + /*forward_only_in_route*/ false); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); const auto goal_arc_coords = diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp index 71ebed11cbd63..2f5c1d9b05b7f 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp @@ -48,7 +48,7 @@ boost::optional ShiftPullOver::plan(const Pose & goal_pose) // get road and shoulder lanes const auto road_lanes = utils::getExtendedCurrentLanes( planner_data_, backward_search_length, forward_search_length, - /*until_goal_lane*/ false); + /*forward_only_in_route*/ false); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 2af34740b133b..5eac8291f0e1a 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -44,7 +44,7 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p planner_data_->parameters.backward_path_length + parameters_.max_back_distance; const auto road_lanes = utils::getExtendedCurrentLanes( planner_data_, backward_path_length, std::numeric_limits::max(), - /*until_goal_lane*/ true); + /*forward_only_in_route*/ true); const auto pull_out_lanes = getPullOutLanes(planner_data_, backward_path_length); auto lanes = road_lanes; for (const auto & pull_out_lane : pull_out_lanes) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index bd8d80884e08d..54f19ff121b55 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -54,7 +54,7 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) const auto road_lanes = utils::getExtendedCurrentLanes( planner_data_, backward_path_length, std::numeric_limits::max(), - /*until_goal_lane*/ true); + /*forward_only_in_route*/ true); // find candidate paths auto pull_out_paths = calcPullOutPaths( *route_handler, road_lanes, start_pose, goal_pose, common_parameters, parameters_); diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 856385be8d970..8ef659b7df7b0 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -116,6 +116,6 @@ lanelet::ConstLanelets getPullOutLanes( return utils::getExtendedCurrentLanes( planner_data, backward_length, /*forward_length*/ std::numeric_limits::max(), - /*until_goal_lane*/ true); + /*forward_only_in_route*/ true); } } // namespace behavior_path_planner::start_planner_utils diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 088dd736e9d49..47729bab4d11f 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2963,7 +2963,7 @@ lanelet::ConstLanelets extendLanes( lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data, const double backward_length, - const double forward_length, const bool until_goal_lane) + const double forward_length, const bool forward_only_in_route) { auto lanes = getCurrentLanes(planner_data); if (lanes.empty()) return lanes; @@ -2993,15 +2993,6 @@ lanelet::ConstLanelets getExtendedCurrentLanes( } while (forward_length_sum < forward_length) { - // stop extending when the goal route section is reached - // if forward_length is a very large value, set it to true, - // as it may continue to extend lanes outside the route ahead of goal forever. - if (until_goal_lane) { - if (planner_data->route_handler->isInGoalRouteSection(lanes.back())) { - return lanes; - } - } - auto extended_lanes = extendNextLane(planner_data->route_handler, lanes); if (extended_lanes.empty()) { return lanes; @@ -3018,6 +3009,16 @@ lanelet::ConstLanelets getExtendedCurrentLanes( } else { break; // no more next lanes to add } + + // stop extending when the lane outside of the route is reached + // if forward_length is a very large value, set it to true, + // as it may continue to extend forever. + if (forward_only_in_route) { + if (!planner_data->route_handler->isRouteLanelet(extended_lanes.back())) { + return lanes; + } + } + lanes = extended_lanes; } From 0dae23f6024629453d544373433621a0b0214e21 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 8 Aug 2023 02:33:14 +0900 Subject: [PATCH 117/266] feat(dynamic_avoidance): consider shifting objects (#4545) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 2 +- .../dynamic_avoidance_module.cpp | 32 +++++++++---------- 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index bb9200514b848..c93707bf84362 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -318,7 +318,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double time_to_collision) const; MinMaxValue calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, - const Polygon2d & obj_points, const bool is_collision_left, + const Polygon2d & obj_points, const bool is_collision_left, const double obj_normal_vel, const std::optional & prev_object) const; std::pair getAdjacentLanes( diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 04b4f1782ad51..52f887e60d83e 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -502,7 +502,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( *path_points_for_object_polygon, object.pose, obj_points, object.vel, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( - *path_points_for_object_polygon, obj_points, is_collision_left, prev_object); + *path_points_for_object_polygon, obj_points, is_collision_left, object.lat_vel, prev_object); const bool should_be_avoided = true; target_objects_manager_.updateObject( @@ -782,7 +782,7 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, - const Polygon2d & obj_points, const bool is_collision_left, + const Polygon2d & obj_points, const bool is_collision_left, const double obj_normal_vel, const std::optional & prev_object) const { // calculate min/max lateral offset from object to path @@ -798,28 +798,25 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( } return getMinMaxValues(obj_lat_abs_offset_vec); }(); - const double min_obj_lat_offset = obj_lat_abs_offset.min_value * (is_collision_left ? 1.0 : -1.0); - const double max_obj_lat_offset = obj_lat_abs_offset.max_value * (is_collision_left ? 1.0 : -1.0); + const double min_obj_lat_abs_offset = obj_lat_abs_offset.min_value; + const double max_obj_lat_abs_offset = obj_lat_abs_offset.max_value; // calculate bound min and max lateral offset const double min_bound_lat_offset = [&]() { + constexpr double object_time_to_shift = 2.0; + const double lat_abs_offset_to_shift = + std::max(0.0, obj_normal_vel * (is_collision_left ? -1.0 : 1.0)) * + object_time_to_shift; // TODO(murooka) use rosparam const double raw_min_bound_lat_offset = - min_obj_lat_offset - parameters_->lat_offset_from_obstacle * (is_collision_left ? 1.0 : -1.0); + min_obj_lat_abs_offset - parameters_->lat_offset_from_obstacle - lat_abs_offset_to_shift; const double min_bound_lat_abs_offset_limit = planner_data_->parameters.vehicle_width / 2.0 - parameters_->max_lat_offset_to_avoid; - if (is_collision_left) { - if (raw_min_bound_lat_offset < min_bound_lat_abs_offset_limit) { - return min_bound_lat_abs_offset_limit; - } - } else { - if (-min_bound_lat_abs_offset_limit < raw_min_bound_lat_offset) { - return -min_bound_lat_abs_offset_limit; - } - } - return raw_min_bound_lat_offset; + return std::max(raw_min_bound_lat_offset, min_bound_lat_abs_offset_limit) * + (is_collision_left ? 1.0 : -1.0); }(); const double max_bound_lat_offset = - max_obj_lat_offset + parameters_->lat_offset_from_obstacle * (is_collision_left ? 1.0 : -1.0); + (max_obj_lat_abs_offset + parameters_->lat_offset_from_obstacle) * + (is_collision_left ? 1.0 : -1.0); // filter min_bound_lat_offset const auto prev_min_lat_avoid_to_offset = [&]() -> std::optional { @@ -830,7 +827,8 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( }(); const double filtered_min_bound_lat_offset = prev_min_lat_avoid_to_offset - ? signal_processing::lowpassFilter(min_bound_lat_offset, *prev_min_lat_avoid_to_offset, 0.3) + ? signal_processing::lowpassFilter( + min_bound_lat_offset, *prev_min_lat_avoid_to_offset, 0.5) // TODO(murooka) use rosparam : min_bound_lat_offset; return MinMaxValue{filtered_min_bound_lat_offset, max_bound_lat_offset}; From 75ccf8ee17120090df360c5014102f6e745a61bd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 8 Aug 2023 10:49:51 +0900 Subject: [PATCH 118/266] feat(dynamic_avoidance): use decision with reason (#4547) * feat(dynamic_avoidance): use decision with reason as return value Signed-off-by: Takayuki Murooka * fix time to collision Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 18 ++++- .../dynamic_avoidance_module.cpp | 69 ++++++++++++------- 2 files changed, 60 insertions(+), 27 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index c93707bf84362..29b012caa231d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -235,6 +235,12 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::unordered_map object_map_; }; + struct DecisionWithReason + { + bool decision; + std::string reason{""}; + }; + DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, @@ -299,14 +305,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; - bool willObjectCutOut( + DecisionWithReason willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const; bool isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const; double calcTimeToCollision( const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, - const double obj_tangent_vel) const; + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; std::optional> calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const; LatLonOffset getLateralLongitudinalOffset( @@ -326,6 +332,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; + void printIgnoreReason(const std::string & obj_uuid, const std::string & reason) + { + const auto reason_text = + "[DynamicAvoidance] Ignore obstacle (%s)" + (reason == "" ? "." : " since " + reason + "."); + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, reason_text.c_str(), obj_uuid.c_str()); + } + std::vector target_objects_; // std::vector prev_target_objects_; std::shared_ptr parameters_; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 52f887e60d83e..6233c1a5dd36f 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -459,34 +459,32 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 2.d. check if object will not cut out - const bool will_object_cut_out = + const auto will_object_cut_out = willObjectCutOut(object.vel, object.lat_vel, is_object_left, prev_object); - if (will_object_cut_out) { - RCLCPP_INFO_EXPRESSION( - getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since it will cut out.", obj_uuid.c_str()); + if (will_object_cut_out.decision) { + printIgnoreReason(obj_uuid.c_str(), will_object_cut_out.reason); continue; } - // 2.e. check if time to collision + // 2.e. check time to collision const double time_to_collision = - calcTimeToCollision(prev_module_path->points, object.pose, object.vel); + calcTimeToCollision(prev_module_path->points, object.pose, object.vel, lat_lon_offset); if ( (0 <= object.vel && parameters_->max_time_to_collision_overtaking_object < time_to_collision) || (object.vel <= 0 && parameters_->max_time_to_collision_oncoming_object < time_to_collision)) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since time to collision is large.", - obj_uuid.c_str()); + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%f) is large.", + obj_uuid.c_str(), time_to_collision); continue; } if (time_to_collision < -parameters_->duration_to_hold_avoidance_overtaking_object) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since time to collision is a small negative " + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%f) is a small negative " "value.", - obj_uuid.c_str()); + obj_uuid.c_str(), time_to_collision); continue; } @@ -574,15 +572,24 @@ DynamicAvoidanceModule::calcCollisionSection( double DynamicAvoidanceModule::calcTimeToCollision( const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, - const double obj_tangent_vel) const + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const { - const double relative_velocity = getEgoSpeed() - obj_tangent_vel; + // Set maximum time-to-collision 0 if the object longitudinally overlaps ego. + // NOTE: This is to avoid objects running right beside ego even if time-to-collision is negative. const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(ego_path); + const double lon_offset_ego_to_obj = + motion_utils::calcSignedArcLength( + ego_path, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx) + + lat_lon_offset.max_lon_offset; + const double maximum_time_to_collision = + (0.0 < lon_offset_ego_to_obj) ? 0.0 : -std::numeric_limits::max(); + + const double relative_velocity = getEgoSpeed() - obj_tangent_vel; const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); const double signed_lon_length = motion_utils::calcSignedArcLength( ego_path, getEgoPosition(), ego_seg_idx, obj_pose.position, obj_seg_idx); const double positive_relative_velocity = std::max(relative_velocity, 1.0); - return signed_lon_length / positive_relative_velocity; + return std::max(maximum_time_to_collision, signed_lon_length / positive_relative_velocity); } bool DynamicAvoidanceModule::isObjectFarFromPath( @@ -630,33 +637,45 @@ bool DynamicAvoidanceModule::willObjectCutIn( return false; } -bool DynamicAvoidanceModule::willObjectCutOut( +DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const { // Ignore oncoming object if (obj_tangent_vel < 0) { - return false; + return DecisionWithReason{false}; } - if (prev_object && prev_object->latest_time_inside_ego_path) { - if ( - parameters_->max_time_from_outside_ego_path_for_cut_out < - (clock_->now() - *prev_object->latest_time_inside_ego_path).seconds()) { - return false; - } + // Check if previous object is memorized + if (!prev_object || !prev_object->latest_time_inside_ego_path) { + return DecisionWithReason{false}; + } + if ( + parameters_->max_time_from_outside_ego_path_for_cut_out < + (clock_->now() - *prev_object->latest_time_inside_ego_path).seconds()) { + return DecisionWithReason{false}; } + // Check object's lateral velocity + std::stringstream reason; + reason << "since latest time inside ego's path is small enough (" + << (clock_->now() - *prev_object->latest_time_inside_ego_path).seconds() << "<" + << parameters_->max_time_from_outside_ego_path_for_cut_out << ")"; if (is_object_left) { if (parameters_->min_cut_out_object_lat_vel < obj_normal_vel) { - return true; + reason << ", and lateral velocity is large enough (" + << parameters_->min_cut_out_object_lat_vel << "min_cut_out_object_lat_vel) { - return true; + reason << ", and lateral velocity is large enough (" + << parameters_->min_cut_out_object_lat_vel << " DynamicAvoidanceModule::getAdjacentLanes( From cdabb78cf597df2f57606a720178122f1276bf3f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 8 Aug 2023 10:49:59 +0900 Subject: [PATCH 119/266] feat(dynamic_avoidance): ignore oncoming crossing object (#4548) * feat(dynamic_avoidance): ignore oncoming crossing object Signed-off-by: Takayuki Murooka * remove debug print Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/dynamic_avoidance.param.yaml | 58 +++++++++++++++++++ .../dynamic_avoidance_module.hpp | 6 +- .../dynamic_avoidance_module.cpp | 13 +++-- .../dynamic_avoidance/manager.cpp | 24 ++++++-- 4 files changed, 89 insertions(+), 12 deletions(-) create mode 100644 planning/behavior_path_planner/config/dynamic_avoidance.param.yaml diff --git a/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml new file mode 100644 index 0000000000000..896c44c9cec9a --- /dev/null +++ b/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml @@ -0,0 +1,58 @@ +/**: + ros__parameters: + dynamic_avoidance: + common: + enable_debug_info: true + + # avoidance is performed for the object type with true + target_object: + car: true + truck: true + bus: true + trailer: true + unknown: false + bicycle: false + motorcycle: true + pedestrian: false + + min_obstacle_vel: 0.0 # [m/s] + + successive_num_to_entry_dynamic_avoidance_condition: 5 + successive_num_to_exit_dynamic_avoidance_condition: 1 + + min_obj_lat_offset_to_ego_path: 0.0 # [m] + max_obj_lat_offset_to_ego_path: 1.0 # [m] + + cut_in_object: + min_time_to_start_cut_in: 1.0 # [s] + min_lon_offset_ego_to_object: 0.0 # [m] + + cut_out_object: + max_time_from_outside_ego_path: 2.0 # [s] + min_object_lat_vel: 0.3 # [m/s] + + crossing_object: + min_overtaking_object_vel: 1.0 + max_overtaking_object_angle: 1.05 + min_oncoming_object_vel: 0.0 + max_oncoming_object_angle: 0.523 + + front_object: + max_object_angle: 0.785 + + drivable_area_generation: + lat_offset_from_obstacle: 0.8 # [m] + max_lat_offset_to_avoid: 0.5 # [m] + + # for same directional object + overtaking_object: + max_time_to_collision: 40.0 # [s] + start_duration_to_avoid: 2.0 # [s] + end_duration_to_avoid: 4.0 # [s] + duration_to_hold_avoidance: 3.0 # [s] + + # for opposite directional object + oncoming_object: + max_time_to_collision: 15.0 # [s] + start_duration_to_avoid: 12.0 # [s] + end_duration_to_avoid: 0.0 # [s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 29b012caa231d..087a39e87393a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -67,8 +67,10 @@ struct DynamicAvoidanceParameters double max_time_from_outside_ego_path_for_cut_out{0.0}; double min_cut_out_object_lat_vel{0.0}; double max_front_object_angle{0.0}; - double min_crossing_object_vel{0.0}; - double max_crossing_object_angle{0.0}; + double min_overtaking_crossing_object_vel{0.0}; + double max_overtaking_crossing_object_angle{0.0}; + double min_oncoming_crossing_object_vel{0.0}; + double max_oncoming_crossing_object_angle{0.0}; // drivable area generation double lat_offset_from_obstacle{0.0}; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 6233c1a5dd36f..e8570f0e310cf 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -374,11 +374,16 @@ void DynamicAvoidanceModule::updateTargetObjects() // 1.c. check if object is not crossing ego's path const double obj_angle = calcDiffAngleAgainstPath(prev_module_path->points, obj_pose); - const bool is_obstacle_crossing_path = - parameters_->max_crossing_object_angle < std::abs(obj_angle) && - parameters_->max_crossing_object_angle < M_PI - std::abs(obj_angle); + const double max_crossing_object_angle = 0.0 <= obj_tangent_vel + ? parameters_->max_overtaking_crossing_object_angle + : parameters_->max_oncoming_crossing_object_angle; + const bool is_obstacle_crossing_path = max_crossing_object_angle < std::abs(obj_angle) && + max_crossing_object_angle < M_PI - std::abs(obj_angle); + const double min_crossing_object_vel = 0.0 <= obj_tangent_vel + ? parameters_->min_overtaking_crossing_object_vel + : parameters_->min_oncoming_crossing_object_vel; const bool is_crossing_object_to_ignore = - parameters_->min_crossing_object_vel < std::abs(obj_vel) && is_obstacle_crossing_path; + min_crossing_object_vel < std::abs(obj_vel) && is_obstacle_crossing_path; if (is_crossing_object_to_ignore) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 87525068c8c34..e686719392e14 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -68,10 +68,14 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.max_front_object_angle = node->declare_parameter(ns + "front_object.max_object_angle"); - p.min_crossing_object_vel = - node->declare_parameter(ns + "crossing_object.min_object_vel"); - p.max_crossing_object_angle = - node->declare_parameter(ns + "crossing_object.max_object_angle"); + p.min_overtaking_crossing_object_vel = + node->declare_parameter(ns + "crossing_object.min_overtaking_object_vel"); + p.max_overtaking_crossing_object_angle = + node->declare_parameter(ns + "crossing_object.max_overtaking_object_angle"); + p.min_oncoming_crossing_object_vel = + node->declare_parameter(ns + "crossing_object.min_oncoming_object_vel"); + p.max_oncoming_crossing_object_angle = + node->declare_parameter(ns + "crossing_object.max_oncoming_object_angle"); } { // drivable_area_generation @@ -152,9 +156,17 @@ void DynamicAvoidanceModuleManager::updateModuleParams( parameters, ns + "front_object.max_object_angle", p->max_front_object_angle); updateParam( - parameters, ns + "crossing_object.min_object_vel", p->min_crossing_object_vel); + parameters, ns + "crossing_object.min_overtaking_object_vel", + p->min_overtaking_crossing_object_vel); updateParam( - parameters, ns + "crossing_object.max_object_angle", p->max_crossing_object_angle); + parameters, ns + "crossing_object.max_overtaking_object_angle", + p->max_overtaking_crossing_object_angle); + updateParam( + parameters, ns + "crossing_object.min_oncoming_object_vel", + p->min_oncoming_crossing_object_vel); + updateParam( + parameters, ns + "crossing_object.max_oncoming_object_angle", + p->max_oncoming_crossing_object_angle); } { // drivable_area_generation From 95695f458e06d6a8ffdaafa806b68115a0ab212d Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 8 Aug 2023 14:26:43 +0900 Subject: [PATCH 120/266] fix(behavior_path_planner): make use of the avoid_linestring.distance parameter (#4198) Signed-off-by: Maxime CLEMENT --- .../src/utils/drivable_area_expansion/expansion.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp index 79e15bf4e68d7..7bff7bef578ce 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp @@ -137,8 +137,9 @@ multipolygon_t createExpansionPolygons( : footprint_dist; auto expansion_polygon = createExpansionPolygon(base_ls, expansion_dist, is_left); auto limited_dist = expansion_dist; - const auto uncrossable_dist_limit = - calculateDistanceLimit(base_ls, expansion_polygon, uncrossable_lines); + const auto uncrossable_dist_limit = std::max( + 0.0, calculateDistanceLimit(base_ls, expansion_polygon, uncrossable_lines) - + params.avoid_linestring_dist); if (uncrossable_dist_limit < limited_dist) { limited_dist = uncrossable_dist_limit; if (params.compensate_uncrossable_lines) { From 4e68889ec5ce4e8eef93a353e503dd298ebc7678 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 8 Aug 2023 14:38:27 +0900 Subject: [PATCH 121/266] fix(crosswalk): set distance even when decision is GO (#4551) Signed-off-by: Takayuki Murooka --- .../src/scene_crosswalk.cpp | 48 ++++++++++--------- .../src/scene_crosswalk.hpp | 9 +++- 2 files changed, 32 insertions(+), 25 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index fd3b0d76107cb..391b397dd82cd 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -252,6 +252,10 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto // Set safe or unsafe setSafe(!nearest_stop_factor); + // Set distance + // NOTE: If no stop point is inserted, distance to the virtual stop line has to be calculated. + setDistanceToStop(*path, default_stop_pose, nearest_stop_factor); + // plan Go/Stop if (isActivated()) { planGo(*path, nearest_stop_factor); @@ -402,7 +406,7 @@ std::pair CrosswalkModule::getAttentionRange( void CrosswalkModule::insertDecelPointWithDebugInfo( const geometry_msgs::msg::Point & stop_point, const float target_velocity, - PathWithLaneId & output) + PathWithLaneId & output) const { const auto stop_pose = planning_utils::insertDecelPoint(stop_point, output, target_velocity); if (!stop_pose) { @@ -1007,25 +1011,34 @@ geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon( return polygon; } -void CrosswalkModule::planGo( - PathWithLaneId & ego_path, const std::optional & stop_factor) +void CrosswalkModule::setDistanceToStop( + const PathWithLaneId & ego_path, + const std::optional & default_stop_pose, + const std::optional & stop_factor) { - if (!stop_factor) { - setDistance(std::numeric_limits::lowest()); - return; + // calculate stop position + const auto stop_pos = [&]() -> std::optional { + if (stop_factor) return stop_factor->stop_pose.position; + if (default_stop_pose) return default_stop_pose->position; + return std::nullopt; + }(); + + // Set distance + if (stop_pos) { + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const double dist_ego2stop = calcSignedArcLength(ego_path.points, ego_pos, *stop_pos); + setDistance(dist_ego2stop); } +} +void CrosswalkModule::planGo( + PathWithLaneId & ego_path, const std::optional & stop_factor) const +{ // Plan slow down const auto target_velocity = calcTargetVelocity(stop_factor->stop_pose.position, ego_path); insertDecelPointWithDebugInfo( stop_factor->stop_pose.position, std::max(planner_param_.min_slow_down_velocity, target_velocity), ego_path); - - // Set distance - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const double dist_ego2stop = - calcSignedArcLength(ego_path.points, ego_pos, stop_factor->stop_pose.position); - setDistance(dist_ego2stop); } void CrosswalkModule::planStop( @@ -1038,22 +1051,11 @@ void CrosswalkModule::planStop( return std::nullopt; }(); - if (!stop_factor) { - setDistance(std::numeric_limits::lowest()); - return; - } - // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); planning_utils::appendStopReason(*stop_factor, stop_reason); velocity_factor_.set( ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose, VelocityFactor::UNKNOWN); - - // set distance - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const double dist_ego2stop = - calcSignedArcLength(ego_path.points, ego_pos, stop_factor->stop_pose.position); - setDistance(dist_ego2stop); } } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 7ac00ab880be8..961126bf4bca1 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -295,7 +295,12 @@ class CrosswalkModule : public SceneModuleInterface const std::optional & stop_factor_for_crosswalk_users, const std::optional & stop_factor_for_stuck_vehicles); - void planGo(PathWithLaneId & ego_path, const std::optional & stop_factor); + void setDistanceToStop( + const PathWithLaneId & ego_path, + const std::optional & default_stop_pose, + const std::optional & stop_factor); + + void planGo(PathWithLaneId & ego_path, const std::optional & stop_factor) const; void planStop( PathWithLaneId & ego_path, const std::optional & nearest_stop_factor, @@ -308,7 +313,7 @@ class CrosswalkModule : public SceneModuleInterface void insertDecelPointWithDebugInfo( const geometry_msgs::msg::Point & stop_point, const float target_velocity, - PathWithLaneId & output); + PathWithLaneId & output) const; std::pair clampAttentionRangeByNeighborCrosswalks( const PathWithLaneId & ego_path, const double near_attention_range, From 2e5752f8e73aecd6938ebac03727ac5dc1b5563c Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 8 Aug 2023 18:15:46 +0900 Subject: [PATCH 122/266] feat(behavior_path_planner): add reroute availability publisher (#4543) * feat(behavior_path_planner): add reroute availability publisher Signed-off-by: yutaka * update Signed-off-by: yutaka * add comment Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../behavior_path_planner_node.hpp | 8 ++++++ .../behavior_path_planner/planner_manager.hpp | 10 ++++++++ .../src/behavior_path_planner_node.cpp | 25 +++++++++++++++++++ 3 files changed, 43 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index e6ed8b7063d2c..54cfccc494e8a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include #include @@ -72,6 +73,7 @@ using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; using tier4_planning_msgs::msg::LateralOffset; +using tier4_planning_msgs::msg::RerouteAvailability; using tier4_planning_msgs::msg::Scenario; using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; @@ -102,6 +104,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr bound_publisher_; rclcpp::Publisher::SharedPtr modified_goal_publisher_; rclcpp::Publisher::SharedPtr stop_reason_publisher_; + rclcpp::Publisher::SharedPtr reroute_availability_publisher_; rclcpp::TimerBase::SharedPtr timer_; std::map::SharedPtr> path_candidate_publishers_; @@ -171,6 +174,11 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_lane_change_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; + /** + * @brief publish reroute availability + */ + void publish_reroute_availability(); + /** * @brief publish steering factor from intersection */ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 02e5452cc2103..f1292c2db7811 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -214,6 +214,16 @@ class PlannerManager return stop_reason_array; } + /** + * @brief check if there are approved modules. + */ + bool hasApprovedModules() const { return !approved_module_ptrs_.empty(); } + + /** + * @brief check if there are candidate modules. + */ + bool hasCandidateModules() const { return !candidate_module_ptrs_.empty(); } + /** * @brief reset root lanelet. if there are approved modules, don't reset root lanelet. * @param planner data. diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 869de6cb4d103..3e2ccd23d58e7 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -68,6 +68,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod hazard_signal_publisher_ = create_publisher("~/output/hazard_lights_cmd", 1); modified_goal_publisher_ = create_publisher("~/output/modified_goal", 1); stop_reason_publisher_ = create_publisher("~/output/stop_reasons", 1); + reroute_availability_publisher_ = + create_publisher("~/output/is_reroute_available", 1); debug_avoidance_msg_array_publisher_ = create_publisher("~/debug/avoidance_debug_message_array", 1); debug_lane_change_msg_array_publisher_ = @@ -539,6 +541,9 @@ void BehaviorPathPlannerNode::run() // compute turn signal computeTurnSignal(planner_data_, *path, output); + // publish reroute availability + publish_reroute_availability(); + // publish drivable bounds publish_bounds(*path); @@ -654,6 +659,26 @@ void BehaviorPathPlannerNode::publish_steering_factor( steering_factor_interface_ptr_->publishSteeringFactor(get_clock()->now()); } +void BehaviorPathPlannerNode::publish_reroute_availability() +{ + const bool has_approved_modules = planner_manager_->hasApprovedModules(); + const bool has_candidate_modules = planner_manager_->hasCandidateModules(); + + // In the current behavior path planner, we might get unexpected behavior when rerouting while + // modules other than lane follow are active. Therefore, rerouting will be allowed only when the + // lane follow module is running Note that if there is a approved module or candidate module, it + // means non-lane-following modules are runnning. + RerouteAvailability is_reroute_available; + is_reroute_available.stamp = this->now(); + if (has_approved_modules || has_candidate_modules) { + is_reroute_available.availability = false; + } else { + is_reroute_available.availability = true; + } + + reroute_availability_publisher_->publish(is_reroute_available); +} + void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data) { MarkerArray marker_array; From 1f91c838ea002c2c1ce1794746d984462893d1d6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 8 Aug 2023 22:08:01 +0900 Subject: [PATCH 123/266] feat(avoidance): enable avoidance cancel (#4398) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 2 +- .../behavior_path_planner_avoidance_design.md | 22 +++--- .../avoidance/avoidance_module.hpp | 13 ---- .../utils/avoidance/avoidance_module_data.hpp | 4 +- .../avoidance/avoidance_module.cpp | 77 ++++++++----------- .../src/scene_module/avoidance/manager.cpp | 3 +- .../src/scene_module/lane_change/manager.cpp | 2 - 7 files changed, 48 insertions(+), 75 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index db2436f796dfe..22de79f4dc7d0 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -11,10 +11,10 @@ # avoidance module common setting enable_bound_clipping: false - enable_update_path_when_object_is_gone: false enable_force_avoidance_for_stopped_vehicle: false enable_yield_maneuver: true enable_yield_maneuver_during_shifting: false + enable_cancel_maneuver: false disable_path_update: false # drivable area setting diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index 9be99f705f560..4e4d2258fc276 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -601,13 +601,13 @@ $$ ### Avoidance cancelling maneuver -If `enable_update_path_when_object_is_gone` parameter is true, Avoidance Module takes different actions according to the situations as follows: +If `enable_cancel_maneuver` parameter is true, Avoidance Module takes different actions according to the situations as follows: - If vehicle stops: If there is any object in the path of the vehicle, the avoidance path is generated. If this object goes away while the vehicle is stopping, the avoidance path will cancelled. - If vehicle is in motion, but avoidance maneuver doesn't started: If there is any object in the path of the vehicle, the avoidance path is generated. If this object goes away while the vehicle is not started avoidance maneuver, the avoidance path will cancelled. - If vehicle is in motion, avoidance maneuver started: If there is any object in the path of the vehicle, the avoidance path is generated,but if this object goes away while the vehicle is started avoidance maneuver, the avoidance path will not cancelled. -If `enable_update_path_when_object_is_gone` parameter is false, Avoidance Module doesn't revert generated avoidance path even if path objects are gone. +If `enable_cancel_maneuver` parameter is false, Avoidance Module doesn't revert generated avoidance path even if path objects are gone. ## How to keep the consistency of the optimize-base path generation logic @@ -621,15 +621,15 @@ The avoidance specific parameter configuration file can be located at `src/autow namespace: `avoidance.` -| Name | Unit | Type | Description | Default value | -| :------------------------------------- | :--- | :----- | :---------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| resample_interval_for_planning | [m] | double | Path resample interval for avoidance planning path. | 0.3 | -| resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 4.0 | -| detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | -| detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | -| enable_update_path_when_object_is_gone | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | -| enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | -| enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | +| Name | Unit | Type | Description | Default value | +| :------------------------------------ | :--- | :----- | :---------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| resample_interval_for_planning | [m] | double | Path resample interval for avoidance planning path. | 0.3 | +| resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 4.0 | +| detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | +| detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | +| enable_cancel_maneuver | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | +| enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | +| enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | | Name | Unit | Type | Description | Default value | | :------------------------ | ---- | ---- | ----------------------------------------------------------------------------------------------------------------------- | ------------- | diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index b6cc840a560f0..3095ec2c03251 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -195,19 +195,6 @@ class AvoidanceModule : public SceneModuleInterface */ AvoidanceState updateEgoState(const AvoidancePlanningData & data) const; - /** - * @brief check whether the ego is shifted based on shift line. - * @return result. - */ - bool isAvoidanceManeuverRunning(); - - /** - * @brief check whether the ego is in avoidance maneuver based on shift line and target object - * existence. - * @return result. - */ - bool isAvoidancePlanRunning() const; - // ego behavior update /** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 2b1a9cf1b82d4..0263eee5fe727 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -92,8 +92,8 @@ struct AvoidanceParameters // to use this, enable_avoidance_over_same_direction need to be set to true. bool use_opposite_lane{true}; - // enable update path when if detected objects on planner data is gone. - bool enable_update_path_when_object_is_gone{false}; + // if this param is true, it reverts avoidance path when the path is no longer needed. + bool enable_cancel_maneuver{false}; // enable avoidance for all parking vehicle bool enable_force_avoidance_for_stopped_vehicle{false}; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 601badee6a9f9..db80bc72f21ad 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -135,64 +135,53 @@ bool AvoidanceModule::isExecutionReady() const bool AvoidanceModule::canTransitSuccessState() { const auto & data = avoidance_data_; - const auto is_plan_running = isAvoidancePlanRunning(); - const bool has_avoidance_target = !data.target_objects.empty(); + // Change input lane. -> EXIT. if (!isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "previous module lane is updated."); + RCLCPP_WARN(getLogger(), "Previous module lane is updated. Exit."); return true; } - const auto idx = planner_data_->findEgoIndex(data.reference_path.points); - if (idx == data.reference_path.points.size() - 1) { - arrived_path_end_ = true; - } - - constexpr double THRESHOLD = 1.0; - if ( - calcDistance2d(getEgoPose(), getPose(data.reference_path.points.back())) > THRESHOLD && - arrived_path_end_) { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "reach path end point. exit avoidance module."); - return true; - } + helper_.setPreviousDrivingLanes(data.current_lanelets); - DEBUG_PRINT( - "is_plan_running = %d, has_avoidance_target = %d", is_plan_running, has_avoidance_target); + // Reach input path end point. -> EXIT. + { + const auto idx = planner_data_->findEgoIndex(data.reference_path.points); + if (idx == data.reference_path.points.size() - 1) { + arrived_path_end_ = true; + } - if (!is_plan_running && !has_avoidance_target) { - return true; + constexpr double THRESHOLD = 1.0; + const auto is_further_than_threshold = + calcDistance2d(getEgoPose(), getPose(data.reference_path.points.back())) > THRESHOLD; + if (is_further_than_threshold && arrived_path_end_) { + RCLCPP_WARN(getLogger(), "Reach path end point. Exit."); + return true; + } } - if ( - !has_avoidance_target && parameters_->enable_update_path_when_object_is_gone && - !isAvoidanceManeuverRunning()) { - // if dynamic objects are removed on path, change current state to reset path - return true; + const bool has_avoidance_target = !data.target_objects.empty(); + const bool has_shift_point = !path_shifter_.getShiftLines().empty(); + const bool has_base_offset = + std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold; + + // Nothing to do. -> EXIT. + if (!has_avoidance_target) { + if (!has_shift_point && !has_base_offset) { + RCLCPP_INFO(getLogger(), "No objects. No approved shift lines. Exit."); + return true; + } } - helper_.setPreviousDrivingLanes(data.current_lanelets); - - return false; -} - -bool AvoidanceModule::isAvoidancePlanRunning() const -{ - constexpr double AVOIDING_SHIFT_THR = 0.1; - const bool has_base_offset = std::abs(path_shifter_.getBaseOffset()) > AVOIDING_SHIFT_THR; - const bool has_shift_point = (path_shifter_.getShiftLinesSize() > 0); - return has_base_offset || has_shift_point; -} -bool AvoidanceModule::isAvoidanceManeuverRunning() -{ - const auto path_idx = avoidance_data_.ego_closest_path_index; - - for (const auto & al : registered_raw_shift_lines_) { - if (path_idx > al.start_idx || is_avoidance_maneuver_starts) { - is_avoidance_maneuver_starts = true; + // Be able to canceling avoidance path. -> EXIT. + if (!has_avoidance_target) { + if (!helper_.isShifted() && parameters_->enable_cancel_maneuver) { + RCLCPP_INFO(getLogger(), "No objects. Cancel avoidance path. Exit."); return true; } } - return false; + + return false; // Keep current state. } AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & debug) const diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 13b3344dc7c39..a0ae98276c05e 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -55,8 +55,7 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.detection_area_left_expand_dist = get_parameter(node, ns + "detection_area_left_expand_dist"); p.enable_bound_clipping = get_parameter(node, ns + "enable_bound_clipping"); - p.enable_update_path_when_object_is_gone = - get_parameter(node, ns + "enable_update_path_when_object_is_gone"); + p.enable_cancel_maneuver = get_parameter(node, ns + "enable_cancel_maneuver"); p.enable_force_avoidance_for_stopped_vehicle = get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); p.enable_yield_maneuver = get_parameter(node, ns + "enable_yield_maneuver"); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 7c12579bf34f5..0f770efb542c7 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -197,8 +197,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( get_parameter(node, ns + "detection_area_right_expand_dist"); p.detection_area_left_expand_dist = get_parameter(node, ns + "detection_area_left_expand_dist"); - p.enable_update_path_when_object_is_gone = - get_parameter(node, ns + "enable_update_path_when_object_is_gone"); p.enable_force_avoidance_for_stopped_vehicle = get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); } From e10db1371e32cfd2ba1f12a289e2af40679e47c3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 8 Aug 2023 23:12:26 +0900 Subject: [PATCH 124/266] fix(lane_change): add distance check for the lane change acceleration sampling (#4556) * fix(lane_change): add distance checker in acceleration sampling Signed-off-by: yutaka * fix format Signed-off-by: yutaka * update Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../src/scene_module/lane_change/normal.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 3d2bb44ad8bc0..2f7c39f94604e 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -540,6 +540,11 @@ std::vector NormalLaneChange::sampleLongitudinalAccValues( current_velocity, common_parameters, route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()), max_acc); + if (max_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { + return utils::lane_change::getAccelerationValues( + min_acc, max_acc, longitudinal_acc_sampling_num); + } + // if maximum lane change length is less than length to goal or the end of target lanes, only // sample max acc if (route_handler.isInGoalRouteSection(target_lanes.back())) { From 3c37d0a0b93e5607584532e7ccab790c4543180e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 00:44:19 +0900 Subject: [PATCH 125/266] feat(goal_planner): visualize planner type even when goal is not found (#4560) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 7f8272e748233..b428b2fa379e4 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1467,7 +1467,8 @@ void GoalPlannerModule::setDebugData() auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); - marker.pose = modified_goal_pose_->goal_pose; + marker.pose = modified_goal_pose_ ? modified_goal_pose_->goal_pose + : planner_data_->self_odometry->pose.pose; marker.text = magic_enum::enum_name(status_.pull_over_path->type); marker.text += " " + std::to_string(status_.current_path_idx) + "/" + std::to_string(status_.pull_over_path->partial_paths.size() - 1); From 0b44a264c19d74eaa269e918d8e95bbc0705e616 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 00:45:39 +0900 Subject: [PATCH 126/266] fix(start_planner): add missing change of "do not request when modifed route is received #4528" (#4558) --- .../src/scene_module/start_planner/start_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 7aa0fd2d690fc..32398c7944435 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -79,7 +79,7 @@ void StartPlannerModule::processOnExit() bool StartPlannerModule::isExecutionRequested() const { // Execute when current pose is near route start pose - const Pose & start_pose = planner_data_->route_handler->getStartPose(); + const Pose & start_pose = planner_data_->route_handler->getOriginalStartPose(); const Pose & current_pose = planner_data_->self_odometry->pose.pose; if ( tier4_autoware_utils::calcDistance2d(start_pose.position, current_pose.position) > From de7d6241403d1601f9d4c441189377e9902158a0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 00:45:57 +0900 Subject: [PATCH 127/266] feat(goal_planner): add life time to debug markers (#4562) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index b428b2fa379e4..d767fc91409f1 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1425,7 +1425,10 @@ void GoalPlannerModule::setDebugData() const auto header = planner_data_->route_handler->getRouteHeader(); - const auto add = [this](const MarkerArray & added) { + const auto add = [this](MarkerArray added) { + for (auto & marker : added.markers) { + marker.lifetime = rclcpp::Duration::from_seconds(1.5); + } tier4_autoware_utils::appendMarkerArray(added, &debug_marker_); }; From f695cb27da14980b9ad8097ca7a290b7701a402e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 00:52:04 +0900 Subject: [PATCH 128/266] fix(start_planner): plan freespace pull over even if any path has never been found (#4561) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index d767fc91409f1..b8219c5057f1d 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1076,11 +1076,22 @@ bool GoalPlannerModule::isStopped() bool GoalPlannerModule::isStuck() { + constexpr double stuck_time = 5.0; + if (!isStopped(odometry_buffer_stuck_, stuck_time)) { + return false; + } + + // not found safe path + if (!status_.is_safe) { + return true; + } + + // any path has never been found if (!status_.pull_over_path) { return false; } - constexpr double stuck_time = 5.0; - return isStopped(odometry_buffer_stuck_, stuck_time) && checkCollision(getCurrentPath()); + + return checkCollision(getCurrentPath()); } bool GoalPlannerModule::hasFinishedCurrentPath() From 81d2c0c886eace2b114bd9905fe12640d31e8e37 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Wed, 9 Aug 2023 00:59:29 +0900 Subject: [PATCH 129/266] feat(mission_planner): add a guard for rerouting while not following lane (#4564) feat(mission_planner): add a guard for rerouting while not follwoing lane Signed-off-by: yutaka --- planning/mission_planner/package.xml | 1 + .../src/mission_planner/mission_planner.cpp | 27 +++++++++++++++++++ .../src/mission_planner/mission_planner.hpp | 5 ++++ 3 files changed, 33 insertions(+) diff --git a/planning/mission_planner/package.xml b/planning/mission_planner/package.xml index f5f7eefd49d7d..49e1d0de8be93 100644 --- a/planning/mission_planner/package.xml +++ b/planning/mission_planner/package.xml @@ -33,6 +33,7 @@ tf2_geometry_msgs tf2_ros tier4_autoware_utils + tier4_planning_msgs vehicle_info_util ament_lint_auto diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 0c9b27a685583..1d37b820efff1 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -75,6 +75,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) plugin_loader_("mission_planner", "mission_planner::PlannerPlugin"), tf_buffer_(get_clock()), tf_listener_(tf_buffer_), + reroute_availability_(nullptr), normal_route_(nullptr), mrm_route_(nullptr) { @@ -89,6 +90,11 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) sub_odometry_ = create_subscription( "/localization/kinematic_state", rclcpp::QoS(1), std::bind(&MissionPlanner::on_odometry, this, std::placeholders::_1)); + sub_reroute_availability_ = create_subscription( + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/" + "is_reroute_available", + rclcpp::QoS(1), + std::bind(&MissionPlanner::on_reroute_availability, this, std::placeholders::_1)); auto qos_transient_local = rclcpp::QoS{1}.transient_local(); vector_map_subscriber_ = create_subscription( @@ -130,6 +136,11 @@ void MissionPlanner::on_odometry(const Odometry::ConstSharedPtr msg) } } +void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg) +{ + reroute_availability_ = msg; +} + void MissionPlanner::onMap(const HADMapBin::ConstSharedPtr msg) { map_ptr_ = msg; @@ -375,6 +386,10 @@ void MissionPlanner::on_set_mrm_route( throw component_interface_utils::ServiceException( ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); } + if (reroute_availability_ && !reroute_availability_->availability) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute as the planner is not in lane following."); + } const auto prev_state = state_.state; change_state(RouteState::Message::CHANGING); @@ -444,6 +459,10 @@ void MissionPlanner::on_clear_mrm_route( if (!mrm_route_) { throw component_interface_utils::NoEffectWarning("MRM route is not set"); } + if (reroute_availability_ && !reroute_availability_->availability) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute as the planner is not in lane following."); + } change_state(RouteState::Message::CHANGING); @@ -574,6 +593,10 @@ void MissionPlanner::on_change_route( throw component_interface_utils::ServiceException( ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); } + if (reroute_availability_ && !reroute_availability_->availability) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute as the planner is not in lane following."); + } // set to changing state change_state(RouteState::Message::CHANGING); @@ -633,6 +656,10 @@ void MissionPlanner::on_change_route_points( throw component_interface_utils::ServiceException( ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); } + if (reroute_availability_ && !reroute_availability_->availability) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute as the planner is not in lane following."); + } change_state(RouteState::Message::CHANGING); diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 4d09f72f81899..7b0427f6d01b1 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -27,6 +27,7 @@ #include #include +#include #include #include @@ -55,6 +56,7 @@ using NormalRoute = planning_interface::NormalRoute; using MrmRoute = planning_interface::MrmRoute; using RouteState = planning_interface::RouteState; using Odometry = nav_msgs::msg::Odometry; +using RerouteAvailability = tier4_planning_msgs::msg::RerouteAvailability; class MissionPlanner : public rclcpp::Node { @@ -72,8 +74,11 @@ class MissionPlanner : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_odometry_; rclcpp::Subscription::SharedPtr vector_map_subscriber_; + rclcpp::Subscription::SharedPtr sub_reroute_availability_; Odometry::ConstSharedPtr odometry_; + RerouteAvailability::ConstSharedPtr reroute_availability_; void on_odometry(const Odometry::ConstSharedPtr msg); + void on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg); rclcpp::Publisher::SharedPtr pub_marker_; void clear_route(); From 1c529ae5e0a83f83a4f7952b1ad1d01f341a5750 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Wed, 9 Aug 2023 01:33:25 +0900 Subject: [PATCH 130/266] fix(image_projection_based_fusion): fix out-of-scope error (#4057) * tmp Signed-off-by: yukke42 style(pre-commit): autofix update Signed-off-by: yukke42 style(pre-commit): autofix * fix: fix association bug Signed-off-by: yukke42 --------- Signed-off-by: yukke42 Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../roi_detected_object_fusion/node.hpp | 10 +- .../src/roi_detected_object_fusion/node.cpp | 101 +++++++++++++----- 2 files changed, 79 insertions(+), 32 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index 8168ad2c9f265..fe95d21eb266c 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -41,12 +41,11 @@ class RoiDetectedObjectFusionNode : public FusionNode generateDetectedObjectRoIs( - const std::vector & input_objects, const double image_width, - const double image_height, const Eigen::Affine3d & object2camera_affine, - const Eigen::Matrix4d & camera_projection); + const DetectedObjects & input_object_msg, const double image_width, const double image_height, + const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection); void fuseObjectsOnImage( - const std::vector & objects, + const DetectedObjects & input_object_msg, const std::vector & image_rois, const std::map & object_roi_map); @@ -63,7 +62,8 @@ class RoiDetectedObjectFusionNode : public FusionNode passthrough_object_flags_, fused_object_flags_, ignored_object_flags_; + std::map> passthrough_object_flags_map_, fused_object_flags_map_, + ignored_object_flags_map_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 37637f99f69c9..8961c0aad478f 100644 --- a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -34,19 +34,23 @@ RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptio void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) { - passthrough_object_flags_.clear(); - passthrough_object_flags_.resize(output_msg.objects.size()); - fused_object_flags_.clear(); - fused_object_flags_.resize(output_msg.objects.size()); - ignored_object_flags_.clear(); - ignored_object_flags_.resize(output_msg.objects.size()); + std::vector passthrough_object_flags, fused_object_flags, ignored_object_flags; + passthrough_object_flags.resize(output_msg.objects.size()); + fused_object_flags.resize(output_msg.objects.size()); + ignored_object_flags.resize(output_msg.objects.size()); for (std::size_t obj_i = 0; obj_i < output_msg.objects.size(); ++obj_i) { if ( output_msg.objects.at(obj_i).existence_probability > fusion_params_.passthrough_lower_bound_probability_threshold) { - passthrough_object_flags_.at(obj_i) = true; + passthrough_object_flags.at(obj_i) = true; } } + + int64_t timestamp_nsec = + output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + passthrough_object_flags_map_.insert(std::make_pair(timestamp_nsec, passthrough_object_flags)); + fused_object_flags_map_.insert(std::make_pair(timestamp_nsec, fused_object_flags)); + ignored_object_flags_map_.insert(std::make_pair(timestamp_nsec, ignored_object_flags)); } void RoiDetectedObjectFusionNode::fuseOnSingleImage( @@ -58,8 +62,8 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( Eigen::Affine3d object2camera_affine; { const auto transform_stamped_optional = getTransformStamped( - tf_buffer_, /*target*/ camera_info.header.frame_id, - /*source*/ input_object_msg.header.frame_id, input_object_msg.header.stamp); + tf_buffer_, /*target*/ input_roi_msg.header.frame_id, + /*source*/ input_object_msg.header.frame_id, input_roi_msg.header.stamp); if (!transform_stamped_optional) { return; } @@ -73,9 +77,9 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( camera_info.p.at(11); const auto object_roi_map = generateDetectedObjectRoIs( - input_object_msg.objects, static_cast(camera_info.width), + input_object_msg, static_cast(camera_info.width), static_cast(camera_info.height), object2camera_affine, camera_projection); - fuseObjectsOnImage(input_object_msg.objects, input_roi_msg.feature_objects, object_roi_map); + fuseObjectsOnImage(input_object_msg, input_roi_msg.feature_objects, object_roi_map); if (debugger_) { debugger_->image_rois_.reserve(input_roi_msg.feature_objects.size()); @@ -87,17 +91,25 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( } std::map RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( - const std::vector & input_objects, const double image_width, - const double image_height, const Eigen::Affine3d & object2camera_affine, - const Eigen::Matrix4d & camera_projection) + const DetectedObjects & input_object_msg, const double image_width, const double image_height, + const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection) { std::map object_roi_map; - for (std::size_t obj_i = 0; obj_i < input_objects.size(); ++obj_i) { + int64_t timestamp_nsec = + input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + if (passthrough_object_flags_map_.size() == 0) { + return object_roi_map; + } + if (passthrough_object_flags_map_.count(timestamp_nsec) == 0) { + return object_roi_map; + } + const auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); + for (std::size_t obj_i = 0; obj_i < input_object_msg.objects.size(); ++obj_i) { std::vector vertices_camera_coord; { - const auto & object = input_objects.at(obj_i); + const auto & object = input_object_msg.objects.at(obj_i); - if (passthrough_object_flags_.at(obj_i)) { + if (passthrough_object_flags.at(obj_i)) { continue; } @@ -142,7 +154,7 @@ std::map RoiDetectedObjectFusionNode::generateDet } } } - if (point_on_image_cnt == 0) { + if (point_on_image_cnt == 3) { continue; } @@ -168,13 +180,26 @@ std::map RoiDetectedObjectFusionNode::generateDet } void RoiDetectedObjectFusionNode::fuseObjectsOnImage( - const std::vector & objects __attribute__((unused)), + const DetectedObjects & input_object_msg, const std::vector & image_rois, const std::map & object_roi_map) { + int64_t timestamp_nsec = + input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { + return; + } + if ( + fused_object_flags_map_.count(timestamp_nsec) == 0 || + ignored_object_flags_map_.count(timestamp_nsec) == 0) { + return; + } + auto & fused_object_flags = fused_object_flags_map_.at(timestamp_nsec); + auto & ignored_object_flags = ignored_object_flags_map_.at(timestamp_nsec); + for (const auto & object_pair : object_roi_map) { const auto & obj_i = object_pair.first; - if (fused_object_flags_.at(obj_i)) { + if (fused_object_flags.at(obj_i)) { continue; } @@ -192,15 +217,15 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( if (max_iou > fusion_params_.min_iou_threshold) { if (fusion_params_.use_roi_probability) { if (roi_prob > fusion_params_.roi_probability_threshold) { - fused_object_flags_.at(obj_i) = true; + fused_object_flags.at(obj_i) = true; } else { - ignored_object_flags_.at(obj_i) = true; + ignored_object_flags.at(obj_i) = true; } } else { - fused_object_flags_.at(obj_i) = true; + fused_object_flags.at(obj_i) = true; } } else { - ignored_object_flags_.at(obj_i) = true; + ignored_object_flags.at(obj_i) = true; } } } @@ -234,19 +259,37 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) return; } + int64_t timestamp_nsec = + output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + if ( + passthrough_object_flags_map_.size() == 0 || fused_object_flags_map_.size() == 0 || + ignored_object_flags_map_.size() == 0) { + return; + } + if ( + passthrough_object_flags_map_.count(timestamp_nsec) == 0 || + fused_object_flags_map_.count(timestamp_nsec) == 0 || + ignored_object_flags_map_.count(timestamp_nsec) == 0) { + return; + } + auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); + auto & fused_object_flags = fused_object_flags_map_.at(timestamp_nsec); + auto & ignored_object_flags = ignored_object_flags_map_.at(timestamp_nsec); + DetectedObjects output_objects_msg, debug_fused_objects_msg, debug_ignored_objects_msg; output_objects_msg.header = output_msg.header; debug_fused_objects_msg.header = output_msg.header; debug_ignored_objects_msg.header = output_msg.header; for (std::size_t obj_i = 0; obj_i < output_msg.objects.size(); ++obj_i) { const auto & obj = output_msg.objects.at(obj_i); - if (passthrough_object_flags_.at(obj_i)) { + if (passthrough_object_flags.at(obj_i)) { output_objects_msg.objects.emplace_back(obj); } - if (fused_object_flags_.at(obj_i)) { + if (fused_object_flags.at(obj_i)) { output_objects_msg.objects.emplace_back(obj); debug_fused_objects_msg.objects.emplace_back(obj); - } else if (ignored_object_flags_.at(obj_i)) { + } + if (ignored_object_flags.at(obj_i)) { debug_ignored_objects_msg.objects.emplace_back(obj); } } @@ -255,6 +298,10 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) debug_publisher_->publish("debug/fused_objects", debug_fused_objects_msg); debug_publisher_->publish("debug/ignored_objects", debug_ignored_objects_msg); + + passthrough_object_flags_map_.erase(timestamp_nsec); + fused_object_flags_map_.erase(timestamp_nsec); + fused_object_flags_map_.erase(timestamp_nsec); } } // namespace image_projection_based_fusion From 7502305eacad196ce7747b0c1d63cfa2715b37be Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Wed, 9 Aug 2023 01:56:04 +0900 Subject: [PATCH 131/266] refactor(mission_planner): use snake case instead of camel case (#4565) * feat(mission_planner): add a guard for rerouting while not follwoing lane Signed-off-by: yutaka * refactor(mission_planner): use snake case instead of camel case Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../src/mission_planner/mission_planner.cpp | 9 +++++---- .../src/mission_planner/mission_planner.hpp | 7 +++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 1d37b820efff1..08da1260b000c 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -75,6 +75,8 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) plugin_loader_("mission_planner", "mission_planner::PlannerPlugin"), tf_buffer_(get_clock()), tf_listener_(tf_buffer_), + odometry_(nullptr), + map_ptr_(nullptr), reroute_availability_(nullptr), normal_route_(nullptr), mrm_route_(nullptr) @@ -86,7 +88,6 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) planner_ = plugin_loader_.createSharedInstance("mission_planner::lanelet2::DefaultPlanner"); planner_->initialize(this); - odometry_ = nullptr; sub_odometry_ = create_subscription( "/localization/kinematic_state", rclcpp::QoS(1), std::bind(&MissionPlanner::on_odometry, this, std::placeholders::_1)); @@ -97,9 +98,9 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) std::bind(&MissionPlanner::on_reroute_availability, this, std::placeholders::_1)); auto qos_transient_local = rclcpp::QoS{1}.transient_local(); - vector_map_subscriber_ = create_subscription( + sub_vector_map_ = create_subscription( "input/vector_map", qos_transient_local, - std::bind(&MissionPlanner::onMap, this, std::placeholders::_1)); + std::bind(&MissionPlanner::on_map, this, std::placeholders::_1)); const auto durable_qos = rclcpp::QoS(1).transient_local(); pub_marker_ = create_publisher("debug/route_marker", durable_qos); @@ -141,7 +142,7 @@ void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSha reroute_availability_ = msg; } -void MissionPlanner::onMap(const HADMapBin::ConstSharedPtr msg) +void MissionPlanner::on_map(const HADMapBin::ConstSharedPtr msg) { map_ptr_ = msg; } diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 7b0427f6d01b1..fd1b317970749 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -73,11 +73,13 @@ class MissionPlanner : public rclcpp::Node PoseStamped transform_pose(const PoseStamped & input); rclcpp::Subscription::SharedPtr sub_odometry_; - rclcpp::Subscription::SharedPtr vector_map_subscriber_; + rclcpp::Subscription::SharedPtr sub_vector_map_; rclcpp::Subscription::SharedPtr sub_reroute_availability_; Odometry::ConstSharedPtr odometry_; + HADMapBin::ConstSharedPtr map_ptr_; RerouteAvailability::ConstSharedPtr reroute_availability_; void on_odometry(const Odometry::ConstSharedPtr msg); + void on_map(const HADMapBin::ConstSharedPtr msg); void on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg); rclcpp::Publisher::SharedPtr pub_marker_; @@ -126,9 +128,6 @@ class MissionPlanner : public rclcpp::Node const ClearMrmRoute::Service::Request::SharedPtr req, const ClearMrmRoute::Service::Response::SharedPtr res); - HADMapBin::ConstSharedPtr map_ptr_{nullptr}; - void onMap(const HADMapBin::ConstSharedPtr msg); - component_interface_utils::Subscription::SharedPtr sub_modified_goal_; void on_modified_goal(const ModifiedGoal::Message::ConstSharedPtr msg); void on_change_route( From a195b0530bb140f7c08c6c87df580b5d196230e2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 9 Aug 2023 03:56:13 +0900 Subject: [PATCH 132/266] feat(dynamic_avoidance): use hatched road markings (#4566) * feat(dynamic_avoidance): use hatched road markings Signed-off-by: Takayuki Murooka * add some ros parameters Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * remove comment Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 20 ++++++++++++---- .../dynamic_avoidance_module.hpp | 3 +++ .../dynamic_avoidance_module.cpp | 23 +++++++++++-------- .../dynamic_avoidance/manager.cpp | 10 ++++++++ 4 files changed, 42 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 336879185f48e..701f05eb89ba1 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -3,6 +3,7 @@ dynamic_avoidance: common: enable_debug_info: true + use_hatched_road_markings: true # avoidance is performed for the object type with true target_object: @@ -18,6 +19,7 @@ min_obstacle_vel: 0.0 # [m/s] successive_num_to_entry_dynamic_avoidance_condition: 5 + successive_num_to_exit_dynamic_avoidance_condition: 1 min_obj_lat_offset_to_ego_path: 0.0 # [m] max_obj_lat_offset_to_ego_path: 1.0 # [m] @@ -26,26 +28,34 @@ min_time_to_start_cut_in: 1.0 # [s] min_lon_offset_ego_to_object: 0.0 # [m] + cut_out_object: + max_time_from_outside_ego_path: 2.0 # [s] + min_object_lat_vel: 0.3 # [m/s] + crossing_object: - min_object_vel: 1.0 - max_object_angle: 1.05 + min_overtaking_object_vel: 1.0 + max_overtaking_object_angle: 1.05 + min_oncoming_object_vel: 0.0 + max_oncoming_object_angle: 0.523 front_object: max_object_angle: 0.785 drivable_area_generation: - lat_offset_from_obstacle: 1.0 # [m] + lat_offset_from_obstacle: 0.8 # [m] max_lat_offset_to_avoid: 0.5 # [m] + max_time_for_object_lat_shift: 2.0 # [s] + lpf_gain_for_lat_avoid_to_offset: 0.9 # [-] # for same directional object overtaking_object: - max_time_to_collision: 10.0 # [s] + max_time_to_collision: 40.0 # [s] start_duration_to_avoid: 2.0 # [s] end_duration_to_avoid: 4.0 # [s] duration_to_hold_avoidance: 3.0 # [s] # for opposite directional object oncoming_object: - max_time_to_collision: 15.0 # [s] + max_time_to_collision: 40.0 # [s] This value should be the same as overtaking_object's one to suppress chattering of this value for parked vehicles start_duration_to_avoid: 12.0 # [s] end_duration_to_avoid: 0.0 # [s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 087a39e87393a..de41fe9359bc2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -45,6 +45,7 @@ struct DynamicAvoidanceParameters { // common bool enable_debug_info{true}; + bool use_hatched_road_markings{true}; // obstacle types to avoid bool avoid_car{true}; @@ -75,6 +76,8 @@ struct DynamicAvoidanceParameters // drivable area generation double lat_offset_from_obstacle{0.0}; double max_lat_offset_to_avoid{0.0}; + double max_time_for_lat_shift{0.0}; + double lpf_gain_for_lat_avoid_to_offset{0.0}; double max_time_to_collision_overtaking_object{0.0}; double start_duration_to_avoid_overtaking_object{0.0}; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index e8570f0e310cf..b5ed7cc217a56 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -270,7 +270,6 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() debug_marker_.markers.clear(); const auto prev_module_path = getPreviousModuleOutput().path; - const auto drivable_lanes = getPreviousModuleOutput().drivable_area_info.drivable_lanes; // create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; @@ -285,11 +284,18 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() } } + DrivableAreaInfo current_drivable_area_info; + current_drivable_area_info.drivable_lanes = + getPreviousModuleOutput().drivable_area_info.drivable_lanes; + current_drivable_area_info.obstacles = obstacles_for_drivable_area; + current_drivable_area_info.enable_expanding_hatched_road_markings = + parameters_->use_hatched_road_markings; + BehaviorModuleOutput output; output.path = prev_module_path; + output.drivable_area_info = utils::combineDrivableAreaInfo( + current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); output.reference_path = getPreviousModuleOutput().reference_path; - output.drivable_area_info.drivable_lanes = drivable_lanes; - output.drivable_area_info.obstacles = obstacles_for_drivable_area; output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; return output; @@ -827,10 +833,9 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( // calculate bound min and max lateral offset const double min_bound_lat_offset = [&]() { - constexpr double object_time_to_shift = 2.0; const double lat_abs_offset_to_shift = std::max(0.0, obj_normal_vel * (is_collision_left ? -1.0 : 1.0)) * - object_time_to_shift; // TODO(murooka) use rosparam + parameters_->max_time_for_lat_shift; const double raw_min_bound_lat_offset = min_obj_lat_abs_offset - parameters_->lat_offset_from_obstacle - lat_abs_offset_to_shift; const double min_bound_lat_abs_offset_limit = @@ -850,10 +855,10 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( return prev_object->lat_offset_to_avoid.min_value; }(); const double filtered_min_bound_lat_offset = - prev_min_lat_avoid_to_offset - ? signal_processing::lowpassFilter( - min_bound_lat_offset, *prev_min_lat_avoid_to_offset, 0.5) // TODO(murooka) use rosparam - : min_bound_lat_offset; + prev_min_lat_avoid_to_offset ? signal_processing::lowpassFilter( + min_bound_lat_offset, *prev_min_lat_avoid_to_offset, + parameters_->lpf_gain_for_lat_avoid_to_offset) + : min_bound_lat_offset; return MinMaxValue{filtered_min_bound_lat_offset, max_bound_lat_offset}; } diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index e686719392e14..e378d43f6497c 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -32,6 +32,7 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( { // common std::string ns = "dynamic_avoidance.common."; p.enable_debug_info = node->declare_parameter(ns + "enable_debug_info"); + p.use_hatched_road_markings = node->declare_parameter(ns + "use_hatched_road_markings"); } { // target object @@ -82,6 +83,10 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( std::string ns = "dynamic_avoidance.drivable_area_generation."; p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); p.max_lat_offset_to_avoid = node->declare_parameter(ns + "max_lat_offset_to_avoid"); + p.max_time_for_lat_shift = + node->declare_parameter(ns + "max_time_for_object_lat_shift"); + p.lpf_gain_for_lat_avoid_to_offset = + node->declare_parameter(ns + "lpf_gain_for_lat_avoid_to_offset"); p.max_time_to_collision_overtaking_object = node->declare_parameter(ns + "overtaking_object.max_time_to_collision"); @@ -112,6 +117,7 @@ void DynamicAvoidanceModuleManager::updateModuleParams( { // common const std::string ns = "dynamic_avoidance.common."; updateParam(parameters, ns + "enable_debug_info", p->enable_debug_info); + updateParam(parameters, ns + "use_hatched_road_markings", p->use_hatched_road_markings); } { // target object @@ -174,6 +180,10 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam(parameters, ns + "lat_offset_from_obstacle", p->lat_offset_from_obstacle); updateParam(parameters, ns + "max_lat_offset_to_avoid", p->max_lat_offset_to_avoid); + updateParam( + parameters, ns + "max_time_for_object_lat_shift", p->max_time_for_lat_shift); + updateParam( + parameters, ns + "lpf_gain_for_lat_avoid_to_offset", p->lpf_gain_for_lat_avoid_to_offset); updateParam( parameters, ns + "overtaking_object.max_time_to_collision", From 9ac8faf5291337e072e9f22679dead91a9a26be8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 9 Aug 2023 03:56:29 +0900 Subject: [PATCH 133/266] fix(dynamic_avoidance): minor changes with bug fix (#4567) * feat(dynamic_avoidance): use hatched road markings Signed-off-by: Takayuki Murooka * add some ros parameters Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * remove comment Signed-off-by: Takayuki Murooka * feat(dynamic_avoidance): add minor changes Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 7 ++- .../dynamic_avoidance_module.cpp | 61 ++++++------------- 2 files changed, 21 insertions(+), 47 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index de41fe9359bc2..1f54786df83d7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -120,8 +120,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional latest_time_inside_ego_path{std::nullopt}; std::vector predicted_paths{}; - MinMaxValue lon_offset_to_avoid; - MinMaxValue lat_offset_to_avoid; + // NOTE: Previous values of the following are used for low-pass filtering. + // Therefore, they has to be initialized as nullopt. + std::optional lon_offset_to_avoid{std::nullopt}; + std::optional lat_offset_to_avoid{std::nullopt}; bool is_collision_left; bool should_be_avoided{false}; @@ -306,7 +308,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool isLabelTargetObstacle(const uint8_t label) const; void updateTargetObjects(); - std::optional> calcPathForObjectPolygon() const; bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index b5ed7cc217a56..7f69397cb3cf5 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -68,7 +68,7 @@ void appendExtractedPolygonMarker( auto marker = tier4_autoware_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "extracted_polygons", marker_array.markers.size(), visualization_msgs::msg::Marker::LINE_STRIP, - tier4_autoware_utils::createMarkerScale(0.05, 0.0, 0.0), + tier4_autoware_utils::createMarkerScale(0.1, 0.0, 0.0), tier4_autoware_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); // NOTE: obj_poly.outer() has already duplicated points to close the polygon. @@ -349,11 +349,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto prev_module_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; - const auto path_points_for_object_polygon = calcPathForObjectPolygon(); - if (!path_points_for_object_polygon) { - return; - } - + const auto path_points_for_object_polygon = getPreviousModuleOutput().reference_path->points; const auto prev_objects = target_objects_manager_.getValidObjects(); // 1. Rough filtering of target objects @@ -509,9 +505,9 @@ void DynamicAvoidanceModule::updateTargetObjects() // 2.g. calculate longitudinal and lateral offset to avoid const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - *path_points_for_object_polygon, object.pose, obj_points, object.vel, time_to_collision); + path_points_for_object_polygon, object.pose, obj_points, object.vel, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( - *path_points_for_object_polygon, obj_points, is_collision_left, object.lat_vel, prev_object); + path_points_for_object_polygon, obj_points, is_collision_left, object.lat_vel, prev_object); const bool should_be_avoided = true; target_objects_manager_.updateObject( @@ -519,30 +515,6 @@ void DynamicAvoidanceModule::updateTargetObjects() } } -std::optional> DynamicAvoidanceModule::calcPathForObjectPolygon() - const -{ - const auto & ego_pose = getEgoPose(); - const auto & rh = planner_data_->route_handler; - - // get path with backward margin - lanelet::ConstLanelet current_lane; - if (!rh->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("dynamic_avoidance"), - "failed to find closest lanelet within route!!!"); - return std::nullopt; - } - - constexpr double forward_length = 100.0; - const double backward_length = 50.0; - const auto current_lanes = - rh->getLaneletSequence(current_lane, ego_pose, backward_length, forward_length); - const auto path = utils::getCenterLinePath( - *rh, current_lanes, ego_pose, backward_length, forward_length, planner_data_->parameters); - return path.points; -} - [[maybe_unused]] std::optional> DynamicAvoidanceModule::calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const @@ -849,10 +821,10 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( // filter min_bound_lat_offset const auto prev_min_lat_avoid_to_offset = [&]() -> std::optional { - if (!prev_object) { + if (!prev_object || !prev_object->lat_offset_to_avoid) { return std::nullopt; } - return prev_object->lat_offset_to_avoid.min_value; + return prev_object->lat_offset_to_avoid->min_value; }(); const double filtered_min_bound_lat_offset = prev_min_lat_avoid_to_offset ? signal_processing::lowpassFilter( @@ -867,22 +839,23 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { - auto path_points_for_object_polygon = calcPathForObjectPolygon(); - if (!path_points_for_object_polygon) { + if (!object.lon_offset_to_avoid || !object.lat_offset_to_avoid) { return std::nullopt; } + auto path_points_for_object_polygon = getPreviousModuleOutput().reference_path->points; + const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(*path_points_for_object_polygon, object.pose.position); + motion_utils::findNearestSegmentIndex(path_points_for_object_polygon, object.pose.position); const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( - obj_seg_idx, object.lon_offset_to_avoid.min_value, *path_points_for_object_polygon); + obj_seg_idx, object.lon_offset_to_avoid->min_value, path_points_for_object_polygon); const size_t updated_obj_seg_idx = (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 : obj_seg_idx; const auto lon_bound_end_idx_opt = motion_utils::insertTargetPoint( - updated_obj_seg_idx, object.lon_offset_to_avoid.max_value, *path_points_for_object_polygon); + updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, path_points_for_object_polygon); if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { // NOTE: The obstacle is longitudinally out of the ego's trajectory. @@ -892,19 +865,19 @@ std::optional DynamicAvoidanceModule::calcDynam lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); const size_t lon_bound_end_idx = lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() - : static_cast(path_points_for_object_polygon->size() - 1); + : static_cast(path_points_for_object_polygon.size() - 1); // create inner/outer bound points std::vector obj_inner_bound_points; std::vector obj_outer_bound_points; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { obj_inner_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( - path_points_for_object_polygon->at(i).point.pose, 0.0, - object.lat_offset_to_avoid.min_value, 0.0) + path_points_for_object_polygon.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->min_value, 0.0) .position); obj_outer_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( - path_points_for_object_polygon->at(i).point.pose, 0.0, - object.lat_offset_to_avoid.max_value, 0.0) + path_points_for_object_polygon.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->max_value, 0.0) .position); } From 2a4363ef7b9953bdea8057e72eda2b3e9a6c69a1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 10:56:21 +0900 Subject: [PATCH 134/266] feat(goal_planner): visualize freespace current goal candidate idx (#4571) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 15 +++++++++++++++ .../goal_planner/goal_planner_module.cpp | 18 +++++++++++++++++- 2 files changed, 32 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 2bf589a122087..8d9c8e147f532 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -83,6 +83,18 @@ struct PUllOverStatus bool is_ready{false}; }; +struct FreespacePlannerDebugData +{ + bool is_planning{false}; + size_t current_goal_idx{0}; + size_t num_goal_candidates{0}; +}; + +struct GoalPlannerDebugData +{ + FreespacePlannerDebugData freespace_planner{}; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -176,6 +188,9 @@ class GoalPlannerModule : public SceneModuleInterface rclcpp::TimerBase::SharedPtr freespace_parking_timer_; rclcpp::CallbackGroup::SharedPtr freespace_parking_timer_cb_group_; + // debug + mutable GoalPlannerDebugData debug_data_; + // collision check void initializeOccupancyGridMap(); void updateOccupancyGrid(); diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index b8219c5057f1d..cb790cff2ce30 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -419,9 +419,16 @@ bool GoalPlannerModule::planFreespacePath() mutex_.lock(); goal_searcher_->update(goal_candidates_); const auto goal_candidates = goal_candidates_; + debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); + debug_data_.freespace_planner.is_planning = true; mutex_.unlock(); - for (const auto & goal_candidate : goal_candidates) { + for (size_t i = 0; i < goal_candidates.size(); i++) { + const auto goal_candidate = goal_candidates.at(i); + mutex_.lock(); + debug_data_.freespace_planner.current_goal_idx = i; + mutex_.unlock(); + if (!goal_candidate.is_safe) { continue; } @@ -437,9 +444,12 @@ bool GoalPlannerModule::planFreespacePath() status_.is_safe = true; modified_goal_pose_ = goal_candidate; last_path_update_time_ = std::make_unique(clock_->now()); + debug_data_.freespace_planner.is_planning = false; mutex_.unlock(); return true; } + + debug_data_.freespace_planner.is_planning = false; return false; } @@ -1492,6 +1502,12 @@ void GoalPlannerModule::setDebugData() marker.text += " stopped"; } + if (debug_data_.freespace_planner.is_planning) { + marker.text += + " freespace: " + std::to_string(debug_data_.freespace_planner.current_goal_idx) + "/" + + std::to_string(debug_data_.freespace_planner.num_goal_candidates); + } + planner_type_marker_array.markers.push_back(marker); add(planner_type_marker_array); } From d9fabeead1aa56c88d6befb60c67e042db1ee408 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 9 Aug 2023 10:56:58 +0900 Subject: [PATCH 135/266] fix(route_handler): fix getRouteUuid to return initial value when route is not set (#4568) Signed-off-by: kosuke55 --- planning/route_handler/src/route_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index f3270dac1d722..4e009836b53d4 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -367,7 +367,7 @@ UUID RouteHandler::getRouteUuid() const { if (!route_ptr_) { RCLCPP_WARN(logger_, "[Route Handler] getRouteUuid: Route has not been set yet"); - UUID(); + return UUID(); } return route_ptr_->uuid; } From cdd5ec87c17e391fcf7a4fa1d9916159ab7fa50b Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Wed, 9 Aug 2023 12:27:10 +0900 Subject: [PATCH 136/266] chore(image_projection_based_fusion): change to throttle log (#4572) * fix(image_projection_based_fusion): fix to throttle log Signed-off-by: Makoto Kurihara * style(pre-commit): autofix --------- Signed-off-by: Makoto Kurihara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../image_projection_based_fusion/src/fusion_node.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 9ce34d8482fbd..1bc351b08c01b 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -205,7 +205,8 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ // if matching rois exist, fuseOnSingle for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { - RCLCPP_WARN(this->get_logger(), "no camera info. id is %zu", roi_i); + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); continue; } @@ -298,7 +299,8 @@ void FusionNode::roiCallback( if (interval < match_threshold_ms_ * (int64_t)1e6 && is_fused_.at(roi_i) == false) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { - RCLCPP_WARN(this->get_logger(), "no camera info. id is %zu", roi_i); + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); (roi_stdmap_.at(roi_i))[timestamp_nsec] = input_roi_msg; return; } From 43f73f86ba69f594ee83300b14ab637311216d05 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 9 Aug 2023 14:30:36 +0900 Subject: [PATCH 137/266] feat(planning_debug_tools): add perception_replayer.py (#4574) * refactor perception_reproducer Signed-off-by: Takayuki Murooka * implement perception_reproducer Signed-off-by: Takayuki Murooka * change permission Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/planning_debug_tools/CMakeLists.txt | 3 +- planning/planning_debug_tools/Readme.md | 32 +- .../perception_replayer.py | 125 +++++++ .../perception_replayer_common.py | 156 ++++++++ .../perception_reproducer.py | 117 ++++++ .../time_manager_widget.py | 54 +++ .../scripts/perception_replayer/utils.py | 125 +++++++ .../scripts/perception_reproducer.py | 338 ------------------ 8 files changed, 610 insertions(+), 340 deletions(-) create mode 100755 planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py create mode 100644 planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py create mode 100755 planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py create mode 100644 planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py create mode 100644 planning/planning_debug_tools/scripts/perception_replayer/utils.py delete mode 100755 planning/planning_debug_tools/scripts/perception_reproducer.py diff --git a/planning/planning_debug_tools/CMakeLists.txt b/planning/planning_debug_tools/CMakeLists.txt index c2bee10f972f1..bf7e36c4c0c0a 100644 --- a/planning/planning_debug_tools/CMakeLists.txt +++ b/planning/planning_debug_tools/CMakeLists.txt @@ -50,6 +50,7 @@ ament_auto_package( install(PROGRAMS scripts/trajectory_visualizer.py scripts/closest_velocity_checker.py - scripts/perception_reproducer.py + scripts/perception_replayer/perception_reproducer.py + scripts/perception_replayer/perception_replayer.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/planning/planning_debug_tools/Readme.md b/planning/planning_debug_tools/Readme.md index 6d4958783f86d..fe9615614de81 100644 --- a/planning/planning_debug_tools/Readme.md +++ b/planning/planning_debug_tools/Readme.md @@ -188,7 +188,7 @@ PlotCurrentVelocity('localization_kinematic_state', '/localization/kinematic_sta ## Perception reproducer -This script can overlay the perception results from the rosbag on the planning simulator. +This script can overlay the perception results from the rosbag on the planning simulator synchronized with the simulator's ego pose. In detail, the ego pose in the rosbag which is closest to the current ego pose in the simulator is calculated. The perception results at the timestamp of the closest ego pose is extracted, and published. @@ -211,3 +211,33 @@ ros2 run planning_debug_tools perception_reproducer.py -b ``` Instead of publishing predicted objects, you can publish detected/tracked objects by designating `-d` or `-t`, respectively. + +## Perception replayer + +A part of the feature is under development. + +This script can overlay the perception results from the rosbag on the planning simulator. + +In detail, this script publishes the data at a certain timestamp from the rosbag. +The timestamp will increase according to the real time without any operation. +By using the GUI, you can modify the timestamp by pausing, changing the rate or going back into the past. + +### How to use + +First, launch the planning simulator, and put the ego pose. +Then, run the script according to the following command. + +By designating a rosbag, perception replayer can be launched. +The GUI is launched as well with which a timestamp of rosbag can be managed. + +```bash +ros2 run planning_debug_tools perception_replayer.py -b +``` + +You can designate multiple rosbags in the directory. + +```bash +ros2 run planning_debug_tools perception_replayer.py -b +``` + +Instead of publishing predicted objects, you can publish detected/tracked objects by designating `-d` or `-t`, respectively. diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py new file mode 100755 index 0000000000000..e54458fee8f69 --- /dev/null +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python3 + +# Copyright 2023 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. + +import argparse +import copy +import functools +import sys + +from PyQt5.QtWidgets import QApplication +from perception_replayer_common import PerceptionReplayerCommon +import rclpy +from time_manager_widget import TimeManagerWidget +from utils import create_empty_pointcloud +from utils import translate_objects_coordinate + + +class PerceptionReplayer(PerceptionReplayerCommon): + def __init__(self, args): + super().__init__(args, "perception_replayer") + + self.bag_timestamp = self.rosbag_objects_data[0][0] + self.is_pause = False + self.rate = 1.0 + + # initialize widget + self.widget = TimeManagerWidget() + self.widget.show() + self.widget.button.clicked.connect(self.onPushed) + for button in self.widget.rate_button: + button.clicked.connect(functools.partial(self.onSetRate, button)) + + # start timer callback + self.delta_time = 0.1 + self.timer = self.create_timer(self.delta_time, self.on_timer) + print("Start timer callback") + + def on_timer(self): + timestamp = self.get_clock().now().to_msg() + + self.kill_online_perception_node() + + if self.args.detected_object: + pointcloud_msg = create_empty_pointcloud(timestamp) + self.pointcloud_pub.publish(pointcloud_msg) + + # step timestamp + if not self.is_pause: + self.bag_timestamp += self.rate * self.delta_time * 1e9 # seconds to timestamp + + # extract message by the timestamp + msgs = copy.deepcopy(self.find_topics_by_timestamp(self.bag_timestamp)) + objects_msg = msgs[0] + traffic_signals_msg = msgs[1] + + # objects + if objects_msg: + objects_msg.header.stamp = timestamp + if self.args.detected_object: + if not self.ego_pose: + print("No ego pose found.") + return + + ego_odom = self.find_ego_odom_by_timestamp(self.bag_timestamp) + log_ego_pose = ego_odom[1].pose.pose + + translate_objects_coordinate(self.ego_pose, log_ego_pose, objects_msg) + self.objects_pub.publish(objects_msg) + + # traffic signals + if traffic_signals_msg: + traffic_signals_msg.header.stamp = timestamp + self.traffic_signals_pub.publish(traffic_signals_msg) + self.prev_traffic_signals_msg = traffic_signals_msg + elif self.prev_traffic_signals_msg: + self.prev_traffic_signals_msg.header.stamp = timestamp + self.traffic_signals_pub.publish(self.prev_traffic_signals_msg) + + def onPushed(self, event): + if self.widget.button.isChecked(): + self.is_pause = True + else: + self.is_pause = False + + def onSetRate(self, button): + self.rate = float(button.text()) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-b", "--bag", help="rosbag", default=None) + parser.add_argument( + "-d", "--detected-object", help="publish detected object", action="store_true" + ) + parser.add_argument( + "-t", "--tracked-object", help="publish tracked object", action="store_true" + ) + args = parser.parse_args() + + app = QApplication(sys.argv) + + rclpy.init() + node = PerceptionReplayer(args) + + try: + while True: + app.processEvents() + rclpy.spin_once(node, timeout_sec=0.01) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py new file mode 100644 index 0000000000000..a86a9ae9b2bb0 --- /dev/null +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py @@ -0,0 +1,156 @@ +#!/usr/bin/env python3 + +# Copyright 2023 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. + +import os +from subprocess import CalledProcessError +from subprocess import check_output +import time + +from autoware_auto_perception_msgs.msg import DetectedObjects +from autoware_auto_perception_msgs.msg import PredictedObjects +from autoware_auto_perception_msgs.msg import TrackedObjects +from autoware_auto_perception_msgs.msg import TrafficSignalArray +from nav_msgs.msg import Odometry +import psutil +from rclpy.node import Node +from rclpy.serialization import deserialize_message +from rosbag2_py import StorageFilter +from rosidl_runtime_py.utilities import get_message +from sensor_msgs.msg import PointCloud2 +from utils import open_reader + + +class PerceptionReplayerCommon(Node): + def __init__(self, args, name): + super().__init__(name) + self.args = args + + self.ego_pose = None + self.rosbag_objects_data = [] + self.rosbag_ego_odom_data = [] + self.rosbag_traffic_signals_data = [] + + # subscriber + self.sub_odom = self.create_subscription( + Odometry, "/localization/kinematic_state", self.on_odom, 1 + ) + + # publisher + if self.args.detected_object: + self.objects_pub = self.create_publisher( + DetectedObjects, "/perception/object_recognition/detection/objects", 1 + ) + elif self.args.tracked_object: + self.objects_pub = self.create_publisher( + TrackedObjects, "/perception/object_recognition/tracking/objects", 1 + ) + else: + self.objects_pub = self.create_publisher( + PredictedObjects, "/perception/object_recognition/objects", 1 + ) + + self.pointcloud_pub = self.create_publisher( + PointCloud2, "/perception/obstacle_segmentation/pointcloud", 1 + ) + self.traffic_signals_pub = self.create_publisher( + TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 + ) + + # load rosbag + print("Stared loading rosbag") + if os.path.isdir(args.bag): + for bag_file in sorted(os.listdir(args.bag)): + self.load_rosbag(args.bag + "/" + bag_file) + else: + self.load_rosbag(args.bag) + print("Ended loading rosbag") + + # wait for ready to publish/subscribe + time.sleep(1.0) + + def on_odom(self, odom): + self.ego_pose = odom.pose.pose + + def load_rosbag(self, rosbag2_path: str): + reader = open_reader(str(rosbag2_path)) + + topic_types = reader.get_all_topics_and_types() + # Create a map for quicker lookup + type_map = {topic_types[i].name: topic_types[i].type for i in range(len(topic_types))} + + objects_topic = ( + "/perception/object_recognition/detection/objects" + if self.args.detected_object + else "/perception/object_recognition/tracking/objects" + if self.args.tracked_object + else "/perception/object_recognition/objects" + ) + ego_odom_topic = "/localization/kinematic_state" + traffic_signals_topic = "/perception/traffic_light_recognition/traffic_signals" + topic_filter = StorageFilter(topics=[objects_topic, ego_odom_topic, traffic_signals_topic]) + reader.set_filter(topic_filter) + + while reader.has_next(): + (topic, data, stamp) = reader.read_next() + msg_type = get_message(type_map[topic]) + msg = deserialize_message(data, msg_type) + if topic == objects_topic: + self.rosbag_objects_data.append((stamp, msg)) + if topic == ego_odom_topic: + self.rosbag_ego_odom_data.append((stamp, msg)) + if topic == traffic_signals_topic: + self.rosbag_traffic_signals_data.append((stamp, msg)) + + def kill_online_perception_node(self): + # kill node if required + kill_process_name = None + if self.args.detected_object: + kill_process_name = "dummy_perception_publisher_node" + elif self.args.tracked_object: + kill_process_name = "multi_object_tracker" + else: + kill_process_name = "map_based_prediction" + if kill_process_name: + try: + pid = check_output(["pidof", kill_process_name]) + process = psutil.Process(int(pid[:-1])) + process.terminate() + except CalledProcessError: + pass + + def find_topics_by_timestamp(self, timestamp): + objects_data = None + for data in self.rosbag_objects_data: + if timestamp < data[0]: + objects_data = data[1] + break + + traffic_signals_data = None + for data in self.rosbag_traffic_signals_data: + if timestamp < data[0]: + traffic_signals_data = data[1] + break + + return objects_data, traffic_signals_data + + def find_ego_odom_by_timestamp(self, timestamp): + ego_odom_data = None + for data in self.rosbag_ego_odom_data: + if timestamp < data[0]: + ego_odom_data = data[1] + break + + return ego_odom_data diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py new file mode 100755 index 0000000000000..36b62bc1ec5ee --- /dev/null +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -0,0 +1,117 @@ +#!/usr/bin/env python3 + +# Copyright 2023 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. + +import argparse +import copy + +from perception_replayer_common import PerceptionReplayerCommon +import rclpy +from utils import calc_squared_distance +from utils import create_empty_pointcloud +from utils import translate_objects_coordinate + + +class PerceptionReproducer(PerceptionReplayerCommon): + def __init__(self, args): + super().__init__(args, "perception_reproducer") + + self.ego_pose_idx = None + self.prev_traffic_signals_msg = None + + # start timer callback + self.timer = self.create_timer(0.01, self.on_timer) + print("Start timer callback") + + def on_timer(self): + timestamp = self.get_clock().now().to_msg() + + self.kill_online_perception_node() + + if self.args.detected_object: + pointcloud_msg = create_empty_pointcloud(timestamp) + self.pointcloud_pub.publish(pointcloud_msg) + + if not self.ego_pose: + print("No ego pose found.") + return + + # find nearest ego odom by simulation observation + ego_odom = self.find_nearest_ego_odom_by_observation(self.ego_pose) + pose_timestamp = ego_odom[0] + log_ego_pose = ego_odom[1].pose.pose + + # extract message by the nearest ego odom timestamp + msgs = copy.deepcopy(self.find_topics_by_timestamp(pose_timestamp)) + objects_msg = msgs[0] + traffic_signals_msg = msgs[1] + + # objects + if objects_msg: + objects_msg.header.stamp = timestamp + if self.args.detected_object: + translate_objects_coordinate(self.ego_pose, log_ego_pose, objects_msg) + self.objects_pub.publish(objects_msg) + + # traffic signals + if traffic_signals_msg: + traffic_signals_msg.header.stamp = timestamp + self.traffic_signals_pub.publish(traffic_signals_msg) + self.prev_traffic_signals_msg = traffic_signals_msg + elif self.prev_traffic_signals_msg: + self.prev_traffic_signals_msg.header.stamp = timestamp + self.traffic_signals_pub.publish(self.prev_traffic_signals_msg) + + def find_nearest_ego_odom_by_observation(self, ego_pose): + if self.ego_pose_idx: + start_idx = self.ego_pose_idx - 10 + end_idx = self.ego_pose_idx + 10 + else: + start_idx = 0 + end_idx = len(self.rosbag_ego_odom_data) - 1 + + nearest_idx = 0 + nearest_dist = float("inf") + for idx in range(start_idx, end_idx + 1): + data = self.rosbag_ego_odom_data[idx] + dist = calc_squared_distance(data[1].pose.pose.position, ego_pose.position) + if dist < nearest_dist: + nearest_dist = dist + nearest_idx = idx + + return self.rosbag_ego_odom_data[nearest_idx] + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-b", "--bag", help="rosbag", default=None) + parser.add_argument( + "-d", "--detected-object", help="publish detected object", action="store_true" + ) + parser.add_argument( + "-t", "--tracked-object", help="publish tracked object", action="store_true" + ) + args = parser.parse_args() + + rclpy.init() + node = PerceptionReproducer(args) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() diff --git a/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py new file mode 100644 index 0000000000000..77bf65a17b848 --- /dev/null +++ b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python3 + +# Copyright 2023 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. + +from PyQt5 import QtCore +from PyQt5.QtWidgets import QGridLayout +from PyQt5.QtWidgets import QMainWindow +from PyQt5.QtWidgets import QPushButton +from PyQt5.QtWidgets import QSizePolicy +from PyQt5.QtWidgets import QWidget + + +class TimeManagerWidget(QMainWindow): + def __init__(self): + super(self.__class__, self).__init__() + self.setupUI() + + def setupUI(self): + self.setObjectName("PerceptionReplayer") + self.resize(480, 120) + self.setWindowFlags(QtCore.Qt.WindowStaysOnTopHint) + + self.central_widget = QWidget(self) + self.central_widget.setObjectName("central_widget") + + self.grid_layout = QGridLayout(self.central_widget) + self.grid_layout.setContentsMargins(10, 10, 10, 10) + self.grid_layout.setObjectName("grid_layout") + + self.rate_button = [] + for i, rate in enumerate([0.1, 0.5, 1.0, 2.0, 5.0, 10.0]): + button = QPushButton(str(rate)) + button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + self.rate_button.append(button) + self.grid_layout.addWidget(self.rate_button[-1], 0, i, 1, 1) + + self.button = QPushButton("pause") + self.button.setCheckable(True) + self.button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + + self.grid_layout.addWidget(self.button, 1, 0, 1, -1) + self.setCentralWidget(self.central_widget) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/utils.py b/planning/planning_debug_tools/scripts/perception_replayer/utils.py new file mode 100644 index 0000000000000..572922d4c7abb --- /dev/null +++ b/planning/planning_debug_tools/scripts/perception_replayer/utils.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python3 + +# Copyright 2023 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. + +import math + +from geometry_msgs.msg import Quaternion +import numpy as np +import rosbag2_py +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from tf_transformations import euler_from_quaternion +from tf_transformations import quaternion_from_euler + + +def get_rosbag_options(path, serialization_format="cdr"): + storage_options = rosbag2_py.StorageOptions(uri=path, storage_id="sqlite3") + + converter_options = rosbag2_py.ConverterOptions( + input_serialization_format=serialization_format, + output_serialization_format=serialization_format, + ) + + return storage_options, converter_options + + +def open_reader(path: str): + storage_options, converter_options = get_rosbag_options(path) + reader = rosbag2_py.SequentialReader() + reader.open(storage_options, converter_options) + return reader + + +def calc_squared_distance(p1, p2): + return math.sqrt((p1.x - p2.x) ** 2 + (p1.y - p2.y) ** 2) + + +def create_empty_pointcloud(timestamp): + pointcloud_msg = PointCloud2() + pointcloud_msg.header.stamp = timestamp + pointcloud_msg.header.frame_id = "map" + pointcloud_msg.height = 1 + pointcloud_msg.is_dense = True + pointcloud_msg.point_step = 16 + field_name_vec = ["x", "y", "z"] + offset_vec = [0, 4, 8] + for field_name, offset in zip(field_name_vec, offset_vec): + field = PointField() + field.name = field_name + field.offset = offset + field.datatype = 7 + field.count = 1 + pointcloud_msg.fields.append(field) + return pointcloud_msg + + +def get_yaw_from_quaternion(orientation): + orientation_list = [ + orientation.x, + orientation.y, + orientation.z, + orientation.w, + ] + return euler_from_quaternion(orientation_list)[2] + + +def get_quaternion_from_yaw(yaw): + q = quaternion_from_euler(0, 0, yaw) + orientation = Quaternion() + orientation.x = q[0] + orientation.y = q[1] + orientation.z = q[2] + orientation.w = q[3] + return orientation + + +def translate_objects_coordinate(ego_pose, log_ego_pose, objects_msg): + log_ego_yaw = get_yaw_from_quaternion(log_ego_pose.orientation) + log_ego_pose_trans_mat = np.array( + [ + [ + math.cos(log_ego_yaw), + -math.sin(log_ego_yaw), + log_ego_pose.position.x, + ], + [math.sin(log_ego_yaw), math.cos(log_ego_yaw), log_ego_pose.position.y], + [0.0, 0.0, 1.0], + ] + ) + + ego_yaw = get_yaw_from_quaternion(ego_pose.orientation) + ego_pose_trans_mat = np.array( + [ + [math.cos(ego_yaw), -math.sin(ego_yaw), ego_pose.position.x], + [math.sin(ego_yaw), math.cos(ego_yaw), ego_pose.position.y], + [0.0, 0.0, 1.0], + ] + ) + + for o in objects_msg.objects: + log_object_pose = o.kinematics.pose_with_covariance.pose + log_object_yaw = get_yaw_from_quaternion(log_object_pose.orientation) + log_object_pos_vec = np.array([log_object_pose.position.x, log_object_pose.position.y, 1.0]) + + # translate object pose from ego pose in log to ego pose in simulation + object_pos_vec = np.linalg.inv(ego_pose_trans_mat).dot( + log_ego_pose_trans_mat.dot(log_object_pos_vec.T) + ) + + object_pose = o.kinematics.pose_with_covariance.pose + object_pose.position.x = object_pos_vec[0] + object_pose.position.y = object_pos_vec[1] + object_pose.orientation = get_quaternion_from_yaw(log_object_yaw + log_ego_yaw - ego_yaw) diff --git a/planning/planning_debug_tools/scripts/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_reproducer.py deleted file mode 100755 index 5fc367665e256..0000000000000 --- a/planning/planning_debug_tools/scripts/perception_reproducer.py +++ /dev/null @@ -1,338 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 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. - -import argparse -import copy -import math -import os -from subprocess import CalledProcessError -from subprocess import check_output -import time - -from autoware_auto_perception_msgs.msg import DetectedObjects -from autoware_auto_perception_msgs.msg import PredictedObjects -from autoware_auto_perception_msgs.msg import TrackedObjects -from autoware_auto_perception_msgs.msg import TrafficSignalArray -from geometry_msgs.msg import Quaternion -from nav_msgs.msg import Odometry -import numpy as np -import psutil -import rclpy -from rclpy.node import Node -from rclpy.serialization import deserialize_message -import rosbag2_py -from rosbag2_py import StorageFilter -from rosidl_runtime_py.utilities import get_message -from sensor_msgs.msg import PointCloud2 -from sensor_msgs.msg import PointField -from tf_transformations import euler_from_quaternion -from tf_transformations import quaternion_from_euler - - -def get_rosbag_options(path, serialization_format="cdr"): - storage_options = rosbag2_py.StorageOptions(uri=path, storage_id="sqlite3") - - converter_options = rosbag2_py.ConverterOptions( - input_serialization_format=serialization_format, - output_serialization_format=serialization_format, - ) - - return storage_options, converter_options - - -def open_reader(path: str): - storage_options, converter_options = get_rosbag_options(path) - reader = rosbag2_py.SequentialReader() - reader.open(storage_options, converter_options) - return reader - - -def calc_squared_distance(p1, p2): - return math.sqrt((p1.x - p2.x) ** 2 + (p1.y - p2.y) ** 2) - - -def create_empty_pointcloud(timestamp): - pointcloud_msg = PointCloud2() - pointcloud_msg.header.stamp = timestamp - pointcloud_msg.header.frame_id = "map" - pointcloud_msg.height = 1 - pointcloud_msg.is_dense = True - pointcloud_msg.point_step = 16 - field_name_vec = ["x", "y", "z"] - offset_vec = [0, 4, 8] - for field_name, offset in zip(field_name_vec, offset_vec): - field = PointField() - field.name = field_name - field.offset = offset - field.datatype = 7 - field.count = 1 - pointcloud_msg.fields.append(field) - return pointcloud_msg - - -def get_yaw_from_quaternion(orientation): - orientation_list = [ - orientation.x, - orientation.y, - orientation.z, - orientation.w, - ] - return euler_from_quaternion(orientation_list)[2] - - -def get_quaternion_from_yaw(yaw): - q = quaternion_from_euler(0, 0, yaw) - orientation = Quaternion() - orientation.x = q[0] - orientation.y = q[1] - orientation.z = q[2] - orientation.w = q[3] - return orientation - - -class PerceptionReproducer(Node): - def __init__(self, args): - super().__init__("perception_reproducer") - self.args = args - - # subscriber - self.sub_odom = self.create_subscription( - Odometry, "/localization/kinematic_state", self.on_odom, 1 - ) - - # publisher - if self.args.detected_object: - self.objects_pub = self.create_publisher( - DetectedObjects, "/perception/object_recognition/detection/objects", 1 - ) - elif self.args.tracked_object: - self.objects_pub = self.create_publisher( - TrackedObjects, "/perception/object_recognition/tracking/objects", 1 - ) - else: - self.objects_pub = self.create_publisher( - PredictedObjects, "/perception/object_recognition/objects", 1 - ) - - self.pointcloud_pub = self.create_publisher( - PointCloud2, "/perception/obstacle_segmentation/pointcloud", 1 - ) - self.traffic_signals_pub = self.create_publisher( - TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 - ) - - self.ego_pose_idx = None - self.ego_pose = None - - self.prev_traffic_signals_msg = None - - self.rosbag_objects_data = [] - self.rosbag_ego_odom_data = [] - self.rosbag_traffic_signals_data = [] - - # load rosbag - print("Stared loading rosbag") - if os.path.isdir(args.bag): - for bag_file in sorted(os.listdir(args.bag)): - self.load_rosbag(args.bag + "/" + bag_file) - else: - self.load_rosbag(args.bag) - print("Ended loading rosbag") - - # wait for ready to publish/subscribe - time.sleep(1.0) - - self.timer = self.create_timer(0.01, self.on_timer) - print("Start timer callback") - - def on_odom(self, odom): - self.ego_pose = odom.pose.pose - - def on_timer(self): - # kill node if required - kill_process_name = None - if self.args.detected_object: - kill_process_name = "dummy_perception_publisher_node" - elif self.args.tracked_object: - kill_process_name = "multi_object_tracker" - else: - kill_process_name = "map_based_prediction" - if kill_process_name: - try: - pid = check_output(["pidof", kill_process_name]) - process = psutil.Process(int(pid[:-1])) - process.terminate() - except CalledProcessError: - pass - - timestamp = self.get_clock().now().to_msg() - - if self.args.detected_object: - pointcloud_msg = create_empty_pointcloud(timestamp) - self.pointcloud_pub.publish(pointcloud_msg) - - if self.ego_pose: - ego_odom = self.find_nearest_ego_odom_by_observation(self.ego_pose) - pose_timestamp = ego_odom[0] - log_ego_pose = ego_odom[1].pose.pose - - msgs = copy.deepcopy(self.find_topics_by_timestamp(pose_timestamp)) - objects_msg = msgs[0] - traffic_signals_msg = msgs[1] - if objects_msg: - objects_msg.header.stamp = timestamp - if self.args.detected_object: - log_ego_yaw = get_yaw_from_quaternion(log_ego_pose.orientation) - log_ego_pose_trans_mat = np.array( - [ - [ - math.cos(log_ego_yaw), - -math.sin(log_ego_yaw), - log_ego_pose.position.x, - ], - [math.sin(log_ego_yaw), math.cos(log_ego_yaw), log_ego_pose.position.y], - [0.0, 0.0, 1.0], - ] - ) - - ego_yaw = get_yaw_from_quaternion(self.ego_pose.orientation) - ego_pose_trans_mat = np.array( - [ - [math.cos(ego_yaw), -math.sin(ego_yaw), self.ego_pose.position.x], - [math.sin(ego_yaw), math.cos(ego_yaw), self.ego_pose.position.y], - [0.0, 0.0, 1.0], - ] - ) - - for o in objects_msg.objects: - log_object_pose = o.kinematics.pose_with_covariance.pose - log_object_yaw = get_yaw_from_quaternion(log_object_pose.orientation) - log_object_pos_vec = np.array( - [log_object_pose.position.x, log_object_pose.position.y, 1.0] - ) - - # translate object pose from ego pose in log to ego pose in simulation - object_pos_vec = np.linalg.inv(ego_pose_trans_mat).dot( - log_ego_pose_trans_mat.dot(log_object_pos_vec.T) - ) - - object_pose = o.kinematics.pose_with_covariance.pose - object_pose.position.x = object_pos_vec[0] - object_pose.position.y = object_pos_vec[1] - object_pose.orientation = get_quaternion_from_yaw( - log_object_yaw + log_ego_yaw - ego_yaw - ) - - self.objects_pub.publish(objects_msg) - if traffic_signals_msg: - traffic_signals_msg.header.stamp = timestamp - self.traffic_signals_pub.publish(traffic_signals_msg) - self.prev_traffic_signals_msg = traffic_signals_msg - elif self.prev_traffic_signals_msg: - self.prev_traffic_signals_msg.header.stamp = timestamp - self.traffic_signals_pub.publish(self.prev_traffic_signals_msg) - else: - print("No ego pose found.") - - def find_nearest_ego_odom_by_observation(self, ego_pose): - if self.ego_pose_idx: - start_idx = self.ego_pose_idx - 10 - end_idx = self.ego_pose_idx + 10 - else: - start_idx = 0 - end_idx = len(self.rosbag_ego_odom_data) - 1 - - nearest_idx = 0 - nearest_dist = float("inf") - for idx in range(start_idx, end_idx + 1): - data = self.rosbag_ego_odom_data[idx] - dist = calc_squared_distance(data[1].pose.pose.position, ego_pose.position) - if dist < nearest_dist: - nearest_dist = dist - nearest_idx = idx - - return self.rosbag_ego_odom_data[nearest_idx] - - def find_topics_by_timestamp(self, timestamp): - objects_data = None - for data in self.rosbag_objects_data: - if timestamp < data[0]: - objects_data = data[1] - break - - traffic_signals_data = None - for data in self.rosbag_traffic_signals_data: - if timestamp < data[0]: - traffic_signals_data = data[1] - break - - return objects_data, traffic_signals_data - - def load_rosbag(self, rosbag2_path: str): - reader = open_reader(str(rosbag2_path)) - - topic_types = reader.get_all_topics_and_types() - # Create a map for quicker lookup - type_map = {topic_types[i].name: topic_types[i].type for i in range(len(topic_types))} - - objects_topic = ( - "/perception/object_recognition/detection/objects" - if self.args.detected_object - else "/perception/object_recognition/tracking/objects" - if self.args.tracked_object - else "/perception/object_recognition/objects" - ) - ego_odom_topic = "/localization/kinematic_state" - traffic_signals_topic = "/perception/traffic_light_recognition/traffic_signals" - topic_filter = StorageFilter(topics=[objects_topic, ego_odom_topic, traffic_signals_topic]) - reader.set_filter(topic_filter) - - while reader.has_next(): - (topic, data, stamp) = reader.read_next() - msg_type = get_message(type_map[topic]) - msg = deserialize_message(data, msg_type) - if topic == objects_topic: - self.rosbag_objects_data.append((stamp, msg)) - if topic == ego_odom_topic: - self.rosbag_ego_odom_data.append((stamp, msg)) - if topic == traffic_signals_topic: - self.rosbag_traffic_signals_data.append((stamp, msg)) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-b", "--bag", help="rosbag", default=None) - parser.add_argument( - "-d", "--detected-object", help="publish detected object", action="store_true" - ) - parser.add_argument( - "-t", "--tracked-object", help="publish tracked object", action="store_true" - ) - args = parser.parse_args() - - rclpy.init() - node = PerceptionReproducer(args) - rclpy.spin(node) - - try: - rclpy.init() - node = PerceptionReproducer(args) - rclpy.spin(node) - except KeyboardInterrupt: - pass - finally: - node.destroy_node() - rclpy.shutdown() From a45624e1a2eaf0f3437219e647bdf7b4ee9358f0 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Wed, 9 Aug 2023 15:22:27 +0900 Subject: [PATCH 138/266] chore(radar_tracks_msgs_converter): change to throttle log (#4570) fix(radar_tracks_msgs_converter): fix to throttle log Signed-off-by: Makoto Kurihara --- .../radar_tracks_msgs_converter_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index 5d3dd3b997f24..ab5e4eb5abe90 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -220,7 +220,7 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() compensated_velocity.y += odometry_data_->twist.twist.linear.y; compensated_velocity.z += odometry_data_->twist.twist.linear.z; } else { - RCLCPP_INFO(get_logger(), "Odometry data is not coming"); + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "Odometry data is not coming"); } } kinematics.twist_with_covariance.twist.linear.x = std::sqrt( From e14d71ec85b5b271449fd1ce6babb9247bbbc585 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Wed, 9 Aug 2023 23:26:16 +0900 Subject: [PATCH 139/266] feat(image_projection_based_fusion): update pointpainting (#4544) * refactor: update point-image projection Signed-off-by: yukke42 * feat: add class_mappings for paint points Signed-off-by: yukke42 * chore: change score_threshold Signed-off-by: yukke42 * style(pre-commit): autofix * feat: update pointpainting model Signed-off-by: yukke42 * chore: remove comment out Signed-off-by: yukke42 * chore: fix param Signed-off-by: yukke42 --------- Signed-off-by: yukke42 Signed-off-by: yukke42 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 8 +-- .../config/pointpainting.param.yaml | 11 ++-- .../launch/pointpainting_fusion.launch.xml | 2 +- .../src/pointpainting_fusion/node.cpp | 60 +++++++++++++------ .../pointpainting_fusion/preprocess_kernel.cu | 4 +- .../src/utils/utils.cpp | 2 +- 6 files changed, 55 insertions(+), 32 deletions(-) diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index 8c0ba744491e7..906ad71d21732 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -124,7 +124,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) else() message(STATUS "diff ${FILE_NAME}") message(STATUS "File hash changes. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/pointpainting/v3/${FILE_NAME} + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/pointpainting/v4/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) @@ -132,7 +132,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) else() message(STATUS "not found ${FILE_NAME}") message(STATUS "File doesn't exists. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/pointpainting/v3/${FILE_NAME} + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/pointpainting/v4/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) @@ -145,8 +145,8 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) endfunction() # default model - download(pts_voxel_encoder_pointpainting.onnx e674271096f6fbbe0f808eef87f5a5ab) - download(pts_backbone_neck_head_pointpainting.onnx d4527a4da08959c2bf9c997112a1de35) + download(pts_voxel_encoder_pointpainting.onnx 25c70f76a45a64944ccd19f604c99410) + download(pts_backbone_neck_head_pointpainting.onnx 2c7108245240fbd7bf0104dd68225868) find_package(OpenCV REQUIRED) find_package(Eigen3 REQUIRED) diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index 56346b5a3eb41..e1be5426cba4b 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,15 +1,16 @@ /**: ros__parameters: class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 9 # x, y, z, time-lag and car, pedestrian, bicycle + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle max_voxel_size: 40000 - point_cloud_range: [-102.4, -102.4, -4.0, 102.4, 102.4, 6.0] - voxel_size: [0.32, 0.32, 10.0] + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] downsample_factor: 1 - encoder_in_feature_size: 14 + encoder_in_feature_size: 12 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # post-process params - circle_nms_dist_threshold: 0.5 + circle_nms_dist_threshold: 0.3 iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 0e18e9ee42a47..e6275a2ee83c7 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -41,7 +41,7 @@ - + diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 01ec679a82efc..5253ac192c786 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -29,6 +30,18 @@ #include +namespace +{ + +Eigen::Affine3f _transformToEigen(const geometry_msgs::msg::Transform & t) +{ + Eigen::Affine3f a; + a.matrix() = tf2::transformToEigen(t).matrix().cast(); + return a; +} + +} // namespace + namespace image_projection_based_fusion { @@ -102,8 +115,12 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt const std::string head_engine_path = this->declare_parameter("head_engine_path", ""); class_names_ = this->declare_parameter>("class_names"); + const auto paint_class_names = + this->declare_parameter>("paint_class_names"); std::vector classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"}; - if (std::find(class_names_.begin(), class_names_.end(), "TRUCK") != class_names_.end()) { + if ( + std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != + paint_class_names.end()) { isClassTable_["CAR"] = std::bind(&isCar, std::placeholders::_1); } else { isClassTable_["CAR"] = std::bind(&isVehicle, std::placeholders::_1); @@ -113,9 +130,9 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt isClassTable_["BICYCLE"] = std::bind(&isBicycle, std::placeholders::_1); isClassTable_["PEDESTRIAN"] = std::bind(&isPedestrian, std::placeholders::_1); for (const auto & cls : classes_) { - auto it = find(class_names_.begin(), class_names_.end(), cls); - if (it != class_names_.end()) { - int index = it - class_names_.begin(); + auto it = find(paint_class_names.begin(), paint_class_names.end(), cls); + if (it != paint_class_names.end()) { + int index = it - paint_class_names.begin(); class_index_[cls] = index + 1; } else { isClassTable_.erase(cls); @@ -253,39 +270,38 @@ void PointPaintingFusionNode::fuseOnSingleImage( std::vector debug_image_points; // get transform from cluster frame id to camera optical frame id - geometry_msgs::msg::TransformStamped transform_stamped; + // geometry_msgs::msg::TransformStamped transform_stamped; + Eigen::Affine3f lidar2cam_affine; { const auto transform_stamped_optional = getTransformStamped( - tf_buffer_, /*target*/ camera_info.header.frame_id, - /*source*/ painted_pointcloud_msg.header.frame_id, camera_info.header.stamp); + tf_buffer_, /*target*/ input_roi_msg.header.frame_id, + /*source*/ painted_pointcloud_msg.header.frame_id, input_roi_msg.header.stamp); if (!transform_stamped_optional) { return; } - transform_stamped = transform_stamped_optional.value(); + lidar2cam_affine = _transformToEigen(transform_stamped_optional.value().transform); } // transform - sensor_msgs::msg::PointCloud2 transformed_pointcloud; - tf2::doTransform(painted_pointcloud_msg, transformed_pointcloud, transform_stamped); - - std::chrono::system_clock::time_point start, end; - start = std::chrono::system_clock::now(); + // sensor_msgs::msg::PointCloud2 transformed_pointcloud; + // tf2::doTransform(painted_pointcloud_msg, transformed_pointcloud, transform_stamped); const auto x_offset = - transformed_pointcloud.fields.at(static_cast(autoware_point_types::PointIndex::X)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::X)) .offset; const auto y_offset = - transformed_pointcloud.fields.at(static_cast(autoware_point_types::PointIndex::Y)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::Y)) .offset; const auto z_offset = - transformed_pointcloud.fields.at(static_cast(autoware_point_types::PointIndex::Z)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::Z)) .offset; const auto class_offset = painted_pointcloud_msg.fields.at(4).offset; - const auto p_step = transformed_pointcloud.point_step; + const auto p_step = painted_pointcloud_msg.point_step; // projection matrix Eigen::Matrix3f camera_projection; // use only x,y,z camera_projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6); + Eigen::Vector3f point_lidar, point_camera; /** dc : don't care x | f x1 x2 dc ||xc| @@ -295,18 +311,24 @@ dc | dc dc dc dc ||zc| **/ auto objects = input_roi_msg.feature_objects; - int iterations = transformed_pointcloud.data.size() / transformed_pointcloud.point_step; + int iterations = painted_pointcloud_msg.data.size() / painted_pointcloud_msg.point_step; // iterate points // Requires 'OMP_NUM_THREADS=N' omp_set_num_threads(omp_num_threads_); #pragma omp parallel for for (int i = 0; i < iterations; i++) { int stride = p_step * i; - unsigned char * data = &transformed_pointcloud.data[0]; + unsigned char * data = &painted_pointcloud_msg.data[0]; unsigned char * output = &painted_pointcloud_msg.data[0]; float p_x = *reinterpret_cast(&data[stride + x_offset]); float p_y = *reinterpret_cast(&data[stride + y_offset]); float p_z = *reinterpret_cast(&data[stride + z_offset]); + point_lidar << p_x, p_y, p_z; + point_camera = lidar2cam_affine * point_lidar; + p_x = point_camera.x(); + p_y = point_camera.y(); + p_z = point_camera.z(); + if (p_z <= 0.0 || p_x > (tan_h_.at(image_id) * p_z) || p_x < (-tan_h_.at(image_id) * p_z)) { continue; } diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu index d9dce27fb0ecc..9789f52de5f74 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu @@ -37,8 +37,8 @@ namespace { const std::size_t MAX_POINT_IN_VOXEL_SIZE = 32; // the same as max_point_in_voxel_size_ in config const std::size_t WARPS_PER_BLOCK = 4; -const std::size_t ENCODER_IN_FEATURE_SIZE = 14; // same as encoder_in_feature_size_ in config.hpp -const int POINT_FEATURE_SIZE = 9; +const std::size_t ENCODER_IN_FEATURE_SIZE = 12; // same as encoder_in_feature_size_ in config.hpp +const int POINT_FEATURE_SIZE = 7; // cspell: ignore divup std::size_t divup(const std::size_t a, const std::size_t b) diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index 1eaf04562b2b8..670c5596001fb 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -24,7 +24,7 @@ std::optional getTransformStamped( try { geometry_msgs::msg::TransformStamped transform_stamped; transform_stamped = tf_buffer.lookupTransform( - target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.01)); return transform_stamped; } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(rclcpp::get_logger("image_projection_based_fusion"), ex.what()); From 9a2e27ea8d5278a6cd7982b30d49b76c92980135 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Wed, 9 Aug 2023 23:27:02 +0900 Subject: [PATCH 140/266] feat(image_projection_based_fusion): add objects filter by rois (#4546) * tmp Signed-off-by: yukke42 style(pre-commit): autofix update Signed-off-by: yukke42 style(pre-commit): autofix * fix: fix association bug Signed-off-by: yukke42 * feat: add prob_threshold for each class Signed-off-by: yukke42 * feat: use class label association between roi and object Signed-off-by: yukke42 * feat: add to tier4_perception_launch Signed-off-by: yukke42 * chore: disable debug_mode Signed-off-by: yukke42 * docs: update params Signed-off-by: yukke42 * fix: apply suggestion Signed-off-by: yukke42 * chore: update prob_thresholds of bicycle Signed-off-by: yukke42 * feat: add thresut_distance for each class Signed-off-by: yukke42 * docs: add thrust_distances Signed-off-by: yukke42 * style(pre-commit): autofix * chore: remove unnecessary variable Signed-off-by: yukke42 * chore: rename to trust Signed-off-by: yukke42 * style(pre-commit): autofix * chore: add param Signed-off-by: yukke42 * Update perception/image_projection_based_fusion/config/roi_detected_object_fusion.param.yaml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --------- Signed-off-by: yukke42 Signed-off-by: yukke42 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- ...ra_lidar_fusion_based_detection.launch.xml | 34 +++++++- .../roi_detected_object_fusion.param.yaml | 19 ++++ .../docs/roi-detected-object-fusion.md | 18 ++-- .../roi_detected_object_fusion/node.hpp | 10 ++- .../roi_detected_object_fusion.launch.xml | 7 +- .../image_projection_based_fusion/package.xml | 1 + .../src/roi_detected_object_fusion/node.cpp | 86 ++++++++++++------- 7 files changed, 129 insertions(+), 46 deletions(-) create mode 100755 perception/image_projection_based_fusion/config/roi_detected_object_fusion.param.yaml diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 24b8a75506d2f..0a9b719939971 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -224,12 +224,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + diff --git a/perception/image_projection_based_fusion/config/roi_detected_object_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_detected_object_fusion.param.yaml new file mode 100755 index 0000000000000..bd49dc65749a9 --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_detected_object_fusion.param.yaml @@ -0,0 +1,19 @@ +/**: + ros__parameters: + # UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + passthrough_lower_bound_probability_thresholds: [0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.50] + trust_distances: [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0] + min_iou_threshold: 0.5 + use_roi_probability: false + roi_probability_threshold: 0.5 + + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN <-roi_msg + [1, 0, 0, 0, 0, 0, 0, 0, # UNKNOWN <-detected_objects + 0, 1, 1, 1, 1, 0, 0, 0, # CAR + 0, 1, 1, 1, 1, 0, 0, 0, # TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, # BUS + 0, 1, 1, 1, 1, 0, 0, 0, # TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, # MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, # BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] # PEDESTRIAN diff --git a/perception/image_projection_based_fusion/docs/roi-detected-object-fusion.md b/perception/image_projection_based_fusion/docs/roi-detected-object-fusion.md index accdc350bf256..4e054fc911dc6 100644 --- a/perception/image_projection_based_fusion/docs/roi-detected-object-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-detected-object-fusion.md @@ -41,14 +41,16 @@ The DetectedObject has three possible shape choices/implementations, where the p ### Core Parameters -| Name | Type | Description | -| ----------------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------- | -| `rois_number` | int | the number of input rois | -| `debug_mode` | bool | If set to `true`, the node subscribes to the image topic and publishes an image with debug drawings. | -| `min_iou_threshold` | double | If the iou between detected objects and rois is greater than `min_iou_threshold`, the objects are classified as fused. | -| `passthrough_lower_bound_probability_threshold` | double | If the `existence_probability` of a detected object is greater than the threshold, it is published in output. | -| `use_roi_probability` | float | If set to `true`, the algorithm uses `existence_probability` of ROIs to match with the that of detected objects. | -| `roi_probability_threshold` | double | If the `existence_probability` of ROIs is greater than the threshold, matched detected objects are published in `output`. | +| Name | Type | Description | +| ------------------------------------------------ | -------------- | -------------------------------------------------------------------------------------------------------------------------- | +| `rois_number` | int | the number of input rois | +| `debug_mode` | bool | If set to `true`, the node subscribes to the image topic and publishes an image with debug drawings. | +| `passthrough_lower_bound_probability_thresholds` | vector[double] | If the `existence_probability` of a detected object is greater than the threshold, it is published in output. | +| `trust_distances` | vector[double] | If the distance of a detected object from the origin of frame_id is greater than the threshold, it is published in output. | +| `min_iou_threshold` | double | If the iou between detected objects and rois is greater than `min_iou_threshold`, the objects are classified as fused. | +| `use_roi_probability` | float | If set to `true`, the algorithm uses `existence_probability` of ROIs to match with the that of detected objects. | +| `roi_probability_threshold` | double | If the `existence_probability` of ROIs is greater than the threshold, matched detected objects are published in `output`. | +| `can_assign_matrix` | vector[int] | association matrix between rois and detected_objects to check that two rois on images can be match | ## Assumptions / Known limits diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index fe95d21eb266c..e11a62c060480 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -18,6 +18,8 @@ #include "image_projection_based_fusion/fusion_node.hpp" #include "tier4_autoware_utils/ros/debug_publisher.hpp" +#include "autoware_auto_perception_msgs/msg/object_classification.hpp" + #include #include #include @@ -40,14 +42,14 @@ class RoiDetectedObjectFusionNode : public FusionNode generateDetectedObjectRoIs( + std::map generateDetectedObjectRoIs( const DetectedObjects & input_object_msg, const double image_width, const double image_height, const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection); void fuseObjectsOnImage( const DetectedObjects & input_object_msg, const std::vector & image_rois, - const std::map & object_roi_map); + const std::map & object_roi_map); void publish(const DetectedObjects & output_msg) override; @@ -56,10 +58,12 @@ class RoiDetectedObjectFusionNode : public FusionNode passthrough_lower_bound_probability_thresholds{}; + std::vector trust_distances{}; double min_iou_threshold{}; bool use_roi_probability{}; double roi_probability_threshold{}; + Eigen::MatrixXi can_assign_matrix; } fusion_params_; std::map> passthrough_object_flags_map_, fused_object_flags_map_, diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index dd71ca462f666..b6165fc7c87d2 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -18,6 +18,7 @@ + @@ -39,13 +40,9 @@ + - - - - - diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index 083a40044489b..32d7a5633b811 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -17,6 +17,7 @@ image_transport lidar_centerpoint message_filters + object_recognition_utils pcl_conversions pcl_ros rclcpp diff --git a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 8961c0aad478f..333ec7d7ed206 100644 --- a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -14,6 +14,8 @@ #include "image_projection_based_fusion/roi_detected_object_fusion/node.hpp" +#include "object_recognition_utils/object_recognition_utils.hpp" + #include #include @@ -25,11 +27,20 @@ namespace image_projection_based_fusion RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options) : FusionNode("roi_detected_object_fusion", options) { - fusion_params_.passthrough_lower_bound_probability_threshold = - declare_parameter("passthrough_lower_bound_probability_threshold"); + fusion_params_.passthrough_lower_bound_probability_thresholds = + declare_parameter>("passthrough_lower_bound_probability_thresholds"); + fusion_params_.min_iou_threshold = declare_parameter("min_iou_threshold"); + fusion_params_.trust_distances = declare_parameter>("trust_distances"); fusion_params_.use_roi_probability = declare_parameter("use_roi_probability"); fusion_params_.roi_probability_threshold = declare_parameter("roi_probability_threshold"); - fusion_params_.min_iou_threshold = declare_parameter("min_iou_threshold"); + { + const auto can_assign_vector_tmp = declare_parameter>("can_assign_matrix"); + std::vector can_assign_vector(can_assign_vector_tmp.begin(), can_assign_vector_tmp.end()); + const int label_num = static_cast(std::sqrt(can_assign_vector.size())); + Eigen::Map can_assign_matrix_tmp( + can_assign_vector.data(), label_num, label_num); + fusion_params_.can_assign_matrix = can_assign_matrix_tmp.transpose(); + } } void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) @@ -39,9 +50,15 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) fused_object_flags.resize(output_msg.objects.size()); ignored_object_flags.resize(output_msg.objects.size()); for (std::size_t obj_i = 0; obj_i < output_msg.objects.size(); ++obj_i) { - if ( - output_msg.objects.at(obj_i).existence_probability > - fusion_params_.passthrough_lower_bound_probability_threshold) { + const auto & object = output_msg.objects.at(obj_i); + const auto label = object_recognition_utils::getHighestProbLabel(object.classification); + const auto pos = object_recognition_utils::getPose(object).position; + const auto object_sqr_dist = pos.x * pos.x + pos.y * pos.y; + const auto prob_threshold = + fusion_params_.passthrough_lower_bound_probability_thresholds.at(label); + const auto trust_sqr_dist = + fusion_params_.trust_distances.at(label) * fusion_params_.trust_distances.at(label); + if (object.existence_probability > prob_threshold || object_sqr_dist > trust_sqr_dist) { passthrough_object_flags.at(obj_i) = true; } } @@ -90,11 +107,12 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( } } -std::map RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( +std::map +RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( const DetectedObjects & input_object_msg, const double image_width, const double image_height, const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection) { - std::map object_roi_map; + std::map object_roi_map; int64_t timestamp_nsec = input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; if (passthrough_object_flags_map_.size() == 0) { @@ -106,18 +124,18 @@ std::map RoiDetectedObjectFusionNode::generateDet const auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); for (std::size_t obj_i = 0; obj_i < input_object_msg.objects.size(); ++obj_i) { std::vector vertices_camera_coord; - { - const auto & object = input_object_msg.objects.at(obj_i); + const auto & object = input_object_msg.objects.at(obj_i); - if (passthrough_object_flags.at(obj_i)) { - continue; - } + if (passthrough_object_flags.at(obj_i)) { + continue; + } - // filter point out of scope - if (debugger_ && out_of_scope(object)) { - continue; - } + // filter point out of scope + if (debugger_ && out_of_scope(object)) { + continue; + } + { std::vector vertices; objectToVertices(object.kinematics.pose_with_covariance.pose, object.shape, vertices); transformPoints(vertices, object2camera_affine, vertices_camera_coord); @@ -154,7 +172,7 @@ std::map RoiDetectedObjectFusionNode::generateDet } } } - if (point_on_image_cnt == 3) { + if (point_on_image_cnt < 3) { continue; } @@ -163,16 +181,18 @@ std::map RoiDetectedObjectFusionNode::generateDet max_x = std::min(max_x, image_width - 1); max_y = std::min(max_y, image_height - 1); - // build roi - RegionOfInterest roi; - roi.x_offset = static_cast(min_x); - roi.y_offset = static_cast(min_y); - roi.width = static_cast(max_x) - static_cast(min_x); - roi.height = static_cast(max_y) - static_cast(min_y); - object_roi_map.insert(std::make_pair(obj_i, roi)); + DetectedObjectWithFeature object_roi; + object_roi.feature.roi.x_offset = static_cast(min_x); + object_roi.feature.roi.y_offset = static_cast(min_y); + object_roi.feature.roi.width = + static_cast(max_x) - static_cast(min_x); + object_roi.feature.roi.height = + static_cast(max_y) - static_cast(min_y); + object_roi.object = object; + object_roi_map.insert(std::make_pair(obj_i, object_roi)); if (debugger_) { - debugger_->obstacle_rois_.push_back(roi); + debugger_->obstacle_rois_.push_back(object_roi.feature.roi); } } @@ -182,7 +202,7 @@ std::map RoiDetectedObjectFusionNode::generateDet void RoiDetectedObjectFusionNode::fuseObjectsOnImage( const DetectedObjects & input_object_msg, const std::vector & image_rois, - const std::map & object_roi_map) + const std::map & object_roi_map) { int64_t timestamp_nsec = input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; @@ -207,7 +227,15 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( float max_iou = 0.0f; for (const auto & image_roi : image_rois) { const auto & object_roi = object_pair.second; - const double iou = calcIoU(object_roi, image_roi.feature.roi); + const auto object_roi_label = + object_recognition_utils::getHighestProbLabel(object_roi.object.classification); + const auto image_roi_label = + object_recognition_utils::getHighestProbLabel(image_roi.object.classification); + if (!fusion_params_.can_assign_matrix(object_roi_label, image_roi_label)) { + continue; + } + + const double iou = calcIoU(object_roi.feature.roi, image_roi.feature.roi); if (iou > max_iou) { max_iou = iou; roi_prob = image_roi.object.existence_probability; @@ -301,7 +329,7 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) passthrough_object_flags_map_.erase(timestamp_nsec); fused_object_flags_map_.erase(timestamp_nsec); - fused_object_flags_map_.erase(timestamp_nsec); + ignored_object_flags_map_.erase(timestamp_nsec); } } // namespace image_projection_based_fusion From ff6fe561d0a4156c1eaa10c698353b7f666ba73c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 9 Aug 2023 23:42:10 +0900 Subject: [PATCH 141/266] feat(planning_debug_tools): manage time of perception_replayer by slider (#4575) * feat(planning_debug_tools): manage time of perception_replayer by slider Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../perception_replayer.py | 12 ++++++- .../time_manager_widget.py | 31 +++++++++++++++++-- 2 files changed, 40 insertions(+), 3 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py index e54458fee8f69..329058cc95c35 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py @@ -36,7 +36,9 @@ def __init__(self, args): self.rate = 1.0 # initialize widget - self.widget = TimeManagerWidget() + self.widget = TimeManagerWidget( + self.rosbag_objects_data[0][0], self.rosbag_objects_data[-1][0] + ) self.widget.show() self.widget.button.clicked.connect(self.onPushed) for button in self.widget.rate_button: @@ -57,8 +59,16 @@ def on_timer(self): self.pointcloud_pub.publish(pointcloud_msg) # step timestamp + # get timestamp from slider + self.bag_timestamp = self.rosbag_objects_data[0][ + 0 + ] + self.widget.slider.value() / 1000000 * ( + self.rosbag_objects_data[-1][0] - self.rosbag_objects_data[0][0] + ) if not self.is_pause: self.bag_timestamp += self.rate * self.delta_time * 1e9 # seconds to timestamp + # update slider value from the updated timestamp + self.widget.slider.setValue(self.widget.timestamp_to_value(self.bag_timestamp)) # extract message by the timestamp msgs = copy.deepcopy(self.find_topics_by_timestamp(self.bag_timestamp)) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py index 77bf65a17b848..c16f3560ba399 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py @@ -19,12 +19,18 @@ from PyQt5.QtWidgets import QMainWindow from PyQt5.QtWidgets import QPushButton from PyQt5.QtWidgets import QSizePolicy +from PyQt5.QtWidgets import QSlider from PyQt5.QtWidgets import QWidget class TimeManagerWidget(QMainWindow): - def __init__(self): + def __init__(self, start_timestamp, end_timestamp): super(self.__class__, self).__init__() + + self.start_timestamp = start_timestamp + self.end_timestamp = end_timestamp + self.max_value = 1000000 + self.setupUI() def setupUI(self): @@ -39,6 +45,7 @@ def setupUI(self): self.grid_layout.setContentsMargins(10, 10, 10, 10) self.grid_layout.setObjectName("grid_layout") + # rate button self.rate_button = [] for i, rate in enumerate([0.1, 0.5, 1.0, 2.0, 5.0, 10.0]): button = QPushButton(str(rate)) @@ -46,9 +53,29 @@ def setupUI(self): self.rate_button.append(button) self.grid_layout.addWidget(self.rate_button[-1], 0, i, 1, 1) + # pause button self.button = QPushButton("pause") self.button.setCheckable(True) self.button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) - self.grid_layout.addWidget(self.button, 1, 0, 1, -1) + + # slider + self.slider = QSlider(QtCore.Qt.Horizontal) + self.slider.setMinimum(0) + self.slider.setMaximum(self.max_value) + self.slider.setValue(0) + self.grid_layout.addWidget(self.slider, 2, 0, 1, -1) + self.setCentralWidget(self.central_widget) + + def timestamp_to_value(self, timestamp): + return int( + (timestamp - self.start_timestamp) + / (self.end_timestamp - self.start_timestamp) + * self.max_value + ) + + def value_to_timestamp(self, value): + return self.start_timestamp + self.slider.value() / self.max_value * ( + self.end_value - self.start_value + ) From 6691971f42caba2270f23089b9dac3f646602b97 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 10:07:04 +0900 Subject: [PATCH 142/266] chore(behavior_velocity_intersection_module): fix spell-check errors (#4580) chore(behavior_velocity_intersection_module Signed-off-by: kminoda --- planning/behavior_velocity_intersection_module/README.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 3ab642abe1e8f..3e62ab75d23cd 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -8,7 +8,7 @@ The _intersection_ module is responsible for safely going through urban intersec 2. recognizing the occluded area in the intersection 3. reacting to arrow signals of associated traffic lights -The module is desinged to be agnositc to left-hand/right-hand traffic rules and works on crossroads, T-shape junctions, etc. +The module is designed to be agnostic to left-hand/right-hand traffic rules and works on crossroads, T-shape junctions, etc. ![topology](./docs/intersection-topology.drawio.svg) @@ -26,7 +26,7 @@ This module is activated when the path contains the lanes with `turn_direction` The `Attention Area` in the intersection are defined as the set of lanes that are conflicting with ego vehicle's path and their preceding lanes up to `attention_area_length` meters. `RightOfWay` tag is used to rule out the lanes that each lane has priority given the traffic light relation and `turn_direction` priority. -`Intersection Area`, which is supposed to be defined on the HDMap, is an area convering the entire intersection. +`Intersection Area`, which is supposed to be defined on the HDMap, is an area converting the entire intersection. ![attention_area](./docs/intersection-attention.drawio.svg) @@ -38,7 +38,7 @@ Following table shows an example of how to assign `right_of_way` tag and set `yi | ------------------------------ | --------------------------------------------------------------- | ------------------------------------------------ | | straight | Highest priority of all | Priority over left/right lanes of the same group | | left(Left hand traffic) | Priority over the other group and right lanes of the same group | Priority over right lanes of the same group | -| right(Left hand traffic) | Priority only over the other group | priority only over the other gruop | +| right(Left hand traffic) | Priority only over the other group | priority only over the other group | | left(Right hand traffic) | Priority only over the other group | Priority only over the other group | | right(Right hand traffic) | Priority over the other group and left lanes of the same group | priority over left lanes of the same group | @@ -108,7 +108,7 @@ To avoid a rapid braking, if deceleration and jerk more than a threshold (`behav | `common.path_interpolation_ds` | double | [m] path interpolation interval | | `stuck_vehicle.stuck_vehicle_detect_dist` | double | [m] length toward from the exit of intersection for stuck vehicle detection | | `stuck_vehicle.stuck_vehicle_ignore_dist` | double | [m] length behind the exit of intersection for stuck vehicle detection | -| `stuck_vehicle.stuck_vehicle_vel_thr` | double | [m/s] velocity threhsold for stuck vehicle detection | +| `stuck_vehicle.stuck_vehicle_vel_thr` | double | [m/s] velocity threshold for stuck vehicle detection | | `collision_detection.state_transit_margin_time` | double | [m] time margin to change state | | `collision_detection.min_predicted_path_confidence` | double | [-] minimum confidence value of predicted path to use for collision detection | | `collision_detection.collision_start_margin_time` | double | [s] time margin for the beginning of collision with upcoming vehicle | From 86fd81899be78d9bcf60c15c52cf0399f90c3fde Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 10:13:44 +0900 Subject: [PATCH 143/266] chore(multi_object_tracker): fix spell-check errors (#4581) * chore(multi_object_tracker): fix spell-check errors Signed-off-by: kminoda * fix Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .../include/multi_object_tracker/utils/utils.hpp | 6 +++--- perception/multi_object_tracker/models.md | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp index bc97c9ba92d7e..f115d8c07f72f 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp @@ -301,7 +301,7 @@ inline void convertConvexHullToBoundingBox( input_object.kinematics.pose_with_covariance.pose.position.x, input_object.kinematics.pose_with_covariance.pose.position.y}; const auto yaw = tf2::getYaw(input_object.kinematics.pose_with_covariance.pose.orientation); - const Eigen::Matrix2d Rinv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); + const Eigen::Matrix2d R_inv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); double max_x = 0; double max_y = 0; @@ -314,7 +314,7 @@ inline void convertConvexHullToBoundingBox( Eigen::Vector2d vertex{ input_object.shape.footprint.points.at(i).x, input_object.shape.footprint.points.at(i).y}; - const Eigen::Vector2d local_vertex = Rinv * (vertex - center); + const Eigen::Vector2d local_vertex = R_inv * (vertex - center); max_x = std::max(max_x, local_vertex.x()); max_y = std::max(max_y, local_vertex.y()); min_x = std::min(min_x, local_vertex.x()); @@ -328,7 +328,7 @@ inline void convertConvexHullToBoundingBox( const double width = max_y - min_y; const double height = max_z; const Eigen::Vector2d new_local_center{(max_x + min_x) / 2.0, (max_y + min_y) / 2.0}; - const Eigen::Vector2d new_center = center + Rinv.transpose() * new_local_center; + const Eigen::Vector2d new_center = center + R_inv.transpose() * new_local_center; // set output parameters output_object = input_object; diff --git a/perception/multi_object_tracker/models.md b/perception/multi_object_tracker/models.md index edf480990c1fd..0f7fc50ed535f 100644 --- a/perception/multi_object_tracker/models.md +++ b/perception/multi_object_tracker/models.md @@ -35,7 +35,7 @@ $$ Kinematic bicycle model uses slip angle $\beta$ and velocity $v$ to calculate yaw update. The merit of using this model is that it can prevent unintended yaw rotation when the vehicle is stopped. -![kbmodel](image/kinematic_bicycle_model.png) +![kinematic_bicycle_model](image/kinematic_bicycle_model.png) - **state variable** - pose( $x,y$ ), velocity( $v$ ), yaw( $\psi$ ), and slip angle ( $\beta$ ) From 8ff2128983765f469293cf9fb85d1e1c6ae7322f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 11:05:32 +0900 Subject: [PATCH 144/266] feat(map_projection_loader): add map_projection_loader (#3986) * feat(map_projection_loader): add map_projection_loader Signed-off-by: kminoda * style(pre-commit): autofix * Update default algorithm Signed-off-by: kminoda * fix test Signed-off-by: kminoda * style(pre-commit): autofix * add readme Signed-off-by: kminoda * style(pre-commit): autofix * fix launch file and fix map_loader Signed-off-by: kminoda * style(pre-commit): autofix * update lanelet2 Signed-off-by: kminoda * fill yaml file path Signed-off-by: kminoda * style(pre-commit): autofix * update readme Signed-off-by: kminoda * style(pre-commit): autofix * minor fix Signed-off-by: kminoda * style(pre-commit): autofix * fix test Signed-off-by: kminoda * style(pre-commit): autofix * add include guard Signed-off-by: kminoda * style(pre-commit): autofix * update test Signed-off-by: kminoda * update map_loader Signed-off-by: kminoda * style(pre-commit): autofix * update docs * style(pre-commit): autofix * update Signed-off-by: kminoda * add dependency Signed-off-by: kminoda * style(pre-commit): autofix * remove unnecessary parameter Signed-off-by: kminoda * update Signed-off-by: kminoda * update test Signed-off-by: kminoda * style(pre-commit): autofix * add url Signed-off-by: kminoda * enable python tests Signed-off-by: kminoda * style(pre-commit): autofix * small fix Signed-off-by: kminoda * fix grammar Signed-off-by: kminoda * remove transverse mercator Signed-off-by: kminoda * style(pre-commit): autofix * add rule in map Signed-off-by: kminoda * fix readme of map loader Signed-off-by: kminoda * remove transverse mercator for now Signed-off-by: kminoda * add utm Signed-off-by: kminoda * remove altitude from current projection loader Signed-off-by: kminoda * style(pre-commit): autofix * fix pre-commit Signed-off-by: kminoda * fix build error Signed-off-by: kminoda * fix: remove package.xml Signed-off-by: kminoda * fix clang-tidy Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- launch/tier4_map_launch/launch/map.launch.py | 29 +++- launch/tier4_map_launch/package.xml | 1 + map/map_loader/README.md | 46 +++--- .../config/lanelet2_map_loader.param.yaml | 4 - .../map_loader/lanelet2_map_loader_node.hpp | 7 +- .../lanelet2_map_loader_node.cpp | 42 ++--- map/map_projection_loader/CMakeLists.txt | 58 +++++++ map/map_projection_loader/README.md | 62 ++++++++ .../load_info_from_lanelet2_map.hpp | 29 ++++ .../map_projection_loader.hpp | 35 ++++ .../launch/map_projection_loader.launch.xml | 10 ++ map/map_projection_loader/package.xml | 29 ++++ .../src/load_info_from_lanelet2_map.cpp | 39 +++++ .../src/map_projection_loader.cpp | 70 ++++++++ .../src/map_projection_loader_node.cpp | 23 +++ .../test/data/projection_info_local.yaml | 1 + .../test/data/projection_info_mgrs.yaml | 2 + .../test/data/projection_info_utm.yaml | 4 + .../test/test_load_info_from_lanelet2_map.cpp | 70 ++++++++ .../test_node_load_local_from_yaml.test.py | 143 +++++++++++++++++ .../test_node_load_mgrs_from_yaml.test.py | 144 +++++++++++++++++ .../test/test_node_load_utm_from_yaml.test.py | 149 ++++++++++++++++++ 22 files changed, 935 insertions(+), 62 deletions(-) create mode 100644 map/map_projection_loader/CMakeLists.txt create mode 100644 map/map_projection_loader/README.md create mode 100644 map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp create mode 100644 map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp create mode 100644 map/map_projection_loader/launch/map_projection_loader.launch.xml create mode 100644 map/map_projection_loader/package.xml create mode 100644 map/map_projection_loader/src/load_info_from_lanelet2_map.cpp create mode 100644 map/map_projection_loader/src/map_projection_loader.cpp create mode 100644 map/map_projection_loader/src/map_projection_loader_node.cpp create mode 100644 map/map_projection_loader/test/data/projection_info_local.yaml create mode 100644 map/map_projection_loader/test/data/projection_info_mgrs.yaml create mode 100644 map/map_projection_loader/test/data/projection_info_utm.yaml create mode 100644 map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp create mode 100644 map/map_projection_loader/test/test_node_load_local_from_yaml.test.py create mode 100644 map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py create mode 100644 map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py diff --git a/launch/tier4_map_launch/launch/map.launch.py b/launch/tier4_map_launch/launch/map.launch.py index f9459be3b8924..169c53814df22 100644 --- a/launch/tier4_map_launch/launch/map.launch.py +++ b/launch/tier4_map_launch/launch/map.launch.py @@ -12,13 +12,18 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os + +from ament_index_python import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction +from launch.actions import IncludeLaunchDescription from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition +from launch.launch_description_sources import AnyLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import Node @@ -57,7 +62,10 @@ def launch_setup(context, *args, **kwargs): package="map_loader", plugin="Lanelet2MapLoaderNode", name="lanelet2_map_loader", - remappings=[("output/lanelet2_map", "vector_map")], + remappings=[ + ("output/lanelet2_map", "vector_map"), + ("input/map_projector_info", "map_projector_type"), + ], parameters=[ { "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), @@ -110,6 +118,19 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + map_projection_loader_launch_file = os.path.join( + get_package_share_directory("map_projection_loader"), + "launch", + "map_projection_loader.launch.xml", + ) + map_projection_loader = IncludeLaunchDescription( + AnyLaunchDescriptionSource(map_projection_loader_launch_file), + launch_arguments={ + "map_projector_info_path": LaunchConfiguration("map_projector_info_path"), + "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), + }.items(), + ) + container = ComposableNodeContainer( name="map_container", namespace="", @@ -129,6 +150,7 @@ def launch_setup(context, *args, **kwargs): PushRosNamespace("map"), container, map_hash_generator, + map_projection_loader, ] ) @@ -159,6 +181,11 @@ def add_launch_arg(name: str, default_value=None, description=None): [LaunchConfiguration("map_path"), "/pointcloud_map_metadata.yaml"], "path to pointcloud map metadata file", ), + add_launch_arg( + "map_projector_info_path", + [LaunchConfiguration("map_path"), "/map_projector_info.yaml"], + "path to map projector info yaml file", + ), add_launch_arg( "lanelet2_map_loader_param_path", [ diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index 6f75950838267..d8f69c124526a 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -13,6 +13,7 @@ autoware_cmake map_loader + map_projection_loader map_tf_generator ament_lint_auto diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 0494b57dcfab9..44f215b2d8c01 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -20,11 +20,12 @@ Currently, it supports the following two types: You may provide either a single .pcd file or multiple .pcd files. If you are using multiple PCD data and either of `enable_partial_load`, `enable_differential_load` or `enable_selected_load` are set true, it MUST obey the following rules: -1. **It must be divided by straight lines parallel to the x-axis and y-axis**. The system does not support division by diagonal lines or curved lines. -2. **The division size along each axis should be equal.** -3. **The division size should be about 20m x 20m.** Particularly, care should be taken as using too large division size (for example, more than 100m) may have adverse effects on dynamic map loading features in [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation). -4. **All the split maps should not overlap with each other.** -5. **Metadata file should also be provided.** The metadata structure description is provided below. +1. **The pointcloud map should be projected on the same coordinate defined in `map_projection_loader`**, in order to be consistent with the lanelet2 map and other packages that converts between local and geodetic coordinates. For more information, please refer to [the readme of `map_projection_loader`](https://github.com/autowarefoundation/autoware.universe/tree/main/map/map_projection_loader/README.md). +2. **It must be divided by straight lines parallel to the x-axis and y-axis**. The system does not support division by diagonal lines or curved lines. +3. **The division size along each axis should be equal.** +4. **The division size should be about 20m x 20m.** Particularly, care should be taken as using too large division size (for example, more than 100m) may have adverse effects on dynamic map loading features in [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation). +5. **All the split maps should not overlap with each other.** +6. **Metadata file should also be provided.** The metadata structure description is provided below. Note that these rules are not applicable when `enable_partial_load`, `enable_differential_load` and `enable_selected_load` are all set false. In this case, however, you also need to disable dynamic map loading mode for other nodes as well ([ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation) as of June 2023). @@ -69,6 +70,7 @@ sample-map-rosbag │ ├── B.pcd │ ├── C.pcd │ └── ... +├── map_projector_info.yaml └── pointcloud_map_metadata.yaml ``` @@ -138,27 +140,39 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Feature lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_auto_mapping_msgs/HADMapBin message. -The node projects lan/lon coordinates into MGRS coordinates. +The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_type` from `map_projection_loader`. +The node supports the following three types of coordinate systems: + +- MGRS +- UTM +- local ### How to run `ros2 run map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm` +### Subscribed Topics + +- ~input/map_projector_info (tier4_map_msgs/MapProjectorInfo) : Projection type for Autoware + ### Published Topics - ~output/lanelet2_map (autoware_auto_mapping_msgs/HADMapBin) : Binary data of loaded Lanelet2 Map +### Parameters + +| Name | Type | Description | Default value | +| :--------------------- | :---------- | :----------------------------------------------- | :------------ | +| center_line_resolution | double | Define the resolution of the lanelet center line | 5.0 | +| lanelet2_map_path | std::string | The lanelet2 map path | None | + --- ## lanelet2_map_visualization ### Feature -lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messages into visualization_msgs/MarkerArray. There are 3 types of map can be loaded in autoware. Please make sure you selected the correct lanelet2_map_projector_type when you launch this package. - -- MGRS -- UTM -- local +lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messages into visualization_msgs/MarkerArray. ### How to Run @@ -171,13 +185,3 @@ lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messa ### Published Topics - ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz - -### Parameters - -| Name | Type | Description | Default value | -| :-------------------------- | :---------- | :----------------------------------------------------------- | :------------ | -| lanelet2_map_projector_type | std::string | The type of the map projector using, can be MGRS, UTM, local | MGRS | -| latitude | double | Latitude of map_origin, only using in UTM map projector | 0.0 | -| longitude | double | Longitude of map_origin, only using in UTM map projector | 0.0 | -| center_line_resolution | double | Define the resolution of the lanelet center line | 5.0 | -| lanelet2_map_path | std::string | The lanelet2 map path | None | diff --git a/map/map_loader/config/lanelet2_map_loader.param.yaml b/map/map_loader/config/lanelet2_map_loader.param.yaml index 971af0147b0fe..24d2b0e8ed7a8 100755 --- a/map/map_loader/config/lanelet2_map_loader.param.yaml +++ b/map/map_loader/config/lanelet2_map_loader.param.yaml @@ -1,7 +1,3 @@ /**: ros__parameters: - lanelet2_map_projector_type: MGRS # Options: MGRS, UTM, local - latitude: 40.816617984672746 # Latitude of map_origin, using in UTM - longitude: 29.360491808334285 # Longitude of map_origin, using in UTM - center_line_resolution: 5.0 # [m] diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 16681f3bd290d..2fb8b893d8fce 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -36,16 +36,15 @@ class Lanelet2MapLoaderNode : public rclcpp::Node static lanelet::LaneletMapPtr load_map( const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, const double & map_origin_lat = 0.0, const double & map_origin_lon = 0.0); - static const MapProjectorInfo get_map_projector_type( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, - const double & map_origin_lat, const double & map_origin_lon); static HADMapBin create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now); private: + void on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg); + + rclcpp::Subscription::SharedPtr sub_map_projector_type_; rclcpp::Publisher::SharedPtr pub_map_bin_; - rclcpp::Publisher::SharedPtr pub_map_projector_type_; }; #endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index aafa66a35be84..42c46e2b5e96c 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -49,16 +50,21 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options) : Node("lanelet2_map_loader", options) +{ + // subscription + sub_map_projector_type_ = create_subscription( + "input/map_projector_info", rclcpp::QoS{1}.transient_local(), + [this](const MapProjectorInfo::ConstSharedPtr msg) { on_map_projector_info(msg); }); +} + +void Lanelet2MapLoaderNode::on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg) { const auto lanelet2_filename = declare_parameter("lanelet2_map_path", ""); - const auto lanelet2_map_projector_type = declare_parameter("lanelet2_map_projector_type", "MGRS"); const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); - const double map_origin_lat = declare_parameter("latitude", 0.0); - const double map_origin_lon = declare_parameter("longitude", 0.0); // load map from file const auto map = - load_map(lanelet2_filename, lanelet2_map_projector_type, map_origin_lat, map_origin_lon); + load_map(lanelet2_filename, msg->type, msg->map_origin.latitude, msg->map_origin.longitude); if (!map) { return; } @@ -69,16 +75,10 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options // create map bin msg const auto map_bin_msg = create_map_bin_msg(map, lanelet2_filename, now()); - const auto map_projector_type_msg = get_map_projector_type( - lanelet2_filename, lanelet2_map_projector_type, map_origin_lat, map_origin_lon); // create publisher and publish pub_map_bin_ = create_publisher("output/lanelet2_map", rclcpp::QoS{1}.transient_local()); pub_map_bin_->publish(map_bin_msg); - // create publisher and publish - pub_map_projector_type_ = - create_publisher("map_projector_type", rclcpp::QoS{1}.transient_local()); - pub_map_projector_type_->publish(map_projector_type_msg); } lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( @@ -96,7 +96,6 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( lanelet::GPSPoint position{map_origin_lat, map_origin_lon}; lanelet::Origin origin{position}; lanelet::projection::UtmProjector projector{origin}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); if (errors.empty()) { return map; @@ -137,27 +136,6 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return nullptr; } -const MapProjectorInfo Lanelet2MapLoaderNode::get_map_projector_type( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, - const double & map_origin_lat, const double & map_origin_lon) -{ - lanelet::ErrorMessages errors{}; - MapProjectorInfo map_projector_type_msg; - if (lanelet2_map_projector_type == "MGRS") { - lanelet::projection::MGRSProjector projector{}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); - map_projector_type_msg.type = "MGRS"; - map_projector_type_msg.mgrs_grid = projector.getProjectedMGRSGrid(); - } else if (lanelet2_map_projector_type == "UTM") { - map_projector_type_msg.type = "UTM"; - map_projector_type_msg.map_origin.latitude = map_origin_lat; - map_projector_type_msg.map_origin.longitude = map_origin_lon; - } else { - map_projector_type_msg.type = "local"; - } - return map_projector_type_msg; -} - HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) { diff --git a/map/map_projection_loader/CMakeLists.txt b/map/map_projection_loader/CMakeLists.txt new file mode 100644 index 0000000000000..a53cdddf93b5b --- /dev/null +++ b/map/map_projection_loader/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.14) +project(map_projection_loader) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_find_build_dependencies() + +ament_auto_add_library(map_projection_loader_lib SHARED + src/map_projection_loader.cpp + src/load_info_from_lanelet2_map.cpp +) + +target_link_libraries(map_projection_loader_lib yaml-cpp) + +ament_auto_add_executable(map_projection_loader src/map_projection_loader_node.cpp) + +target_compile_options(map_projection_loader PUBLIC -g -Wall -Wextra -Wpedantic -Werror) + +target_link_libraries(map_projection_loader map_projection_loader_lib) +target_include_directories(map_projection_loader PUBLIC include) + +function(add_testcase filepath) + get_filename_component(filename ${filepath} NAME) + string(REGEX REPLACE ".cpp" "" test_name ${filename}) + ament_add_gmock(${test_name} ${filepath}) + target_link_libraries("${test_name}" map_projection_loader_lib) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) +endfunction() + +if(BUILD_TESTING) + # Test python scripts + add_launch_test( + test/test_node_load_mgrs_from_yaml.test.py + TIMEOUT "30" + ) + add_launch_test( + test/test_node_load_local_from_yaml.test.py + TIMEOUT "30" + ) + add_launch_test( + test/test_node_load_utm_from_yaml.test.py + TIMEOUT "30" + ) + install(DIRECTORY + test/data/ + DESTINATION share/${PROJECT_NAME}/test/data/ + ) + + # Test c++ scripts + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + add_testcase(test/test_load_info_from_lanelet2_map.cpp) +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch +) diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md new file mode 100644 index 0000000000000..bbf15f34929da --- /dev/null +++ b/map/map_projection_loader/README.md @@ -0,0 +1,62 @@ +# map_projection_loader + +## Feature + +`map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating. +This is necessary information especially when you want to convert from global (geoid) to local coordinate or the other way around. + +- If `map_projector_info_path` DOES exist, this node loads it and publishes the map projection information accordingly. +- If `map_projector_info_path` does NOT exist, the node assumes that you are using the `MGRS` projection type, and loads the lanelet2 map instead to extract the MGRS grid. + - **DEPRECATED WARNING: This interface that uses the lanelet2 map is not recommended. Please prepare the YAML file instead.** + +## Map projector info file specification + +You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `map_loader`. + +```bash +sample-map-rosbag +├── lanelet2_map.osm +├── pointcloud_map.pcd +├── map_projector_info.yaml +└── pointcloud_map_metadata.yaml +``` + +### Using local coordinate + +```yaml +# map_projector_info.yaml +type: "Local" +``` + +### Using MGRS + +If you want to use MGRS, please specify the MGRS grid as well. + +```yaml +# map_projector_info.yaml +type: "MGRS" +mgrs_grid: "54SUE" +``` + +### Using UTM + +If you want to use UTM, please specify the map origin as well. + +```yaml +# map_projector_info.yaml +type: "UTM" +map_origin: + latitude: 35.6092 + longitude: 139.7303 +``` + +## Published Topics + +- ~/map_projector_info (tier4_map_msgs/MapProjectorInfo) : Topic for defining map projector information + +## Parameters + +| Name | Type | Description | +| :---------------------- | :---------- | :------------------------------------------------------------------------------- | +| map_projector_info_path | std::string | A path to map_projector_info.yaml (used by default) | +| lanelet2_map_path | std::string | A path to lanelet2 map (used only when `map_projector_info_path` does not exist) | diff --git a/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp b/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp new file mode 100644 index 0000000000000..746f16e0f6b33 --- /dev/null +++ b/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp @@ -0,0 +1,29 @@ +// Copyright 2023 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 MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ +#define MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ + +#include +#include +#include +#include + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename); + +#endif // MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp new file mode 100644 index 0000000000000..de19ac5dabda4 --- /dev/null +++ b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp @@ -0,0 +1,35 @@ +// Copyright 2023 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 MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ +#define MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename); + +class MapProjectionLoader : public rclcpp::Node +{ +public: + MapProjectionLoader(); + +private: + rclcpp::Publisher::SharedPtr publisher_; +}; + +#endif // MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/map_projection_loader/launch/map_projection_loader.launch.xml new file mode 100644 index 0000000000000..6448675c4a75f --- /dev/null +++ b/map/map_projection_loader/launch/map_projection_loader.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml new file mode 100644 index 0000000000000..84f66583ed840 --- /dev/null +++ b/map/map_projection_loader/package.xml @@ -0,0 +1,29 @@ + + + + map_projection_loader + 0.1.0 + map_projection_loader package as a ROS 2 node + Koji Minoda + Yamato Ando + Masahiro Sakamoto + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + lanelet2_extension + rclcpp + rclcpp_components + tier4_map_msgs + + ament_cmake_gmock + ament_cmake_gtest + ament_lint_auto + autoware_lint_common + ros_testing + + + ament_cmake + + diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp new file mode 100644 index 0000000000000..a93a94f296d45 --- /dev/null +++ b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -0,0 +1,39 @@ +// Copyright 2023 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 "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include +#include +#include +#include + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename) +{ + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + const lanelet::LaneletMapPtr map = lanelet::load(filename, projector, &errors); + if (!errors.empty()) { + throw std::runtime_error("Error occurred while loading lanelet2 map"); + } + + tier4_map_msgs::msg::MapProjectorInfo msg; + msg.type = "MGRS"; + msg.mgrs_grid = projector.getProjectedMGRSGrid(); + return msg; +} diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp new file mode 100644 index 0000000000000..ccea8d7417cbc --- /dev/null +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -0,0 +1,70 @@ +// Copyright 2023 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 "map_projection_loader/map_projection_loader.hpp" + +#include "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) +{ + YAML::Node data = YAML::LoadFile(filename); + + tier4_map_msgs::msg::MapProjectorInfo msg; + msg.type = data["type"].as(); + if (msg.type == "MGRS") { + msg.mgrs_grid = data["mgrs_grid"].as(); + } else if (msg.type == "UTM") { + msg.map_origin.latitude = data["map_origin"]["latitude"].as(); + msg.map_origin.longitude = data["map_origin"]["longitude"].as(); + } else if (msg.type == "local") { + ; // do nothing + } else { + throw std::runtime_error( + "Invalid map projector type. Currently supported types: MGRS, UTM, and local"); + } + return msg; +} + +MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") +{ + std::string yaml_filename = this->declare_parameter("map_projector_info_path"); + std::string lanelet2_map_filename = this->declare_parameter("lanelet2_map_path"); + std::ifstream file(yaml_filename); + + tier4_map_msgs::msg::MapProjectorInfo msg; + + bool use_yaml_file = file.is_open(); + if (use_yaml_file) { + RCLCPP_INFO(this->get_logger(), "Load %s", yaml_filename.c_str()); + msg = load_info_from_yaml(yaml_filename); + } else { + RCLCPP_INFO(this->get_logger(), "Load %s", lanelet2_map_filename.c_str()); + RCLCPP_WARN( + this->get_logger(), + "DEPRECATED WARNING: Loading map projection info from lanelet2 map may soon be deleted. " + "Please use map_projector_info.yaml instead. For more info, visit " + "https://github.com/autowarefoundation/autoware.universe/blob/main/map/map_projection_loader/" + "README.md"); + msg = load_info_from_lanelet2_map(lanelet2_map_filename); + } + + // Publish the message + publisher_ = this->create_publisher( + "~/map_projector_info", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); + publisher_->publish(msg); +} diff --git a/map/map_projection_loader/src/map_projection_loader_node.cpp b/map/map_projection_loader/src/map_projection_loader_node.cpp new file mode 100644 index 0000000000000..1d9336be0d9dd --- /dev/null +++ b/map/map_projection_loader/src/map_projection_loader_node.cpp @@ -0,0 +1,23 @@ +// Copyright 2023 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 "map_projection_loader/map_projection_loader.hpp" + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/map/map_projection_loader/test/data/projection_info_local.yaml b/map/map_projection_loader/test/data/projection_info_local.yaml new file mode 100644 index 0000000000000..cea4aaf31d439 --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_local.yaml @@ -0,0 +1 @@ +type: local diff --git a/map/map_projection_loader/test/data/projection_info_mgrs.yaml b/map/map_projection_loader/test/data/projection_info_mgrs.yaml new file mode 100644 index 0000000000000..d7687521be5fa --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_mgrs.yaml @@ -0,0 +1,2 @@ +type: MGRS +mgrs_grid: 54SUE diff --git a/map/map_projection_loader/test/data/projection_info_utm.yaml b/map/map_projection_loader/test/data/projection_info_utm.yaml new file mode 100644 index 0000000000000..002383c97a474 --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_utm.yaml @@ -0,0 +1,4 @@ +type: UTM +map_origin: + latitude: 35.6762 + longitude: 139.6503 diff --git a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp new file mode 100644 index 0000000000000..52abacf67f344 --- /dev/null +++ b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -0,0 +1,70 @@ +// Copyright 2023 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 "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include +#include + +#include + +#include + +void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) +{ + int zone = std::stoi(mgrs_coord.substr(0, 2)); + bool is_north = false; + int precision = 0; + double utm_x{}; + double utm_y{}; + double lat{}; + double lon{}; + GeographicLib::MGRS::Reverse(mgrs_coord, zone, is_north, utm_x, utm_y, precision, false); + GeographicLib::UTMUPS::Reverse(zone, is_north, utm_x, utm_y, lat, lon); + + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << ""; + + file.close(); +} + +TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) +{ + // Save dummy lanelet2 map + const std::string mgrs_grid = "54SUE"; + const std::string mgrs_coord = mgrs_grid + "1000010000"; + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_lanelet2_map(mgrs_coord, output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "MGRS"); + EXPECT_EQ(projector_info.mgrs_grid, mgrs_grid); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleMock(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py new file mode 100644 index 0000000000000..aa0e3245565b5 --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -0,0 +1,143 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_local.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadLocalFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py new file mode 100644 index 0000000000000..ae29b4b06c61c --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -0,0 +1,144 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_mgrs.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadMGRSFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + self.assertEqual(self.received_message.mgrs_grid, yaml_data["mgrs_grid"]) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py new file mode 100644 index 0000000000000..8da98bbb8b25d --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py @@ -0,0 +1,149 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_utm.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadUTMFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + self.assertEqual( + self.received_message.map_origin.latitude, yaml_data["map_origin"]["latitude"] + ) + self.assertEqual( + self.received_message.map_origin.longitude, yaml_data["map_origin"]["longitude"] + ) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) From 1680656a93ddb58ef50b32a2fa96987966ebd2a0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 10 Aug 2023 12:05:04 +0900 Subject: [PATCH 145/266] feat(avoidance): output unconfortable path with unsafe state (#4536) * feat(avoidance): output unconfortable path with unsafe state Signed-off-by: satoshi-ota * feat(avoidance): make it selectable avoidance policy Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 21 ++++++++-- .../avoidance/avoidance_module.hpp | 9 +++++ .../utils/avoidance/avoidance_module_data.hpp | 18 ++++++++- .../avoidance/avoidance_module.cpp | 40 ++++++++++--------- .../src/scene_module/avoidance/manager.cpp | 17 ++++++-- .../src/utils/avoidance/utils.cpp | 2 +- 6 files changed, 79 insertions(+), 28 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 22de79f4dc7d0..ac3840baa1c4c 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -175,16 +175,29 @@ max_distance: 20.0 # [m] stop_buffer: 1.0 # [m] - constraints: - # vehicle slows down under longitudinal constraints - use_constraints_for_decel: false # [-] + policy: + # policy for vehicle slow down behavior. select "best_effort" or "reliable". + # "best_effort": slow down deceleration & jerk are limited by constraints. + # but there is a possibility that the vehicle can't stop in front of the vehicle. + # "reliable": insert stop or slow down point with ignoring decel/jerk constraints. + # make it possible to increase chance to avoid but uncomfortable deceleration maybe happen. + deceleration: "best_effort" # [-] + # policy for avoidance lateral margin. select "best_effort" or "reliable". + # "best_effort": output avoidance path with shorten lateral margin when there is no enough longitudinal + # margin to avoid. + # "reliable": module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid + # with expected lateral margin. + lateral_margin: "best_effort" # [-] + # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin. + use_shorten_margin_immediately: true # [-] + constraints: # lateral constraints lateral: velocity: [1.0, 1.38, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] # longitudinal constraints longitudinal: diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 3095ec2c03251..55ecee17b9778 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -480,6 +480,15 @@ class AvoidanceModule : public SceneModuleInterface */ bool isSafePath(ShiftedPath & shifted_path, DebugData & debug) const; + bool isComfortable(const AvoidLineArray & shift_lines) const + { + return std::all_of(shift_lines.begin(), shift_lines.end(), [&](const auto & line) { + return PathShifter::calcJerkFromLatLonDistance( + line.getRelativeLength(), line.getRelativeLongitudinal(), + helper_.getAvoidanceEgoSpeed()) < helper_.getLateralMaxJerkLimit(); + }); + } + // post process /** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 0263eee5fe727..94b914b65a067 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -113,8 +113,11 @@ struct AvoidanceParameters // use intersection area for avoidance bool use_intersection_areas{false}; - // constrains - bool use_constraints_for_decel{false}; + // // constrains + // bool use_constraints_for_decel{false}; + + // // policy + // bool use_relaxed_margin_immediately{false}; // max deceleration for double max_deceleration; @@ -274,6 +277,15 @@ struct AvoidanceParameters // For shift line generation process. Remove sharp(=jerky) shift line. double sharp_shift_filter_threshold; + // policy + bool use_shorten_margin_immediately{false}; + + // policy + std::string policy_deceleration{"best_effort"}; + + // policy + std::string policy_lateral_margin{"best_effort"}; + // target velocity matrix std::vector velocity_map; @@ -465,6 +477,8 @@ struct AvoidancePlanningData bool safe{false}; + bool comfortable{false}; + bool avoid_required{false}; bool yield_required{false}; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index db80bc72f21ad..92f586a1ca70a 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -95,6 +95,11 @@ bool isDrivingSameLane( return !same_ids.empty(); } + +bool isBestEffort(const std::string & policy) +{ + return policy == "best_effort"; +} } // namespace AvoidanceModule::AvoidanceModule( @@ -129,7 +134,7 @@ bool AvoidanceModule::isExecutionRequested() const bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return avoidance_data_.safe; + return avoidance_data_.safe && avoidance_data_.comfortable; } bool AvoidanceModule::canTransitSuccessState() @@ -448,6 +453,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de * Check avoidance path safety. For each target objects and the objects in adjacent lanes, * check that there is a certain amount of margin in the lateral and longitudinal direction. */ + data.comfortable = isComfortable(data.unapproved_new_sl); data.safe = isSafePath(data.candidate_path, debug); } @@ -616,7 +622,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif return; } - insertPrepareVelocity(path); + // insertPrepareVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { @@ -624,20 +630,20 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif } case AvoidanceState::YIELD: { insertYieldVelocity(path); - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); removeRegisteredShiftLines(); break; } case AvoidanceState::AVOID_PATH_NOT_READY: { - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); break; } case AvoidanceState::AVOID_PATH_READY: { - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); break; } case AvoidanceState::AVOID_EXECUTE: { - insertStopPoint(parameters_->use_constraints_for_decel, path); + insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); break; } default: @@ -835,6 +841,10 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( const auto avoiding_shift = desire_shift_length - current_ego_shift; const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(avoiding_shift); + if (!isBestEffort(parameters_->policy_lateral_margin)) { + return desire_shift_length; + } + // ego already has enough positive shift. const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3; if (is_object_on_right && has_enough_positive_shift) { @@ -847,6 +857,11 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( return desire_shift_length; } + // don't relax shift length since it can stop in front of the object. + if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) { + return desire_shift_length; + } + // calculate remaining distance. const auto prepare_distance = helper_.getNominalPrepareDistance(); const auto constant = @@ -883,7 +898,7 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( } // avoidance distance is not enough. unavoidable. - if (!parameters_->use_constraints_for_decel) { + if (!isBestEffort(parameters_->policy_deceleration)) { object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; return boost::none; } @@ -2369,13 +2384,6 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat return subsequent; }; - // check jerk limit. - const auto is_large_jerk = [this](const auto & s) { - const auto jerk = PathShifter::calcJerkFromLatLonDistance( - s.getRelativeLength(), s.getRelativeLongitudinal(), helper_.getAvoidanceEgoSpeed()); - return jerk > helper_.getLateralMaxJerkLimit(); - }; - // check ignore or not. const auto is_ignore_shift = [this](const auto & s) { return std::abs(helper_.getRelativeShiftToPath(s)) < parameters_->lateral_execution_threshold; @@ -2392,10 +2400,6 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat } if (!is_ignore_shift(candidate)) { - if (is_large_jerk(candidate)) { - break; - } - return get_subsequent_shift(i); } } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index a0ae98276c05e..be8c610611422 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -191,10 +191,21 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.stop_buffer = get_parameter(node, ns + "stop_buffer"); } - // constraints + // policy { - std::string ns = "avoidance.constraints."; - p.use_constraints_for_decel = get_parameter(node, ns + "use_constraints_for_decel"); + std::string ns = "avoidance.policy."; + p.policy_deceleration = get_parameter(node, ns + "deceleration"); + p.policy_lateral_margin = get_parameter(node, ns + "lateral_margin"); + p.use_shorten_margin_immediately = + get_parameter(node, ns + "use_shorten_margin_immediately"); + + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + + if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } } // constraints (longitudinal) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 58beaf9cf3a87..ed38cc663bc84 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -725,7 +725,7 @@ void fillObjectStoppableJudge( ObjectData & object_data, const ObjectDataArray & registered_objects, const double feasible_stop_distance, const std::shared_ptr & parameters) { - if (!parameters->use_constraints_for_decel) { + if (parameters->policy_deceleration == "reliable") { object_data.is_stoppable = true; return; } From 9f22504f4562c826b372fdf1ebec712001f6b9bc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 10 Aug 2023 12:26:36 +0900 Subject: [PATCH 146/266] fix(scnenario_selector): prevent changing scneario when same uuid route is received (#4569) Signed-off-by: kosuke55 --- .../src/scenario_selector_node/scenario_selector_node.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index dfba038dee898..cffb490464de0 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -197,8 +197,13 @@ void ScenarioSelectorNode::onMap( void ScenarioSelectorNode::onRoute( const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg) { + // When the route id is the same (e.g. reporting with modified goal) keep the current scenario. + // Otherwise, reset the scenario. + if (!route_handler_ || route_handler_->getRouteUuid() != msg->uuid) { + current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; + } + route_ = msg; - current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; } void ScenarioSelectorNode::onOdom(const nav_msgs::msg::Odometry::ConstSharedPtr msg) From f52d0aa90b7b6b5a3c3691d9af3ad7ea60fa7e94 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 10 Aug 2023 13:33:24 +0900 Subject: [PATCH 147/266] chore: update CODEOWNERS (#4550) Signed-off-by: GitHub Co-authored-by: kminoda --- .github/CODEOWNERS | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 1c0587f1ac1d5..4b1727e8a67b1 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -79,6 +79,7 @@ launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp +localization/ar_tag_based_localizer/** masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/initial_pose_button_panel/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp @@ -95,6 +96,7 @@ localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp masahiro localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp map/map_height_fitter/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp map/map_loader/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp +map/map_projection_loader/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp map/map_tf_generator/** azumi.suzuki@tier4.jp map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp perception/bytetrack/** manato.hirabayashi@tier4.jp From 0c2c703de2e28e1ce52831aec96f74e6e6125e73 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 10 Aug 2023 15:11:15 +0900 Subject: [PATCH 148/266] fix(avoidance): remove unexpected comment out (#4587) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 92f586a1ca70a..a763bab7897fb 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -622,7 +622,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif return; } - // insertPrepareVelocity(path); + insertPrepareVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { From 715996523f6254e04669d25b7679d5274fcde7a9 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 10 Aug 2023 16:17:19 +0900 Subject: [PATCH 149/266] fix(behavior_path_planner): fix bad dynamic drivable area expansion at path extremities (#4259) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.hpp | 2 +- .../drivable_area_expansion/expansion.hpp | 14 +- .../drivable_area_expansion/footprints.hpp | 4 +- .../drivable_area_expansion/map_utils.hpp | 2 +- .../utils/drivable_area_expansion/types.hpp | 6 +- .../drivable_area_expansion.cpp | 203 +++++++++++------- .../drivable_area_expansion/expansion.cpp | 51 +++-- .../drivable_area_expansion/footprints.cpp | 8 +- .../drivable_area_expansion/map_utils.cpp | 4 +- .../test/test_drivable_area_expansion.cpp | 32 +-- 10 files changed, 202 insertions(+), 124 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp index eadfb72a42afa..53ef91473fe24 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp @@ -40,7 +40,7 @@ void expandDrivableArea( /// @param[in] expansion_polygons polygons to add to the drivable area /// @return expanded drivable area polygon polygon_t createExpandedDrivableAreaPolygon( - const PathWithLaneId & path, const multipolygon_t & expansion_polygons); + const PathWithLaneId & path, const multi_polygon_t & expansion_polygons); /// @brief Update the drivable area of the given path with the given polygon /// @details this function splits the polygon into a left and right bound and sets it in the path diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp index 33bccf90ffbe8..70cc8a8bc5925 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp @@ -36,7 +36,7 @@ namespace drivable_area_expansion /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multilinestring_t & limit_lines); + const multi_linestring_t & limit_lines); /// @brief Calculate the distance limit required for the polygon to not cross the limit polygons. /// @details Calculate the minimum distance from base_ls to an intersection of limit_polygons and @@ -47,7 +47,7 @@ double calculateDistanceLimit( /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multipolygon_t & limit_polygons); + const multi_polygon_t & limit_polygons); /// @brief Create a polygon from a base line with a given expansion distance /// @param[in] base_ls base linestring from which the polygon is created @@ -64,9 +64,9 @@ polygon_t createExpansionPolygon( /// @param[in] uncrossable_lines lines that should not be crossed by the expanded drivable area /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionPolygons( - const PathWithLaneId & path, const multipolygon_t & path_footprints, - const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines, +multi_polygon_t createExpansionPolygons( + const PathWithLaneId & path, const multi_polygon_t & path_footprints, + const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines, const DrivableAreaExpansionParameters & params); /// @brief Create polygons for the area where the drivable area should be expanded @@ -76,9 +76,9 @@ multipolygon_t createExpansionPolygons( /// @param[in] predicted_paths polygons of the dynamic objects' predicted paths /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionLaneletPolygons( +multi_polygon_t createExpansionLaneletPolygons( const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler, - const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths, + const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp index 25f061affaa48..e5e1c76f2521f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp @@ -55,7 +55,7 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t /// @param [in] objects objects from which to create polygons /// @param[in] params expansion parameters containing extra offsets to add to the dynamic objects /// @return footprint polygons of the object's predicted paths -multipolygon_t createObjectFootprints( +multi_polygon_t createObjectFootprints( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const DrivableAreaExpansionParameters & params); @@ -63,7 +63,7 @@ multipolygon_t createObjectFootprints( /// @param[in] path the path for which to create a footprint /// @param[in] params expansion parameters defining how to create the footprint /// @return footprint polygons of the path -multipolygon_t createPathFootprints( +multi_polygon_t createPathFootprints( const PathWithLaneId & path, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion #endif // BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__FOOTPRINTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp index 33c4cc8a0eff3..4524bd2be2299 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp @@ -28,7 +28,7 @@ namespace drivable_area_expansion /// @param[in] lanelet_map lanelet map /// @param[in] uncrossable_types types that cannot be crossed /// @return the uncrossable linestrings -multilinestring_t extractUncrossableLines( +multi_linestring_t extractUncrossableLines( const lanelet::LaneletMap & lanelet_map, const std::vector & uncrossable_types); /// @brief Determine if the given linestring has one of the given types diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp index e56ef4961589d..daabfa97598fd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp @@ -30,13 +30,13 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using point_t = tier4_autoware_utils::Point2d; -using multipoint_t = tier4_autoware_utils::MultiPoint2d; +using multi_point_t = tier4_autoware_utils::MultiPoint2d; using polygon_t = tier4_autoware_utils::Polygon2d; using ring_t = tier4_autoware_utils::LinearRing2d; -using multipolygon_t = tier4_autoware_utils::MultiPolygon2d; +using multi_polygon_t = tier4_autoware_utils::MultiPolygon2d; using segment_t = tier4_autoware_utils::Segment2d; using linestring_t = tier4_autoware_utils::LineString2d; -using multilinestring_t = tier4_autoware_utils::MultiLineString2d; +using multi_linestring_t = tier4_autoware_utils::MultiLineString2d; struct PointDistance { diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 21e3580c1f19a..617c3cd633cda 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -21,6 +21,8 @@ #include "behavior_path_planner/utils/drivable_area_expansion/types.hpp" #include "interpolation/linear_interpolation.hpp" +#include + #include namespace drivable_area_expansion @@ -33,7 +35,7 @@ void expandDrivableArea( { const auto uncrossable_lines = extractUncrossableLines(*route_handler.getLaneletMapPtr(), params.avoid_linestring_types); - multilinestring_t uncrossable_lines_in_range; + multi_linestring_t uncrossable_lines_in_range; const auto & p = path.points.front().point.pose.position; for (const auto & line : uncrossable_lines) if (boost::geometry::distance(line, point_t{p.x, p.y}) < params.max_path_arc_length) @@ -61,7 +63,7 @@ Point convert_point(const point_t & p) } polygon_t createExpandedDrivableAreaPolygon( - const PathWithLaneId & path, const multipolygon_t & expansion_polygons) + const PathWithLaneId & path, const multi_polygon_t & expansion_polygons) { polygon_t original_da_poly; original_da_poly.outer().reserve(path.left_bound.size() + path.right_bound.size() + 1); @@ -70,7 +72,7 @@ polygon_t createExpandedDrivableAreaPolygon( original_da_poly.outer().push_back(convert_point(*it)); original_da_poly.outer().push_back(original_da_poly.outer().front()); - multipolygon_t unions; + multi_polygon_t unions; auto expanded_da_poly = original_da_poly; for (const auto & p : expansion_polygons) { unions.clear(); @@ -81,59 +83,6 @@ polygon_t createExpandedDrivableAreaPolygon( return expanded_da_poly; } -std::array findLeftRightRanges( - const PathWithLaneId & path, const ring_t & expanded_drivable_area) -{ - const auto is_left_of_segment = [](const point_t & a, const point_t & b, const point_t & p) { - return (b.x() - a.x()) * (p.y() - a.y()) - (b.y() - a.y()) * (p.x() - a.x()) > 0; - }; - const auto is_left_of_path_start = [&](const point_t & p) { - return is_left_of_segment( - convert_point(path.points[0].point.pose.position), - convert_point(path.points[1].point.pose.position), p); - }; - const auto is_left_of_path_end = [&, size = path.points.size()](const point_t & p) { - return is_left_of_segment( - convert_point(path.points[size - 2].point.pose.position), - convert_point(path.points[size - 1].point.pose.position), p); - }; - const auto dist_to_path_start = [start = convert_point(path.points.front().point.pose.position)]( - const auto & p) { return boost::geometry::distance(start, p); }; - const auto dist_to_path_end = [end = convert_point(path.points.back().point.pose.position)]( - const auto & p) { return boost::geometry::distance(end, p); }; - - double min_start_dist = std::numeric_limits::max(); - auto start_transition = expanded_drivable_area.end(); - double min_end_dist = std::numeric_limits::max(); - auto end_transition = expanded_drivable_area.end(); - for (auto it = expanded_drivable_area.begin(); std::next(it) != expanded_drivable_area.end(); - ++it) { - if (is_left_of_path_start(*it) != is_left_of_path_start(*std::next(it))) { - const auto dist = dist_to_path_start(*it); - if (dist < min_start_dist) { - start_transition = it; - min_start_dist = dist; - } - } - if (is_left_of_path_end(*it) != is_left_of_path_end(*std::next(it))) { - const auto dist = dist_to_path_end(*it); - if (dist < min_end_dist) { - end_transition = it; - min_end_dist = dist; - } - } - } - const auto left_start = - is_left_of_path_start(*start_transition) ? start_transition : std::next(start_transition); - const auto right_start = - is_left_of_path_start(*start_transition) ? std::next(start_transition) : start_transition; - const auto left_end = - is_left_of_path_end(*end_transition) ? end_transition : std::next(end_transition); - const auto right_end = - is_left_of_path_end(*end_transition) ? std::next(end_transition) : end_transition; - return {left_start, left_end, right_start, right_end}; -} - void copy_z_over_arc_length( const std::vector & from, std::vector & to) { @@ -164,32 +113,134 @@ void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_ { const auto original_left_bound = path.left_bound; const auto original_right_bound = path.right_bound; + const auto is_left_of_segment = [](const point_t & a, const point_t & b, const point_t & p) { + return (b.x() - a.x()) * (p.y() - a.y()) - (b.y() - a.y()) * (p.x() - a.x()) > 0; + }; + // prepare delimiting lines: start and end of the original expanded drivable area + const auto start_segment = + segment_t{convert_point(path.left_bound.front()), convert_point(path.right_bound.front())}; + const auto end_segment = + segment_t{convert_point(path.left_bound.back()), convert_point(path.right_bound.back())}; + point_t start_segment_center; + boost::geometry::centroid(start_segment, start_segment_center); + const auto path_start_segment = + segment_t{start_segment_center, convert_point(path.points[1].point.pose.position)}; + point_t end_segment_center; + boost::geometry::centroid(end_segment, end_segment_center); + const auto path_end_segment = + segment_t{convert_point(path.points.back().point.pose.position), end_segment_center}; + const auto segment_to_line_intersection = + [](const auto p1, const auto p2, const auto q1, const auto q2) -> std::optional { + const auto line = Eigen::Hyperplane::Through(q1, q2); + const auto segment = Eigen::Hyperplane::Through(p1, p2); + const auto intersection = line.intersection(segment); + std::optional result; + const auto is_on_segment = + (p1.x() <= p2.x() ? intersection.x() >= p1.x() && intersection.x() <= p2.x() + : intersection.x() <= p1.x() && intersection.x() >= p2.x()) && + (p1.y() <= p2.y() ? intersection.y() >= p1.y() && intersection.y() <= p2.y() + : intersection.y() <= p1.y() && intersection.y() >= p2.y()); + if (is_on_segment) result = point_t{intersection.x(), intersection.y()}; + return result; + }; + // find intersection between the expanded drivable area and the delimiting lines + const auto & da = expanded_drivable_area.outer(); + struct Intersection + { + point_t intersection_point; + ring_t::const_iterator segment_it; + double distance = std::numeric_limits::max(); + explicit Intersection(ring_t::const_iterator it) : segment_it(it) {} + void update(const point_t & p, const ring_t::const_iterator & it, const double dist) + { + intersection_point = p; + segment_it = it; + distance = dist; + } + }; + Intersection start_left(da.end()); + Intersection end_left(da.end()); + Intersection start_right(da.end()); + Intersection end_right(da.end()); + for (auto it = da.begin(); it != da.end(); ++it) { + if (boost::geometry::distance(*it, start_segment.first) < 1e-3) + start_left.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, start_segment.second) < 1e-3) + start_right.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, end_segment.first) < 1e-3) + end_left.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, end_segment.second) < 1e-3) + end_right.update(*it, it, 0.0); + const auto inter_start = + std::next(it) == da.end() + ? segment_to_line_intersection(*it, da.front(), start_segment.first, start_segment.second) + : segment_to_line_intersection( + *it, *std::next(it), start_segment.first, start_segment.second); + if (inter_start) { + const auto dist = boost::geometry::distance(*inter_start, path_start_segment); + const auto is_left_of_path_start = is_left_of_segment( + convert_point(path.points[0].point.pose.position), + convert_point(path.points[1].point.pose.position), *inter_start); + if (is_left_of_path_start && dist < start_left.distance) + start_left.update(*inter_start, it, dist); + else if (!is_left_of_path_start && dist < start_right.distance) + start_right.update(*inter_start, it, dist); + } + const auto inter_end = + std::next(it) == da.end() + ? segment_to_line_intersection(*it, da.front(), end_segment.first, end_segment.second) + : segment_to_line_intersection(*it, *std::next(it), end_segment.first, end_segment.second); + if (inter_end) { + const auto dist = boost::geometry::distance(*inter_end, path_end_segment); + const auto is_left_of_path_end = is_left_of_segment( + convert_point(path.points.back().point.pose.position), end_segment_center, *inter_end); + if (is_left_of_path_end && dist < end_left.distance) + end_left.update(*inter_end, it, dist); + else if (!is_left_of_path_end && dist < end_right.distance) + end_right.update(*inter_end, it, dist); + } + } + if ( // ill-formed expanded drivable area -> keep the original bounds + start_left.segment_it == da.end() || start_right.segment_it == da.end() || + end_left.segment_it == da.end() || end_right.segment_it == da.end()) { + return; + } + // extract the expanded left and right bound from the expanded drivable area path.left_bound.clear(); path.right_bound.clear(); - const auto begin = expanded_drivable_area.outer().begin(); - const auto end = std::prev(expanded_drivable_area.outer().end()); - const auto & [left_start, left_end, right_start, right_end] = - findLeftRightRanges(path, expanded_drivable_area.outer()); - // NOTE: clockwise ordering -> positive increment for left bound, negative for right bound - if (left_start < left_end) { - path.left_bound.reserve(std::distance(left_start, left_end)); - for (auto it = left_start; it <= left_end; ++it) path.left_bound.push_back(convert_point(*it)); - } else { // loop back - path.left_bound.reserve(std::distance(left_start, end) + std::distance(begin, left_end)); - for (auto it = left_start; it != end; ++it) path.left_bound.push_back(convert_point(*it)); - for (auto it = begin; it <= left_end; ++it) path.left_bound.push_back(convert_point(*it)); + path.left_bound.push_back(convert_point(start_left.intersection_point)); + path.right_bound.push_back(convert_point(start_right.intersection_point)); + if (!boost::geometry::equals(start_right.intersection_point, *start_right.segment_it)) + path.right_bound.push_back(convert_point(*start_right.segment_it)); + if (start_left.segment_it < end_left.segment_it) { + for (auto it = std::next(start_left.segment_it); it <= end_left.segment_it; ++it) + path.left_bound.push_back(convert_point(*it)); + } else { + for (auto it = std::next(start_left.segment_it); it < da.end(); ++it) + path.left_bound.push_back(convert_point(*it)); + for (auto it = da.begin(); it <= end_left.segment_it; ++it) + path.left_bound.push_back(convert_point(*it)); } - if (right_start > right_end) { - path.right_bound.reserve(std::distance(right_end, right_start)); - for (auto it = right_start; it >= right_end; --it) + if (!boost::geometry::equals(end_left.intersection_point, *end_left.segment_it)) + path.left_bound.push_back(convert_point(end_left.intersection_point)); + if (start_right.segment_it < end_right.segment_it) { + for (auto it = std::prev(start_right.segment_it); it >= da.begin(); --it) + path.right_bound.push_back(convert_point(*it)); + for (auto it = std::prev(da.end()); it > end_right.segment_it; --it) + path.right_bound.push_back(convert_point(*it)); + } else { + for (auto it = std::prev(start_right.segment_it); it > end_right.segment_it; --it) path.right_bound.push_back(convert_point(*it)); - } else { // loop back - path.right_bound.reserve(std::distance(begin, right_start) + std::distance(right_end, end)); - for (auto it = right_start; it >= begin; --it) path.right_bound.push_back(convert_point(*it)); - for (auto it = end - 1; it >= right_end; --it) path.right_bound.push_back(convert_point(*it)); } + if (!boost::geometry::equals(end_right.intersection_point, *std::next(end_right.segment_it))) + path.right_bound.push_back(convert_point(end_right.intersection_point)); + // remove possible duplicated points + const auto point_cmp = [](const auto & p1, const auto & p2) { + return p1.x == p2.x && p1.y == p2.y; + }; + std::unique(path.left_bound.begin(), path.left_bound.end(), point_cmp); + std::unique(path.right_bound.begin(), path.right_bound.end(), point_cmp); copy_z_over_arc_length(original_left_bound, path.left_bound); copy_z_over_arc_length(original_right_bound, path.right_bound); } - } // namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp index 7bff7bef578ce..035cc579d2a82 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp @@ -22,10 +22,10 @@ namespace drivable_area_expansion double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multilinestring_t & limit_lines) + const multi_linestring_t & limit_lines) { auto dist_limit = std::numeric_limits::max(); - multipoint_t intersections; + multi_point_t intersections; boost::geometry::intersection(expansion_polygon, limit_lines, intersections); for (const auto & p : intersections) dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); @@ -34,11 +34,11 @@ double calculateDistanceLimit( double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multipolygon_t & limit_polygons) + const multi_polygon_t & limit_polygons) { auto dist_limit = std::numeric_limits::max(); for (const auto & polygon : limit_polygons) { - multipoint_t intersections; + multi_point_t intersections; boost::geometry::intersection(expansion_polygon, polygon, intersections); for (const auto & p : intersections) dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); @@ -50,7 +50,7 @@ polygon_t createExpansionPolygon( const linestring_t & base_ls, const double dist, const bool is_left_side) { namespace strategy = boost::geometry::strategy::buffer; - multipolygon_t polygons; + multi_polygon_t polygons; // set a non 0 value for the buffer as it sometimes causes no polygon to be returned by bg:buffer constexpr auto zero = 0.1; const auto left_dist = is_left_side ? dist : zero; @@ -66,7 +66,7 @@ std::array calculate_arc_length_range_and_distance( const linestring_t & path_ls, const polygon_t & footprint, const linestring_t & bound, const bool is_left, const double path_length) { - multipoint_t intersections; + multi_point_t intersections; double expansion_dist = 0.0; double from_arc_length = std::numeric_limits::max(); double to_arc_length = std::numeric_limits::min(); @@ -93,7 +93,7 @@ std::array calculate_arc_length_range_and_distance( polygon_t create_compensation_polygon( const linestring_t & base_ls, const double compensation_dist, const bool is_left, - const multilinestring_t uncrossable_lines, const multipolygon_t & predicted_paths) + const multi_linestring_t uncrossable_lines, const multi_polygon_t & predicted_paths) { polygon_t compensation_polygon = createExpansionPolygon(base_ls, compensation_dist, !is_left); double dist_limit = std::min( @@ -106,9 +106,9 @@ polygon_t create_compensation_polygon( return compensation_polygon; } -multipolygon_t createExpansionPolygons( - const PathWithLaneId & path, const multipolygon_t & path_footprints, - const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines, +multi_polygon_t createExpansionPolygons( + const PathWithLaneId & path, const multi_polygon_t & path_footprints, + const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines, const DrivableAreaExpansionParameters & params) { linestring_t path_ls; @@ -118,9 +118,32 @@ multipolygon_t createExpansionPolygons( path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y); for (const auto & p : path.left_bound) left_ls.emplace_back(p.x, p.y); for (const auto & p : path.right_bound) right_ls.emplace_back(p.x, p.y); + // extend the path linestring to the beginning and end of the drivable area + if (!right_ls.empty() && !left_ls.empty() && path_ls.size() > 2) { + const auto left_proj_begin = point_to_line_projection(left_ls.front(), path_ls[0], path_ls[1]); + const auto right_proj_begin = + point_to_line_projection(right_ls.front(), path_ls[0], path_ls[1]); + const auto left_ls_proj_begin = point_to_linestring_projection(left_proj_begin.point, path_ls); + const auto right_ls_proj_begin = + point_to_linestring_projection(right_proj_begin.point, path_ls); + if (left_ls_proj_begin.arc_length < right_ls_proj_begin.arc_length) + path_ls.insert(path_ls.begin(), left_proj_begin.point); + else + path_ls.insert(path_ls.begin(), right_proj_begin.point); + const auto left_proj_end = + point_to_line_projection(left_ls.back(), path_ls[path_ls.size() - 2], path_ls.back()); + const auto right_proj_end = + point_to_line_projection(right_ls.back(), path_ls[path_ls.size() - 2], path_ls.back()); + const auto left_ls_proj_end = point_to_linestring_projection(left_proj_end.point, path_ls); + const auto right_ls_proj_end = point_to_linestring_projection(right_proj_end.point, path_ls); + if (left_ls_proj_end.arc_length > right_ls_proj_end.arc_length) + path_ls.push_back(left_proj_end.point); + else + path_ls.push_back(right_proj_end.point); + } const auto path_length = static_cast(boost::geometry::length(path_ls)); - multipolygon_t expansion_polygons; + multi_polygon_t expansion_polygons; for (const auto & footprint : path_footprints) { bool is_left = true; for (const auto & bound : {left_ls, right_ls}) { @@ -161,12 +184,12 @@ multipolygon_t createExpansionPolygons( return expansion_polygons; } -multipolygon_t createExpansionLaneletPolygons( +multi_polygon_t createExpansionLaneletPolygons( const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler, - const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths, + const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths, const DrivableAreaExpansionParameters & params) { - multipolygon_t expansion_polygons; + multi_polygon_t expansion_polygons; lanelet::ConstLanelets candidates; const auto already_added = [&](const auto & ll) { return std::find_if(candidates.begin(), candidates.end(), [&](const auto & l) { diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp index 77c8b7faa27eb..0c31093a83c0e 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp @@ -39,11 +39,11 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t return translatePolygon(rotatePolygon(base_footprint, angle), pose.position.x, pose.position.y); } -multipolygon_t createObjectFootprints( +multi_polygon_t createObjectFootprints( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const DrivableAreaExpansionParameters & params) { - multipolygon_t footprints; + multi_polygon_t footprints; if (params.avoid_dynamic_objects) { for (const auto & object : objects.objects) { const auto front = object.shape.dimensions.x / 2 + params.dynamic_objects_extra_front_offset; @@ -62,7 +62,7 @@ multipolygon_t createObjectFootprints( return footprints; } -multipolygon_t createPathFootprints( +multi_polygon_t createPathFootprints( const PathWithLaneId & path, const DrivableAreaExpansionParameters & params) { const auto left = params.ego_left_offset + params.ego_extra_left_offset; @@ -73,7 +73,7 @@ multipolygon_t createPathFootprints( base_footprint.outer() = { point_t{front, left}, point_t{front, right}, point_t{rear, right}, point_t{rear, left}, point_t{front, left}}; - multipolygon_t footprints; + multi_polygon_t footprints; // skip the last footprint as its orientation is usually wrong footprints.reserve(path.points.size() - 1); double arc_length = 0.0; diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp index 39a69fbd74914..ded67c251f7ae 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp @@ -26,10 +26,10 @@ namespace drivable_area_expansion { -multilinestring_t extractUncrossableLines( +multi_linestring_t extractUncrossableLines( const lanelet::LaneletMap & lanelet_map, const std::vector & uncrossable_types) { - multilinestring_t lines; + multi_linestring_t lines; linestring_t line; for (const auto & ls : lanelet_map.lineStringLayer) { if (hasTypes(ls, uncrossable_types)) { diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index 7c4967be14bb8..b02df9753e0b5 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -165,13 +165,13 @@ TEST(DrivableAreaExpansionProjection, SubLinestring) for (auto i = 0lu; i < ls.size(); ++i) EXPECT_TRUE(boost::geometry::equals(ls[i], sub[i])); } { - // arc lengths equal to existing point: sublinestring with same points + // arc lengths equal to existing point: sub-linestring with same points const auto sub = sub_linestring(ls, 1.0, 5.0); ASSERT_EQ(ls.size() - 2lu, sub.size()); for (auto i = 0lu; i < sub.size(); ++i) EXPECT_TRUE(boost::geometry::equals(ls[i + 1], sub[i])); } { - // arc lengths inside the original: sublinestring with some interpolated points + // arc lengths inside the original: sub-linestring with some interpolated points const auto sub = sub_linestring(ls, 1.5, 2.5); ASSERT_EQ(sub.size(), 3lu); EXPECT_NEAR(sub[0].x(), 1.5, eps); @@ -259,13 +259,14 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) params.max_path_arc_length = 0.0; // means no limit params.extra_arc_length = 1.0; params.expansion_method = "polygon"; - // 4m x 4m ego footprint + // 2m x 4m ego footprint params.ego_front_offset = 1.0; params.ego_rear_offset = -1.0; params.ego_left_offset = 2.0; params.ego_right_offset = -2.0; } - // we expect the expand the drivable area by 1m on each side + // we expect the drivable area to be expanded by 1m on each side + // BUT short paths, due to pruning at the edge of the driving area, there is no expansion drivable_area_expansion::expandDrivableArea( path, params, dynamic_objects, route_handler, path_lanes); // unchanged path points @@ -274,18 +275,21 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) EXPECT_NEAR(path.points[i].point.pose.position.x, i, eps); EXPECT_NEAR(path.points[i].point.pose.position.y, 0.0, eps); } + // expanded left bound - ASSERT_EQ(path.left_bound.size(), 2ul); + ASSERT_EQ(path.left_bound.size(), 3ul); EXPECT_NEAR(path.left_bound[0].x, 0.0, eps); - EXPECT_NEAR(path.left_bound[0].y, 2.0, eps); - EXPECT_NEAR(path.left_bound[1].x, 2.0, eps); - EXPECT_NEAR(path.left_bound[1].y, 2.0, eps); + EXPECT_NEAR(path.left_bound[0].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[1].x, 1.0, eps); + EXPECT_NEAR(path.left_bound[1].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[2].x, 2.0, eps); + EXPECT_NEAR(path.left_bound[2].y, 1.0, eps); // expanded right bound ASSERT_EQ(path.right_bound.size(), 3ul); EXPECT_NEAR(path.right_bound[0].x, 0.0, eps); - EXPECT_NEAR(path.right_bound[0].y, -2.0, eps); - EXPECT_NEAR(path.right_bound[1].x, 2.0, eps); - EXPECT_NEAR(path.right_bound[1].y, -2.0, eps); + EXPECT_NEAR(path.right_bound[0].y, -1.0, eps); + EXPECT_NEAR(path.right_bound[1].x, 1.0, eps); + EXPECT_NEAR(path.right_bound[1].y, -1.0, eps); EXPECT_NEAR(path.right_bound[2].x, 2.0, eps); EXPECT_NEAR(path.right_bound[2].y, -1.0, eps); } @@ -294,12 +298,12 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit) { using drivable_area_expansion::calculateDistanceLimit; using drivable_area_expansion::linestring_t; - using drivable_area_expansion::multilinestring_t; + using drivable_area_expansion::multi_linestring_t; using drivable_area_expansion::polygon_t; { const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; - const multilinestring_t uncrossable_lines = {}; + const multi_linestring_t uncrossable_lines = {}; const polygon_t expansion_polygon = { {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; const auto limit_distance = @@ -317,7 +321,7 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit) } { const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; - const multilinestring_t uncrossable_lines = { + const multi_linestring_t uncrossable_lines = { {{0.0, 2.0}, {10.0, 2.0}}, {{0.0, 1.5}, {10.0, 1.0}}}; const polygon_t expansion_polygon = { {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; From c0a6c0f6b5fd54df02d0ea6ed604e3f8088f4e3d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 10 Aug 2023 16:28:18 +0900 Subject: [PATCH 150/266] fix(behavior_velocity_crosswalk_module): prevent to access null stop_factor (#4589) Signed-off-by: tomoya.kimura --- .../src/scene_crosswalk.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 391b397dd82cd..64410c08a6f80 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1051,6 +1051,11 @@ void CrosswalkModule::planStop( return std::nullopt; }(); + if (!stop_factor) { + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 5000, "stop_factor is null"); + return; + } + // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); planning_utils::appendStopReason(*stop_factor, stop_reason); From 60d001e591af85420e9e89994e5ecc324ddbb260 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 16:31:49 +0900 Subject: [PATCH 151/266] feat(map_projection_loader): add backward compatibility for local map (#4586) * feat(map_projection_loader): add backward compatibility for local map Signed-off-by: kminoda * style(pre-commit): autofix * feat: add dummy typo Signed-off-by: kminoda * update test Signed-off-by: kminoda * revert unnecessary fix Signed-off-by: kminoda * style(pre-commit): autofix * rename test Signed-off-by: kminoda * fix Signed-off-by: kminoda * style(pre-commit): autofix * fix comment Signed-off-by: kminoda * remove comment Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/load_info_from_lanelet2_map.cpp | 20 +++++- .../test/test_load_info_from_lanelet2_map.cpp | 66 ++++++++++++++++++- 2 files changed, 82 insertions(+), 4 deletions(-) diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp index a93a94f296d45..77958c20a9e75 100644 --- a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp +++ b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -32,8 +32,24 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str throw std::runtime_error("Error occurred while loading lanelet2 map"); } + // If the lat & lon values in all the points of lanelet2 map are all zeros, + // it will be interpreted as a local map. + // If any single point exists with non-zero lat or lon values, it will be interpreted as MGRS. + bool is_local = true; + for (const auto & point : map->pointLayer) { + const auto gps_point = projector.reverse(point); + if (gps_point.lat != 0.0 || gps_point.lon != 0.0) { + is_local = false; + break; + } + } + tier4_map_msgs::msg::MapProjectorInfo msg; - msg.type = "MGRS"; - msg.mgrs_grid = projector.getProjectedMGRSGrid(); + if (is_local) { + msg.type = "local"; + } else { + msg.type = "MGRS"; + msg.mgrs_grid = projector.getProjectedMGRSGrid(); + } return msg; } diff --git a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp index 52abacf67f344..206053fd2e8d2 100644 --- a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp +++ b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -21,7 +21,7 @@ #include -void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) +void save_dummy_mgrs_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) { int zone = std::stoi(mgrs_coord.substr(0, 2)); bool is_north = false; @@ -47,13 +47,49 @@ void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & file.close(); } +void save_dummy_local_lanelet2_map(const std::string & output_path) +{ + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << " \n"; + file << " \n"; + file << ""; + + file.close(); +} + +void save_dummy_mgrs_lanelet2_map_with_one_zero_point(const std::string & output_path) +{ + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << " \n"; + file << " \n"; + file << ""; + + file.close(); +} + TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) { // Save dummy lanelet2 map const std::string mgrs_grid = "54SUE"; const std::string mgrs_coord = mgrs_grid + "1000010000"; const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; - save_dummy_lanelet2_map(mgrs_coord, output_path); + save_dummy_mgrs_lanelet2_map(mgrs_coord, output_path); // Test the function const auto projector_info = load_info_from_lanelet2_map(output_path); @@ -63,6 +99,32 @@ TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) EXPECT_EQ(projector_info.mgrs_grid, mgrs_grid); } +TEST(TestLoadFromLanelet2Map, LoadLocalGrid) +{ + // Save dummy lanelet2 map + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_local_lanelet2_map(output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "local"); +} + +TEST(TestLoadFromLanelet2Map, LoadNoLocalGrid) +{ + // Save dummy lanelet2 map + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_mgrs_lanelet2_map_with_one_zero_point(output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "MGRS"); +} + int main(int argc, char ** argv) { ::testing::InitGoogleMock(&argc, argv); From 2b7afb176b958fa7041a43898c008204c431592d Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 10 Aug 2023 19:14:35 +0900 Subject: [PATCH 152/266] refactor(initial_pose_button_panel): delete intial_pose_button_panel (#4519) Signed-off-by: yamato-ando Co-authored-by: yamato-ando --- .../initial_pose_button_panel/CMakeLists.txt | 24 ---- .../initial_pose_button_panel/README.md | 18 --- .../media/initialize_button.png | Bin 164979 -> 0 bytes .../initial_pose_button_panel/package.xml | 30 ----- .../plugins/plugin_description.xml | 9 -- .../src/initial_pose_button_panel.cpp | 123 ------------------ .../src/initial_pose_button_panel.hpp | 65 --------- 7 files changed, 269 deletions(-) delete mode 100644 localization/initial_pose_button_panel/CMakeLists.txt delete mode 100644 localization/initial_pose_button_panel/README.md delete mode 100644 localization/initial_pose_button_panel/media/initialize_button.png delete mode 100644 localization/initial_pose_button_panel/package.xml delete mode 100644 localization/initial_pose_button_panel/plugins/plugin_description.xml delete mode 100644 localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp delete mode 100644 localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp diff --git a/localization/initial_pose_button_panel/CMakeLists.txt b/localization/initial_pose_button_panel/CMakeLists.txt deleted file mode 100644 index 6c1c13e000a51..0000000000000 --- a/localization/initial_pose_button_panel/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(initial_pose_button_panel) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) - -add_definitions(-DQT_NO_KEYWORDS -g) -set(CMAKE_AUTOMOC ON) - -ament_auto_add_library(initial_pose_button_panel SHARED - src/initial_pose_button_panel.cpp) -target_link_libraries(initial_pose_button_panel - ${QT_LIBRARIES}) - -# Export the plugin to be imported by rviz2 -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package( - INSTALL_TO_SHARE - plugins -) diff --git a/localization/initial_pose_button_panel/README.md b/localization/initial_pose_button_panel/README.md deleted file mode 100644 index cdb4824ada0e2..0000000000000 --- a/localization/initial_pose_button_panel/README.md +++ /dev/null @@ -1,18 +0,0 @@ -# initial_pose_button_panel - -## Role - -`initial_pose_button_panel` is the package to send a request to the localization module to calculate the current ego pose. - -It starts calculating the current ego pose by pushing the button on Rviz, implemented as an Rviz plugin. -You can see the button on the right bottom of Rviz. - -![initialize_button](./media/initialize_button.png) - -## Input / Output - -### Input topics - -| Name | Type | Description | -| ---------------------------------------------- | --------------------------------------------- | -------------------------------------------------------------- | -| `/sensing/gnss/pose_with_covariance` (default) | geometry_msgs::msg::PoseWithCovarianceStamped | initial pose with covariance to calculate the current ego pose | diff --git a/localization/initial_pose_button_panel/media/initialize_button.png b/localization/initial_pose_button_panel/media/initialize_button.png deleted file mode 100644 index f7bfe8aa652ac736f730b493eccbc58e8944d438..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 164979 zcmY(q1yEeU5-yws3+`?qIEydt5@Z*5cXxLS4#C|axVw9BcXxMphoAfYdiCx-HC0=6 zc6Uz8O!qh4-wBnK7DI%?gZuL33nEDTm;9G6kOyDBd@KGA{dwnMQ#|SO1JXeVr1<^w z^89WX^5x5qFQ8w7imvIWYfi~ZB0K-CF3KZX*VejfS{>Pcg5mVP#KPgI>PG+kA)e&- zvzTgFf=X+e7IC@?c4e*I#U^8e*hNj?QUr46jWg?@*&~aW)8ssz(_w#fGzJt)M)KY7 z$NwAMI?~j~`;dYt|8HzvWYbbpKehJ!*Uvux@&UdM))tKU^wzRA>a0~0u6kAD}cX#7?xqqXovc6mT z1kZt<<=;&b&~*_}s1ZQgU*g$N{_aOdxou~0{mo$G$p3^;Ofl9mwYfG4MTNG|`(sG* z82uXN`Rbi!m7Lo1<>@CA52d&av;~e8<4S()BlL5#eau`>gp_jo9Vx6I9DPq(Nigjcw%#U3 zBIfJO77pg{+=re+``z0DrLY9B8412X&NkfP_H5-pkE{>x6+7GgV`M@h<%ylu#@oiX zLs`-ayb%WJiBj{tfY{$_}^6gq{|_kmDy?B5ZDm^g!k!Bsqy_%lr`jqnh&U)J`+ znWl>q?i#nH(6sW7{0FYG4}q_uQ=9{LV)chQTk1E$Yd@jykooQGQh4k_xKCW%4Uzdx zZRtf;Y0WVQV~-LVlb9HKd)M&p1`Eq)3$XC|=hG7$hwQ#8FN^$&d+7x^0d1?AyT27x zBT+s6rWWPO^am%JhbB&cPLc9|>M;{_nkY zS$T=SrcP%zyN9cd;8dKVn|B$xBtPZ>!i0k&%HZ2P86sqi`w9oI>0{DI@S8c0ctja# zpr;Gd!~=f!-@J^;b=LKG*=rjj$YOnOv2xv)CQd`QA~rf44Gtiq?cu^S5!Cuk*Vrr! zoT-K1%_hvhr5d(Fo5`NxtnpIiac7&J&{_FsyiptG`QGDOJ_3TBnSdNybgL!r%P4>XR$FKpa zS*jR-)ufU3jv<&D4b5zTt>$77Rhc0(u-eGwSR>>Q=l{s6{pV_DK&IUz_LrL;(Y@Z- zWg}Z@!A=|6=G?n_NEn{h(E?vzr{BFrr5^u&|PnW~Nwm}%V6 z8Z+QHvZeHQh+w+JBXQ55^VK!pg&Y5Xcp%$yhb{XuXj{aK#A(=TZ4yzY|)Eb?S*b6JHlpK{r3Ej;k`GUFwl|} z>~uIuA{s^Hwc$1pMLaM+f8VH*czgP8_(fulxXQ~iOw1ct_CHJaV}-X}cBR2eLRNNC zYo@!WhxjGZ-mN37 zrl$7f68zsz6GVAWFvN=xtxHG$e|bs}C7{#S)x`I|<@xa{6(8&P5##{v?<VKk1=PIv_Mf=`zy#)sc$L7}7l}gZo3?&GyxVSjS zUi!Zhqu}GpoAF5V=PK6J()!S;Pi@UFDfzR(W&IyfA9W1l$sC_ODwmj35Pl#>cgGN-C+YisYWUzJaJ-jnU%!~>&??EVUt+?T6?mg{p(V7&(dl0tIh7D13szMBM)9I$@jSK2OqkPfb| zXSHv3od$gG=GUp0o|ryM5+9~-zj(bW%~9ohHp9pfndk5B3M(dPj`iM1bYKTcaM;oL zQ{un8A(Fgo$dv;bZFU%X^Dx(3-VgJGAFVZArr@p^VzpGe3W{9eMpzy)I`tQf_&lp| znNv;~kW&6*idP$1$#f1ob0Z`2{r!DKMMYg}>qs&X871Y;_O|>Br1w&dk)fd>3MQsV z7#7|8zAk@iY%E$^TiZEzWlKxySQ>j=OpKs_z;CKwuR+ub1%DS#mg+6Am6Vh$H#*wy zH7XZsolca)MM+;CE(-N}f_z+TiHE!VVL;;I{{{wN62NyZFk+9yG4vx{KX9uA>JT1* zW>a=riNDi!Z(U&ah=pTy*ZUm^+LG_nM)D34W`2%BFqoWlG8%Tj;gE-30it4*RP8pN zVj*##jCdC4f5i)W`;&EHYcN!uNKV_($7QNWYw3vj@t%EjN564{Vtae%2AX5zKmPyO zTAfhL9poy|K0Oui5(81BNJ9oHdF#khD3oUMe6)=u=6?@%p}>vciHun%13fGBhtC{2 z67aZ2(`&V$prHKw40lsUj!|CxAH*!ClfN@%5*hccOj;bNI!{^^EM{&a#|)@wXD1@A#0+p?M1vcDyHof05;z6~3Enu2%VMXrknS%Q*!G6>9tV6@~eul;j$LY-* zS1S>G={~W7`~`yd)Qr&XW$R>Was z=AqX9;BKJP?myd)fgFYrFJjQJ=HvM~SYw2zsHTMR3mBQsjqtRfgH&>!$%7XXr zU%pXg_1Ws#H=Xe%)=%4A#q`A5+5>aN5cC!YnJinCU!$lT-xBLB7W^a;|DZ&-z8$aR z@2`BduuuR*T%Vd^g%b}&tE}s8RWy0P7cCp^ciuoPA(z1eZ4X<5>lov42!C6o zi&$It3()6>27J({a5&K`8U%D_cl?C+kM`5Z0PE466&IMBX$c57r`dti*6RTqiio~y zNgTGpc(#{2gT8Zs%UIHIWv%Wg*dFnRQc{h_2?-q0aR$G;_oFuc!?XSg^)TvlP$ zQ!o#}C$4Lbw-^AGYJ7aX`1&M<;Pr&q@$^Ik4I5dRHS+tNf$6opx@;X?YEEl_QZC&! zcFAB}_j06?$>WX>?1;=ageGHUG8VY9kUrdNfPg=l_0?ZnZ!{c}3|pCh-QQb0EoVE0 zuZ)-f;xWeVEfw|r0O8-`*K$>02c>jFVsa@4&kR>`me2cBg%iNO5@>QN9@P29bTBOu zLj!!$e@$y+(M7R|e2RZd0-m>Ix7As2GTdEEOfHC4yLw^tJ(P2}rjvmgK6(KV&p_Qv zTfQfI(&oL7asv6jiXnf_#OvQM7X3VIV;La(qjpMx?i4Sw#COh4GkIlLZfVNt+!$aM zL-NRqSLzp(t%L4iWwW_zJcf)`w1~SoET~Tc|!(s zvvRjSWK0-rnkWDTxU6wqVeI-iQjW_E3HVD^;M@_M8-uJR; z4j7L)I$e+#E)@DFwcn88=XII@>8YcDw!2{gZ9IZxU{myeh>Woa3PZ`8ZjAfgp&3% zn|fqRR0uCY6e?3t&s9y?{_NI_gD{eUF;*6aH{bh7sE1e5Pi?BnPf$3c9w@h#aMMZ3rwXFKzD!-mY6?#IQ; zSNEx`7NY9vc;Nh4Sagaij|Xe_hx4(y(gMK-asy0kXB#~&N75EnHwYsqysU_~_+EMk zw|omPxEY)1XyxA#CX7xzw4og-GOAiWib`s|1-P*H%Bc8hzw*0%FGEl)6`2Ku;+kSW zVMy2g@n)|0%!9Qog)BhdlTglN?ne~01$-%IwCbUyLrmo+F7@avjgWFN6sK3MsU&O^ z?4;lGtAXxYg5rD4no;ec^P`~!cV6O6jwwIOaY;~7o0ipiy?rdy_P8L8M#-!Qjr(>lRVGi6WQ&2?ATDxz0*TWp)xJ(P$w;+5)t{;4~r|y z6AW?gxdsH;?W}rRtFz^m=z0D0Ta)7n(&q2$>+2mDFtD+i@P&Z+4i8Vt&!4qFmgcbC z3%lH4<>8@cfQ0EBq4qpv8%O^q)fn$_uNk6l%KOa_jWyfY_}uM@0oBRTID4fUrQkik1S zGCSsATyqotZebp#7l?zgjQxo;X%L9j*w}tH5zf(_R0$6Pt{I^||6493IMC16U#Dkm zE;HHS<&mpA++<~PA2m@d9in&0Nh6lx>AUMcov2vu0kfHqlo9VSJ(2MLqJieXGK*-N&vC_UgtXO!3v6~LjWcfsMBuqb<6=v6h=Oztc{S;X zKU{?^;2SQp2Y%AT&()O`^|0);QenU;5a~_Y0ykol1|km@%NA6d%ISc|qH)x$Mpp+A zO*LMeZ!lxKtxm+~e-r(ylNDCzFQ+r9@D9hXy2_qrby~krlPC6`%4>e>{_fnE&9OsK zP3>01dm_8B5i?!(Yg^%_+7_N-bptmLflTV_KqMg9<<&t5Q@5f)P$hG0&LY%wm+jZ{ zo}J~yS5J?C8LBoC!c6Nx2(B8mZSiqBQRAb4Tq9PuKqXg5kL*%dQFdrhUeZqo^=qeHj20(|u)xy2F5QqajmG zZf39a-T{UEE6bNkQ26-Ym$C^rp`_l%ncyq4eI7nSV=f<7k*jdR){sG!eqebd)Dd;U z;GS$|lH_d!!YF}f5&mg}V#>ta$ra8hVQ2^fs}k+1o!9K{`ew+xnY8y@MsL;u&|=TJ z!}Ed~twN_z+(cS@jgeq1f~-#@PRpFENYG0&o(oMshk8l_4NnalCTw8gd17n|58ey) zqU{C=3JNOx^bJABk~1oUBpIrg6j05#ld6$5Hkbrf8^o_t|`1-VALJ;dWJ z^Fb1(Qj~fXj(5Zrl1AoSGWO8JN5@fu_F|oZsOxmH?bsSds#!?U`GK|Ltr-t%JMy^T z27{6QgwbRse+U`J95X^>_eP{obcg9^xsft=Z!YRsI&dhLd$>?Z+|kkTMZ5)!c5UV6 zcIt}c$rBQ|qRyCW&C&>`Qq_Iczb_pZ*)~{w5d94Q#LVVUQomShf`s1@#o{ zW{z-$+qa1$RLiJB#Fo^+qOw&~wwtn`WAdqFxV!a_8@BW=6|Js4coVk@EkYJ`-lZ!O zwMJ_~UXS}St;Q0Lz?L=bgP~yq&pJoI8K2jmxWW=wr?n)=ymZ5^RTn1Dn$*l}q%VdU zS~6M4_squUkfK~lvOm;h^;u#G9DH~7IRiw0ZCjS-Pyu5CW<4$2g}>j}2~A_5;uFeL zOGg9;LW&=j{%OLC6ShsJJhH3CP&}07ewJmQ#fK04rT(fUf5ZA15U_JnMp2_BHd=iNT8bbYc)#DHMT&@^m%Nntj2N9Tc*(wwCBz-J`2xu?nQ z42~0%`CCu7U87uVqHRW<5M758>1B;vG>%8cD;P>}%gL_V`%w?~Q+Zx>=r{t8(9aCI zdA=n$k=UiEbkgK}Pvz~~HGAifqZ7Rp!<-rAHg44FCeTr48zedjU@k6|_DO zGc1BJW(}2KHeb5!A=0ntwR;z};R;q?U#CEebv#)Y$l)@AK`*fU`;k`+iCb|qbTT1Z zV+aF5HYgLe^Js^8{+TxH8_7Sd6VIkwMDvrLB2zv$fjWvkNiH5$MiczC;oQ16E8^!2 z6P(fxBVN-{XrzRw^#Ld@M1ZJ)B{5w~)b42w83j&)Ra0_MxHuXW_woSg#g?x4OZ(P4 zX6*g^{$uOPYw-*AXW8WgjPzHQ%KHZD`zOB1DJu()jz;-%yihq&qEyOZyZOc8V0`bN zFT`jHFgS|u`LN<{y7F}M#Xo5%oV%}SiCML z2cv@wG!*%sxG1lPh)7=M#y=JQi~^bu3J2`6pKO4r)1L|pKXa!-rl@$YXH-G4s;$m+ za&mG3K|wWMFU~Xoz|i=(@kk;ai`jI*-bhld%Z2s~T)(_Lvz9Hjw602I%xqB>hr$7( zreT7qg#6=UT%V>)`;dtNpRR@@SJ=SBfqBBOttpYw=Ly&j;uq)*!ic@yX&1EyKtX|s zUu5nL<&^2>i(~jDX_L2wI#jZpT)d3798oDnl#zlEYhh=~@U?;3FB^@2_&Z5)u|#7g zS&}4`ngjPnGmGBT30a*f12ypEt0C$G0b|s=n2EY9$5d2q~hLm@KXf(6tAxS~Crh)D}EM)U8Ni5QF#Ix|jVII6BRsH%>c6 z^|tj2#x*3s%Jj{9c+q5^r@{V#N&dfWZRx_nNOre}a_Jcvp@05#cXxlQSC2?Yz)WJ$ zq4>l;pPL&6(~0{$em{|ei);H(H&`*X`}PRFDKT+aC9eOn!um z*|0U=vpprI8k3}Eo$qNl4j)-h7S*n4F9DEw$jEhGfAGVObK zS&lv!z+!qmO+DJ$HO-yn~v);vFZr%+9q9sPQUetJs;@_J#820wZ3TW(*&sd9O-nUwx5$@|@w z!!tkr8WK?*=*jNI=Aj@lGz7?|-NBpbg2!bakvrhe&lSLn!q%at`R+{p- zhMR-zBeN0pAb&^6a++fE8uX_~^XKrZs)=ey?)H7MD04ommX2$psGxS!(vqHqNeO}q z)mXKiZQ;$|DTM0f@kn5E;|)U!fdsw=0RcfYew|{x=4KpcDM&iZWH~uSb8txSew3kE zPE%T2j=ZJ&*ZPMo(Sc1r^GQS_XRMn^oFUMXkigE-v3FQ#e2JWN(UUE(W|g+&t^gm| zf9iKNa}-pqN?b8udnJm`XkyIrp4KxBR_BZqs7DMmrY%$i$i-#}tBsQzkEt7)Gg0C) z;UI|jmw1fN4V;OcX|o+a{GBM>-FwZvm2+yg=vd9B{yg7?%lsv#XEWbr#{DtSJq$My zy&tagj@W$QJl}8&XllW|nfG^X^)Pt#?>1X0rk)RC;rqCRknSg|-5W8p3>z2JP?FZR zqZV7B(;cc#e+iN*sQEWPP6Xp&Q8zc&Ym+jpvND0@V+@bpxd>8T72L1j1*^H?8maRp zIeQObzvwqL`5+o}w7%NXnG)$YzrPtcZA3e{)()@IPLDN9q+evzBw!}z7%?`8;=C*Qr*b9V!JMyK(x zH@*jXzj7|0h=Bk@`?YiYdICS62h?bJGzFG3pCq+CB5&bOa9Q24n2w6el7Sh?eqf}J zs$_ICH-dLPBpU`kq3gLf1TQ;^LZq^-GuCPxr_fQ49rRd$bygc3P~!BIpsJQhEO*LY z_m0w%%fVkEE$MPEl(wew)M#-Qk&KKSC8HdsgpcZvTwW<9H5Jug zsWi4mgZ0r&ZH7ChJvz3A#v7~zC^n>XNBnmZ|EEMk6MLHrS&D(_Wu%Yij1*?ZWRb9Y zG!I=)pmPC9w!wj)-0I*$l}+D(rsSyM2m4HN$2kYP_fp>ou~i-!e=4dCJvj+5NCxIk ze=UY1_F-bHl#Y_~>WR_2LtOy0%%^O_sa4x!9%;EcI{2`WXGG|8%yRaNSB5;lIc3*m zfbnK7hCmu%GLYx{`Y3^=2IX_AervwK$mi*Ufr*JZn#qd~(4rsVKkSc6V`DTNM1giH z>DleFTB_26kVvF$w$S4KpgdY;LvtavNhdrPznOQ2WI66HT5!MI>kq3pd++rH-l|uD zHNLd}UoOD!1NFH+?mBA3V^?3pJVu7#S@@Hb#(T!OK9DDu0qhmE-6#Qj@JRyZX(oRp zlmzb*LLASW05EfwAx76B51% zA(`?)nD2(I+N2LK+B1q*R*rMm#|-o45m{ZLlhm|(MBbB#WW%b1ci5d%(Ge+}Ve(pL z335W(zB}KdRj-TAm*6wF4?&uJh_<^wRSQDIzb~arzQ!=QXsLGtD;tr(7ffus>O+?n zh94BBHEMKYWoY*`x$(#1wWb{@U@H`qx>Z@Q=+lN8tWG{~5aACT%Q4ivxP#8z-KCHY zBJ@1j8i2tvZ;dAjz6yYYop}@5wbUTlMkAZVvEzTCRxn=%B|&7sJG_|!+MgpuCM!7; zoU*cGTS~x`&K)jnb_U()<66Z70;BCBnNZLO8K4jc7S=#&$?2p-Bz=q~zv=Lu0q7R( zhEIWZq9@`K8)#rnGJ7pD>|Bx&``(Fcdr7B0W z#ps_8{%bH0S!XsA1dmP6Xgc}B&);8)Jx`uf?Pv(3L#S-mT9A!_l+cS?lNGP@hBthLb zHB`)|iT2mov8QJ##Wo3Td>|ovP7!@FhqAJ53Z2~_pr!2^IREYrrm?o))?~i(UKB0VNcGSD|ixWIKrH3;r;wIGhVWU5cEeO|L$bKVr=IdJxu6NbK7 zsxYO`;*WGmQ-+*{?P0j$uEf7ZC=I=#I<8=ZE}&J?t?;m&8vdRA6amX?-h z?o9lZIbu;nJRj?5aMKUD2q#^a9d9^uYmqh`8x#9ucDK0vnbnIzPt`88x-GY@RCxr{A(Tib6mS$hx;*e#_7#`Fj=? z?zsbktI#@_F4$9S3f|e)Cce2=WR5`Nst2^YJLd}ig{Lv`(OmO0+bty}Eqsib`6BQ@ zxn`z0K~$fQro+HWsL?vv7DMXXK$A{5b|DTiw~M(nnePGcetrG|Ba?2j`{Gp{r=mx- z3=+yF{3;#!s9{*UhfRldPw&dXjlN&9CFDtNE)kmJXYS|UCOex~tl=*L`dv|jPzjxJ zxR#4MMaeK-CQK;w)1O-F0pe&`Oy;7IZ)){#_7c3}vYBZz>gek>vaKA)nu!{3bufFC z#!_5NhUPgBu0VGGh5|@VPEE>!HX1=q5^psFTXei|W~5Tj>lObs^LRqSOJ`f;!*HI6 zPK2(splUf?SBKJGfj;I4M=(I=2c4Dyr#D~eJ$p<^6 z$NS!4t@&rHGhx=c&EmIXabq>06F} zZca{#EH*{c9X2VzFMZA>RD5-nFM(Td!k)a&#`}~D`|Io}l-T>xx3~9~vQP7G5c$@(yl=5P;Ax(Qws6G26BKFz!~so9 zZHs0iv2}<=yjZCh7J9W> z|0!*(LvjpT?7Z(s9ywmT({6}*Txt^|M-oI(tWKo;{^H|I7((&9?UqRZ^zC|kxls(^ zlvm=(VgUUt(#H8(u5N#Gtb~DOPBUCmbqCioFYhaVCNRTxR(xO~r4-0H*7}g6kOyED z^Utp*9lwu!Y$|Gs*N$jV7c@*Vadmri5N~~mwQ_yj0MjSQX=!P3Yj#&?wW_v01NJ9U zMa|5pKjYf&a40YB+ciAj%W3U$lH(hf&C`?FeBfMNcCpRvs%qK@jsNwpVY5dG;4KfJC#ef6nQ`86-{!bj_!#>9 z7#lH~EpUqv?diQT;HYyT1*lYzadM_GV2v7fHzC8q!gftfU1i<@YUryyr`(@ACUH|7 z0a%hZWoPL_6XTUqH~B_f-@In)%T35Z-zzV01#y+c{d;umMb%T;IdC->Od2IZ}<(zW3Q*mkEx zQQ5Zce|OW7y%OE%YPZSliqUJ|XBsJ|5Y#n{i3}q#Zv7EDiQ@C>=^x7Nl-SK5&F~cm z@p+ku?Nd`)HICpri^QuDhR&+b6E)I><|jhTVzydlDJw6(Q2SVL1FH+tRvRg^+}joU znlN!Akl$WOw&HkrShCk&)UhccA62MG#|eOl786goGASLyaYqtCUjFK4cF-x_`2) zI5Gy94KF$|rzxKag_vT2_dDKRYu;e4Q#-n%J0@m|MHs=O-!0~S8&J7$>`qoRt6{)L4k?RIxPV`I@u?e@=a#g#C3%?ZAr z-tuH5IZ>2cnTm3yR2R13ktT|ZDtw(_5zQjkg6132xJj~AG#^ljD1Vw7g@fVNI3?6J zw#1jgDA4$#UI)9sa)@JUa9m?lM5}vW7-l-_LuC$6UJs!nftIZHms!z(Wtfp&At#9} zo(BH()Y8sV{|A8Zt(eQJj*V}oG15dt-U8amR+Qw$i^0@2+UaDT>9J3RSXPj7u0vKZ z+j(oLk#DcKBKYuq`(RMprGI`3OM}~@|FsF17@4;KL-!Yjf`N%mSdtVrpXrg*(}bAM z99a5ZRekL1Cj)4*ObuvnZ$CIPLdwmJpD!P(T-rB0{3kpdVLXdp=HYxTG`x*>(mkV4 z+xWaJ=0}_Y!N-_ZCpU9+xcnH40KJ%+l3>1Ex8yf6TtTk`CZ>Drj?~GdWIGMq*=bA< zV&YSVN|I{BFEP#q-Z;(Joq9)KSsCi>n4LCQ&!AyB6OG;L)Jd5EtYCklTu5cM`%l=- z{Mug4;b5W0h?Q}0=I!97x9(a-8}E`K<1@Qw!Kvx_@6nVwC0!-R>DROcRas4*!Or~c zdj&E;rcwXoJ7C)o4Vr9}uDrUwKL2Des_J33#&!Oi& zckjr*xT36E6`fGLk>-eO=EEKn>AqocsX>2iLT0NxelwdpV$}j$%yq>R>zHiOs1qS7 zvqH7_e4$<==dk-hQYWeJ7K(WD2MlikqxkRYpMhtT;dMmYb{-|G8PuhXSMgb#aLwUu zgay7kF_K5(70!C6qh^}C4H=Dm96fa|->U1Xd&cK8BMmxwh6eiLS;$~hjPUtZZprn) zvQ$cge#)D+Z!BROJ~0(L`~nn5OtXpw$@Gx*jrqwM>bkSa2E7RRXt%f;DSQubq@tZ6 zDbw*3Qa?dGD&Hk2;YNazB-iX`39gn4S0uF%u zH9iwEGE4QS{Q;Y2gIxKaao3!*tp={&$uxzym>+V#AXVse-^Qz4DwR|<$?GxE(lU)eA*tG@fWAM~ zJA+reJMU(c>O=a>JhsxNwQ_bjo-V9`C7d{w_$3fQs~*c>EP|HxsDwf(JKll`hddsP ziOG6|H+1V$UjPS7ZVpe#T#4klXo)3}7(aQs=e9U(-arC^bj= z&rUC|kGhjGyaqW@0+n3=gp|hi-p}`o^6jlo?_x8+cgMs;R2}w!A z#VS3?EIvY;3!N+lv_KPOW-l!g2R?iUv2}eeV}m6`HbRB#S$raw5A|5cSl=1S%FU%? z#Prby`4}xb?uoK77%~ida`p1BpzPjmT>;8DZO1CbwA_Uw0b^KZQs*(9+|vW{Q}Kwx zx%3}19foYPuyv$dz^DSg0xaI;Q;Tqd7ewI={E%fy>ylePu@)pXb@dv||Xw8-mEpf2V4SfxJP z)@<^_0FSsCo9@B(FH_OqaM48nO%FqBXsBqXv%p|`a8gFNw0#ly7AT?cn&%o>m^j(< z>fDwi`y=l5cUeOjC8)rnr`(lUD(>Gj9K1gkh(fHS`Fw#w4J5R*sl@imh~SX`m!c@? zXw^YB5E78!z{{8N$|mOX?02NnG6}9=tgpMd*$X=&e9Fy0B_t$NtJa5_;CrF{w0XWn z()@U7Ma6#m!+Ng8LIsQY>|v(UMN;7-HQDIg{NmE`l;>fgqy5ePvHr|-ELqR;II4yQ zKvXi>KW)s6%mAuC^-xi5#lXZOOktys<@PfXE7I%_ECCiX>Z2qy6np#jYtE0kA6HYB z=DbTyr%RALyq^M(3q5q{7tmX+D2?AQzAczwjcaOpMZX*m6tB3>m$9i4uiNO(<_e=`31v(|zU z#bG#f!IUGx7_>nZtl@Ima^d(NN<>$@uKRJ3e6e|_k5subP`~&4tobKlvA8Kmk>=vr z`v*`1FCekT>F&Xh#m5ip4r0;yk#@|}($40c)DlT8#JnRtT+GH)F5&kki5)T=G%UC?Ffa&>j4b%fl81NhpIjBuo&Jd8 zPi~&oh(K;Z>`zO^{}8=W;>;>cBjk}6Tz^A*OS?(Q4((Es3lvdhA5DN}jHsUVQYEZLqL z!Mafps}BNko@J(o`{!a`w6mweb1U0YXath5Lyz<$9?eciMPXZRDH`!AHlRWVbE0jh zfgJy!S4P;H9CUoPAY*U^u)zO zuo({Ez=6r*GAL@>Fn|eg^|>%4P$Mbrl9BsC&<_l<>e_kcrjT*Ns7C0XWzx};ey~}^Cas3m7OEj1}VCv96ji)Nw0YLBn; zvwd5&(UWy7wZZk$7eFg}DAAk}EuJs|6B8Z#Y~BYcRZ+^{qXhK$@xOE&}o4(TA}MIYhJ;Sc5`t(*Ac(7jxCe$n>)Jp z(^nfGc}WEux+8mTT2hb8fId}aPa{##savK;E{w65(rzI+2?KRkw}@}KKg1Bf6=~~% z?JAw5M%++Bks{cTSzx~xDC|*nd&1CcsSzMjd*6il%Ylj}NI#bxF2!%2aJgptACr1; z)8>30H#P7vEGzzWpCvowvD zA3s##v|-Qu0d2A!FZr@s%7%o=%==l%*-0BA*No&6S`nP7Qd*H4u=PKZ=oE2dMJ^S9 zS~a14_CR{Nhm}Q-N_6x*Alye>8^1=nccEiYpkh*3|6}9ARae@RU9>ZMV@IB2ff6&e zQf)d+mgsEpuU^w3vjNFy)|7w#g7?eT`K;NwXjk7FL36f}4jcV&B zIFtLcfB6(PL#=K>cN-uw9UdrutSR8Oaws?wEZ6luw&5U^)Lo6gKB}{b@o}n&vB9tf z7;x^zQlEZizaG?)X;)HiVHGnw5`}l7xWRnGId?0~uZv}4=~$%%yiPw zEiR&4==F*+KqRI0qSy=_0?9yr7eiszi6rT;@n zP2^~P;wwL_chPdur0N<6T%bvAVl29UT)B14Bwl}y4n4|%wTs@unMWE}7H9HWa^sJ% zS`y0fuI^v%Pda#JF_I0V!SZU0rtH>&MQ{|h#vkNnU^jehYKHW=hU{;fDbs3?EkWl; zw&pZ;9)OF*yYI&h3`%HnEF=im!{ic3E1#f_!VpdBR^10krhwPq)=== zj?VoY;S)DxfhC9W9qRnpbB_)vWHD)+W{M|i4(G~V=B--d+Jb+QmLBDFg_aHt7~dC_M& z2{ghb@ai4QKxBAUQky>c%sino4lQ79)&nfpda~Xj$t*hgZIVmmc*uv+C^zzWeDdqn zv-`W%cHi+uqOR#$qU{OBG&nq2E%hTCo3@#I-McL}exynPKrL7L{l4Y}Lc_!LE78X* z`waYNEt?@WAu$o`-cFPN4wNnw&S!SQ=W@TLLPbS&JY9_W%!XTATXteyr`Caifpu0Z ziGz;fGc&c;@H~bCQBPEFC$FYCe=zf*_y~RPz)WDx ztK_tUge?L zQE&o%R^6!(Su-wuhoEYFzJk$CSg8oEnVFL7Q>#L1T2Ou*Hk=i1vDuL#?&u{FQg<73 zl&0ooZIZ!kQe0{>IAuPhzLx##`NR5O-m>{}jho|3J~9f5t&;;8XJv|WqD%}d3|%XO zu|W8w#oHb4Pln*g`C2R0hy*2RBc%T-feJCd=B)iSP=1iQSjg-IR29XWuoN1f*1BU% z7n7PU-K-s1SjmrM4h5xVwu_;pe}ekE)Qx)qJ+IIm+!h>gkb8<}a|_aQZc`qUcR;Al5AD;UDwKWKCo0}g=D^ayRh zfEk;f86{oN``KqZIi`(u07PpnqHkUVij0l@F)aE?N*<8|M~Brw|LC?9lac-lltatp4~!OT@k9Fh8}s#^tNW5de2S2=AZH@dIiwqRTtZ4);kVYvE>&EAF&BZg}?&;%dL5-8rBQ7I4x=QSa9>Z6tKBb4(3#)p;;Rv+G8AVPW}5u$g$G-pPMZSJPOIBZ-v z*xQc}Ir)g<%5e%K)1g3^;*B}&&9ZTZg29xWG$F^=^6Keua-m0g{ehd7CHXZKP;)pS zV`scB=*d^4KMx6;T#n9sENm&RT0qP(ZOLpV!ve}JE1JT#E|8)=S4nP$VDVL5`~pgP zqG(fTB%B8oE@*33MFll3`Im$f^*kGU!6Z(QQNFHCSwUMvN^-m;TIXFWp2N4eP-3&B z_b&&F?@^7ef2j4)I~+X5R)nTHhW$%#kLV1MCPdB3{?@Dqts9as)2HM$Rgr3wvb05F zm6ROYKL6n0Nv)gxh2g=wHy4rIy)z^pDrU#3psXDxGlQPO6R?ZIke{!NRvV0BJe$pt zN^L&NL`&L|>k?7YR7^vcyJqu~l{7>5G(JIjXGTMOgg`QRT};W1ldTc#sLnFw>^c(FyKf!JphLG^naLrQx5$FYQjsly9XsxWSRyrg7P{*Fsg zd-b21RAa~fAKkg=;?g1gc?-4;s??>{0zgRAtVF4RM(9#BG57S$mSJ~&1$jI6h3sGb zxfb>Mf26v1&9mFqB%Sq9>R-UH(h>vJC#;!j_~XPEZ8bZ|d>V9nXW0m#(8H$jiv~G0 zxxgNiA8vyv`lFMY3W8c;=;2t?wLvHaF7n#yzGLvAW+?$r$JE93dR4y|U2SO=PpHbR zNyz9^eu!~rADR8aaazPHnG&JMsnsYhG86hV!02%Iq;Vf{#;^1)5i>dTp`IDWtj(~n z0<+Wg_Oyb63V?TiZ!e?yY*7V2!<>YZ8LU*KKkqbhXT#}+PQ<6h(QqZq&A;vUWQDRY zu!@MVxUnJ#l8_bT5xo-5y|O4L%A4Hi!bR%Ziqb>|!TIe>Pd00q-3CUZ!S2DNisKMS ziHLBk38P)kp7s%@NNE-YAxg#aVSYd&o=#kLm29 z(Lmaif*SeMbZtpNl3sEObZocXm!P21{K(-J44t22F7E77c8RII!;txZq$0Xoo z1bb(ty*&dRhoVpd(#yDUI7DYA})^H-`9l{LPI6JHQw z%Fa`ABDW2NJ}#%-+Iqn;Re zMl|F6hp)lQym-~c!s376a@wKd0cG=7ke6ul zR@cN;DI+_3j0n6~W^ZNyiV$S#xN)u7r*D6WirPQ={LSSkETOq*e;^Xgy(;SCY+aMK zvt#-sOdL&|Ql6UjadJEg+T0z_C65`8bDfk~Ph5urS6VMRBpe-Cb_Sv-c{G*N(S*`d zKd;4V1DH?HK~6>Wy>mlGNeT1l=!o!Qp`^t5)|H>brX*;}^t9<*@p|t>=5n2nv~k@T z$Z1E}S@Kx?Yvw=iQB|q_e?)y{SXJBiwTdDL0!p_ulG2Bk2I=k)kmk^x(v5)9B}hn0 zH%NDPmvnc-yN=%9`@fGLu5y6A_nLdnImaAhEIPu5BTSL+6%`eVgBF0^gM*yA-R!T5 z!Z_uScUR9U#uT}DLmsfDYBRew8tGOsjy^s!(*yE0cj`$P4QeC?uU3xpYzWVs3)6S zS>-e|+~sl)vlfoxAN|}{15XUnr&>HI`4Q@U4W@YYAYZk3y`XF$BO}A-84}j7kFD?lsKf(6mB1as^ZomGWIWcOS*s@A z-xqpICZ?va_KKXGTux1`>-OpdM%&5FMG%qi0=&nrFC@FuWq|wT^FjZPY0uc#|E?y2Q9d*2Nx#;+y_AL*`6((RDCv~dDY2(-wY@uT|GT5CalaZ z$A*;_(=C8Gr&eQ2fs2bR+r0huHO}a96FC@;vuL%gH-GcVwvf^V;!Xp&#%{aX6p^&CSiA=uiFi z>zxHVKC}uyva|JvL`-f$!5?tLpMW401a;4jCcl}9$x=orLq=m`YF-`zq!ejnixv zTsD9hMMg~x2U?XhGozu!fbH3o2FS$erg*>-WH~ENhm@RL*ptZk*V)b_Xq+GY2C!%3 z^jq+N+5~DVD=VRkxT?iE^TT%gQi}5O0)V2DZh%1Ihep+RaAClTcXV?{9pVFCD4dZT z>JOa{qM5JK1_O194{%(wN4H!X(_KxX4w{&sC&Aag#ip`5oB|2IzQ_La8mxGEukHWtw zO^L2kjP2Vzw01>5AO-FWTi5+n*>vAU(}M?YIJqAhZ@RgqW^pW(SeV9O77pk$jlC%P`T25xG@jm$6 z-w&Vig|78!Oo<_oT+hh64LnvWR3Sj=#ATxrwzhu9#Kd$Q0Q-@DKZ-!|L}qei#CBb2 z;s5^04-$^Ev$F%2BJkg5z?Xs^cdG$`)F!eZf{iF1lm1iCF@28s-_KdWa2$IE`-}a= z$cUh%WG_=ya99{QDe04#?lIY)|NGI&17Ul6dytfYgSjC?=2z(Gqo`4SXe(m|6&eYA z9$dc9QTf qUpe`S0Vqy1MQWDgXPT!a(%Hvyf?;1@vUpDiHJkiaN(f)T z^&d7d+?&C6Ui;>Crv18Iw3$jbn&-|vy5-Eni2!UtkENxhf#w=SQDTNZhm{XTy!@ zZWANsJul40({V!@Kcmmxe3#hgC)SQeNEC(=?z4s}kLH9My0Lyr9kiamQJC{E&~AVg zjj?d!qy*mLfZ07!Wo1_B%(c4*`J>Rq%v#=bQ`Y)xN?$B(u@S=1;iP`&1|2~`!6$_3 z|6Na;>2Cx*_9UhRsY`kzIxO_Wc42@R#p)r!SNW%>zp<|^3a4%IjH!#AwBD-!emRRj ztvl1!)(c&3K@9%W*O=IrE^z1J<%gCrn49;)`>ZBzD9{hh0kB)c`%QEh!;9+$#;%Of zdCYJUv!6kJ{udNMqyDdc>zCN;CYPzbBdC2@tFoaq9!bKK)?37trl*8gS>Ilq<{9=1 zmDk(2-%AbKi<2XQYE}Y$lDV3%8KQnisFe5EEhVw zL_%J?wjct9^`?2t&i^NW>M8XUzA24~=KK{EA#Js@s3E1hmMVMrCIo20pi0 zu-o08O*$nS+=9*T$B!R=ugFBL_bMh=Y-`lOkOI^^kELk*Afq_Q@S@>(?ZEa2jxbAA zDuwGCCansA6E`mb-GDkBmJdA^Afln_prBAr9rv&8yAC*HjH0J;M@lR^d>vzV)Y8^1 z32um0zujVtv^|I%AXCU0QqvLKr*Jx+(k1%iL&D&B)kQTGxoMKY5?^CDTzs`-5NSL9 zj{D*ES914N!tTwnWHJrw{%q@%#PnCod*lZ{eCN}s=U3DInO_pN{m?wN4u7c#Nnv!v zo80!(mwPs1Ng8o+#k|rE$}&i5)MHM7Y$V$upr9CmGR4Cd8N9j~#cb^C$JaZ>C*X0w zeMw5{jb}0dpFpuL{oK2HB&VypxM%5hzWW{U<3Ykps1!mN-oX$NkjE%3Eqy{rkI))eu|mPP4>Z>C zjDu6b&kG|*7d$1A9+gx6*5!Y4$W|eDQk6B`sZt-8B|4qNmph>G+<$0D4rD`+ zt|iilz?SH@X%6-v3=E9JrazCGIbqAQiSl`6N3!82~LK~dU*fq81{YxB8O=+48@!lvyBH^pI63rGf zhq{hzIbU95evs-Aj=jCF(n=t1UnFvlC5=4)hGQBVWh^|zk@@-aU91V+}A1um>ii+kuUtb9wJQz_c=13od zu7po&9#wHDXf5>l^Vj4#v;`x+c(ILBnuml+aXx_`)NmFcGn<O$^;Va8d?EZ9sZ3e;OKk5*w;13=K%xoblOGVZ6USwtXX<>5&N z8szt#TTUIobL^e*0Kw8y!k4NAS0ryB%>m_F2LPFX-N8J&Op+^SB#NnkP++s+x|=+c zaNzSyINO27C_@8`EPzb)P#)=CTh{ahao2S6#}EM@MhKn_vqL9LtCsxxASDI zu5@ZEtu?FX%jKLro5v^BZ_Lm{-|#@GnM%kwFXo1E?BAJ)^TlM&4%^4X6DPg5kQG}5 z_ihss9-dWN8V!ms1L%e|#IOstN!t*B;s^}nSL#m&4E}UQSxlGu$HvCK@5HkPJ%wv| zO13Em7FP6^FTec|(bWJ8l$Z)#5cz3hb_odM0p1HOzT3mr$EuecEzO9R;Qxi}xd`KQ zJvmi%Tqqu$ot@R6&zNhu?N!WUY}!BdZ~uacb+YI21dZU^@8-AK{XdLFJ?(rQtueEI zZ9auJ&LS*&~Bn^Dn4VM?i^zh5{Ao6hT7F^ojw(7e+6Y48Ex1;g(o#w z362bMIo$LIxd4`lg%@W*$0L)24yq2&w!je@zc+(I_s_3e^UEAL9K_t*xM7lw z<3HU$a&j(A`AFIlWaTjuladmcKlONP;Lbpt_UGOkqpf^ZQCFAH(9lRX2pW}=lthA7 zaSt(ptQa&JFuG+3>^JDNs=oj?nG(?1XlQD}5t_f}9Im-9P@x5+KEvzNEj2nUV9Vsn znSiGM<}CvQB_(CR)RY$oa8cLQ z3t?nBF->vU#)~GVs--0*Bm@VV38^IZa8&-=cSBL|Ut@5w3i4>oCkjY7IN|_%si(Ks zjS2RvhFQb+W~*52H-{c8CUY*aDax;h9ePr+3nAbUh&MIJ}{EM7DQHJh(q#i1`Z~U>6xdYGVPoq^0g^q>D)wVFFN$r z*HB0yZ26NeB7MeS9TWw}_d( zh3d#j6|9jMzYpCT1+&WYYp!XT5s`89Yt8)kQJraC-+V?U4E6_go08JzZV{fNNOP~# zU3(*vF&Jvv4H8lPy8+=r%f-eNkfa`gCX~Km_$F#}tL@+-?bP#pcUs8YoE8QrKp@rF z(TF7Q8KAj>ISQ$%sezlQk!i0P85xOSQC@7f81Y>c$!!;Ri1C%Jnpi!*wz*NF%qCua zIX2m4Hz~b#z{n9`5x7orrLNxEw;Wk;dHsx+R7{ZBzy3qrNpd! z5_Kisg7b~}49fV5U_h$ua_R*xHj6bSB?jz)qh&NzYcZ%4YCLt(>ZARdNy_Qu+6Nkt?j+omR(Ao33&aeQk{Lwi)sR<%Z!Qb zK81yPH3i^i>dPyKlh|+-CGz@Vs}Q~Edo58m-@>Rf*OD39;bdBMapHCI{s@Eb{tu^U zNBq!Zjz_tR$i~VZD5=-u^zJigA2N!f;7^|3Uw1JgK1-gBJ;@{{d~Zq9j^)KJ%YVv( z%!co>LToiMqtw|kf{?0t&Pvwgp(p*ZKNPi;bUmlQEG zDPft}K2tSL$6b46mw!^P>g7@eL~|oko@?D6U&SS?y2jvp)+CoRkpouB3s?$g1nv9!!8DPbD2xt5CCPMX|VOL1D*+Wg?jy8ecjyJu!-=X0=^iQAT)>^7oTG4hJ>$V07`EyDieKapyoot-$P`*H+rLlEh{kGu( z+VuG0OBySyDb)8})wC|>)5cewr5rdajmfefc7k!4qjVQfG>M!q`HpF0kJiqMB)!cO z)AqP8SoT-UC0_7;l{O|dUe991g8tA^HmPK{8?cN#IX!t;nT(^f-bmwXd#*>&{BW}> z#B+IL9(>^3rc}vyg+4-**jDT5 ztoh47MyP_tzRgFJ_tvdb(Afl`mS5u>j>raQaqb_CIxeU!Zq}uLYu2X37m&n1w*MYR z93$$|S`{ll=^vefC8C}bI;f-8;!w5NPv&*S%{|j_={|4YKCy*>^fJ3-V#YLrv$%|i zo;761s$nt5Fs#i+kAq&!!|J%i+?Xi=*Ypt%dLR>fX-cfh&8tq4c9sa32zbhZ{ZU64F8UHHobTw??j|QTF7C9AhZV*+3=#VJ zR#E)J2d*s-u(!lcOsIgYFtE8?m=a7r_A|1^^$F>(ev=2vsr-C97M+p%xIY|CX+%>%kWyMmtD#EN3%dYSp@B|I2F;MPD?6Vu3*TT{tW2l+6^O z*y$k)ljru+^Zl9N`K=7o3-}j=!N?&yT4Q5d_UWc39T0~5VGlZwE5zLgx7b2QD^xGx zzi*%*G7l&?0IB!!J6ppz33Fj$d_H&Q&QE1mON&m6Y_;2JD1#IbqdpwbFr3fLLwDk| zp!<*kl)ct~m)r)}h}-tXz{1XL?%kOFpNzL#N*r8QW~zkTy_Qk*`$jtFp9LIZzHx^HrHijWEc(w~UE5-%**)h^Jm=)E-lhq=lt@0M^<;gE zq?q|_YWt#Q{kS66lb?*SF{z9hJ*YvCy{YabkPc}=(IC>uCim6oChZXaHG!21{Ysua zTsoP{K!3e!Q&LXcT$=&(*-PFnMbDNy)wRd;-Yqwg^Bog8d%53zU5>xoF;Tfz-`Juz zHSH_FQ-rO3)*Xb{%btem+_I8+o@o}<+Tw1PF>wGTcNLM8luX;bI2q&z%}b=|Xm*KF zed6(rE)84!5H04a!S>~vBD1q6@k~b5llFoxUUtf3N1a(S_6BP)H#Zkj z)KYzr+*% z_>qJ!tyuN^tsmrMZEa0nNy%P;*X3qp?584NH@4eUai32q|9j8;5YUpwoA=qP(w3!+{+~0-avC#}Mxy~nWs$B@oZ9BrX?u(F|e`IqIf@oJ~I<^h|8^kY4V{$r>-_K@|cd3yUUq` zv`5#G2K$eszt>ox_IIkaD;?G37MOphiuq%Du0gYNZS;DSFY_(y*WHZfbwvBu|9+DU zqGwZ+0Z9;08E1}eJxMmvgY|MJ2IZhvRaNZ-of%Vt;W7_NTgjC>9}LZm;JeoUk&~pu zIM7gc#!Ga)`LQEAqS+7Lr3@Y4IdxC!+$->!BtyX zUFBw|(<38vx{xh%Ep>Q@!>A^ zpxwiTr`QMk4;RK2N{m@Mv39+fNC~`lTr7iJf#$LGBKg_+R%X9fxm_Pi9dZ7&+FuSK z*jKR_uyRc|P5jV3<7Ic0jN2E_8Dqy#9b5H+)@178an-{b+?c^$ZZ4MIsz(w8mF+w%!n!vAG3I547-?4;QQwho^oSkl$# zVk3Gzco%i;>{wLtzk!xY9F>ctjp^#n6AUUkhQ15IP%C?yf$@on<3BO7sYAz8#YJA> z#*NOgP1-jQ+!9=|c|bP9)^fNzz&UFbbJ=M?b#`iRx*C;TNAol!lpW2T`{i?x#-CJ% zrPE2flgD|>zQlR>iobe^&M3u=zPRA6*zoV#RWB{O1*z=5_`&Enj@A95#vEt0`5aV_lG?2=_w>ZVWW(9N<^WOwP!vad zQn2>6-lNELV2*L;%9B6d1DvmLIBgA^h*S}5u74I3kkip2`!=I(Qd1T7{+a+Dp1?=! z?Hu$%9^W)k)WQ5Et&?Y1wyAr$0fpE7p@1jfgG>O`OaAr8RmBfM>u;M3k2uMK!y`y3 z89w)onMAl#H&mwF8g}z1xX!lnTt2KH&FsY;4-fdZYO}4rDY_pg1D1X9834UVMtm>F6*?#N_?uFV5SILMNB4&+RzY3JNN2CY{h8r-SBo$HQ%H z{x@6EbuN}$x)5VS9#P4sLV?)^oLbIfTJ<+=W#oNVkFSJAgMuTB7 z2S=6edOf;ea-*4<*+9_p;rsw6HXfd9Ur%PnTb|Nmd8{UP+Cldt0$KNK^0I(|6*qK- z`vEvE%fhzoEOh(a^*@Zdtzkd;4Le`)wh`3DwN}$suhn-;sULcHy2?=N?m`}UQ;sRyPk6`-bYA`5`}Stj2CJ{p z`=V;{F&8q)@Q>{5Xf#5f&W~#iIbN+VIqttID;JI_Po_VMx)iKk0%+qe%h}3^-kO@4$5N!%zF=P}FaJ86DfS$UgH|w9R8%@(&@2EQ?7zm0 z{DkC;ZpA}vNP(d&*E)_@=0aB*gNHZM+f0|k%s^`wZ65b_-+1IjUdH#f>(+Ubw{f;N z&7boU>%x6n8Xzd)n&U%5nk|R5T7dyBdF8XbYEp|jS}mdd%M`5QoswSH^v&4xAFq-g z3_ofh1gbg>m6HYfZNGc!AI;>7C7F7OD(My5lR4<=m(7xXc}IvOSm3hd*%(pnt*TNm zy+_jWKQ6#h+{OP9+pyayaa(v(gs*EJEnBXVE3GI zl2OmrV^z6cs)V=r2{FCoo)$srGL`X=JK!ou+FZ8KoYNNYEQNK%{i7i9Pd1_PfXY!$$s4v$LImmv}g zK<@j2faYvHhMool>CtM_^>AT$vGYyu%nj|<2la*Z5n8XlkZ)-xTZz(v>oH|$_;AlO z9rbYU;aaL5QquTthz{zl8Jq6XB2JD`QR2?V_m)o>RgWUwidTs#x|6xd5o4NVMU;8z z3)$e7xDWhcMmh<>rq?2RP$iWyY3OrJnqG8mm@ zl+TegJZ_`=AX%X1H#a)&k>}4 z5P-lbr<@-k1}xs~J2i3Nh7X&xncO;}R_t%tb48QJ;H0vK(Vi6lHrf1GmrlK|?ZVbQ zR`#)#vS)@~%ca$!Z-7{0p|5+l_!o<1kMQ~cj>uYv@~&0nDwUV>7j;f~9BHf;Eli8K zdP1>2Vb7~siZGcM25L|S%h@Kw{(y!y8LmjX!Bl~n&7Xek%1cD-2?f7=jmI&>2sJ0X z`Xe&TMvOhuC^%BYw6vaNqTgERsCsj|zl+myL>%s)z0~g)-9?Pye3*0jL*C9}>&&d# zbm`;D7GR1l#=>TWGoGYcQkeVg2wS^*?q{p%{2k_j$2psdHj3nabwC^1FE^ifhy%eg z{3AjxAqWe0s;sd2E6u9Cc3jTbx(91w#pu?d@5_!5iIjJ7Of{pyl?Pco7Ib7QzF$s! zK95dJh#DFWh71Z4tlQQcx;8X$QNh{*tNJ6+;yqcg2|(rnWEg-#7}9O152`^30Sdqm zalz#M5h&b{tXoEPb##b8%LU*aFzIdv<8$!ne}F-Z?nVlCG#E4foywR%p`yxlVe$aX zvL=cQ1XG)BFx5>Yqo)t2Ev`SVp4}=RFyN2uUCtiK(n{{8p`j6%l|{8jwn;RFLOY;U z=&xQ4o8M@`hH6?iBLBOxr_Z0;%{xpkTSKPGP0@ilB#d29Hpqt$tC-1uBg%RKhfhjo z=4ddb2SWusXw#h|Xp%v1iPSYTLDt^U5uK3G4X7G$i9!fAW?aB*Pp!d~4JD9F4>wyT zr6&ZFHlj|u3Q6$vt4vPJ|9bQcT>v5huPRun4iHaodyGv<0RaKR$ODPftxYz7ZUDFK zcaFPL1`K-CemL;}TowWojC6zKFEKR#1v4O$%L{)+*iFAy&7oVij;CywQ}R{253ft}8> zJy)b_olFiH1%*EVi9MxY<3Ve(BZdnD0^pUDKQ;S2bH7{;EEV@ddjgrNa|E7tz!MDKe!pgQ{3pce z(*L5anN^rgy-RJT?@)stH}Kxk z6$3jG;b8buqyJ!|zd~8*^*~{n0cQht4`xoLRq;%oDV~?70n&zSpPq?6j$<9~`|iJ` z7ktF}y3xwY3P9hZbQC?h%qmLVuWWBU0olqv|L4zO!0>$sxH90kzj?+*^7K&>yCo?b z+c%G!^JiQiA{}T30IhpuYN`uRTZVQbbr=*eo>j@NO;^x}wl*)=;0bs;ZrZZ$nyxWE zxFw+y*ZxqPP2tY3z6v*!`feon5>HcujiHZKaVMa<>x~cVw*YoV_|RaJvIvzr)VL>< zF`v~kTk`f^epOq#E&1N&|MZpR@Ur8LsRQliDSSq2SiHlM^|i@`DK(y&&*`QzX5142 z0nrTKmpDHrQy_@Xxr59w2uuvGRG(KHni-{&{oPuTalkP3<9c60TStdJtU=odbIjv! z1X=wN42}mB2(^$3L4=vvSzym5T0EJ?E^-4v=%&R%;7U|7ZISG8J}pK+^ftt2Hq%Ub?m z!|(XQYk#Ril%MORU~7MT10Nm_O_WX4?bbFyc3av|kPg#t7xxzr>e_v~!`*RfUSc+|Lg)wG zA)sm@*e4ThDR`V*xff{F9LKkwprDwa=?(4ts=1xg@|;1vv$DG~wYxT{aNB|^R3DMO z?h0o)Y}uJrzg+QDnY=>4O>T>S$M`U9Xsj#3E$s>yqv-RN2AWMl7qWpJ`Dq%nJ05k9 zftL1LWUSPmdkL(ChabsLn*5vQSrhAW{L5S&aPc+SG-m35go%Gzwd#o8v_WU}gb-_` zi5jGYpH&nsxIJz6&Y0YCKI^@!uXN=PXXnt}D_Y&BrP70l$}0X%qQiAy_;Pr22P|1W zvi3+g*;ogegNA=JTRO(45ba6+_y=ca2%w>WR+CJd<^^avf$2~X;CW@TD=1?YPx|JW zJ>7D69vEbX7m~4ZL<8Y{;VF_?7nNBOEMI@QT2gPTh=T18slHegDLB!H=VT3wmR7zs z*5!`fR1>)&hUB^B$ii<@?)7J9bXRbnB-QUZpZ@p3$#1w`>| zqycY?kq!=Qm~32MNKjf|pK3AjC*2qal(-qg;qP(j`<#|f6YLh+$PJ?yDD<1)#7D*T zMQ&tUPoLT!XK)!GRMT?R(&N0a;ZZPXg-~&X_rP;wOA`@nLjFQ4a1ry+PQd)a!~0QtQC?G15&-P2fvEiJJlldnENP=#P-uSHdC6IDl%59)7At`J`^*)6M^(uF;e6sJ?AQaY?<^wABgN*}!~(9!IPapR?i zha1h#VxsM6t1gS4y3xT5)ip6#D6sJ4=TFkCP)Jp;MB;X37JEs_L0_6AEO?rlmdu|R znuBa)s3Db}`L|y{h7d(Q7metoPh=jVUuM&^iiQT}`!M-j$+cfOMmIgUKKcBBthp~O_z~s7~T|>+r zN_axd3hrzBcQfOvYqn=qGh(Q+M$?A_^RKaWnWNiNu>IHW-Lf6DJXdlQxfqIX6z7~4 z_(^I(+8O!8++7&{i7@WWm6wx~^DgYCM4lX_Vil-SqVI=ZH6d6AKDBN`@G$AgrzlQBeK{4BMD&R)j&NAfTzK z3EPaH7K@o| z4%AsgHhyT2)AMNRoDPft+79{=C8{wyD5#MDsQF5I)Z6!@S2}^&9}Hz3EC8`#Znd4l z4?+mOcod&sZ;~hqIF?LIu*?ktSJ=zCMoU<K`va|Mv0-FkC=607oc+Fgys5 zHIOmd+S`Yxra(YwC(GFsWo7w;mU47#%rAr5B(VdSYQ3eS1EgZWGlX3vBV%#Z$%|L- z7~(<`Sd1NO8pmd2%q*xq)1K#y;(8nYdtVem#S|PI40wPtZ~zG(8Bt(pywqQCJK*IZ zl7&6m>uI3<>F)04qzJW338<(nFF!S*z!#CXuHm(K>m;wXo}E7CKaMR_NEIS#iFWpZ zfR;n$uzUTO!ID?HF!|=U>%jfZW4ycPZVNwU@Hu!c*)oY~bL983+$e>Khjz|V8Z}b* z8Xqn<3g#6jSH~m#|2~cb>zarL@f0*MQ0y6O45X9}C85E6?KdK$rVa`V3j>4248=iC z0P285T655NgMf<4Z$_r9Y*TYby__J0pA_PF317HMtn^an@_>Dy`@lVCPlg}b6jD(h zjQwGxhP(6kc4P>($*5eo%#4!U#kZ16Us1ezu4Aen#~aTO^(tdJlz|zy9=*){tow4iZB%+k8!BvU*+@l`r7r@lV5Zd@g>4*xFIl`#^G~^ z01wiv++1o{q}+)sE5nqO1N;x}03SKLl1XV=uCqTg1&rNpsx8FXTiRoUHS#_(g)RRKex1XzdEiTbIzd<|8aQ-f}lq!A!vf z7Rpp4QNNN;9=MTvM=NF}WqEV$o3Cu7!hOYb7rICE4>*wbOp8Stl8|UHS z;ZB~LAJi|1BJmq!#J-fA#C7KiDYMn{z0~Hon@J|(56N4dJ3@?4+^%`JGt28^a<{U8 znCK7?h1bG!(;^kt*Hri$MGBfWZ0Nlj(9>)FVd&|xpf^J2**G&FpqXcvL7X5B&ybMV z-kWw{@aZE3iGb*Oge0Op-QR2sNHx?nG^C(j2je~%!!{!g^a4>aG3c8(DF74QI&)ng zNa+RqKli?sU| z)9C=?n%duP>+0H_6(v1q0vo9NPsbQ;``SPV8ue!tdMkBOsOcINFfQHs_BCt6?a~&65=PtV zOQPa`Fpyp+$mFcX+KDkS(B9T4)3Ktlne1aBJSvs>tm<;v&u zC1<55#7kupaah>Ul+Vm>`qVQ1;Y`7cO)t8eiGH1_#xp1=LyhBuez}7gSR@;~LUn>{ zC>F@HA(oj?J}VldYH;2K5nX#Kgs%6_dijU&h#)d@cgQE1QUNURR&?l>$SEj1`Mvbc zd3WaHn2M_XToLsPz;FH>0$5(Kn1sma6vqL7AZA$4Wwj922`W%>5@CMWnMxqjs1;7U z7hCrG;Me_gi>IdN`IL!SsY8>2Z)%!0)A!yp)1ORpi8Bs2mp`bXk|A8D+D}yn!#3^R z6w%WsSzIihU}qE68KvGE%OeImQ~ikO*2=-B8EDbTPB%{KuF8!y6+opNH8&gX5&4z_C!7 z)Y>^FKr^Bav;lx_Z}{nx&C>7B-bP!F6%&f`)>2O=Wu@QHYQ=j0y>B!@@7Conq#^(M zVpUZZgAQc-(oL`p3IeDMHhnBIUAS&RbPxiq)yI?d{=a>#QD3}(lF}HH2BM8CEhA&+ zvNge(V~UKJt1A~MPVeIX=59fRVNEl0a|tOaau${{gGN)pIx4KGNdPQM7aH2>^8)=F2CqulsDN`(w5 zoM97-lc9CM?0kjyT3Dg_6)zq=J8HPhvr|`i5zQ_lrl4K|Xh)(0Bt>U?=I&DIWyA1$ z+wugtOcZJPT&t6jb$NkeGSWUN{oKBfR1u5K{#vZ;SmP({5oTCv+{{B!|K1d|hPGvE zppOyv1ipl-#VGa!B*Mg?T7t3ZVq#js)aXg{cSSG_#L)4)`UHd|z?M$9_`tIP$Y`wH zFtQ^D->`8O&05k4xGvn=8^`V7YiKzu5pvMu^sKzX($aZJ_{+r{^TIZV!+4n#XNb7e?K>-SL1R4e=L!(U|f+n9C9{u-B!J_&oHlhjvFL>AV8UfMH)zOx$# zW1y6+JvlB;#!-P>Cz5;U=zll-qogDX$V`CdVyel@D}5D^X5}OmeNnl3Kc<1_rU*_=Ss7Qr}kGPjZZ5VZ6X^&fsiBY(Ho%8B(g}xrsrh|K9 zVPYH~V@Bz)!18B!Plst|WY@Pxe?jq6j-1ip#RFKy3qRZB#Sc_PpuBwwOLdXslauJ+ z?_Ug@-VXQ!2Y8d=41<9*0FCPuKNlH(x8<<;Sb6l2mWCnHXLPSK$DaQ}Q_1})s;3t@ z<2+B;j{ZE)_4?z9T6b1X40|Zm1HDO00$T4W28-A}3HeORo0Ne0%&0Fot&AHe`Wvb@ zSIwby>MASQvzc4r$i#-f_mq$F`DW(ux=ok;oEAysf({H>H(j9taE&M)W{-+cs7FGwN=MfTEzuLVs$N0bX zj|PEG4}S7jc1W&;y~6x%#=?4b_kPyTdEd#!3S$j*5hSbqa`}UipchQ(*O(f2MgeWl zm+f2o<^;5um{RjQM2CLzC!^SV!&iHF!hdSBJ9xIGHpeirSGCGLL&#&#j~wu3Br|+> zL8D)+PUEdZZ_BHdHgaKqYfn$E{yiu|A`b*suKm4qkFK3F1tq06pj!GM_a!+VdqoO# z2@#`Pe;&%57LVkWP2oDdoLr4YklvDiCV!965KNjux|SubNasyU6GC`1Bd0{STNIM7 z_8Y|~_sxsi3?+fB2J|-#7tGybZU;BdqbcwO5zzy_oZPt=$?W%WZX}?!q-^kQBo7TK zGA>TUn-y|SmVW9jgKpZ_Qvb9aX%XZ6G@jW1b18a{XsfQzGGrO~EbBE=A_B$8 z({E#2Rq+YGQln94lfHO)x^yTr=dO&eQFVCY_`icImtIlEY?b4~u^WS=0Q49kfLaf< zZA4aqWC(&}(?I>GU2Ffnx*A8h!CFMSBHAt|KbAXT*ihdsRyeURe(v?oTiwh&8r~J3 z?c{?Qw%CKZj)^@Mo-e9Y4y)r2ocsp~d|tezhj;m^w`Wsvp9V!HJU^6egONw-ioXP>#wH)c?k>3=1D$(|9Ac;p)MoVAuro&rQGO zf#ESY$dT2`v2Nbn{HeAXD_+047o|l6V5J^iTu=da2#_hcauW!k;eDp-1^6t$wpDh1 zo@j>)IIYKxIRI#Uc(3%DGMb1=0!@#JojOS-jd8r*#nii+4jjV( zEv@7#q5qEUycYwx1CYoTP=rh<0X{4aifBX>lA3 zG7E0FFfL<8+pPK*R=kdvvift@R$~8mlq#!8DP7s8UMzTIoZqz$JHKZ47EmP6o}%^+ z3}gdyBLax^qqv<@f74Xbb9&7Ge^9Ak8F?==OyVJ%#%JtV@&-W~#H%5wT*{&I*FNFX z={+@IFbN8e#{gDVRyI_Jab;vuxW?-{1_uv(3RTl-UbwWg(+m$&js;C^2$&#)bN@Ol z*e7r5GpL2d#L!>AwtbulJ024DXAoS>xg!F01!$xJQF;@YN(1Ek%n{=A##s&Yw}7fs zr?<*R&8Z5sd_WTg3^}?=kqKm{_NL38D=UMBR?A^r`E-ANHnVv`tYX&rsuylbQ|#m@ zJj(rI^f6XV%aw&af~RppZp=J$!WvXxFwEq0W}uz(Zk$5ut>)`Vzn~{V%a{7CIoAn% zv6=!>@z18$e&pr#AVvL)0R$iG?}WgH0~lt#0+5ird{kBItEbJapvQ*!PJ{o3JM+Fd zfCEi{sNygz+)%y4$mtiwc=I|2RZ_%scX{BKH3Tx8sptm3S_|b(KiZ7N2cQ>9t*Dun`%t=mvVbbJlHuye((2+kyf_DeO;w-~HXq)@)Vr6q6bng8)E2z&VBoKET$-wg@nJ0Ll6b z5J#*Y9Ozn+iOAArt4m)JV@*Oe2_MHo7b~@P{mTKn^g9qO+%sCJT#(|v{QPr zXt)oDNFrW95LmJ8wToSz2ZbN1e0OK1`Rdij-&6a9gI)vvsD~a=3(8eP6>S<2|9TsR)whAJ0z+r^|NV=Cf8s*p;%o<2LO`wzWqk|RZ(=kkQ5nKys0FefyPtY^G{#P_{%cZ#c6X_3Xp=8 zu&q4f`aUH2&))cbsp3vC-3hVb)~>&s|A@6_isNL-%0cmL<-qud*CYZF4w^`EelnFO zO?sm^8x~7sWYB6!zTnZfH+&@CBv*312S=L9IM(SGtd0=%XxIe9+wSxfdm#f>$E)@h8*vy(oe&oX5dewZC0P36@R zaIu1$E#1|cXrhhOHWgJ+&U+zw`AG~#vljzHUBG7cr<|g6^XS7eD2el&L52XVZLP699kI zl5P^_PuaNW5~5I!6whUf)S{;wXI5YjRWY4*B#%7unHB-xA7H{X4pzFxBLt!PruYiX1gQ%lbJ zxZQTHh4mwgoI8>@dYVkK#9}R zMRkAY^_=*LxGPcONGM5)yNmfaQIQtyvJ%^zhca3tpJbLIM0K4mq2;<{LdJlJ!xB4h8~5PH|Cf=s3v66k3OuxF-1>rpUc7| zzJ3<-Xu)qJG88w& zbt1k7vxV-xVNfo>N@qG~%a^npImV#c^%i!S!h^wz`L4 z!84c>D{K@@r02NJ>eZ&%7rE7a(aq(rByEu5^@DkBx5rAp|*ExB_v;3zMl!tr`I+4Z2 zj98)1h>3}B@9qFa`6ZAw`2_}|0}lg0#RBJKwpy^mTnCPhnoU?qdzpdiWgTRCm|+AU z>Vku+0WMAg6luUV8UWRxoB=ZZ0+syE#mGh2+zCg;aUfCP(p*_ zXu$glXw$-g*#b^CHwJfWu~44?PTxB5)CH3jqRV{*so zSTE7yk_SA%_1>YqdL;mb7KzPPzO7T4r$5M7*wO*w~$bpHcsMFjqd)%!AkVPgi26i;K&gFp|wV(g#^%`Z!R|Rt7kk+G>GKj2&!{~lBz0)D-Y0p0s|&rfLk4&P3mS2n;;+{ya9uspdf@= zr-OltNu6FGbP66fqoAb?E!3>zg$I~gF0n)QX_<00^ju0-RT%M^9g5e3<0zO zz^{4*CKf~oRVua&fN=uOF9&B7d(BkfgL;2m>C!d{MYrtPqq9E`dEdWmug{P3AC86% zSInrWD3zUCb2dla3okF-d;`b4eJ}kp@y>l$COVV=qV#h3BcI=mNp7BFw9d+pnL_I`dik4`@hX;IlPpp6I&{dk` ztN!h>GFLCOTU<+$MTje4Xa-IEmw;f@r_%pN)OUw-*|-0)9 zmP>(*iZNpMh*TMTb%gQ-K?>Fr-+1t!Ds?+LI4taRp$W~P9QP!NR>vP;Vsa8r{v#qz z&BR!2%}6C33!^REh0mj-r?T8{8~-rU9EN`bgR>Wr->og-=(hE`K&a!>1Zn>t;j^rp z^ou;^njaEM@5G&Wq~HB$_lx~*A52NDrfNs5OP?!Kv*dIhbjf>?Y<%8!+Pv!Ne6qrN z4pq96lvBN|7~{?1SI)^3oY%O+pNQPMMe#s}H|)cQ9qO6oQ;)i3Sa{<78)jn|Z+F2?*%WDHkPep4U(dHbwtd(Bqj(u0zB;LH4?*H}K=$>aTs7FJfY6|f;=h-t@&^wxI{zX^ z(OSk^<&1Qr+J=TXhx|~E7qxcPnrf1j#Fd51@OA50cw4`s1leym5(Xa~wmb?Vd3bnc zIpykV{3#Of-PI;J?cK5=#<)(k0=%>}ZXfK__vwvSx#Ji!%&d9hM9#~YyrFl@?N9Z? znCN8uuj~IZQ7h9B;d{HYeazb}CjEwE-RSzg<)1TsYfiVQJTmHU#?*g|tZ~Vn`JVB_ zd|F`M?GEs?WFHdyv_Eja;@K>*Ejgstd!=K!dJOn z+3!m7@Ob~enMtyym1NO;flHNEMf=_rsvlAErY@n-T)iQ@Z9?hXEx*Zk5ywk3Dr3`l zOSN7on7g0Y&3ieF_su@~nFlIlJGic>AJPmV^a{W!K+m+~-tLq?$KxnzV8ELZ zsw&GoK8K0xU3pgeIXP)Zb^OlK9{_vaJgs!d&v`vI+z8Dwnw!d?6Y}{#{Z2#7yj|aY`2;eAj~zYwu{)NeLQoKanDMMS^z_eTi#YlTg_qRDa^t&brQ#cmRn1(c5Zs^n3H(FmKxD_mE_#ym_v) zxo@O%-YiXkZZw>>JaLmosygKOmbXUNRE+O$^h!N$_nduuPHS&=y)n{gc&N|N2kfw9 z_0~{HOPVAB7vtwp+G*J8? zFG}Zl5<61k0cu1>9ueDEGQ>U{zAJL9I;vPhR@uL~;kfJIk;nBz2B1qhv_Cw-e+AtB zm9Xg>HT5BQUW(_w$~Qy`z5oQt2Pq*)UU>(Hb4>T<$X!bE5v}tG5}E9roUy(VVeLH2 ze?U~EPg|QBdLGo~Ke8UVyrvHxJP=u*YlS~K@fvTUo-LtLvQOW$1}3K; zFcFbP6hJ9b(O;9+ob2eTAW7r7-N6BOT~)7R{}<%qoJc4pQ4B$9!rywXTR%Vf?#F$B z15B)q4B^nU>C)s3WmZ=wG)4dhExO+OqNkiHniiWXS=7Tuf^sxv#Gyn)Sl_| zym@TkRsAd|ND^u!lbq#;7In;fBnRJVrGL(T(qcOIxvfL1RSQ9aO)i~#L+j<7gDExD zpR@cvaxl-P?yc^k9~}PE;8+t@Rut*Cd56<1KTTgGb8hz5a^cy8^_Pt+ zZuwRU+PhZ1J5SfdDQxol^j2-28Eg`ISvj6c;`{qs(5mZhgE=1Fu@vixv4Y}a4$lKs ztS87$h*HXYFnkvi;IaNv?usdG>!pi>apW{}l6PMC*xmTPPfG6bocOH&P6;xR3+n37 z#vs4k06aG{k0Ujao(T#Pr z^F>HqHs7A1;jw;ar+!);OU*!FpY?BEo4xskSI=|xxK}M#f8(~H6DYNL{9(|AFRtX9 zhPr7!QWP-Kpdn01N!iHVbwZ9=NQj<^DaJ+r_*o`ELKrpH)VS><095O9g=@L_pC6JdSq zdlYp78AXWzU$mTCU{v>!_NR`r6+fWmYxB{5z2I*OU#MWjeuG4&fv+vu#`46ZD9IOh ziUbt)V5_n?(ZhESoHau$3~AJJ^wDtImOno(Lk#_GZ(7Hk)@Ev)@edn2`_F_3O9M1_ ziY|se`;w8bhOGbD>cdvnBTqJRF) zq6c0^M=K$C@Pki)7s(wYDdsfAze=KDfn1t6!nJZLoZf@71 zp2wk}_7x96fvUT*QHN4S8AF z&&1O(LqBafg#9T=DOx$yO0X*2KI270MrN%f9LL5f;A5N0vpd{usQ>l59kEvsO746A z{(YC2P~%s)US~Jt+4e}zzD;3AJ8}bmS>M5U&ASCU4N=0OwJ%uxb#=Y>{SMK#yotNs z$i#%#=9es<%;4lRPC3*!yXn3tA4ZqQbbKb&Uy~|cCLfJ>XYl&`fq3iBP^dny-KYvW*b^DY=%0Tv8Pwlg zp($})On?F`O*7{a202$@4vD0!JKg7yIp$quFhkI5XD^tWv*Yw3TJVRMd2rIu$jI?} zUKl|C4R!4fyHgJeS=ZO;JE}`IAKs7A{Rro7&9YlLiPofxPbXAU@6no+czGZ~OLHX@+D8>U!0D7^ut0YNJYs zQd>z&`7=Y>JOaNa3Az`nh`K>C2+#Wi2ODJ8jE5hDMWxam58$Pac}TdX{t}q5tK_p<`OSf78?Q zmfxspJ39~Xbo}aKv%fqy*6SzWllzgmJgZVrq=+LTE|~phY^lgyc?!=;{>O4>Dw2~@ z{JyXmHk&n@vrw*M(Ip+z*dNMp5ofB|=ZY+qepb55o0w`_8lG5?4ob zCoSf=jEZWa7+H~J**!T7j3bxRfb&rR7pw%8z#)irB_=t(W*HAxpE}>E3&Cy%-uUuRetkGUwEDNYSb^L+MgMjIi{_m zAtSrJZ=OjyD&6qlkW%HC2JLEfrrT@{PYQ#jdslelc%J@Kx#_AX-<=YsHnP8FGTW-uVf5&@_bhYm?gNNjZ}=^H#`6vPtSZjJy*1P?uc1e5vr@x7#^ zBUnsBls`s>%vfm2-1Hp9cMf>L#6ZYh3EvX3F_0bPC)=RA!(pmNuFQS?8xP5v2CkWxPqPFQ)7TDIA3o_3GOVOmDqw|Lw8f$kErW?tLZhr_F6P`!#++ z^{;m|N4OQ@mpS^!-qhKz75_3cQ3<4`vS|33NWyA=)q>*6^Ns!EQxA7`4lXy|WJ2aqEz$q`YZ2Pfkhs zTek$sFFa)|az9H~rwqS@^PA>wmK0e39o#qcNlg=*ArZ~Hg~*^os1JXHGTr`1e4GUX zX1Mr?peIDG{rP4XsN0<7EiZ%45Gu4dXtR4<#?vjjKYZyvwwDzbJMqLt=G(5ip@1J-ewr$$SE z1`Cu_U9~smmD~Wl9Qr*$1mLXU!?@^FO$KLM6EC)`|0aAJsPVDJba2mfm+?$f2$} z@j`2?;^)if(k+qJ)Q=V(4@B6@INh%0+z?%6|0j2#w5d9DjoY}6D)Y(uSYk{znkRJB zs#gz;1Q_*vf5x)6L{Aww3MP44+RsSnS(U~;%<2BZ|8Qr?& zN@y1v%aL$E06mA>J^NmI`xH_|BB?A2&@& zPH){sJ4W?-DB{qo{Sz-QSiE~Gu5seUBx#D0r{3TgzdlQ$UEq%{hT!6b@0?U0r-tXQ z-rf0NkcpnDxRg(#^wNr>*%(3Em~MkC7;{CMUdhVCr$uOrpvW%=E)=Mdn*K_)OD!@f zB^6fFfeLSq>+gtU9%7#+RO&u~fy!|;WKjR0??!|4vjzEwx10CgdfRSZFdTlH2<#!E zIv4vr#FY}Shb|ZlqgoX^@tB#J5j`moVVlkMMgIWi9hr!ZB$^zjKR4XhW@N6^vh7iP zj5MtQ>$6FB(m5jaGR4OqEg#~Q?l6!1nmo;%>gSiK+{>bWvHr$}V7X6NNN&y7mF3xu zUWV`b317>NepSsd$a32JQ2A)|wUx8(ap3WXc{TNR&7L3RIrt3K3^=sbGW=LOZhln$ z%4=jQTxcH1y1zyz^rLY$xxaM1KPAP??E(M3q@nT_-_ILjqa5_nQOyr3%mr#x|2i3} z(@BWUD_0*17x1sDfU15g_cq6cg~2}$?(sLJrd+nLNDF;KxnsbfBTj}C-A3L%A)+=c zkYiGV9{Qd{bu`*{NKblf>dz>$m$T_O;m8rr zG@L0PsGzU142M4>g4kTf&t|wk(=F2Z47nLrC*}bqx(Dji{m0l2cMz`1c-q zuCFc%Bt^YV`7NkC+>?8YX>;Y+;QP!L^Al4?x}I-{a`qW{>!^MHtjVTEd-mHA-q`fG zFae$rZl2rH=jAS4dL&!8cO>oY+a0Oxer084H7h;;e@>x~NlE!sQeZZTrGh zZ#}R^0+Nc5_6~((veyy>(B(v>C{Ee07LAdDB7Z+0=U2b?(E6c9s`1=t3*mVz#>p>6 z0q8rJ{GG`8*t&HqhhFiw79p;|gq_otsLTXL#IA9Y-tKgXcBoRr^w;ELid^hL9!ITud$*>_ODA?x zF#MKEl5HRqCX6tEfSMy3AR41$3C~?wX00cUG%e4`#ZlgFoyRnU&fa=3K;ZAk?WAXa zhrM7`PQWYNV_kV5R6+X94?2PcfRC3%S!8Ah^q9B;zdWin`s-vM1~?CSGTdm)+}G!? z5n5y1MGw7&Z$|6%%oge&gT z!7pF_`Qb?l7g-b1%PwBO9#&J6ALbh~;4cMH5Joao>woo=UenWZ88GiV^Y)bROn&+U zahC#^&z@~Fe6Y8oY8ZG=VsF9axRz&OVWTZ(Pf)rPi2-(~E;vAlaJvvopfChYFt3DC z2HOEYOO|_jE@U^O(|u0eLSmEr%(~SuF-~e*l@PgCOK51pwf~TS0GRj+h?fIf==m^i z@bW5^y>E&Ki&D{jY>$Va^^YyU-%#W_yJI2UdJMgmys~m4z$*w-sHDpWtlweY!mPFH zK1cm~tNv(o5rMn3{ZkAa*+%E--;Y@5HH=yFdZ_Pe&uZ!EuWc)q-wg?DOpG$P)DtFXJrhs#oKvoccwXm>unyUi|Ybon)QpQiFXNh%@$eiyu zWvC0y)Y`cI=FjBBXo|gsCg#K&f!_?xvaW)0$wiDyGhk<+3uW%}*t`eJ*injW6+4IQ zgxI*aSb2D!qv8KoLFnbuPs@eY+iPg^*JnSeyqO4(2by*C=G+lqP-YO&PE0762-C~9 z=e;ZZPcO-#d8sCILgGjJXmuuLYn25U{uWiA=qr>!f zo)DAZ3HcD5&A5PLI*|aj!vt+lT9wRG1MDM2T=Z8gEjfwQHZXXZr7M?pX7|$cVA~Q> zVJi)?{_#Hec)xV;^TU!QJQy;KRS8#yes!0e>=^Q%m62dMEN^iA6MyP_B0V;SAk3`4yju_Un_PyFy;)ryzoKzoAv9*Opb@Likf{%^6wlxcZ7Xd zyof}zuqbSMJg3_0w1(=~Bd6;f4`r`}9SUWB5vftlg;i<+ky`E#D825zF=rb9->|QB;<4=a)VA@{&qw~?~JEvt)!FE!+ zb8%8toSuOehATCzOIa$HxROs@;%n;ZeYN$Fw8Ap`_S)AwL!X>G<<-Pwx&3}lU1O(* zQHvN)P+u0wX1K@WF9-L=m47M=dbm8BhXF1Ah0cy`jPvWZFUJU-s$ckE?{cdT;)3xkm zOdjm#Clxp7yEjVHO=iF9UAFP;KxKxR12ZEpb{EYKjGl7i|6!fHpT0ZlOq2b9x#G@x zhv3$Q-%1uvrH2P4ji{$j4K%!P*ct2Y67{H9_3&&58 zoFYMQa7;+3Yw+GCa3e&#maZ>o&$teY$OU=zTHZoftjNMQL&oX;{{EO-(ax79k{o^c zBEB?)^Y4S%3D{7URyu~E{Er8Zod1YrhYhG1weYzBUTbb3m|KEz*S-jKaH~42;K=lJ z)A2x&hu2*$IQ3qmkRvhCE|LXb z0{kx4Z`rOD^+3g+TKkpfi>qEI^^c2bd9x?_?PwElzW7zvl!|repzo)S(y%AH3cW6? zsTGi&{<3#ODzW{~#`?7^cMnd(TWfWr^@H!i=Kjga!0!Y*_Bs1_Y=GgL7KStcpk{2V zub-825Q{G&Aqg@waFOBgVPf4`)rxKCJM;s1kR{9$*pAb6Tt3M8ZxWf^52Zw6iIhjNO{3gR@2HnKmMuL`geMZQ850;DT($iif=9}Q&3Vi znZGzW&?6W035^Fd%qBo<87I4etKs%}{<>%ffEv?`vxWMp_uT5E6rJ2H2t^W;)`fvJcrJ!#*w1BcbitxiiSU4MRd0)YuB!(?%Olk=GVE)$B_4MSew8$zst2B z{Px|7y~#-1;Ty17C}FYV*q$#i9zc%ZRNN2j@eeo?f3vgzv_nS@?uG=7215tqqKPNV}K+eQ;LrkP+(!*{&uy2_K22!^k|*l`C&?@EAVz zt}nqn+HT9Dxn6F!$Y1T851k|Z-SM~0b7h%let}aVz4h*%7*T4~aW$20(}hwS0|q80 zjWUXbPQx>c0n>H&SW6tHX zt~+aSP$NaWw6v6e`~cnlU4XuS7oX#Px6tEBsm^VZLl^PIp>9Jt_oEYx0E*oR?lut) zp2dx81eGqn`g*iVG|%B6wk#YwNnq5_GJRGSU;j1v%**5rI6oAA&`T|+1W0yD4?!GF+9i zE?vBMgPYbo3PNN4!O9u_`QQG>MMa|^QF5X5Q2dU0lotFi{uX%F@OBI^=O9pU9L621WNb<78=#1ZWJY^XdEXW9rwI+d}?i9D0N=OmF#*F~lM@oeD5~6^ay>@8tyWU*MY}y&+}e!8m{;0XpK}q&I7=R|}nt z^W6F&w=%JUVV&2R&ohyOzIg5phgSZ33ve>92mWI=Fb_s9@MHMU1yW%rBmM+39v9HeKQGs?C1}id06ro5T+_sdC)=k4w4^vXo z`d(EhY!{@p(~7jDi_?>T)n2|^+~QUvrPTOBTpiW0k*fMQy?h0iNC;U>Ye4e5#aW+% z5%J0E8()s^h*rNDRF}b@%B{!$jAi|M@rIr5_s?HG*Icpn)P5sff4yNPXPrA<)$PV1 z?YhCGveOjjyWdF0-#8PuOXSO}c=~{!hCNrY#LdM*eY2KXA?7m%rzfk2?Sz2d>XtNh zTbxVN7~lCsmdtBkEp~uLCT>J25fDOyt{01(BveND{NVcil^i!t-zTUv)Mv=dLauH& z%Ll3P9a4*HX-m6;2?8LmOo%a@pOB1QNNuN}r`Ku?{9+j)+5)=3S{Y$9P zu-iqM?iOy%C|lqr{5<~!zV5gH1Q{Yr#70p`CtqE5_?Z+~Ka?V;2j;iKMJcuYE8e#^ zadC9#ENGz*M8}6{_6MzF7q3tSo>W$j2l`38S=i|y%m^wz|7=08CBc(qlx?^$y8V$z zP)g64k2-qR4@ysH5&-lI4$;5G**cJ$aej7o7RU1ze=tDsZ!sF5Bb? zMu)F)RNr2W^e^w8toSWoT%aj(TS%&J?DRjeZNLN~%I2@@pVmnG0W5{ex4{1!s^3Rl z$KERJ>=6ChkBNL{c2?>N)ssud#l*xw=8#cQdBI@SYYCnxn`6-WJT$za_3AGk*EKXC zMCLfCwe4+dn>y=OU#Bdhk{X4VH(Af6H;>tYhQ=V2&4I*O^G48OSJl;}_4N8QYdGq8 zp)B3~1KCQiK{P|xhS3lk^swFlbDF|nL?}^X-2VF3tWtC8B8n_A z+QpC9Ocmp?@haf3z`vIU%QZwxT;_k`rJ)Kgeb{`l{c>Y)a4?~%AQC}A!Z-bil{mpE zYg~~OvAie~V>n6gDSV5SYb~A2MTVSM^9C#~z4zkZq2U_+5fdXl**>|SZP)VCy?3T; z-dIz=`c2&;ZgnYi$?h^0rH^<;pQ^V~r+5QvX20~tbdK}rD$6p^j6Y(>h!$Gepa*9OlZ2lYp0+ybtRMNr=aQT8&AjT+Cmd4 zjaE+kCVl%}HYXY#p7l&2kt=S>^})zAy;qCo=O7R98gUwniwDe_q_|4Tz1(NEtci_? z3As<#Cnb*XXm0KmXu7T(eE5yf!5dxOnYQ+6kEUa2tLFM`RMrigT{|j^1!j1nyYpjS z_v`(#;yM#wF;$(XE^gvBcdoOFPNhDG&e5KW@k2W6Uixlpu?Wa zFwV$&pzA8es=d$I6VEqxGyz!`7Z-0Z;X`GH5DLr2ma$_n?EKxIf|L1LL`qu@;1M)z z_~PEi$3w^loadc!Cej-e(JZz#~w&-L|{1J;q9YTsazBSL3D-=a=Rd#;j)ClXj97+t-4 z^XhoPS5D@7-o1Fy3w}WQ&n7uYm4n0n7ijl?1!q?h-?d7N)WGw=LJ1NQ?mMQ8x8nNU#20Jpd@Hzure1^cZRj4}j}&)q z>#g4tGd!a;XLE3|c;!S9`qx>b8-wefNBECLChn~@&jU4J%D!=hg7bR%j}NVojs zdaIMM;;DTh=@(uUJ`&#C*f#0DPIAB0vG~hF8lNAAa|1t~FnkJh3Rz@4eDUvBM_RsL z(-u7|^tIY~w&U-Edu;FQrQRHOuM$MQ5Ziht(ktD2euAw3Q^ zFGAITIzBlg<0K#7?31h4u$pBra`ZkyWC`@I&|%UKv00#0vC0L9%Uy{_n}b?x>Bn}W zAwj`9yio0J@@2sK4;sH5^LF-(!r$z$xD629u>tBJL7U<1@+ZH2cXUrpyIiB$S$g6R z4Ge5DJA66l69QwMfCYWaziX)Yec?Tg{tp~e7H;l8k=t4#*7uMe*hxj=!1=3XWW@S? z^W~c+dnYd|vwyK?on6foKL38ms^RNx6(fQ5)!`hoS&u!_>zuwkiO)|d)OlPfsBHg@yFzY$l*U-jr zfp2!#6IfsKh0QF^%CItch>Mj zS1F-rMrQ<-Bq4CaR34Qb&^>vQg9GtFPi8aNu^0>@Dp)^aOp07iq6QNK3^~(tN3uO02y?VDowS6idR1Un(&(AmUyA4Safe3*xVMQ({ z=%^bx-`{<=NbC)ZL!(RRj{t+eZ|TgX-^Q?^fkb=djPoi<10jR>vGqMx&=lf-k zg(+c?6yD9%rB#J`1(#zCvdW|U@9v-7dPR*)dgr0ezuMHRS{j|%g+*ya-^krMK9D%j z&}1?Df0g$->mn<=RdtV?Y>ZrlO|*EB0xW`Hf0(9@=Xnbi|Y)$lqO=fp`T?9 z3=9xl5(jA&x^0N{xXkSyl$D92I}ijR<(H1 z5fKsmvdD=!0k;z}#2gYW86apE%5JQw*)1R-0L9g1I3ie;qu;{iGB-D;(YZbo=lpN#{pY-s7bLrtBF~pY2XaIgI>OM8CnNX$TXj}k zc_RY{5mPjJl9~DWp^epPnRr!AnQnD8H5D~Am@SB{LAHn3dg%C!&rfgs+1a?$Q|@$% ziPkK8@b-e$joZtWtxeB)ZyjO3$IvOV#u67=Ci^j6dG=HP<-PXy#()1JA-yi5?2JeF zSGn!4);#L-Pjoa`O*@AakgHqtvCmZOHkA0Fo20Iq&%K%Dqq!X6V_mc<{=_c$bpV&r z?k`#umCy73jEIXh(N0sipL;S`60w_{cgS5#Z-q44gNIUD>4=};;@$NdhwNK3-%JEf z&#a6m?qLw~IdycShSW*!#iilW7~0LbafLru-{oEP&}6?9Nc&md<6f|5rBuPxlrZh^ ziG&Zh^}l&?)Dw}l5S?-6*>9{l1EuP;l98W(UrlZUC80vJ$SX{tKx&sk`3M~;|9XDt zYj1DV=%}e0`yt5nh#nB@uMn5hGPFW0{X*|rRp`lp+{_)X;nz2D`3?4IW^V2mh{TiF zn(SGABPyt;BispLx!AK{yE11+>}tYN35ZXiz`X*h1Sm3om7rjW9n;Vx0!5|b)W--% zAo4wTYZ%-h88e_!jID_j_lQ0w_2^l6`0r8G9TKBEaUnvX+M0 zT8R*2Y&*j|U(wq70_0N`h_Z89&jjr!_B6H}|I>M@T@|nv|7UNust+6m_{r!YLxTRJ73B$Q0GaB^*zmbrhk8eHP zs@7z=-o3P$8x?%?g!ZA<_qj89S3I5$vT3S?w|QM6HE!N=?Lq>x_=}efZbnfwJW_^# z95g)R!_y39YR{xrirej3v7cSio{181o~1oIwXvUx&NH>*^DC*{D&Ex;6Y)E31!V@W z?xhpnntVRkjqUO1QBs8yiRWJ)=W$V^9j@EPg}1~NuQOWm5OPrj5ixkn3ga`+H;Ow=Yiy4t}&@y5)u zjXFqmk2(lXNMU-(pZw5`*$0BbYRk+ku74I5Ob{HMc0KDM$cu)SAv;q53xt>wBgbDL z_riro1}M-Z5W^+p$cbVC@mge@yTLINaBWoSR8U31KC`};>tgrAeDyckQ^l6{mbr@E zXrFAc>(Af5Z+EG4plEIFTkVrGEBez_>b(q1Z#h^tCk4_}*S+nV^a3xtX^gkiR|-mu z?k8`YzX$Ujdb-83qMk>y1Sk^9)+P+X|eeehLBg7VL1Z`z??*2>3 zs$_&jM&`(({Z6i~gCirXmzwrI+^%DO{#NHrjb1+H3(R&E_G``)cf1~vPF3H?h|O$i zz5Ddlmrd_SgI~{->)aEU3h}7+SKab6E*vFl8lp@LhsC;GF29o#FK%f)fG_Lu)2G#) zodkgdai<_;6-CE?A;dY1`{p+GU=qy`!gh*9@Br{8-q2jw1T8m7-6)D10cx2p&O3YO z!7H&r`3L~3*HAByCF?cU*Gwb# zX(bCwm=N3%n*-;Y5$|{7PZL-&dft64KdjN5H99&PmQ%nX4?;s}@H*i-`tk58S-Uwu z&TR*|4NzrtLHl=Ao|wLrq;d+)ac=#?v8|C~>Gl7o1=zavb2djbQ!hd|{D>Ra&+oj` zpQ9-0_$CPbDE7JnQssg7SWHWa00-TdmR<6N4M@UUAd(J~CNvwH)_pZ5x zRB==azy7_@{&Zfi!(n}o^?B(#l7ps`0V32ZPeEA|BtNWTM|2^erimr>`sWUA&Ve53 zW~f65r>=RZ!-{b56o<|hAj3C*wa!ug$&Te z6ZxR7Qw53glZ2j?5U?54*^)wqPAIW49HNlmNfFkHvh_(T+&b4C{q7L;nTUGRNWJUe z0FXB$7S91zeG(FqBY#eLm0k)lCQ>aR5d+$L&mjD!>(!6mrGwZo)DR;c10^1LK8YmL z(F#E#U&Yh}M*?zlyMm}Q+8oT*lvX0wbj90D2W2*h~rR2x5P}EbHyZ|z5 zrH9OpG-1zehNb3yf~-Ns;PkP@)%UOX0960!{M8e{%6~RdWWXT~X9VJM1FT|d>*#># zua(`2k3N9Vha+eLK$kC8fMcf<+N1ruw&T`wY>p#ec}RqvTlF^@28vey9ja&0ecG)2 zIa>k7PJAkwTsb(tpPu-?&j3H+ep>F=^^?TvC1&e_izt{x>I>mE17QudbGi3ICTwYj zc-!0B+ld_`(6@3q*Zr;nEeCGj544Q+bjhMaaykH~XLuELo#R;HEMYyeMHPHjNs<%mL-|~Li-vDuhxC|6rY8L zj*QxPxxaz-0YXuk&||Q$lMO@?+WWHrmUItlzjjYA0IKR|ok0mMg@Eb-t0StOFysIJ z{kuz~v!=!eWt*IWLK1EyaV%pE%p82Ha>@yp^5kE)<=L3chPvR>lPbZ@beH3U2vQLS zuBO80vRFBV!h%a;KRoDo9l(+ju16S$BgV0I9t$zB_M8y6VNqm&UM9YKAAH05f0j?r zDepdbPrD@rjH|Wr>~RuJgAsVg=%e6Z?CiSXsAZ8gOOn>Fs6Eeb{_JDMsuI z98dBlCMGf8o?RqcIZfV3NUyfd_j7V-e@LsJOw%umMieoRdB%3!qktW~3JZmxFu8?e z)GeZ%*hfO}NEQadC|R(k$V9 zQV^+Q`rFki8P#|BBToY1{OWRSa}Nqy+h-9JAh zAS?I19RCw87$`8bCcbu)f-fgUt_A!=xDA;xGL&pX zyYN|lES7DSM6pwJ9halP*KHedSi(*kRa1KzSC7u(z|YfKM2DgO!uUI9YduK3 z1ihK^>gWD%0$)u~C5-c_zq(VME#TbRhFWa1 zIgZ!cWIBn2=0Jo&PDXYCjaT0L{_{hq&%qIvg}yk>LBYY&ii!dAk^d!fd`DO!gp@4j z&xawD3Z@qB@&I!K;R(Px%uly9$Xw|DyLQ&2MJoj5f{xIqfT2X_1-^!2=#?)t?Y6%hPvPk3 zi1Lb|0n3rozs%B$PmIs6a0W0UHi9T*xZ{q>QCyDydQ9B2Iyqf;Xng#(kGa=VA_jyQ z36a`ue_I^$DdZKzF7(Ib$MF;6sONUA4HEWaJUFDZ0=9rJp?_zm(F7Yx5it^I=9rMf z|9}_|^jdi1KqI1fp{A?q=_#SgU=bC_svPV`#^Ge?XdVBEiC440CLZ6}$}z~1q0WX; z>O-##>Ar`}{LKH}_mvV=>6XGQh6UgUcg|3e)b01644G1D`Ld$Iughr9D+`7 zT+2Xo-Zo1{9EAT_kL7y(Pw4Jtlht@(KZAm|5}E^-w@vs;AREABGu)wVbpmo+G!|$> z(nqMMsgZR5ST*?<@e7dV;I3U5{Y>pG`5-S(0ID5ULLrOd34<@O#S|{rD*VXkB@@AP z1CL2eWJN3S1V0R13D*7h76}QY4c<6h?{YXci4GN$%7nlb^~wrVfXjsQH#+3#+1u@v z6cD<%au)K@^2*A=heh#t0JEQp#Qz=Q+mV+|GaU+r_wz=4DgIk`8WGssw!;b{A|i#k zWu?PF_qPzkeMfGU8oPSlhRy^(Km7!s-_?9>T;<>x37W#i&B#nnZZE;tLZpnfkR&ix z;Ht4`#8qYS?cG+?{_%uEqCD;G=zfvd5{>JKn3#yM2W&WM=ec7BaVTo&!N59B^c1{+ z>11GVP)b2zKTH>f$l3cfG&F-pmxbF#BW~xaaL#u^*Qc3nwAZS1IU%l|d?gl-l!A^< z4jY__@)P^u`t=K_KBJup$}x?&)eCzFMGG8uMtN>OLXGKe-MU4fSc-}VFlFo!=&|

    n{eKN2UO6m_hWq&$}MIFhgD}?KeT1f zk+cgTCegd&OF9o}>$CuUK%}taQ~Yp`fU9Q|4AbMjFESPdiChbp2;7-m$V4%~N>4}` zJ#naBVyt^l*Pttls1OuKksye zkiqCafUB9nSxo=ytYh_aMr09aex6tZlzf|Brbm;58t*bBE-z}mYK??eN7Ur?-nLoRE5<)7Im^mw(r> z6SF-9u4l~X0M$EIQ&Uoi#Zs7$h%G4iifk7qG?9MES)hy?GWyj$m54rS#A?b-*FDNYJb)3>cdxHP7K!XZ2mg|uR$I&O0 zegb`fiuNg!xaI5vL8$H#bh}5>C8RXU-TmMT_=!-O_K)H&eu}_SD?nJ7W_GglX&cU5~Am$XvGaq!ViV(L9_q zJm$OTtZu}su>)kZv!e?=k*-mX@FC2fckS3{)G!sHvJJ07}UWj;zqB&Wv6Ng@yP%G)VPV$#74CQzPQkBHIh*@^>e_7iLkEpUU4ZRB$HuDa0m$*jD%TRw~ zpa2|qij&g;k0w4NgV@^v!3{0`i9L0zJU0 z0m#Gdj@mXryl+tTFDU>g{D_8()w7o`iT;=9mrxE@)=f1etk3@Muj&An&7fOhthlT0 znOsf7u?AZ5*w!j|(4+Q@7M2qbTXJ$NYzi&$cHtcL=(-_n^H)ta0!IWG?)r4zbq=tI zSst72m?RqDM8A^}gAsx_G4sFMqx6&&cpRvH3)958uSvY0F1;CgZ3cSXC46&4s>ozB zeH(4S+TwQ~YffQLp8*b~>Ef;Tsi^L|jHM?rZHRW|>5bW!Jplgq2oM}PnU;9u#lW8Q zlvB$38ICfK-&L}SPsoxD%Aou=MK@ddZh5=fcFdM^*GZM~_EG1D?E9Z`rjU|1DXyxX zqC&6x{KX5;7E`>UmD<8>E@^__ghEVWZcy-|0WUqPL{ve7a|3BK0m!55S5A zr+(hoM+E4<43fTi<#9l@a>dj}@j&k8ciCR;>EnqG85ssql=}MvFRXU$b2_(g`M3Lb zrAc`!8*>k4!lL^5*)al*BEXUw2FDv3sVyQ4Ta*@iJ(=H`{fb)tBxkOt?Kw8i^xD`d z`Ps9#jhkX)vQR=`zWhmq3&Dzyox}3xHAY#_3YK<_XWjK+R`o93xDfPvbIt%`-IF7N znBMlwgl@YJWt$PNVB!Aqtw0F~5hJDz%FSH>S&5sDxZ_s-Ml|)(IzKbNtaVXOU$v%8 zt~EF1F=-+2YAvIXh=P$|mb7Ctsqq1ta6gjRs7< zPxM2Dv=8q)Gm_`dj*%sGrO%b9)`Mp4GgsBzcPp2R(srFKPo6Y(vd>JsjKhqzHljsW#H#eNj*Ki zz=hND6kVO0mXrqqW9Z< zWoN<7GlFvCUQoyxkw#wG~(!29=D$3Y-GK2OV2(AI%7cXORu{>u7PZqQ}#aT%*P zT7ebGlI~vkVK8~fy*R0BbGSWD=7xh~4&z~u@0NjIT@;+13-*k7=^YmrkAaMxz`fRk z{#QwB+uIMJCzT0pG2{O%(#;&^FI~%EYVoMjs`|47r=|He#bL&2F>w}S^h`M{>i07oO6p}MkTuZcSY)wU%<(J^5n@!C3ja(xh!*au;mV4 zy_Ixi;jsCX`<6<6|94bTd3xh>&Ah)D!%1AwVW5ULLM6djaKP;EMN?{v@I}_Hxc7{R ze>+w|7TbB=c6dLE18yp^l@tFf#-S+lVM6xiHLMG~W7p5OTDW!dCpjIy^+#&Nwdmz zi71`f461$KuXAtflih#m!Efg7&sCD-y!M|*w=hxdcs=@y-MIv4)=6+QKvzNos;$xK z*@|`~a>$v+xP5Z55VF}n%O#vvQ@v?%aj{{r!*J-=-mt|ft31W3KgUjm2T-Ky6_C`b zZn_9qEgftI`4BH_WXMyqrc6`I zaDDxn(dV+!j4E0kGoE&~(zqU3(m!nQT+>ipY@ty}meF9l@|4co{O=AHD=ur>ovf_f z5wUM5uIh*+#N^EmX5M}ICHzsVxc-)FG)c)4oa_mf>z95_^f-9z`>e$p8Pa1Un&C1K zBRi?Ex3lyQRer&Pj=giceoY+t-QltQL_C9dhovgEV3<4V${^s7M5Sy@0k9L=M5JvA z79NopeF0#KYfR|BQYgukO-iZ$6>MalN1 zqEtG`*X(>h<<7vLpVkjtH9GxlIb3M!joDTgKHhGg8JQF|^K;=%!T#M_-q7yLyjnlf z*5XFD!cA4|6~dOJ@?mDC$E!iCVa=C4yL(h_r-D?~tSQ~sL_?u+KtqyoEwEqr+1@KG ze7)yS9;3GE*Jr2M)0<4>huMt$cgkH6e=beV(0(%_CDnvK_u7@cnu!rB+n||zBu{ggYlsEVW({hzPmLUgsHboGEL2oxPZm_GVD_wInQAWErVRdBR%fMHDZVBs0-xWb=IS4xHe)P`RJCLB5 zAc7@Q$o?`165>NYR#gq5TDNN9X4?@g;-~phzpwSnAN()z_zMc@yH;6z2mD<5~W` zZKA!|zf^W7T{$V~yj35k@IWF?6Zi83lGS%r#_tZb5A=#T0$tofh@Aubv z-uH9f&+|Ozbjp3-zj0mPbt!B?079cL*BM^TP+eANK6Ho@W}U%M`coycFVGMRbg(i6EVphT~=XiH4i35lM- zmiNBC`lc~AW6g84k~XGiq-AB1QA5ZHzY%lsRable`=IaA1K#1Bj9iKfhyQZ8=GQ6p zF|H*2yw^5axkMlSC;0mty~L`8Ln5LoqXBQ2Sv&fbMm1bb-t5lp&%Sk2QRc@@sh-n^ z{duV+18!ue=yu6;ZH7EIdRJnM!5x!rHXbbPMWtCu@&<7yzPC32bl=?AabNg|%2O}diC5+$ zeJn5HEfyKYJVJ%1M~+*_UD;dtQq8`gKA&a7z;LyIp&KjLxyB`rNRF=@??r2?yUmlv zwOl0{PL-Q)*Kh z&NR#2vnou^yDNepIMFtosJc-4+xIDki0_geuHNjD)Gy_r$@IvpqaBc%lkDu3bnZEp z|3C7y+P*2f7#wpgF*M4`zJ6~YJ+3duM@qF)@=ELRzwTF@U)(WInxf&I-LH8|xz6tH zan*nmaw8VS7Yl!8QkHLQY7ty_=ne13ceZSs9=itBkE9@t#T#D0(303T}ylHby>+JCq z&zqK0FJH*BFLLQfSqfMCyJ#qh-S&#^M?HL2lMN}j$& z<6?&+Mwci>vz>i=tlp=!S<(lF>5hH#nwr|YO?21X2{1YqlCe(*Hi57IAE~9ZeYnr$ zW?J%*2kqba9y+caGW_xLt54L3ndzg)U3uG?ndc9k`(ZD%1{1m2C7M0zcJbv>M>Zy8 zn!ij)8`{dTWTWX}$|M#j(m*D*ZTKRRJo?(bVqX9IZ2r}vw?6J~`6u#zjRoT{p|mC@ zwO=%=$qepBn=(5WuUq4i$-Gb(QkBk2pV%Eaav&+W8-2Jf>_Ct0A#(^(6y; zM^R}X+A(ek&JUULbho>BmxW%M6uj^A58QveT8dqG>cW!sG0~KP^zL6tmtDM0hLng^ z6?T8oVd`#g9eQARj$z5%zAR;}){hpW_p&Vg58IW0%(BRu{29=lSjl)5ex$uKj15Oz z_tuo{H=v{2sNc?#C+xBI(Jfj&1Y-k5+yfTM!`9%Vwrldkn)06~PoE~~OzfU*TjQjx zRu(-@8*G~*U4@&wlm4}94h03fmrdgt8vk5vSB@UJykBpjS7rOpc7y6N6+9Sk7YfeF`)n$W3{{PT@XC0@j+CVQUz~0MXBASyHr33;_d|5oWsQ!&pvTXqw`ntq zD&M3n=(p|uE9_9SWE*ib*!|`6ryXA?+dqcHN}Wi(y22-M`m~Je)K8aW*5DMzl3 zI+;QPd%q@T%WJ(R+pi;vybkK?pe_LSyImt>{NWPg!Md3jo7y!v?+zuFPIXgli{933 zmLTKU@UNt0axHww~q0ned50YJq7f9ASVUa3CHCy*vjN za$HN57iTx=FQeZ-lyAT|1UZGg=-?y4Rs|zDsRg#od5oK`#RZ(MIVr(TEis?i!%N@W zo15Je6Uelic}G%g=*8dEn`SrIJgBKIZxnd8#A~mkEctX*pj5dSV@wg3?Lp(;`#J8d z$vLg85t3oXopNMwb7(|HT%Du&;N|qJ@X1NtO^&~xf`{pA*&MgUlt&>iCZq6Wf@Xy)+1JBz6dOD|nAh}mxgm~NNXXl>$Jb2z9r&Zz4 zwZfcC#aNb*xmO3pRRRsB_uBLYS6i51TEgP5qH{YLUo4Khe{H`~xJ|fP`P9nP`(w-3 z(zD7IJF*;l1>@$2Zf*DON-6P$1ZEU12Wf=F#(??n;ODPxF{4#V7#baIn^pgR&T%); z{5$vVjgCpkims-<7)xzne?KPZVb7jis_V{?v|KYZvUkHD6+>&FM}hU0!6*R5978ar*1K7nYVW>N^-u*YRmbw!Bw+ z7I(7ML#e;~4L8|PrfguWkM;iXV0mY zTHAi(4L|wg*(R@7)p+(SSg?sITHfDgCF|xt=D9BO?~F2`Eyzwk25^qW zb+7jLad$@luL)OoXdWIgN_$cZQ252Rnzr!0HF6&CMx zKIl+z>dG^n6@S~_dF_o`!i1h)wqN>MmHDl>(*0&o(Aty}2@tpef^+eRXug60a$qa~ zNx@>hFYiqZL_5t_y5uO(lUxGat@u~+8PIoe*mlaN{WkkWc#piJ`)EgBpdt7rxV9*D zkxyg5F2i?LP~D2Q%;{rJU;FDV!3)i^J1skJwwTxJvCb!Ua6B-uc{S)?JJ2$8-EYH3 zd$zL1{hDj3l5)GKltOE_w+si?rhK%gIhGNxpXjx@^M}4gWq?1`;-d@eIHC$^N2H8D zd45ImK?$hcI}s6nEf$9(_+i)uDOO~)o%cb(?vT3S`*$2EI&B{n7Wtow_O$eR(M7}w zzm{-N-?h)G|A^)R(;p)D-o8zH{*$dRT%MxXD7T$=U(bwUMB-FMxcK%1eyuePcb*?m zOr$99E1Hlt>7R+$Sokm6ha~L3s(Q?=Aiy?RaN-dy-KtO;OG|Mswc5fZdE3eCXJ4!3ySr=&BT!7=KVdE@+<8l8igNdEyY$s(UInyUnwN(ZCN4+$ zDXBG3I_QFY9j4C2ah#Q~UD|SY!+8@)gC99Nue!VcylJPI%)Fg0fKFIYa4n@sd;{w$HNjZVUOnEt)m)CJBK=}wQrTNfsp;W*8jH&HrFGlYRw=RD<13VwF`S(H|hNPPZgWh`%v4W-I-aS&}^&zx`?oa%zxomkC;C( zVvimVBJ(GOg&&vpo))?X1(gGG16+Q8r4M+V6ZUH&9(r5V>^Re9ue~}4|1hd2Q*ALV z*fPGFZaNPAMy{)Ojc-|7#);J;vv0Kf%C>3?0i}?N5$o&+ZE$tacdgr4V$kB`74Kv7 zNliXl!B0+pydrL#Cw_6sNjK+Q=-DhN5XsC1gi4-x!)WmOnrl{37M~C+q)au4`v66( zwa{%)xR33Gf_+5#j)megP3$X*?J`$qKmHI7{yoOmBWGom_IKh~R`#6(y{E#qx6Zjb zE$)wsh;XTqX+US-Qs4EbVxOLKeLmf}p3_hzy?*x&{FYyH_SdhLB-IN-Jpd75VyaAH z$NncX5WNP4iYhY3;A!_NJ^ojZ zO}-uZ<2ZGz*6`yyn>`zfWcD$?RO{_Gd3ITqMa_+GDAaFVyoVJJ&(J!z;?Dbz<>U6` zN1Qc(Y{Gu@f$!N1bShzzoZg#5S62nLctLRiht6Hdtmy-kjH44gFLI*m0TqOpicW-O z;k8T+z74rzkjn_E1lV~p=N@v8g0d|8*uE1HW)}K2SrrMnRPCYs-8PIbKH6Wy1|+{F zW|N13fr=#YGYWUDXqTbgaD#4QW^S(bg7^%WyL<>OAt!)%tIkvcHi8Q_Ryev)B?d#_ z2~}!y+8s%udp8lp5(xAiOxi@)Zi`1?LL|~JkE|bQ=TbALgWBBFN!{s!V3|E1)XRQ)9^pZ*o(7mR?;=9ZLX@j=9XzHOiE zBd_#jkaX;jl0hQTZiN95Kr+t-Z zpgG^e847L!^zc`)T!u&F67c>X4-t)+07T0f*`~nMF?HxD^f7zQ-*LkR05t^!X&45A zY_PWMzjHeE2AP^24!jA{%#6deeH(^)p?%sS>ts=~_S{c*P1enudlESklOfTCjA#ZT zFQ;7$#(DZ~5Y-|wk65~P^75_*yG`7Fpgv(d`va}jD5RMgjjxrUf`pQzzrP<5teu6f zNDQFBd}4npsRPnHF{1T`F1RJ_R9*hjfS)bDv+8k@^Xh!vy|mPC385tzMrV)5+;hx8 zreH3SeMWz1tj(#hQtd00`9ux*H%dN5sypOt76~6f%){=nd5!G~eZ9T6&0?Ss?S@!o zY@gHf8&Sfjh1RhSGTc&nb8-JHUG{;HO|twDO2!=Y_6iR@T+rco^wxudDrns>cxB0E z|JwQ1^69E7g-=Ux8~q|0Py}?{<`0IJaoe?Td%(+fKmQ4_A#4-OY;5KgjgTFKdxRF9 z{h*gex#s}R<&q#Ef4B;h=93Z zc`_`-Ww~+FrV%XLL_J5x@h@R`tYN`~ZP%jMEekrx1a?PLRW@TIs5xRd@9y|CZ4|^%Y`S4?WpY7nkCs zW2;_tbaX(f>#2yj;%E+G3Xuc*UHa|+`Ll0%d`~N?Ws1%=Vl6?vw-?iw+{;0&KtF>d zjMuVt&VWG=EH94kad;v(*;igtzxn30^;k0-Heh&uz69j*SiPxup3;FopQYQypMo}p zo;?Tx%#deN@SwG^bi5kOhJx6Bby!=Sojx0JSMg8G=Bi2)lDD16bZ75?Dj{?GQYoO zMXyhi^yJ6& zCXL4uFUrWs0AL9_!9taI`u}AG5&X_q=X$FH=*lJCHM4X{vIKM?)&-7*M zJ2IUL>Tp~gdgrbN5H)Sm`|h4;Rsc^^_^`iNJJbxcFxXqP)5UI=p<_tH$AQ+bk8}( z1?LW!lb#1Ui6;dib}TI`8=9I5%g7LhJWzhtF4l6grJo3R6QlF$KeoeC5(@!cQELZ? zx{YALEo&cyhchCkYU@F-=Y118Laflp7{dk)*M{q}m4+6u>-Dhh;A*tGgz&^Y9*Z+# zC434qP6<#)LtRG>ZoKUKufKGfhkDkH$hnJU-y&`aOzj4B(qYzf94GyfNJ)^^It#eqUUTP3-G!vNA1@RxB5x_CaQxuJn%_~^~E4f=e@ zJT&YeI>+oA{@uHqvaODvzrij;B=U1s7zkhvAGVR@2psz3a|gR2Yg@NTU&|Ar?Tcc8ixqrMD&Wr`CVEMf|H-s}Z}6+bY~h0)ov53k zuA#95X-^pHl%$nL^y_d&sztyhYKG|^cout@7$K3y^(BC}2VE(u9Vj^jS=K8lDUn}~ zX--@5sc_We2*jOdf)r-?pVX!Q>rgc!o``u1!fqYkUG@&jMd6(1`8tAQBO^5sGRYP# zNAjyf^A8V`cT0z1Hh%2ET*mwPB0Xk$oy9KCSiV7Uj8kI^*}7M%X`%Zg^Iu3iO#!;o zGdjK~3SeSzdV0XJAQanj`15C#PGx zbb5Iypg@IQ4+D3@Rgw;6>B2%5)MCMpVgbe%&>Q=mzp~($KxT`iC!cLsJ^o)V3sF<$ zu?}g?6BQUa7>FaV0PzrWKww?sHHmTv`v5hKOS-pu1j#O!t4RGlO5$yh7e%z{Y^8`X zK`hL(kFUPAWpGJ-&8ZTPIZkp^;3MqInsa!1Qm}M1%D@eEK855aqizro6>ZG^E2*$z zWMqV(w&MPCP#6-~HVVwXzCQQgK*@;Z;|!)mh0FicucAx7^zObdc8sua1C~tnj$_A; z6>QlfOxuU6`!*7ppa#dwXrI?II|GsY`p7q?e;1z2{?&%ax>0Nh8p))V8}Lhb9m+W= zh#wD@oij~V)~BOJH7lei-u~V{%Ya!*5OQ^Q+a(sfGj|N)JB7phzMQKVLKq6JCJjzb zHbR*Wb4llph284R7}`qmbEA7z&hJAyMv(0-o(6|#*KgEFbD5G(D%*M)KK^!RuHCM1 z{0(99+o5EwQ+UYJC*+S{Ta?U4KX^dq7lKc>a{kS#XLtzGs`+B9nD0;pk;?=nR<>>cdz`T_sB>otQlnx8{4>? zeEtBrXb=d<1O=VN)U`1O&Y$;9M4d$T?AZwGA@&(2p1V59^a)5x-raoOgN)FuGZ}*H z@!QYKcVS+6@`NAb*+QY!f`Ui!Z_pwdWXJh7z0+sUS{j}B0Xw>B?TwA3I78q;m$gvK z8Gvdo>)w>d0c;_&4dJ_b2v5lAk+tUzjorX5fHoUP1zb50#Q1yR{lEx^qQvd$Rd^Oq z7@|qR_6-qf0OjoX{gXPGJpvV4R)G%ekub^Z`%=0&n zM))61hSuN_{@2PhES7zek9YpB5?tU{|N7nC_+(YsNrTe{C{$Y}=5Zo)_8x>+10qQ4 z_JJj_Bmk(6^?wkJBZhi%ZN^nAFlv6n@0%#HXI?J>bH;aOI0)uawL5pDoE+FR@^t@y5}+*Sb?2GJ4|b zfL_-W6(-Rz!vKxFa`Ep%VR`UBLV(E!YHkS$iDw@X@JEG0ptwvFMF18RMlxAA{zg(8 z;VocboYqR%{2iHv2-f~)d%33tlf>#_gXWzN522!glZXt~ z!M&mfo8|7xMKaN24K&FwL#6xGAdXf3Dg%Qnn#$aDy~OS6xm4IVoq|dlYTU!{;h+y- zkd1%8arEa6+>a43FgBYH*{l8_s^4`=+g(1r-Uz)Z+MeccL@pwD?!KJG_`YeRn2H4gIMA1z*Ciog`dQch_`u%f1UTrN>jgQ zy|m8s${O$ZZ%@YiLt5n7MOkk1yw1q9PAX9~IhJS>5h*qOW#r|Ev1UZm)so`N-xa2teshi8UU+c# z0iQpUQnPl8{aACNW>%uM5Gq5vY*{f85qe~p9Cmkqrc;MA8ZZ^qEtS1#KZ*j3*&&Kv z4c9_JkIW*1jslUhYbT$vSeq|`B_~&roKjfGvQzUx?kR1I4TNk3O@AqrsXX_N{$i*% zKj$%f1ZD-A)xH#X4)H;FVWhqq0{+f;W%=(|Pf1Q&@gvxCk>$b*?U-CtLP9vkL=k|4 z3Xg538I^D>WXt%nzY-6;ayYzc?!0#Q@Y77W{>F5;I9Y1m zm+eJrhuLMt;R3T5h}VAB_$s{t4v8 z&hDYeuYO@IRf9kfbf#BY^aL@V2)ofZa!CQ^1>4r^Qvg`mrELvEq)k0y(SN6Obe7sD z)hxx_79eSx(pOZ-{kG*H5w8=I5hb>=5~RT}V9+lzLXSWjpx9>LXL+}67Q&)Ki6^-+ zi&(B0d91JmZAQqk1QE!p23fk&v56=mX%T(?FNV=)*yB46aW$DbGC8q;|q)~EeWB%Y*L9IXUT2NgM5 zjWZQhrtCDR$C!c-BfF5{@`gjxRO@*Bnf|oVOYPlT&}zk{;6a=U#6Dp;Uw;5V3G(3p z;f~MA*s|4#lX_|)u_8kjQ^XKCKgGi8*oZ|wGnN$Y;?9M3%i!$QT-bugoMh2P#7>`- zorGMu9`h5qBi~Rc@Cpz+ja%5)-Kbb$2~tH@(bnXS2Zqt7RMcLi!2|+Ta{gfUL7#1# zg#s>fEUDdOYHUjPhb7mrZyIXP7>myKWqF+scEm9Uv3a0Y+F>Q7)u@FBM@Ft=!t~rk z2O~f~ymLGyZn7YiR-f0Y`>AMxl&3zgOD^C1=X&+VtsgMJL?<;TCkVrzv6ayrF|o2z zU%7Gxg#kDITv$~7!2+OzR6fTU|K-D8yr}BEfyOg%?+hJ8`ff`5x(ypf-Oo!R4^SDW z+3tHH^fjbHQag661`z4c%n#RgV0iZM9m%y7Z;3J+`ts#cWD$TTvq)#P-*6_tj!FZ> zQKUWFsOPJAbT+qy1T#r)D0{k$F!wqDleLc8q7X4Bx=#1Q@u&iGj;jZ3j_e8^`(YPc zCAsgH7vi)w!o&%w^?E>fpRz7J6vg0CDtx(4`0xi3nM@pkcPP2J?SG=R3ke$oL$__; zT1)Zm-pz>3Depd)<*m;8|5|_-a7wL`tY~T*cY6KyZ8e(d3wioDvO?h1Ym25q^cz#fyCUQAbo%XyB)Vwlf$Sbw9H+v{b91csG3Jv<^NKX|AN4oGU?9 z3P;~>RHEfssS&4#njX$K*?m_<04@SFE_E1P&mQQDTE-UBE{LAIgi6toQ8rEcCf?-6 zgB)tU8QWp69{bwKp@#jXM(epc+?C>_HiS--&nZ#sHa607qhD_UaldA>q zkyI`|PuI8Nb$-0ODHQ9%FhCi=fzMM$gU!3okzgwOxv^6?$?-EEz@LRbV{PTi@-<=( zY}h$Qg4=;-xVX>UmY38sWd3jpgd1L|AAVmFUBeLMbP;D=7^L1jPM`vG0 z4BeZ;ta~_~%2Z%L)(}X|M!>=Eiwej^#WA$@Y*umWgbPiLIMez7w@-Ietv{S^dI;m* zbySck$KU0Ngb*0fGz-{4_jsj(9)_`n;?Ob1FEJcFqxVvr9!9%2HtTGxt!q)4j}``( znPY&5A8>_*L+dO!nn|~b!o{v0KM(Qdk#UAZ4#}q-2XLwOiF#zN=^N%s<;(Z*wFY=@ z+djgBdPUt(hQSKgKvHfl6HJVPf`W>8@Q|ogA`PTsdh&z{?;R<9%IfODIwsjMP`hHJ z!yTOZfTdYjSs~tkm1yvHmy9YckH6t{V|HZ1xw<1>c{};AXcAQL#XedVZFoF!Akg>% zhP}f^l!R^Z&xyoyhTQJ({P+PTX2l<@8B?kybdOBIkga$RPk+2+Mz-*WiTTBjs^tKT zLU&Gk$%MQG67IVPW?XUl>!?McoF^@nN05s$&UKg$>#|DvEp-wN&!1~O@A?5zbzIL;fTxk^}g7( z%AM8V-dZ|4Z@hhbG%oYfG5VTEj~}nb)~ZF}^NV4vVr$S30Bb`P3;mAWNDsb`&E8pH!P_y*jh@UZ@p(G1;=S^F05WTp zp!etikujl3@*R|$^fKCz7eaxlt@NTu1ICVSV&7vzMP?39Eut`)g%f8GsWo4QtD@rK z41!GT?qW|5lY<;J7*dND8B#QiJSW75qU%h2Rg!$Ma&X9e*dg;p?mV`)zbZ}@B>9`B zbZiVhTnb_ZCx|uEy~#cFYXXgPFEwp@J?e1a&rHp8e !+LO~7fCp}9&G_7->gv8J zDJdH5?kN6k@)^drMw!iGbl(Notu@cj^DxnpK~}~v|6}>%Um59NE>p)~N1JWtG2*{tn!2tVT z?&#Bxs)Nx#7eGa(VHq(1ZNAy4&y<1fXeNk5Kfz7X%WbB6;he|Zg!Ux-PE>fVx`p2i=lKo0Pg$rq`o1xUGwwfnxikfYlLI)fxa50#;o;FgI;=uSD78 z6wH6G&Lppk=>|&qYUI?IikfiZS|!_xm^SPpPsEdX<@iLeb?zc~jR~n3(w!5P!Vs3ydZBwqNiIq$!g{mXH{cAi z%Bcv1Pr16Mhf}fDY8)WN>~P3#69mNEZWz^Vg0Yx>s%piH3?VLsBXSk6x{cAh&#M66 zUDzM58AN_}IMd1as=+T`I;L`ZS}-1#7XO4?z8*nJH)>L~h18O@Dr>m?H^+~kw~Biz zi#@C+jjM~$voO*XFN$}aL+^tirNLJPa>9YeTOXo8_w0b1>lPAkyG*mNZVu&ixCZC+ z+#_RO$Z0)OyXnLrcK3+fR^jF4Wt5S8(cBHMU%x<`4XmUmalY0Blb+A|7Zyqq$1ys; z{cw*0`G6Jyi;rscD*dPcRJ__kbpT^S&sDgi`KoDc-Gupq)u=ba364L3z;WaL=T}kt z)FXw3K1(+QE*fK?f~1yI7upWV`deJjRw|S zsXT=G>jJ>q8#iyRrU0}e{#rap$*(eCg5o%<2|`QpLC6G|8l{iH_joTPjYKLTAtojm zI5*;@HUjn`!=|u{1928nmGnB$kvLc2c4VcYPJ@jK1#~rue?Xi7VZL-HlAk^`foERV zbK71Ci5UzKzA!WRl4N;WFU#lN!@=xpc7|AeJ%SvR8!Kqn$O19)&&|r>X_IAODplsiG9h)$*ITs%LQIW(TIfB@$@XX znKeFbQl0H+;K@~r#!Mh`9q{BJHU4T0IlqBjM}`LC)5EG0cv2ALCKcrZfH<_ll9 zq39gyI6|0_)HR{R3g8N4ZkO9+QHMAjtDIhIt!tW^7|C28oFgBS-5b03hK?DAzr3J` zR)3tA#a@Ovm`Wlhv!*GtkhJCJQYt*d4Pi??f-%NwJ5n| z5CvpLgxhfNP8`n%x%v2#jLs)jV8i1qT#f3bv&?blz!1~09lj9gL|}L1l`k>`F$E!O zWkS2^h`XyA)_0+=F}oUn1REPHr*ly zV&>w#dLV4*xyDv>VvGl7DA?;%F~?~_>imFe4dRFS)-1j;UUTiEG}m~2kz(gkgl^%U z!ijukRHdCqf&rFOoY>y>Y0 zjJ*@5_4%)a(YOl7x^;0o@}vR@#8O-$n+J%9F!xdh(=gEi-Wv;()R-jT!-?9 zY-7^@p{Az;-dB&|W)upN#r8pRIu&uEh}O$N0XY@BhML zNc2g#{^PqfP3f>kuT=d-iuYev489EQ(5D?bZDS*f2%|}dJw8mA;Jpjilu!8I)8ZbE zk9{%cO1=|uN2eTX-a~&K@|en+!3_=hkbN#fPGIwMg}_$i%1b+&PbY&NMP_Os^Mw&7 zJcGQehsOaxkG?SP;roD?KfUn8LS`KPlk;0b4-Xao4W1TM~{tyo|H^f%kPTCRaK812lY2)Vk!cWLrCOM zK?=q;To4R4J8gEuEudrqc%bC( zBWEh^X=o#UF$6G`hd?KUi=K``i$P~VGdiaBrT$kSUdI;Za_#j6_=Pt459AtB26AZp zQKX=X)6_ZC5wkx2XE$bm*Sv3w`h2qtxNg@|j1{}ogmWb1!?=?hIZvT^N8(1!)E7XM zwHTGOU2IPZE|6-v-KC}`3>F+mXYoEvaDnNral(%&?mjoh)-xKmRR*KGzFb6gP&$!a zzI91%XLJMMUJT0|sFA?09)0wkQ3DiDT&u@b5W92d{{7eF(;ik+Q%mW1^l2+lkPm^| zg3fatU)`M6x@p=`fTjM49CwHCyCNeyzFH)8yo#FuAEmwT7Erknw^9 zux;qkBQ#2iNW4B6YRx5`gZ=o`)ugcGsJD5YNg%Ax(CHtXr+_UV{=&F`_5wM9KL8oJ>|hRNVq$6@cNYAw ztqeNMdkD3S%XEJuSLD%TuwuP;4;hTLWo(8%hKZehjAi>b!(A~>Hg&xy$ZVed#C-cl zZI(9A1nfnSID*a^jzB7+Y-|WRo_O*G>Tt({-hi#31Vi@_+St^_%F4p>0y%SWpVm`A z_F7n5BSC=4^_{iUb+a=>Lx7l(I;<<}@5bXQLb+yrcF$T0LRzYkOX9Y&r1oXs&MT_7*nO}5_}u037eFP^r2`YZaE1+0 zB`<&qP{(Ut`r+t&gml5k^2GIGTXb(8QuIP{~)6Lhf5lW>! zh@I8D2lyL04xEyxl6w9qp9dL>2pc9AmQO6KPJLS%@^K#$E!Qjx=}xCfLN^niX04%g z1R&~537!x{{^FLu_h>i}FUDk=Fjc6b3I zK(?$83C!e>q$L<7uFtlw7+oNWZIkJ~1aAD>K-G3|!lGUs92^|Ec0)=eNEPeX@1$Vi z)jvv!Ojy6$P;+2Db%j_@tRgp4=jd-`+GcIfOs%xDb2s?I+MZ8J2nf)idd8uujHh~{ zmDV zZYRxl=|hCOU}S{AiHGmzeN5PCFs7c!rutk5YzlrnD=Q;td#TenGx-I_{Oa#~`6TR% zawQZKP!a(mOP#-lg~voYwsgsrj8G!)0D$%@^6%d(oxXvnMRM_ad3jM{V^dDx>Oy%` zOuLyv((%u`KAXd+8x$jm;k!;=KG4J$&%yAgWjd z3ax_j zhaVq5KNaQ-1sIA2oy`hVP1-UIQTOlE#(vW&6*2Y>>7!iMn{1G1J;0sc5cMyCb zte5T7MaRa~Qto<%qOsXauJyftzYH_Jf%jhM)*mQ%cBi}V;Ne+?_>~gN`!;#{B;2aY zW7r~mo4hz$4AM9}KmK>(J?nWK80gyZ<2-2GFKE`WS|XFV)uj0 zy$M$IIl%Kp)Ii@9{*XTrY!vASJz90DQEOmw2i9Ui`a6QvL2uJ`xWk<6cG6cu6LVf# zy=&vj^vd6Zq~Rj?7NlS11G{+2{{hJzXyD+QS3Pnhpv|6YSU&2ns=YPEI?FonKF|1vC=ih&GauzyOPu<|k%Jy9gB=0UTh) z3BcN(uriK!bQ#6Fuza*l4) znUH?(>mq80Ae5yh=+=7IzOuS38OyePZr+`AG-pF&(2(LZB$q?bV`S#KqG6gf2S5|!X01Ss>SI6Jmbo{jfNS@FQqJ9^0EnG!Vx+%JG-iR zPC+m6V2U>edM~52Pir1zRIHQpU2GtoK5QF~!Zfx6X5O~-tBU6Jh_fKQM_Rh-`$Y2n3Wq$)j^Y+;Y*wAwMSB5vc!(c*Yl;DK}dR+?6R zHF=X|-ur_L8Ub?mK}_8(sf9L6mktOBZW#g?;FTQAg^`#-V&F;a5<;vMQ(Do;K_*hX z^wJUpB*FhtG23BwIcC&eKxgEJDc?vZWq@o0*bZWSR+BFeGKKtfXtYaGYvW{{g|HN$ z9Lx$^OHG|vT+D_fv|5P6%Pjq^pw{3K5_&5%t_Lm!zosNsWM9m2edwb|Z$my5BB7_6 z7nmtH?`NUkzqvT0tkE+1tLGWik^V~ z+8xCCcQAsYRs|K|Dgx$2B`L4*=ITIWJLL8Q@p&a?-}pdg6Y0Egy&k^KD+|(;Pfo7K zwv`1AqCAK@kG?Cr4W;ieWQ8On4ATn##Ci3jY}f<6(3EluD)(=?SAV;rv)hG@wmiME z%;;WGS@#zYs^sJ(iE#9txc3eEpcMMYXW^7W`vO!G!K!QUHa`_F9z-=0(T&iG0Rq7I_5YLT|ix9Q&druno1ifpkX<0g}=R6 zwetHQs8J++KdY(AfU42&xIhhlaKrQjW}bLwa6;wuQ9RO5+bp5~D5X<0$z#Xu00#hd z^G6Pf#k1FBLm(3r>J&xZJBnh_NvL*k%BX_uhe!s85jsntI$%F<G*eEs&+IK79Q}l;8^u9`| z%U%;GM8R>+ZHRhoeo1#{Xje5>714-hm28V_Cr~S?Nub&DQ3W&}7+!_SE!S<4Ooq za5nP_*yfIjJV5yr67Y^~pck+ev8?hghyf&RF-Vp+6RyZNR0!Tj_fMg8L{3kG)W+d( zv8_W;PL3117mbnCybMCvR~G9JG6D4cm)-6;51fKbYr^3|FbUC!Xrq{uf=+M7Z`S60 zwA_aSa*UTP{4noEtU`a>CywRvVuqzJbUyAo{~BT8gbF4cBH?mSvH|48K(cMvAov>m z%_wZp*mUZS%`UEn{VP>fXrrRSOj-vF~S2Y$TUo0^s7td@zDzt%_hw`e6s zj*ycMMOEO0ZJP&9*L5>UEd?%g!Bt(51%iD> z6soB?8Aq<3*(3D!7yzZgiHQ(g7gI$_xC60}NTq;#9x*^+ATSV)%>p5f?q<_x1yBc3 zd;o7BP5wIPK4%-jq;#W!4kH4cor~Jmj-u`4=H-2?yuFtEt2-aMRY&m@6MT}u>x3S# zQE1tB@ZbPX+kvW;<#LUVi)YvXgn|wENM9Dy#O)muNQ-!b#H$_)&B! z{MM~nL`asM3j#JmWSe$~DGI9H$+Ets;L-_lGwlC@ZvJ1hhOlG(3io{oBx2gKWgT#~ zjQYvmvP~pUl`@FiWy(&;9k-UWoBk-tvVQ? zdh5lbmZUx3!sMDSHFMA12=@K55}P|=lxi<)Zvz%OKGs1)79%Z3Kz|YT0Me=(C||h+ z1!=J(m}sfU5#^-KVwo;{$9+lMVQ&-9@3#s2uYG6wIx*cS{p|m>0G2H!SI)yPvf9GE zDjB=N(C}SWPR9hQ8|pygL0FI{cN@Mnl|ZCEMKL7gH&W7>LDrv)S zDxGxO|Hsdd+tu;?;Qmw0C56)=qol+c~C((a%)ZOOHRB8U2VS- zk7G4*-?-5ZfHTnuunquwl%a4GxE=&B@#&Rl3kh(ou!J4%B;cF*)O2ivxCW>wknJ-=4D|vC3s2;m8Ju=W7#LYz)rDK`)cNyGI@>V{ z@WM+!YTd|!oShi_1BNH0Ef1TJ1*9Bk4X2DISi9UHp#{4Y3_%kIxxOGhEd71m&u<2l zNz#b~1)xdqH0oAS%&4hpX*UGS30z}nJHL1Q_HH~W{sR4`z3%w8bSSuRP>~^(1Bs>d zfyPXnoOE~8{J(ws#uiyhy?WKcxy(Uug*a!8<$yS z*1$%%Fvz1^DsHl4SCRDOd*UcZdO4r|6nM$c9ITuTyS00B^+ZWS~><$*JW!y$s)%Nkp2a{&dR)GI6aUUqQ>FM^E zLfMi@GYoYH>ZI86c=R^7W+(b9-DY{COXCzgWpSs1z3VagFpjU4#e5leyMB>nn}&z8 z2J3mPG!})G9)b0e^Cf6;fqg!o%4I`2jxT)ySTGstIraR9Ciqrjh5?pS?Xzl)9efu< zK#8SU*HZ4^Qn~vH0w}{?jf$!C2i!6p$N8C^e;?gky&KzT{@T%R;l}I$Y+;MtZdt^E zyBQEsuas_p(kc+Tcwpc+_~936sGz5$%}gG5KFiNs)7QEd_Me_KRB!>f7kF_tq7ldE z0>Xmq-c>c?_-=i&GCP@QaeL84nVr(oGAVbqDP|@BXdO{Dx>xk42U}gZ@Tjrm0s1aR zz|^-jI-cJ_-X+m>Aw=1rd}pvGP-mbbxu;FNF$Kh?L$~+yLkGk_)}a{Q8hgJ7tp>Wa zw0!^GX82F9|0HUMkWeK=_Sg5a^Hw zWqT$5By>G?^Ivu19)=jRf5UBxsUMFTJ8T;W)eM~^6om(Ve=8vDWu3{YhWspny4aFn zcj)#+UZL(cl0MY26$C6$YFbbusP>3qKFG+kV`83kmIa_f`<2u&8J#kWS%TaUnw!V&!l$;fFv-O${M>}*b!t%6^dsdnf~CpkkYRV zzY4hZ-oXN_QN!nM8}%e4hMvwH%1J#uck9;m4>fD`vP}m;t@Tnr#jgNlu?^7M477&m zlu)OVuYzx%1oc(Z?yhVU#F&1;eebCKukU6VbbsP)I+T7(5QOjvfJC$<;B z_eY&S7)pY40_E=!^MS^upcU?FniKN#EJO$^a=!9G2E%yj2fx*eLH>#Y(dQTT zNP75|J_ZPgKsmJPaU1e@Z2*Ts7odu-*ir0nb_U!xR!PRfb959$?1A=PFW6ctu51-k zhgL>g@5Q(dNp|{4TfGl$#8Xwn4TDhT)TZFWw~r=sos0X|1RI8F3mri_Ni;rObQ?At zLHK4HtGEG5edrjmFRGzmEmfHfdkh6Nb{plz<0Byy3Mu{2OT%VN2E{eIQMl10pbsa5 zN@D9yvnSv{tc+79O z5gdHT-2Ah1f)##qBy1CLA3s|`%Z=d&TMr8eoLiW$IsQgw*bg-U+QA)Pw%#&3Gv@Rx z?&yOpp|9d9-I}|GE*qUf{5*x=>%fkS$Ge@j+$VMQmVK5iU_xx1Gl4owaRzwtLAV7h zqn-pCJ5(0``8}}m3XGwf`a2^l3=}~u=dIKHpDBY7h&`#@%42jK(>USC$OBQ>Fv%^IM2HCk`o{BY7BkHK)%{P5KCA@*045!sgSRkt z35ZgL{mjo=ae5SCkb14bphN*MF-yVyvC$cJK4 z0vab;cf~AS)BwsjLb}bjG~aESF*+UUB-@* zIV^G)ImUmeV=3a;slcS!mzYUx!D>ULef3tlGZr~m;95K#84yv48SWTtVUPa&0)$5B zyhr7>D&2?&QvrEdk7bV)?ijtlgMwJT0a@CYtg^Qpt(A5cXj^QZ%CV$iE* zHef6ih7*R&9Xh(YWIzKHYo7vffWYDb;K{Z$S%>$I6CV2C8*#dZyBRqdacy}dO<`BY z=jAYC_8W(J56rw+qr2h#n??i3sbFj*bERkllt63ycfJl)=+)EJ1(I$cKZVL45EWpu z0#`TPw;?wn?W9n2%*+_%7ec|=P$>JxcQPFD4p-M}h8UHic<9h7z|7y=#r`4o7h>KI<6FGAE0`ug{kO{|}$r}^q84Vl;p;0{o1U5FGYW>#(aGri!; zbZH-kb4^t*qPzL#^`8)Zyd4*2CXKKfKQq8~Xw`%3Q)M+F)Wj4WAX3YR43x4j{`x*j zDso)Zm)8sPh$)G%mAF3#R*o_gW#UlSJ=j-xd8{ z8HN^&kUC4mfS;t488TqaplFn}SvjDJn0YSPve(BP4=m|-r$g>Y1db`k4I4J}BEIUk z7c|`X-9pN3#MvR0=IXzuX=D)c?5kz!))}6h3T#mjdIwaM3`rRTj*;kB)3IA{)S_D6 zs^HPd^W_O)XK&kL!LGyUr&~`7MBwmVtMk|RDpDZegtLqlO$vdg78%|QL0L=CNND#t zl@f2`$0@z>dGfwAhHnf_PTDwsLnQ+TL$Rv9jnKQd4sS!0K@d?WC?Ov5@njRR{KS_d zHwu7Wt)dwII$u}7cal_zY9%{R()?MppK^h|f}Tb>dVF8UIq3I@oULKh4wEY(EwYDy zv9cz=43bn-&s!v7=rP``IGcI68Yc+_kkiDoaN{#1t$?u}qb*Xn}g z$$iIFPRA`spB7}1_Bif1UG~}LC{{T!rkp$Xu;E0QcA7Q>5B^GtgJLsGCRc!^0c!e! z<9R=TC&1g}Y=`xud)_clzc(#}^WS~+VUjF-)V3#4r4baL2QK&e)Wte+dOe+J)I4yi zQeMEg$WYLA3;);{{ukY*J8JyW^S&i~%U(MiK-%BmXT^4y_f&|ePGQ|mruvN`b+_L> z@d&bS<#5)x=Xi+c&`IfZgWf9=v87arhGO-(8*5IUUg=Pz(MX~hc@yyo{yKb!fj zY?0Igt@Dxo0!ib6>aQk5JRAF@J$#I|gsK35!6^a1v20-zv%L{^+U=v|?5%SWOhaQx?}Q^*9eZ8@!Ppe5G@Ptza~8-Sgu13orX;wpxaAV6TGP^VRNO zny`<%cPsOUZO@MP$3)nEaINM6SlLT84L2n2J=p^^|DDz@C@NvvE9=3(i9@z(y#H|a z*J*C7H4Y--0 zLut0O6vpW_l~_?RjBN}n%h2R#X!oDrJ+exotf&y7$Vg>8HrdHaDp|>U$82~y**~{~ znA!nRC&*3+#0}3wMpPVMn43Ej_)ljtpv)UefKe&jbJ!n+0VTXrPf$N+(>?Eopw_Nf z|1fS<_Z$FJtwHM8zs7kc8+q96!dlAiLh+h?ORi)IHFhQk7`MfBQ%Np- zmG(k0`SOt4PJgy<(r43urHBoaAkL+}@#==oyOOyO7k`?dt{pG;KD`=}6;{m3*|)qH z8Quiq`Ig~cM44~O2(n01tRy%R97l#r?ff-6JNoJ8+ECFm16XBTzH>B_F(A3Wv1Yx% z>!`wA)k92NZuby%C$r12lnG~)1M`u6dFV8ScJ1tydA(P)E$Jr4M2-oLx*Xl`Y+O`a z+%B*EF`E}=TL^d#WYrmC<4|I&mhiZSQ2h8Q_5UuvGTO+s%k!xcn0QZfRM8ByX@F;( ziZg5}7{O0EFM9QE$VIMubf73OtjES^G<@mFo?qU%l~@e))}r5oVZHNSjDZugg`}_0 zin>42?BDp`ix~>=_s5f|9SgGsQUgNgf9DMQvCx_a7`A2yXDPPnlqJZo#BQ=i>*&6h zIe2}xET^(#%hNNR3{Mnq-~PPude9(y+O3uqFmt#AjW}nt04B_#8N?HjzWzH`tEixd z@xRjXDuO@>igpiKTmo!oKu!96zbLZLf)#3vJYAVzhHHFZOY${s(feg~SFXW+;u=|= zl;mi3ktl&M6{vA*Q~A%CnJUbXVXJ89 zYWccw)Li#42CTcA^p9_<`FWxWx`-G~==Rdmvz$kN{2Jc(IH>xvubR-U%EY5z2Bc}z z@1}J2L}D-rIY^f2<2~@EcRBa3b1CIPGQ!xCVo-{A@8{x?RRST&SNu5aoEntP z)M*vlgFv^p0mK|mE-{S~3aCO)%O00Vxd&SuZkGI(o+?6t{j_M~{?`3+$Lsb*>C<8u zb$a+zn+BEIGtBahbU?WP1aTuL=UWevXK|z51-l?2Vk8kgKRL|C036)N|KFnqYy$#p zUm&w((N^*%JJ5Ym{UK7r zU9KaP0#i4=p5uECE4672xci;h{P75g2|{us!j42#R)Q0;17rN88A9ux(Ju3A`M)mz zEN0|0=^%IYR7^iF^Xok)4&Dm6{d~8@_CgJ2eAX#<$P~UamXd3l+AS)deJ;7*Zt4ClB38Wg@2L6(Ac)Wt7V3|DAXb*(7wY7H;A| zmH?BMaLn`yH5R%1>%05+Zbo0h` zAf1XKO!xuRWQOsZ`FY&5-z{=k>5{85#vOO-*8%AvUds0;ZYW-l25_Iy%4=rg@V8n4c1t zp-WFwQ!^v#3bF+;90M5_>lrtDWJ{e!BMjxijQ3GDAf++}G?wtsBA|Z~Vca&Szkhgi zv^%?geEu3#RGZK?krdb7K>3FcA9Tcq2|*?}h`39Nb)&`r41kG zw|)9pRogFh@B2OBr{phKB`6a!B}-4*X}MEG#D;SEl)CnlS0=CbLWJMP1Q%xz&4OqZ zNd!v*@n-CB+6qj9Jleuw)aHq?3aYjCb7JqVU8(KwkKhT>^LmnSFy)T5yTR&5m(25i z$OR+(YnOr9wJ!K^qgLVbv%Q+1GSku^r)2ObFH7Mgt|*VYh@gcxK!Km~X{)!(G12b9bhZTW}g-qX%;$1!K9xrk{j z!u4VeGBERi4zyE?=bgm?NY(3cFpa=gA~Wh-c!q*3D^LX^1|REX5ZaJqxQk;^B3CN_P#=N5lIXo;}`lZO?y1mgK1_a=Cf7L=>yY! zz4=T03+FD|HqDi|CypUCCC^7TJ=VUY6H_?0$dbto#}F`x?(P8+gO$A+0Mf5kzrR zuGRJ;mhUIJL4R|CP%CY3%CUKiOn zl^kPyZ9QR&V7PZHW^Kb(mz!5#qkD4L*C=>f@ERSxKu6N>?f^`v=hyc1^tgZbtG&U_ z5_DfX_0Ha~d-o>4h2Tbi^3xTE0v zH+->g>mC{1Pz9NzdoWfexzRJx_VVSb#DCq11CRioW~W7wyi);#N0gvFa?IlOPp02) z^t`ShlK*njIQSQLAe18sEuTM!LgSWft;rh}RK&Ddnc-&UThv0vj+24xLXqmZA3XSC zK8{Mx#~VDi=5p}9vLS?0H9jx+iM?lX=VVER^gGX-kCOHmPo4NY9UB)ni@C5t)Jkfp zZNFh<;576;s!Y^9_Xv;l!t&3V!-q^A3Wu89Pn~V4^u!bPQiiy-^??q_sl5L**)2u~ zIpvx0vxB7+8y~+)_j=9ecZ!ORo1gjhYvI$xZ?FEEZ|jbqI8mK1o*?_P&tYE>mH_8* zPPi{Q?DLzrg}m}LXJsts>#QeRSUmw^egpiCS1tHikyPK57}PcdkD8{Yj_)OsF8J(f z{SYfnPEP**)pjatTt-GlLSDY&PKKa=_@(BL%MtUJ5{7Rcs8fDUq2UbNE!!Po$|*7N zhCch#)2PA2ujIMzB^Q?$r$pI5vZK3Kef&dXBh_2-N7`ko62t7|EgP1)N1mSfwXjg* zP%t>O_2Qc$v6v^L^XK}{o|Md*A4Le^zEO$xlb_-1RbHlAkPahdEM)Q>cO6n`@BjQ=CW7MwarTq>BZwF@4kDq~)i>roj_4f%V5&Dhw@27O= z@JPG7E_-aKcQemwYnYI_fsE9@KolWo7kOCf%hEF|Dk?nTO0_rZHk)#SRxHK-_wYTn zt{(dEe9;LW3ynU3?WYF6&qg}QJocRX{jRM3cG1Uw8ON616kCS`#$3F%t=OSIKf8SO ztHLt#jn~QhXVz6t(<`V)_@7c(qVZXHdQ?S-r#jetm($=lcX@?)em#bP+y;(92L9*z z$n^9H5%yamAvl$AZ{ggwt@{1@5RR53@!GC#Zcm;*rPfZ}9B9hV8)j~2$8_-E!JP)l zl9G~NagLp2;)zi|7`S;X+wLsgJazPUH7k@JBoZ7!YOoKylQz3Nt1x53c6!z=MloF` z(y9j@^?jV(O;|9UUBpF|iYwfEg(oOFIyzZH2FI@1moc&K!zPb#q4g=&HN!uvhg>H5{tlm4});vaM#vNt`*Ue{-%Di|(nmHzn> zQ^SLaw!-!hIK7E2tZ1Y}lsJ#mH9eN`d-Yl2MRD=qkF21N#@4)kO+%xk2!$Wy zDH4*B{t)bA1C~e#@i6(>d?}Pq<}|V)BGn&NH_`%pm7!4y%1d zg=!}bny0ucb9wRlj~oN^0RyL#B9}yt6nz|5i$hu%wif*|lq2haEq^xK)H+ZfzoRY^>(P z2c`p$?z&wM9c=082{DnlZE;|ITw@XU#f4WN@gD%tH^^+;k0%D6_{G#U^$k+o*XZd7 z9QD5(sBUo+IrNzKo`L5?zMUR=PS!sQCmf8oad{2mfoiHm+ctlhyvK_rTxU0l_ zNoobWMs~(|4U?Z0&o~3A8ltkli*;_z?z0!KkIsDX{sL=9+q1Wq;g+(l}X-|($Z}{E5kl4l}8Vgy=-h4;U?F#H^;`@A(8b&Qv$6)O32|d z8Syk7k+mq$`B;0`OXHmRlntco3Vd6(i2hnaT+E;TURxR(%EE+Z==;NffydUd4Z#G0AKz}WZ==4@K~`|m-XfS0SxMuRi1 z9Bp|wG*rJ@zE)ynV#2?9xEAWB;=Z?u4~E^#ouNo4nr^w~9rx7;rO{`1-O6))3VbX) z^7>MMAuXyeMVd&IOb+k)(jSQuwA(U1K3+9)j>Nwy_`%~B=yNSr-v=om(;bo(u9Z+V z;DyWZZH%hEvZ}wBkypA+YtJ4MsntqldZ0FUtKDp`7|xeNU&+nY-(jm&ST)WNRC^PD zotGG%`TO^;C`&B=QVdS4G!H)JPdP$M3XJqAj!%lUnX_}=j+1_61qT@bD zsF|Pk92h+@ZiT@@pbxeN%lskBFW$5CV z)WZ$_%F-?i;ygQR24339+&ix%ePP3SVy^UAHWJ}$Mqznjv&h;?N=5oX+x|T_39^ z<6;CZZ6-C;wzc?YPpJ@-Sb;%7)y_P`G?ksy9h}xP5*N(T%T-lX5&VO1-sFURR@irCIHgTH^cmQIoc8*+PUT3`cMK_wV0B9I}fS`Cjs}@+y=Bd;Z$*DRsEb zV(&J;-bqytkA1?sb`2~pZG>l#q$EwCX{K>RvdAq{PME<+$2TRXXFrom7~aSdwC3sL z2VXfRhyJnv1mB6dF%9!0Ec9X9RruK{V=F1vf_gvvYjid+5H~qoUT{?kD0agdZfd&cTSHk z^#f=kY|=8G`zDJJer-fMam?&zOPRujmgsrU@rcJ3ycw2Q)7KMn8GCpq`O|IU^-Rf5HO(GaXGjr|hvsC8KMOE7* zGbo>v6s{pKde_$05(-G$Elt+3fkQ)zj__7+KI3_7`;v5aUNrD^_on#>WKqSPjtD^8tS8(=4RSglTiD#2VJM9{ad z`4_@X9z3R}{$26#I1JtuO~IXO-S_A5XnQB$oZMIOqAW^!>wB$Jrv?!)jXiEv7&jih zdMoNOJ9Vmdl)O?zs&!B3GD`|k4=vmd2%ug5wzaZrMykBuSn9DkXUaGBC#W`NuK$S% zK#)3Fi^lx0}$yuC= z>#EE+BLBG><&51scc}e7>d<}Ay7&=Sr?Igyw|A2K&mk+YZS+M=DZ0{*j*eKKtt9;m z#U46Oy-Y}pj{Ud(-nCnOjF(o4^jR~#xPymf5ZLKH?QoG?b+o+bab zK(*5iC0tXJHkvlP2E{Y%I1EU`itMVukQAdWHMO(^IGK`5|B*hXb6nP-ldG>8SlH3^ z=@#k@{2Po%Gk>9`^;42ObO=MBRFFxR&$Lf5qxKmYA6L0_Y1f3itfW@$%#1`}U|=r1 zh=yrR2ItkGAVkuXVR4-samKdips8>mazYt;TBxoZj`K z7*9*eeEH-F6&h_A>5yD%`SFBBU+IM$6SQ<3md^h6Ksws8n%v5^Me&{D0iVF42O7oG zJ1G<$rdgEC8QJ`q?0aDqN@=pXaD`8+P4rc;xCc+0c{&C|L*#*C+`pREd4d{kU1=VL-%of|NY@q;?%x9 z7qx0~?!8_0hR-mUAR>82y&*rF;(wQ@;2Grs4PG6FTSSIq%fHS2*!pB0o0d9lUUM1-@jP zlN1*hubN(b3M5W=z)+HFk4&jWtd*8_u4Lg0{*SGBqxFZ53x*fyX@-U>L>^s4k642v zf+~xSp57V!JM@Jwv33P&T>tscKnCc`E6(SuM7(>}Udcp4U*QZ9GWsh|IbJ6odaX8u z)BQ(}Ui>BFy}IHpzGn{rE=6`4&Xo1)vDGy->vVK<-miT4ev0H+n7@3y`Ny^8!M zldoIdwnJ1|hr$W}ymDA{=)GQST}!yTSQcvriAuHokor|brSN<(|VnQ+@=YiOXPRS2< z!_2RmQpx-IIbD_eN=xMu+)}h?mNXauk}^1lwX$@4wRhFb6wqOiXrZ*FQA z{7NkvbYF4k^WCdMMV^j7{!qw`d5jtC?zghXEsGg!V;9cXlxj2!s7JILWIoU!S1D%4 z=6#GFPMtmYg702fn1T1OyK&^@*js((gpLOW zhG(*6PP;)nK)h@~*QhLKU@Di4M)F1_AK_fZ!$L2qr6R{$k5dTTN?2If-K*PzdsFbS zM#_@<{H<#K1fP|wl7|o14!L0O$FnwTG{FpLd{FxLUD#DxFe*7^Tp5}Yy@f~mn(K+6 z+0)WQ#pzI3T)cIj7U=uKxVYXrj{E(mci&AH&P*pCQhl{*DnGmQkHbsE!Ake!bEj4m zZ-<_Lv??GQ#_%(66kFxUN1sm4zdiit5+%&sSnz(@Z>6+Y-<-28*&-TsiIEz;FPUo7 z#)k7gIGFZ>!iFB)JcwE>VNkr~d{WcD*|y;FyZHvjq9<3dzt(VBvhn%~|%J>j%; zojBYZ=mzFIH58hxik}u#@_FPKc?lO6X9KUZva*`Fb8&f{yu3Uc4HdiwZq^R?HV^wX z53AIVNtxD4NE|s5tSRh=VWk~g?g-phJ6%~OuiPdn60$DZGQH<2eQ@$^^xt)azBq?h+Pu0!{8++34YHMR(`mL5_?#u}OZBp#K`lcf&ukyl#pW%SVL&qjYTc zux+mm9{!VWkbHA2u;6&QWaei7+)Qq>P%kb#;|w4X5cG zI+tp@KTWlBK7{YhPIb|8X4xnWy;WZA$I^KNi)nrD5a* zBWwppnBP_!X~VrV%1zS;cG|)p|l$DsthdhtK9eBWr?X7kl;Of!_d`8MWy!D(JLq38lP#T z>Fxi0+E8nL(mkljPUls%`);}B3vMpRj8#Uavfr&j$#<5zCKueEbo7X7E3p-^o4KDq zqGsyk#D*jsr?8^GXU`sDvKm2n{x)IuzHaf3Y6^yfplajs<|<(3Vx3umQO- z&grCN+uGX~@*X{S(9csY6!scBc*C%HM=0{0_nBbbX;e6#9|O+6kzm4Q0)mBb0++b^ z$$M&NJ;9D_LS8R{YOJXDM0nPdHOR@x1`49szOlunh8tDuW!Ii0^hr zcf<#0!#YL{;w&5wN!BF?n3#qgiMDhGQG|Y>uhNGvHe~?K9Y@%i5L5z=2a9`|L2w5j z>&VJ@{@k*m`AkUm_?G}xChDTEUN*79nxqrgu9?{7Zts$~8=-WrwDS|RZV_R3>IW^0 z;b`0%5fvSfGby_>uJIf4knEkr$}JO&oO2G(?$4foZa?OpQTsQk7dEtb{#)RLd!^H*0%PDps;&2r683kx{_ zhGL-sQ4CDOQ#QG`!JfMaebr_?YIJd4Ue2)7C6%t+aVX{nW8a_q@%8w8G_yp57G;ZS zp4o3biblkcw6u-H%`zvM$+ok5)3k*)S=PRW-jccYSgk}z(ds^NaT64Itb7W`&>~2O zs-UVh+#AzgeBdI-*v~&LU%p&)eVLxV+tv#scjD}-c^!pPFAcawEe|}37~eGx3sUd> zTHfV2gUAZNH#RcSwRU#W$25?CRYY2DL-9xenD5^+q9q>n_lW=R9P|%JJJhnuxW0)6 z)P_J-3)~791=b0u;5++y@6=Hg66yz)@SwW79=aL%_#DN;mg48>A(rjs!!4U!9GK4m|~pQdjQbAHX<5u?qq)6q!6aU8sF#E$~mx z$W>-j*?W1(V!-z0Ninc&`CEr-i}h(_an`f4ve;;<$6}6@iR}YD@W~6KMXEAuKd2&!y4Y~@|MEGGCZML7p{`e#e1Tf z(b`_Xi)*&$f+ZC6<6qqIRP z)1@y5S?U2uLfuOQCltUuEL-RAHt^XxIIs}!0&s6liHp31`sDe8c9czwAQSy3);ko( zT|+I&(EXsd*l`fUCkg~~;UxWX^0PNUdN$S8zo!#4g*%x`_=n!*8%pW+X&xH1iW>KM zE1_Apa(jrfO-x>4Q}FqTp^=||L|NQ+r$QL;tuuFHQ03V=?^)=bwbf&r{-3+pGaDm;=EJG*#?$!!A>;J#;PtrlnuJyY1Xh z_)Mv}{TER^JQMa^yRw^M-FzKCUV(L4HsOZm34(9t-?R@OT#u)Uj86e$v^kxqom$Ls zEIc*i?CG=b-2aMa$1AR8ns8bf9Hkzj(BlfBe*-?zpiqPhJr?`{wV7q_v-1?I%=6uP zjr(o7n~}kRz@To+va0V>d(J3l)R|#(^jx-0r(|OYxgz~M#mq_HI_r^Uidnn)bGHZi z@tYOd39t2ZS-Iw|@!Q#HZVId6kKGa1rMEH$u(1Rcx7XrjWT&0o8?QaByH8Si;g-$1 zD3|y0m@%or?d4&JuKa9OU@!XEtEVleSnx}4E&w$UJz}MnGV$63uw_)z2T`DunjJO^ zev+E7Sy!jXe|mm)p$zvrS>nK|j1wxkJ;gHr!Td)0vUyptyS))@wb*EwSXeOdckA!> z@Ypl#w8SE)si`-RH5YRE>r|e&!K_DO@8sU{sPeNMX7U&I|NXb(=Dj+Hfwt(- zH9#x8tf2MT;aG9iw*{xjWPHaeAWD1on4&r+R(dASmG`2bR3j!8XMor666dALKMCLg1*5{tmoI2|J`y_(VxWi+5GM8 zAMyK7Y=8RnDKW5z>Jh1Zp)SrR|0mJFqx!BM{y9J}B>mGjik}anaYkjNAH!TLLV32s z|5GT10wlk@;%*r}CV_~6z@mrx6Oa2i>J8)y)Te|cAf}rMvdhYfE{yN!o4L6I30Rxf zd-BUUQL_HoLO~|yIa5_8jz;eOg8zgE3B@KysLR2>jQgm2G;pk$G+ z(oM1J>Lr-)2S8JZS;B9Jyj17pShdb+u`O=>jFXt~ZM5=h8}MzI4Af%Z$Urxc+dJT1UcEt1H&9h4 zB8kF?!aTWEcgpsI)e{@8v+smBqg6$tlx5&x* z)TsrdgPHMM39EllL-dC?THSB7+Ak|>YXo%Z2vMM-&jPMMO-+r1L<+a%J_rg3VzSGz z$K~T~EyT`6bS4w^2oUkGyxvJrui$u)3sS5JWRiyk#Rh{MYhp8fP(Mpf=Z4Lt>NWub z+rl%j?~5+ol}oN3ojpS`1Nf1Zl^Z};#+i3DCrU$!Ouifo#vjgZ zR+lbSZfKX>v*?yCnp?Kl^pLm(r&VEo@XZH}%Ivfwfx%8EH`uZ4+7v9*qpzRzc9Yr3 zJ7C*y*Clgud#Um1C+vqqp{~9@oIeyD9SPW}VATBks{CeUwTd$LNiLYh1)`)!zwKFJ zjKLF56qO8ge#G4VENT`rclRw26L`*ir9y~&BJ$p0pLa8*&V+w0XMBoB3rbX+G5>BH zMf2_fBzi(YiEXU{pjkserS05hfqAg&9XCI>`N!}ufLfE{?y8?J+qp4mjQYq`uhR`| zx7I<^5xN5|bYJgup%WgoyCAHEhHvJdcUKobcQ@31L z`Ycfz9%e}jwA2ZU^s=Q;Ldfgi=8N|^6wmW?+YuBA7%JLOx#rdGo~E(ZF+GO^Y{_Fwg-~Uez`jOB4u6CXk!opBG;R z!9`&J^+#OxgT6G!wi~gh)zswQCrS#|0f{2eAJT8Q_TX11?lbrtkU0pL=qwE)9r)z0 z`NNAwAg(dncE5@{?|&6wQ%}Jug~YI$Bl$V1f*bLdM<|R&XIt7^LrqpmOmU>pVO$4K zB~q;f-ssmOEK}{131z1I@!CqAu7E%u3UfwNHMr>Pj7>=ox1^wUSyNnwwRkheEW{IzJ~I)sf&79~+9w(RojQFG2{ADvo&73k5Z_c!BTw z6NhOT0**+CZNrPs$M$fTgTGxnK94N- z4aWaqlP=rZsvv-a7~*d@060A*H5L3A23FQv6m<6+uN=e^A{fb_;Xlc*6nN@eyJhqD z!3a1zdoPe80=BppV|+7vOt)1?L_*-UAYk7rXWS%I&E0k#V_WNI`^Ka==y;l`%M!*X zQ{qUG8IL!sQfa5Mip@$(8mYiJN{$zOT|Q-iGWi^!eJ17Q*$O+xu);GEF**L=$H8rN zxFPO6;US5Y6a))iXJ)?45@hNj&Cjq7ywJCAg6GM*yHaX(pM<2?yggcwZEf;nc)+8y z%F|m{`_jgf&u51k9VJ@Y0#=7tm-&_}Ap+|78Bw8ihTZVh^=$-^hJ98ca7K1NH=uvR z!0ib#1!6irTKlz9{|TJzk5y6I5lgKT_%Y zam!Hsv8**Y2uL$^v_lv+;*Gg@Z$`D zBB0imSKUUGBs&)yC7+~;c4gAkN@i7w@wskGSq~w~d#Qd2om%;=x2ls0jb5B>H+XX0 zH+ow30_TS;=Eb>oXP$b1CI!IHkJ4ORMn)|@Rme5n*sSECa;5kQn_Dzl%~NmS*Ew|u60v$g8Fc;H=e z(}`L3GH&V;cwa!tMEzG{?(V~cgyRPu`G1){0Z^Lg4|-2Rv}1JWz=2!$?{74$xYkag zaHEny7lr@~%z%o7F}weU4mr8G#kjs6FZv%;p~~j(X5PTf#WkX`zdNR^yd3PhHjg}G zaX(duY0wFFfh@X{f7Yk|X=xmAQf!lanDQv@+54YPnc63{Qrk*-9hj)Mj`^?0?C3nl$^OHuhpLpMeTL9s;b`EHJWn&Nw2qaS?Jw$DzGfIp zm)f@8+IfB3BXQ1$y6>M26b4^r{=1*=p1`(KCUt|y;r)cE(*R<#+SnJBg=_#l;5wj6 z`WCR&xC$NC{B(LmVXrDB!sQtYZ;9 zJ9N61`GaeCJ)Re}|4>m-L|cJ(sHA+ zno;b-ha}S7d-tke$l z2{H0{=K*fhSpEQds%C0f2L)1iH<5vkW;<*$jvW%8#Ve$wg@ zZ1;|%K?YS?Qwj}_951VMD0Tf6QvJ=K^_49oqt5#wdlXHig(9s>>;xfaOcG%%D=W)n z6}6a-ef;?K@88n6RL-#W!o#t@<{~CwacSt{VKwh?%We7MTjwdV*MEaSkwN`{0uh8U zzFIpv=tu;5fWt?m1v{yen_C*zni}A+EWlySL4Dcp$%2>Lu#@hkXEFHozlz5-DtEe# zYvlpmY=|1)9>bci8{J6jl;J(hDE4u#`hq~4BqkW8GIbBCZnTnNj%mO|#(l#{>Rok% zwAEZDv2V)Eei&_FFqy zLalINNS`wI=u;3j7JNepgWwWp9vB>?2s&Y9XuTjHQz4VV=pjjLfi)gV-0q>MPQJA= z3}6zfU+U(c40P+l&(p3krAVEIg1{Rj~jv={$qQHAMaCIhb8>U=@ znG=SgSYbxMOJAS(Orf#4nP^)O6^M2Xl%`($AaWE?K-A(J_z!2{4SDQ}(Le%klpyx^ z+zksezkZ#EFk8jhXn{Avt5*srK2d_AEv=b!AB6AMZ|pL~3@HTi?p}X-1sT>svRD+R zLg*oY6~*U)jIptSw=h-h6%$E1G~Q{=JTpcm(K(V}W=!4&UsMY-HrP!+VA; z+@8H7ijpjL{ram5+fhylZ9<$N=Xg%eZlIPSA-xmo9q{cfeSJ*j{n`V42NB+{qXq^T zOvvq=7N?AWOH421qggnWFB^Y(dYqbc_w%cJs8T?$e#LZb;2Lar6x)q(c3VGv@+SGd863Llcz7QlNIpV(%|eQ z9iLln2&xA(Lar=Nu53JLcd!RyWtG|Er3+gl{4s^S6@iX;SeSMss(g6a5muFuDJ)KZ zsRva4ZT5G<#Nl`~p*8eDK6)*_`G?EYI`aT#f$Zhj8Gj*lC=)v-|FC7`x-^Zt-WtA| zk<+Iy%k{zjOsRy!#MKK3(A{*2WS^dycHNS+WJqnp67V# zF~$EXxLPJ(+#GEmDvuJk@hw0_oiP6YYkt1kp?Hum0E96M)VKTPagmSUh<4)~B zuD+Swf4Da8`J2I6C|5HMXm+~U@*gvu(a|MGuR5L0spiSOVGlrzIk@X`gx%*Jlbo4{ z+yPgfPhH4bc8^^ioNMO0cO1}hh5}2v&!{UGr1^wRC9x$Lh$JL+&%gg0gr>%|LsOXg zqSEhUlwn63Wfiy>*1omBieG8<`#Xnycf!2`)@Yv>?j8_hk)j8y4lq5`@=sWNwZiqz z{@26@*1(4kANoQXf}+J4=DO%2@bznPaR=@yMBgh#;n4_!9S6;#d zG){qKt%@c-BK~_t6QfG{b;r_s>q@{m+gJA4vCY58H1b%Pa51&)>$%|)aPfp`dtZ-z z#-GuwtG2aeS=onIAOE4KDzSxp_K&<&i(nc2`Li*OEe2q?h~*F6R6-V4~#JvYc)TQx|}TEy`oOCB6z6=VW8F|hXy zoH{YMMd*lUJ)IyVAQZ$nGQ^6O{Ra-5jqF^?`YO!=#;XcuZ#G7Y80*+N|FWOy|5J%3 zL?tMmOgT|~#-`}ur77foyZV_itb@fU?GkszlWfUHZj<%_0tpm~>cvVxJ1>LZ{2Wr& z(u+oY4Md5bfy@^Ft3j^M3b#wS-b@!jIyg{Y?@1Y>}s#zfMQfOf03t<8Miy&NtE*~S%rKdF>W zdry0z6xD2X!=}pr#hOb26v|tx0swESom=TH1oSGNBu8>6?7bKq!#Z1}!mdi=r(|*9 zQL++899de=eX^+Ir3Q!FpH-T)A4M$R!n z)3(@ti^E0^8sMtR5ziuejlC84ZY&fe-WA1FEnre9BA+I7o#U+7Oc z!QK();xn743oj1$^im4@6)m5Jl!Jo~9VA50ZgyuAAqu_mGwurkj!0;2hHZ5{wl<$7 z7hF|hGb!#(tPx#InOvy(MZ50u=vd9Wt;ULwlQI;(_~hoJbyk)o$nQpx`@;v?JIaCw zY=M$3ul!5p`oO`3Ie;9Wf40lLmH)UEmS%xNvY+8z z#UYXkwI;JK%jqP8kDqFT7y@fKGKS~me~ei=H6Z0cK4^d=IqpI5J2zH-CJv%iCDh`= zw(Nqyfj8ml(vt|nkq>JK@P;#uSpHNS8K@G~PD5eoW2ANsBa?LkQbwxt*M++);ht|IC;{l2Hkq5dU|?F_-3sg zI?4;&(Uw^Q)GR?y(_~nFXN!vSS!`vwoA%>gYRV|7XocaAWpaSGcMyP;;omF~Jp!{;cZzaQTTMQ`1@(Lh&G zD!z%VG8q}7Wz;q^nPnjDzH+_QHs6|4wb~GFZL~2B0VWa*q=%0lDd7T0#bv!CQLu4C%D9ZD!eWR0B+WTcAT}~&^5Ka#Ous|VpYZX*>G+zQ)bl>2 zE*!45(=kVR!+WF4^7GFY6mH3W$}39!w(TI4MIE4yo(*2gMd+HXo6t(eXEOQfjwUn__xl!glk`ao1n- z0+HG(QI_~OLeVi#b~BpYxg$Hn@hMF6K=8=2Tx@Jy*0|NKT^YP9gz`N)dJ8@xWJJdV zZ=z;1vRw~s{>H!Yi#xDh1$vUyQ;EkR-X@0L@T+3|490BAM)oTtvf_3f1J}(NSPifc zjQ8ET?JMPLl0zh(rtiB7e-szTrdZFvq3Q^_f`Kipe77pl<8bL6^~yijkzMIzV4J?D zG(i3bqY9QybkKSP#2g9johi-O8De&3S}d*+01%*`&WiiHnqNWTw!BbWS$E3k?>WGq zYwJU=46}fB1HPHYp|TA%y^Wn+ag5RezY?2<&b_TYxvXh6=cC*um^R!mQ29RL6s%y; z&d%e$OOvQx(k(Vw7jsjRO{^2`uEyg|Ik|BUf1D79qO9xJe#C!#adC5_sPKcP8Qw9k z2c1Pi=04SyT|ZSuq-NsNBPK)7(fZ{}7!vhYq(_mZV$B=g zIq3Xs)B0!MX7|uu;f6*HFcXy4(9c1tga3tMUbsFd8cDU$@dm7d{Xt89MK?}Nm_c(0 zm1d#5hlK?VtdrhgV`QEAoLuEVXh7o{jizR#XKY+#%z5*p!7qlZ(EvL2qQUkgQAE-5 zLB(<4k>OV1p?!db5lTDeqZO9K(`UgWo48d$lBhyvf5=6B z|EJk*j=HWc6}7YOK^^)RHEXM8+A}Pt3yNea^nuW>aS-d?R(OD0hKkQG#rkx@NB2cw zqSxo%?JB{^Tlt%_$_3Ep?{XgKTZ|)|=lDQXy2w{JGP*V~MnDn!wKkV!8&rIsd!l1n zXgILtRGZ`z5k|xgk&qTQ?*_-mi77QnS%wl9v=wv*ufDq6AlCfTfY(3Iy@UqiP0}oA zvr1R=WV_g6KONPJp8c}=?+XOhwP;OdclpfiV(;2?){!!DBqr6C>$@i1Uz>}^)FZ%? zK=x-H>r@`s($6e+LoP(q%E!(=>-DH>$9L(yF&h9X#HK*MCs*jiLITP{Y#P+xHHh(8 z^tU+j#9Xd91V4lc^$*Mr$b5FMRsH`4;4Xx$`uex}9SE%(PV6egS6O2v%Q`3dxAJ3L zAb+5*hcVBFI@jj>W(J#B9alcR=#x4nS(B$?Dzp21Z@+|CK4X_ry0LpebKZgsrVnnN zhO`iqV-^Ppb)lWR&-qi~A5lRPB_4^e7;mf)AV(7eFj4tGC%J<3i$r6zhuo#g! zuc{=&8ziI-ECPqLEL(}p!5J88aUfJvIN-eKs~nXhN^DOkg&P|2M8q2aEFiwiDqJ?* zgA9nlfI)E4P;;f9XM}LJ9*_(*-9Zi{Jt)idB<-hbZpW$RwPkaUVZ zdwA6Nk(f#c`=n^r0kD|7=vet1=AtX3YbY?tx__S|S933u_wN~jkE8!u+-{#Agf09! z$POnb>yXBQc+R3DJEwR;joGdu=ECUaQ;2%b4lMaXO7|@@GhgSvkTgr`BK^M>fL{GQ zf24Yi}&Y; zytE<=Pb8Sk$wm8_3LL6%(6D*({=8>ygf{+N3AA(Xgj_56a6ZIT~8k}xsy5aG<#i7LWFiIgv4&E_b7BfJ2~hcq0zy71BM=2nMatYwb=)T zju0Xh^i8VuJD0-#8>plDzEVL*eTgf8q)apwK(fC1u_`FKBxn3oDRHVD6|-)L>4d^|dFjy zIo9YwlXaw8UnB49H*%E~PM>G5W8Csnz`&HXqQ*L%+uqU$Q2~NWiP4{bAUK6`zw%*;v{ zsAbu)<9S9sI1zMnNg^8knqgR4SkLYF(sce^IS?yC(r{jsJex-d7lz|KT2L8dBP~R5 zgT%^9f}-l6D^&g;mb@JsG%z}kRO**(GgH=QLd$!L-`7$PuzAI3W03tHn-|O8m|i+h zrfvR-czuhXotFGZ5!hB*2%~Bva}>x#9a^sNxc4dJGFwOwM_;(zMWv+|$NZs&sFVTB z*E^&B4S6i9()5$(Zu`=3#@w8#!KqVWh3z}}qKCXzzklh*{uu?FsspFMmP;uX;2 z$rzow#jiWQ@4Dg2Qq=SY^H^bNb>)V)V7%@GVUnzv`+lf)riG?8`RINi?=_*;r(d1wb#%?^Z9ED? zjds8INH1mE+bZkI` zedn|}Z8C+*(RgwG!9nyDr1r9-q zwV!(M7C#Ri_1jy&uT<1SQ|>DW~hqg7W=Lc#?)Bg8Hl)c<8NEyfkTH1_YHDXBPY-(vH6S6 zqgf;@jFc@lR@UFKI0L=DTEy$VzQ;%YeUf0pTg4HvD9{7Ri8&7G_`Tv=+CO~Oi+iN= zSI@@xG-IIZ(=#C6pvn92%Imtu=<#j#5kj#33~Cq>jMqMR`0yod`#tin9vn%f)bX3| zemFdTEl)qIq~8I@{79otryDA!M~y}9HWP#6v~XzJpZe1QgIP$!sA|;Pq^IYQpa!yVdIt#Qmc^XW5Y%~MGpE`@}9+pnIT+P+D|F!t#|9JWiaIV+>{}xGB*+N7% z*?X^$y|?T=vdJh!5kkmb*_#kTIQ9zJdncQ$tpEFSp7Z;k>pIuB-}h^p zdGQ&#Rh`Nykil@@YZ?G9SHJV6hdcS?TSG(lA42atY>R8i2|FLE3<2E*2o&%e*=*I9 zBsFOLcMve|F+mv68DAWrHXfI2Ehtx!iJ;Y?hJ%;)ZRL#Ij|EHEoC;gTAbb0bcylki zUXryYI=LCU^_Q043#sbokxa69u4JZMKg_SyLxsGo1(~+$#TM`t7tPcZG{bumlL5u}D;>4VL`T5OGwapu*CJwKYOCTOT?{2UY z5x@W5aFel*&$+DMn-(@Tbdu5)SN@(G?(43J05c`+?Y%(sj&nO}AXHfcQ7N!e+g1#* z6lem3Xtx-If=oNsU6-7`a&LWbDA(qDu}GbjbwPc9P=b7>9kP~TjYnz);48p@15#4t z@O|d~;Jnb26UuNqq4=IQs5f&%o@Wb9FzO&3o03_BH@i0V^!1nFFvdm@_QvSsjnO>Z20%9& z&t`Un_fA9qdzvlnxfRx{DFlmw=C1WVWPo1{q@>@UZ2?Yhu7xk!AYwA3LtRBLOt4{O zWGo~$Cjg0%l$eT{%kNxcysIoApEM~_M*G&w-Ro13keLH-YkP-auC!KF4|Sb5o+5g+ z0yiym0@Oe;m%nfMQV4E-=p8c>5UM5;J=?GDSz)i-l`{q1u$?N9C}D?lnz?@%3PPt= zT0k&DXQQL6GR#?d*Va!Vp0BVkc+u&D8s6gFyRU*iuaEzrXQDkB_V9aj!$mxygJVt3 zAcE&CRoBpP^{L3;dmzW12O;X0>gs)grUL;G7A3%eg>7tm&;0*L7+?vB!!5O zmXfdfx^MJyaMej1};l-~X0nQKLgo$8cK5GJV zUYToQ|6MrnAemY8in8%iz#^cW%s}`~5)NMMl|Mz7&glHZ#g!=hJhWcEdeKSwV73KjZ6ehiv6mA5RDGfd>f` zzcf)YZ{;zK)v^b4-xUx8B;m$Ox(Y&Rq=E_*O-L3@jpN)Z=pyjbtkt?R?}oJcoK4Nm z9v(&0BAf#)RFJ8|$@YJWqImCm$09GFz zTHumFp8#?0uw<9*BC=hP#NVm0-gjCWhXkf*?kSi9u3<-?PGP~ zH#iU6IVXINf$YG2ySuw}9dYf-1@>C#)NwaFpjX0>R&l?Tq6ybGFfYP<+%HH2{m_3S}xsSf}?p06LC z&))_qYu1Lh&H(6M!paF-^pK{*vZcJ z1_jBEMH%#O!Jv&qMkzC0*2QjBV0;;QbTU=Ew8s)#?}aIbkm4t6_s^F5!(VtRVQu23rc0@#83ha= zfJx?k(W37T#po6JC3;;e&U&eN!1~(fQsSe(Vcsw|ubi+SD>tx@*{TSP?plsBgfxrx_R!#-zH{Z5B~zL-KdtX8;t zL7V#;*3^G@4Cb&s=*J>E*?<`T3i|8^^aeANJ*LTuYdO~Q1qD!Z)C%+l6!X%dX6~P! z*R||qpVed*FjO!(o+d9%V!Fd$J!kQ8an(W}v~_fhy}UNo(WV-(@UV5O>oUK_+)UgW zz5W*Cz8DS`F#Qrbry(H!2fy9%g&Ryn0O49VI3T$1BgK+v3%JwRKRqf^w{m3dxVY;7VSUdm^5oRV&{ZEV$P_+eQP0~^&Mjpn zx@Y042zUV4vQ5=}4AgZnMQyn!5w9Tx>^yW4J&uz3AVUp0*XPd8(O`!hT+rsd|IKix zai=iY=D9Y8a_HRBvRHrDBT)}gco(c~ZL?}>;+5&l$SWbs5dww!A>CDya7N?brG`Qs zre+BL05vSCZhJ=u;PLPVe-t`m9iA<;E&xg26gSS-;qOy^X5!*(d36Tq>T%}a2;Xh2 z8ZLe~;LfBoMP&A5A|iX;c;tC~Q7cFa?VC?qyB&g3%y}K+8}c^lK1DN=@-;vI02#^^ z=I~DFH~BR@TB1i`hPSi3F%1GOUewPZ&1T@I>9fen&VB<_Q7SZYrk~7Az&i+nO+cXl z;}cHf5xIg(W=44zpAZAJrr}fd%!>|P?)vbO7z0mVLv@YE@dNh^LfHj`p9vqXT(b1A z!>@(NXgHYEmEeX;!#c+oJK%Yg29t9X8z#y(`XB7Bt(RIab^w>G9B~6w8O*e5d4R!9-;r z=+kB9Jk^_%VkU>)B7LYYk)b@2QiP3(dA+S^%g~Vx4P-O`6hjZ;kCBl#tqVva99*&4 z^XWBbJ`UdaK8r4kO5n%91Q2ZeX^uYF7*dfagn7iX7;KMkJ(q9dGJOO+BpNGF;G}~Q3+P(B$|wyDgX3C9d;6JvF2Gz~KM}bJyOK7O z1bCq}+h0k(mkeOZnCVTWT z2y%LhhJAzwAT=GX1OUE(;3A@QXfA_T<_pi4PvZ&-08)h`IZ_We@uo{PZUHb4&?JGr zovi2nLvU3Lz5s!bw`%_Bh0a=IkrV`uu#In>Wjxt9X>+xz{yG`#)Q8{;fVgIn&76V2YVuudcYoL*;y#aREsp2D1CYAY97 zf;stBVszZLN^<;FG}%bSm1vKP6MRgTX%2nOoNaXCYZ_T3cJcgIUk52M#K{GK4|CWii+K z-E|^57HqzbZOm|^)f#XRjZggiB}!4YSQ@7 zx4JkLrZg7zT=@+~6F?|jv&n&k#K6z?TzEt1j{g}_b_Kexjk)=1C728J$r(;*KOO#J z;2-f=7R=3=bfL9Mw*$p0>7$u?0P}GXVZQjH&6I??;ZefOX?F ztG&GtZ;FFULTh==-B*wQTkngZC!x=RLrGCC0YQDv%xPc0OG$R!)S_uKd{9_arDGaf z<^Gq)t%;-qDz6;`Xwn91valv?x2RvCPg&|Zfa4>(h`tYux?U%{3ngQf!*}JgX)pz< zhC8-D?>*~MOzbQ2y#Ut>wJiIw5X_)6!Ha&NNHwY+@DxmC=CB6oSJ~l??l32Zm1_6s zuv?0!pduiy9De{!2Pjk{CYD|>K|G_ZkRlP?>X13jWY7*U32i9b%?@w81Y;$g~N6BpRD%TDEZ0h^1 z7Z)HA$%u#E;Vdo2N;Lh#v@k_iTblw0Z5MRu(7sfrTMTjm2v!vZV@ovk!9kNspMt_L z&{<>QX$8Q!fu<8$=V5aPVJR#z5cBikQpfmigAebHI8Ws3cgx$ruQfwTy)2pgp z_H=AkDHi_seif>J;vopT-u9%Sf#4G%T!@H9AK|8~=Uomt<=g+jiuc+CM@9t?(kGY5 zgdAxTB9wbWr&%h?%}u;b95xq{k%T4iiQBU&yMx<*W9*8({W_9E$bLO<*`(CQp}k07eFf%|DQ#&<}wT zu*lnSpQ-cQuFx(@7CLLmxMlX=(Onn3^PA}+DT-Rl^MGHAdDgjkc*L9A@3`8$=u)ht zEPQOcPd5_t=hR2w(g3oQF_kKwspSiiM-qSI?UZlr3te$MN`zT(<|R|O3rDu~_uG(L zcd)pwn}qUD<-}%ia|`r78*^*IxlFUrZKm;)Ty}RrRK0b3jAAYkS;JF7!vb2`C`DR6 zaF4?@R10y3@Xo81KOA_)q%d6Knv)4Mc$|5%V(!FuDGiMx%|fqa{ogqxXtzd%{LRhZ zSaBk`@qT`=iM7M!Yc%TR{hh4HGc&VRHszsdVO+UhBJlYC9&vsB&-G_Lc>8cKH~1xC z0SGA5f+-0+^as^UJ&Tgna+{y2oVpbKEu*Qocmwxj?KE?3E61j-YN=(DES!X9mG6co zSS6uc0Tt*`MH-s$>45?3Olepi?C8q}Ua$dn$B8s0RrDf^>(3s-hzHmca$K31 zxPw>o%-a8hd99tuxZM?uPmo5-&duEp5wbGbs;hW2a%NKGD6d7qhv!1q-7jIGnEO&I z(m(mXXZhLKVFd|4z%8X?fKkm=yo3y-0E*3A5I$GVlHw(aZRW%jIDH`sR*7P2?=y6% zF(oD^pN(9wlZpO}S-B6}#uu#518aJOycJVhNpZj=3xc%X!cB~=aCdK03=V*XUwnOj zXBQM~u>681qBaw$Xin-ouCRBp%?(c;A9|*Asybn~&%Uy#QO*B&>LI0q2b*^4Xzm6- zJnQgfZnRPMG0RBG*zXqu|a9MHCps}R`ntpWxlaVl3ykEuaIAhNI zDQEmCx^d=kHc871UUE0k_87``6CtnE2>&O#N~bSr!dlbRa?RSth9otwB%QkJ%NN(p zzh3`;`vTDU8q965{ofmY2g_2B1XRHr#c|zk3r2ytD(}bJTMM3y=61z>b(3^AZDFk& z98`f{<^|6EzH8q3caR`G2-Js%71qx0l>>%gR>5u(k!Oi-bMRO^7-8q&=m9?mG-3kw z%b$`1^cJ+Rz`0aK17BenqRH;TuNgm1d=G}DnLUU62|37yS#bu>z-yDyS`(RMig5CS3m8tC?F_0TF;{Jc<4klAVyOY2-HHlLKlQu*(S+NPrI0?R3=ChJ)L- zP{hUsq*UDhoC2GyU+*3cm@zor)_?tC-4L6ta|?s(z`v`ODCrfFv{LcsEz6}8!h&zzxEthKiFo$oDw&3 zT3B4nm1G8EHn`%tz*~0Y+j|>4q2@}*Hy@1NnBL;&Hm%XC`DUbo=OfGmYR&iVwCvIJ?3YCB0YH%O=@V;Z z1($Mz>6dxBu!ok(KW3^uxx>!%{UPBjgl7Ohkm7(N{p9dsNbX{lD8- zD?{A^qP<=SF1BJx`t%9Fwe124Fp47ROh;HIjE^vSYh?_gA&}%y$&IIVB|CYI2^kx} zT7nN%j;oD3pSgP2O*0T~9l+e6HeCR6K=g&K9o!92yuuLO@)S+&8@$of|apeh~g8i^nLLyCDF1`ePd_P(+JQ8bv|sSi$sAhR3Xnwd?^Z`zzxQx1B4#S-;w* zV>G{GSnrMr2S!-rb8_HtgbHvoc-%lqFf=hCo1qNalpyF`gp>~$?g6jT{L4)GwXF?0 zIV~B5Fk=2&taku+1wAZsHZwUpf>&=44`K|&c$GB^WA(Rt9?jRMIMAZCY{Sv^N=*jy zW|Hyqo7AB(xcH&O&TmXf(ivfz0HjD4_Mrdur?&?{yGS)XaGV7 z^b-QG3T)&Yxn4%Il>Xlm(*P2&HWN0-c=W%*(0>+?bsw32>fxPW2ey4y6EA!7Oa>?D zBA2fF^-l>kdel|9E0V&Vg2MgD1z0r@;U4lg%p>Q1O$jgn&-6iKH9}3c6&JnSh=}1n^oYwge@AIdRHx-=o*{m)yS)F)MOj<#YzBSy zj%phE9%_K#YCz;l5aRwQq0M)``6gHhh{(xH{(NBU-Z_q+!FuyM%}VIM_oV@BgSTLA4w@$N5VxnJtsIZjH!eg-CbN;w9!mg@p=6`~~_+}fq+MYTRqyXwr& zjqypt0Uk97?0?2<5s8oiULGX8LHXQ>j=SHLd zo0D3i;0r(kiG|u*I0}Hyd^hjkU(G;-5oc~$ug?PeBiu`T(pU;o|K{hr&+FdE-AB>! zW3cVr3ITZoJo~UV{~Q?sSubK$vvza@!aW6EUVzy8p3l4h#IT`(uy-noOKHWD3 zR~aN+p984w2jvE~necs0Y%xLKNQD$>fJl2Ga}r9WgaN@3Jm}>BU5H`|e;X7Zd9K82 zolFe)wJ$GIue;U_Nz8g^7KS%Ah9O7B2}6O&0$*RHSp{(%tZq1sLtYSkvZ3keUV!5O zA$tG*J=C-~Ttdn;w4F=f1rY}2igJ=}gv|RSA9e|(lUs1Dry%%%{BWlQv!~J4M-!Kqj!;4Z?BKci~riWcf zXy7Bt>QUgQQ3mzwzkf~cwE<$BK2CoZDT6o%H#$gkh=PBWQ=usZ0w4nz3kYT~`hf`6 zXBjL1_6S%N3iXISi`Fgoc!O(4o`Oh_4|4wm$>3gs1bCx>&+RCY} zjza>j&WD~{MDwX_(`oC-;=JpPQYrQ4sV*=A-Kij`{0LevaYPb+a75m^5 z@@IB{Z&AxKY;;eKjdei9Fv`=%XiB%!20YAi1<{l0LEQjd8K0}Fpd_0BkwL+u2fQ?} zw7XhB%s$P`S?lbSU?RAit0)9!_L(uaFre^}ZwDG$aD~}bKN;>4IbFtuy@Y|60r?YN z7dpNnfanCK4CTBbiJ1UEl$VaSlwhR0>s-6sSgh0Fv12%)L22v(wj)3g%!iBQfE0jB z`O+c(?90A)1LWgC&Beq%>|!w3PN?5B_JCmm5YDE#rfuQ!x$W?QH3;X|OOYRgjB;?c9p*%)RuJXrts6U7zj#4lFtAru+Hgyhy|#vi<~JlS z!=dSntvYuU%o63=MNB^+7Dxu5H}Fj3lTHkRKoItbjQ|$_L_qbZVrml!UlH_!=2ITV z#;*Z^gKr@Qd$o^`{;f5vA0W+zL@J%QzEw7m)M{u*34!h5mhk`+!809-{-r%IYZxLk z+OSyMO4hwkj0PBSpSvTLUeSk!=HO%5T?89{7+5=<55zu!m{Md91k4>I;?97u6=^a8 z4R3B{w*0-lEDeMpkfP?lxK`+1Z(v5UslrQYVPcZW#0w+}te=Ea?%33_nabK%9boWC zFDMwVe!1*i3w6xq&Cot9_Vj58{F`*TP&6E}vVS*lF%>)x-WvGw1_mi~6impHnJ{AW zIKC&LMu49m5oI#)J`(fvR(}~>P_&_qdGpSX*U3z#q?HsY9ZR_x8PGA(GCjROs`rGM z8IeODz$>!{L~t9%PrwIo-$|Yvh+MhAxd7XoNy*098HO@8k_UlGe|$8OgLY=5r+%je8=0}EP+ zgbJRfCRPsaswO;Mkbqh^Vq@XL{Nzc}YjK^p{Nmy^oAT$wZg{MLE+`aFdWt@)uD)2G zJPa16gql=1C}`+$%fy+VU$T-%Mv79rA6`eLh=Ov~a@ati$x#R*>$)I$A3>@i9r1j! z^nwJ!^%1U1BLywPdJ^|GXQZT4e<$<7nE#)Slev>pud1USa)OCYw5zpa;g#a6g@>v} zZ;F`<+@@9+IV3r;F~vNxL-zlHes{U}p2o(zy=ayp7qo|E;XO(LX>TY}!zG>^E z*u%k7FF7yCh$ZyY)$jctJ&&(1ZCOv-^H`=*2Ob3p)sH3x#U=PP;nb8p>_)+27$2Cw zxVcew6`sAy$XZ90xes0iBK|suYxgTueH>^SJ1YcazGpw`L627Vv2SJlU`FiqaBa$Q z%xf?GXiD8I(JCXjnx7|sT+qXz@5S!~VL^gk`$w|u`!>&i{&4#ivxc5gwp~aEEbf@O8Rh&DY&fZBOY^w)*;LadQ#X6q8iI^q$@P)JOIB;Xyy!ZD#itP6J#ezHIHQ%;ZN4)E~otUkO_Pk3`B_?ZXuK~)}q~la9%{z zw8{q&BBX|;@vymoa~-s(ZB3YU5mT(n*NDr;?Ks^$aFwXxzeNdEb5Tkalx2xug5xKW zh#zv~$4vvu1!iW0uQS4eI??leXij2urL4440vrnH2g;VExl#HxzgZ{Rz$kVVNNmS)TbCuw;qH%F-H?o%!LL<1S$~Sir=Q`8nI@DE(xVq( zYE-GrX-B5&n^C6Hq$y<8ll-z_kRFZCI*>QZyw!rK&2b>lv{F{^p)aCRVkZOk|e&QZczycbXOQl zv7uXOijXlIV=-9nupUiyjJ~I&=hasfBtTKBX>WLX$2BWX-8Fdc6b~y&l0P=LyaBf+ z(cI}dMq%sgxMx`t;;z*r#%4>seI1=^6`wJA3=G1p?gnD8*mx!ru;+6|kG$4+{c|7v zkgOp{pCHbnLq}$P{PT_VfY_r5&CRnfrEv{CHs4g8;0&YyzFj?c9H5a^@TBC$kmIg9 zGafpmo7f+?Ls)ouGXG<=k%IdA`b`ecAMlg{0QMY`FgA&1Sur>jvXtpQKAh@dPZ$Zt z31u2~UA%=A8KPI?m~^;~(fZug^&^M^j9pq=O)B~BpxW+w-T*kFNOLN6Z2kBQh83CU zFD2Y-#vt8WovgBjY6mBn4IqdQ85UrTM+S8WQGMu5V?cp3UgM_mZ8bTSWZwV0p=m|y z@~_CQx7w$xvzl3&gA~gI-{Y$Vk!ilJvxn!xeW%u!>+}9MrQ_1hn|C;7&!*0IjeKHy zv(jE{rJei#s(Y={tP_%C-+F;Tu`bPKWrq6baYFiBv#K4j0`|3bn|94TE=*U9tXF1- zPK%NpzpR6Irm0B&EE)ER{(QDE#Ffc``9Y$`&)U9L*Q151)}duOjwp4F&c+6m>@>*5moW$L|6Z;B|~|@oP#k-Vs=#)K1#})sN2-4ZsUS4 zuc9Yqvad>nnSp2OLrO5?P?liK*DS31E#Qk_eIrtF=0GC!1iSzn-1(-ZNa1|mt%Y?E zfCJE@&fsQMS_=+l&D#(*2SX5u!kgv>Ao;tF{{@Op&U2z$H?RLzN`6jHVCw8VBzQUI zmIA0rx~IPPCnf?$_xhOXYQt}aSHeXD;;clU0gg&ce6kS+ze$6dR|}2>E#TCLV*`?p zls3>Y)_BAPkSHkRPVNG}hIJu+;rGq3Ezrd@?OTUYJE_^#@!YDt&Qde2$H`KLe|y3N zAJf*8`(@YovOcYwn-Qn!W-L4~$SWjPlp5hH#y{Glo?+Dv?=NoD3e>NDMa^h5+wk`Z z-b1~={;jN{6$>w9mhZk9Iee~J#)%PbSN&>aN0h<-8CA#6PP)XAH*KAXYFbUn(ss}B zoXt1`%^u15p*WrF3M?-Y9j_TUmh)k;^4?w^xDC`yUwl%nr~__w&Z3eM=-e8N zcnzd56G7PNn{iO}xC{t&%w2BHX?mI=JDdt4{sf$%R=;0=)sC=a;+g@JI0>IS!GxLWKf6!}cicr@Y##YE zUUkap?nTo|+PRT`um6Y|2D@+eg3;cStHa3CjhZ^v%htKw=YMxxCKEH#A3PuD^{q}7 zxtcoG@vOW@6+>^~zs~QC(j#aeXRVHIwH31Hjp3@0mHxo07C$Gh!ZY#WxlHGB*YZK0 z)i3FMZr!~(@r-NU!Jg!!qchSwR0q>zz$EkK(l;YQ)eMs}c^sw}`$LTlJsSUx(@UZEN`29l za>-85%1oq2qdfzR^$XOC1ZdYu)gMi1Cb-qu}4x+f0%%yf*sU8YmMF z9@%NVTC5&9s5MFVsG6lFBJz&#d?ZzteY;eFstV6&=BVv^^66DJiEHo|l5Z~QbnM&8 zn2J)f$G&dNDlXej%uGz+mFoc&-gUhC>Z7A0=hOX_0$ycgQz}TKmOY;yxFCf9y6W0q zn<@fZ11%@rL<&I#crpOc#eaFBI-1Kn^JT9+scheB+v&(TvYYwz+`oNygCWw{Lp)pY!52w+HuA z>j-WPt6>O-Qsldn=#ij(#gGn0{r)4Wn1%Xg@&XNd*6^PWJn_RmPLD6_Y(mmzBxWO0 z&n!72d_xt~Gl?bXH_ASWtznJgh6R(H-Y8;0x3abltG|PxC)~i5c z(e#qn`Rf3ByDAs`c@~0oX=p<{KL-}+TG=_YW)NjtQYIv6KE~N+<6!%T^uw@uz>rPc zFVl&v_QZIpib3TyV{fNx2GM2OGhe=Nn+Uy9EPq7d`V|0Vm=FSplW!tDbijc;{oSJt zr_4OknyEf0rq_vU;}{U6BEh)RLg`$qkH7H^P(px&VZeYm05}YRv_Bg1koRDqE+vkC z-AXw)biaM8nnU;!3}2Y|)=M?z`Yb)Yy}TS8OL+w-Nqw(pw!g34T|5ki!4$+Lpo}sp zFGAhH%8MAHJX=@t5A9i51Wp@(p2pKYM|N1I-~cLv;5ob1j{%94NS5DL;7&3Ja1cl+ zmkHQ`K>i$SpHjrk#+jN?+3@15LlaEIpOTY7OLz?+Hb{|wOVLTb;>-t%D#M-l{BBUo z{`vDqU8iR!ODY;Egt4-=o;Y?hs&#$?6|=T;V=sR;98KB+pjfkMv%%B2hdJweJo6te z$N-u=AV&~Sg1W{^{oDnMKSZTyFGRsXVhN$GpqWni&zM0Pv6lWQAlJwmjgVR-BsVaa z2*{e|+Fb@3-e+omeR<5Wx)v{!YtD`SLx+jL5L)s8cz`s;!MeY0AsL)fBMVOO(#caO z2hMD_tp7T>IWI!wUe`F>@Huz{DVrs={SluqE80^=KkP=GqE zF>TG=&25jdX`d0OqWy*)Uu+lvME*X#dOLU4FgJBrXLfI%m)B%!Tfv-tEtNcE&TeU) zqIzxt@+-+L2U3~!;=0TjI7tx1FfYHf^vT&Q;7j^K#DupNSY@Ksqn2MKCXyiPQ~nh5 z9?Vt>Xlj#H)ls`Gbsf?d?d_=`6ficH*BRx3+IA3A4^+@09jP5l8Ooi}@+{Ek)!x#= zTYkbcA%6eV>7^EF9-#Y|zalT+MhgE$dj;q{;`!Q#C@s=o8-9m{Mk`}}TVoLA=$*Ny z^=)-pMJx16Poyscz7*Srp~m~=+=eZRdPnl2A<~nMt_q)YuC-Lu?2DtlExpO=r*3Ka zs7YHjEzJq3sc_KFEsB^2fgm7h%h1R8KQ>so4=_vNv{I(5$1u4swTC13Je8$_N$Yc? zDG+jy5L-Xf4{NJtB7IzgRZ-Y-x1h2)WX32?PrC9Uh$e!72afUZNtWMg+Agzv|O);cN zF|_dF3!v^IZTmj0TUT-bZSd>@0zGYEgtcHXhLqKBP~rKqKxqr85Fq(M_{|*;G$e4* zsh)o;_(eqgsY91E7z;-by}{Z+EHm~Saj2|dAao0cq1{)bf89w6JyTeC{1tQDrkiDNe-~a%U!y*R>U;v^Vt`<88^%e&I z9nWPnG=O7kR`T1&bSZX)+=>sPvUGQkLwt9LTJ`P`Z2t&(_CI>k4jfy> z0`zAB{%bo(&r6dyLcFPgObv8ok4l9E1fIdu2s*+_BTfZK|4-mxA0;6rwQzP$Tv@r5 zSnU_5#h!qe(Pt`p71$Ge7WWvyWB5`4@2ukOoqsntgkOn`7-bgsPyx(@JZ4ULUG zg=j`r3|LcfJ^m87lp>TImC~3SFv5th8E(Aji_pCn0(r1|;v6Z#kA!eJgglbuB$?R_ z(#Hu39EPGd2k%qkZi`BR%V}Du0}8YSuokrI7bKJXx*6Y3zF%YP>ABTv?9)uqE&TCk zmw6?C&HJZ<5Qzw#$FPO~iVf6O>jG=#^+@NXDl_&ju(Z(Op(74@5P9v6>N&mu!#QLs z);V~)fnXb43u~z_`4`_Q6|h&&)s+9w^y$QO4oUWDUeF1P2%RRr*s)b< zz*iWT0kad}Qk;%w7k)s#=>JPkAoAg{avj%4lF7#Sb)0;OT(QDDUKHt`wvaIL6a$SzSm#{q% zD(E0(s4E-|6bm6VWg%DOf*$lfzy!fVhI|KbHLZZVz=FOQ-e?F2?}WRA7^xf! zzp|iU(Y+q(dZ2J5lg_hY)=i}C3m4>I!77ypdu;udbFHKnQexP=?8J)@3{Vqi-UFhe ze?Dr8@tVPG4dS%JG@+X}TOII*lhi}6^H&k27otwMCT71uA)l>lTLaMk4-0>kO=7Uh zYlqqqFeMyRrd_-T0z487v&Wa;=2~zbgQirQ3FxvS%?;Tr zBbIpV?s1^BgL7J1#96-WimNl=|2UAHgT0WL+irXwl?G@h3}O}*mgUt|lX7kE$i4)Q z5SZY^-pk?iE1?Fy1{F>-Rx2B^&;;(poy(VKQJd~{3N&*22NUJSH`_w620^2=bFAIF zday54rCIoxnmWjOIEM}Pv)NSdr(1JPX;5czY4gr>MQ2YEo_^lD@KP?Uu5ynXCu;#` z*flT!-H5@!B3}ay@Z0ckvgJ->0myj7%^jDSnK@euPc2)5Jgog#Ch7rBe$Fl~S#@>Z zWvxyT;i(0DXOTwFL@piQMpM80J)~;W)3djK&^j|5^Qx?@8Ov7YZDgb+*xRhCbn!$K z>tU5LZw?O_pfVoObi>*zlp0&a`N2=Y!VDW7xRPS5Lo`5W6}o0NX1+USRV}E z22wLKhl5Vym}ZSyw#A|{Dml3q=+WDJ{0P^`>gDAH^sX2vLwCya^732?BBLpi6{crq z_*{SecpkFwK|Y$2r>DGUOGr=m@pn}A102Q_0c47kP{73G;!=-~Un0Z{$}N3T;w^N| zBIeEpTkJn;kYFh7>B$RDRE!7QMKzen%LQ!M^2&;eswyZ&auFXXkk$9e$@?>6Xxr>Rlz0T)>MTqa|<;CVWD;N+E;2oJDPs8mvJAGz+IRFf*vW`xd z+nB*qZEd21)jrdch(%XYQgVlg_?N(3U{~oX zSX!=8NYkLTOo&H(vwXS1mww)PuRD@d?93EpruLubtRFso>U?{T%E`my_IE2zRb^#S zFqVP|u-%IDs9xIK{4wbFmtmf!W@37;=TQ3wG@7dV`aaXOH}@_xdBUh<@1J3h#3X-u ztM%dG)hS)r>e03zd)|HSXFMqe1d2YPk{z#=z8*X*9h$b!W%3unOnLfX-R)qmgWSZU z=iP%19R+-!^A*ia5knX%0zrMqA8zoe_{gZSSg&H(esfc&rZR>_jfeZCNTHm;^2)Mt z`GseM8MQ!7nMdI%y&>tdn!S#+d|cD`{3~05`hu#cCq`axlK;B!EHR@6c3E+nK&r@u z9jAXyxWwH!<)iswb-_!)5dW7CMy|XbBu%`ZaS$o7d3JILGx0rA()Z2Je+k8Po>VdvQt}ulpZcJ54cv-;)AoS4ZZeT%SmT8#;5me6xbau*=G#u$V zG@e?}C?>x(EbTBUcY@l=S-&%TSdzXs`ks-}tVS@fu&lyiH9ap64I3M~r0zEZjY6WU zG=ne#0o5>9Cck>6T!c<+xXpi~H9)&I<3o?7)Pm`cm%yJcZ@ z4C|x6Us$fT7>_H}$fZ8%MwFM|9}5brJ?!qX)DbJ9NcN9t^vv@*_3zYR`5OK(yegl# z%O>mS@c2a%8_L%1FPA!|bGv6zF!SRcNA{j|Ah2MjBi&M&3L zw43~dz%)hzS4j2oZ+;3~4dG%2FOooB~Kd0C7PHHIkF#LnY$#J(igmJ6y2t$BDt znDp#-868IN<&4qEg%nkkaTe>AnxU5^X7Qx)`QFYkYrntfL&5-xWGFm?pb$0z>`ix! z%G`|bi1c6mA!Suxj7y57aS7epOLlg424Iw!I;-M%VgacPYPe+#jEpIv&4al~Pj|A6 z>iP$({N4cqIm>>OwJ`!`BlB*&(Gr8Ruu+IS!0Bg!T#}Emv4b-g!~H2yR8K<#ViIq#Pk;?w#+tV`6MB{Xp`biUFo{4G>+7`fKy-}JtFwtY-# zy1zPEeYO44$M;TBaZ-DzcxY0wq^Gv$MwhvE&gE-D$3rUHzIwq6DYRpS^8Id9Di4wR zWUF`w&Q$lK^Bu>Zrx$UAmj{+d#oj6Yz8_nM$LdYD?95gKO7~MHrKMDeaS3Jub9)9# z&v1R0%?#@|xTn96EaREVoMT4Lc?rqA2_2O%I#~C6_cGNRB|b-p$$#%o3%M7DsR0*T z{9Jz)ZotG@7ss~?S$^ypPLy9>rZ#Lg z>y9=LJvDl)Z`l9riErBRJ=+Ic^+)MgSpTSwT_fRgufKS&(Vsu^TX>57wrN;SR;nOP%$>rK-%ezfa$UfB zrszVa@5<+{#`JWG9Hq2b+EXGz!l$ybcjD3%ve}dRT$4W+HPzPYs3S20$=S=!e2`gc z))U9<8?kZt*GON160K!@(2CQlYBHwr=zdU|8bd5K4UGva5gI0D+wd@MRh^}xxQh!1 zghVf|tqC-kAG#LlR)xyO(6Bi#%j77gg!XYeVWP!Sh1{+<3JKI__jsgWFHMrfAGMh- z8Zlv(ol%v7Bf>0aenl*nARkfRj5|jmbSFdCxj>iVd>nV#%E0ZHTM6luSa~*k{1x-n ztNl2KqGC-84>z(J_lY>IQ{UC3uU6B<9uxNZWVA1i{Toh~HmT2len{j`#GaiEIo&_) zjkI66(7Ni$9@FnJi$tyVH^L3pDFsb>^Ij7C;ZbJ-lYv?_|XL&Hiy(iEi`s z&!$vY+kE*9$=tClHTv)9>~HRRH;|*;H$QX7{pifBBG!n*8S~;gBb}{H>uo+=4<#R; zn+d%9p^iLbf6kYWP-o8%cD#%-M7PL$9Ube*c=R3^6?>+HzYJaHb~AaF{7PZ}DUFuN z?jM@(t#4#%92g!H=N<24Q#1uVy-K|!GyXQSi+Yw5y(Pi@3q!B{s(PY`p2AAll~jfH zhuW{{p(Mc!k2c@aIK7uPO*7=PshZ5+n{lq4&R2573ytx;c7RJr81FZxS~x-%D`AQA z72<)qKhm37S{{>g5Mk(h%(&5#hWHi0Uy9y(5XfLrSv$A0v$^R?^wfWhw|nsJP1)#V z@4b0CVsDz50pPeSL#4A|GYJ4=>8xp2R~K~H{rZY+b4%>R&GY3;HDzViabq-zPpbL< zw6(q2-E}fCHGLNrw$adMQw6XI9UUD72giZd6uCWj(kUd+!g0%Tv`D9+tNC?ax*EwJ zmfi%C_SIsY_ex~%s-~nrG+hsClQx#ZSGmqW6Nx3^hmN_k%ucMDMtPeZkDYiGSDpK_ z{~4z6-K+kzkd037Q|SmS?)V7eGaU9)i%YjDbypiq211mhYUk-#=AR>a6#u+Asz&{o zDs08oIK4YS__b`4)u_pnXC(e2<(kOjrrJNk1d5woc-{C6KP%A9&>uHm7Ylmx8x8Yo zQ1O&uR_)AtY09iFv)88ezq<6lJDgeXzL9@7Fx$; z=@1Z*?naOh5NVJOr9nbUKuV;fQ$k8YQc01L?(VK{Ui*HZ&tw1Cq3pHRInSA6jJ$0SZr25$5-Ja;~fHupP5Q;_ zr>0kw4#Pll6=O9o0Uo42Ha3L;R> zYg@0n`3|ob{)GLt>VVT)iNfbWA@2zf?CXLrX3mi#9q*KUv}?^ZmamWq{$)YK>cjK6 zMEib4wJ8~2)DwHr?5BI@laxb`xng5kNDGh!nfy^*@|U+b{$kHks!wt zQ&CYNwgMX^!iwhWN9ST3ILfX{vRaY8zP^~0toMUj=LDl-b7U7Bot=f(wz!jj<-bXN zh>OcZwSf_sH9UO*MeM>K{l3(dUxM0&BXjScL7dV2GL!txhA$;4kTG?%wY4=gEX)K} z!W%p9AR+yHK_x+C4mM-MN(hW(P-uJm_&`~$n9QAX65v}u6*Xd=lb;_3Fg#eJ4E|%5 z3nU1DCC9jjWM^mhD^2*M_82Ws5)$6;(>iaIiW#c6OIoZFaOY_)hrUw9hsQNCe^~wc zXzoSa$3Jt^niL{$`CRCl?C!6JV-6NX)Af7{+Z?jP!J#R09=Y}%fXQmWrtSWk}#qHbKbWaD=)w*KBJ>w}P=&-PI zDoavZhpabQu!4Vf%x)EA7w>Z_ty9r>yXdCKcNJ>HU=u#IHKFL)6}Z&wWSF(lr0C9S zD0z@986^7xqg=uXbLSD2`y$gJySDrRR_1*rx@R11V}{*xvLoz+wM_i!VXF~M1dsUS2$nocG!B5^ z6Fzr&2s5hf;tnTAN0W{SVsFs2kn&WBP+sDlhull&%p_3ndKyq)rt~I z>swpzt&HK(it5v3l2kG7c!x+ye$IISTM_2yZ7W;bH>V9iOYdU+NaBkqT}JI zRC(M6)IeuID%`%HihXYo2;9e^q4y$$8Uv?TTfy3zg@S?t85wzYdwcrg(~toFt&GmaQ|THD%U=+#5M&kPsA-$lMv{D*fU%dAVf87}g$dD?}LD6hH*@sd0M zlM4(CoLyTRzo?n8s6h3(19DQ=QQ!*4M3}98-V}$t#~`Zfa_iw^9g{NML4O zRu)pEOh9R={SIjhL`+zf3{lRz7(p>bZ9VH5d}=JflMvm9A?mnHW_j-`Q-XX5+Ot(T zDnb3u-6D#$({U6MI{dePhqVIz9Dpq0`Sg~b=1{cbCptbE6lr@{p@d^ z=fd&`GH^!A;dmWynjCMA7wMMYfe-++NuNKz1yEFFZgUV+I-SXna+{CeCK-D{aoYe| zeCZ2{t=MGt$uLp>3HijF5KBUj$>Z~KgB<98fRx^P94ZB$4UwRrps2>Eiu%Z^B3mC3 z%OlQng+PO1?GOztQc}_jC7OvX*N{ec@&_f3nm(^;CNGN3;l4_Fmc==UeAACKWZ&V* zmL~dCrT+--vYS;vVIeDYgN5g20Li2b*%Q>fFcH>JQ)_|dZhvo6L0?s&z{8mTsQLOx zwY0RLNsfb!4FC%KTfj16=+sS5BM6&YZ=K^@($btjRpmyZ?Y3ubiBQ2)5!Z^Nv2rue zrdpf&Tdc~IB;ZH`JKK&G)g-G7U32R-nIh#y;P z+B@}`bH`+4aCr8^Y!yQ-DwgBPP71)-UPwww$tfsoG(Hj#NUEsdhK{|T8h+=K;{XwI zxZlmI$5~gOl{==U8fO-Bl=C*+d}I?sV4QGu{Mx1Jdd;b7>0)$XYDx*_v$uZ#{*77l z*v-X7U}|!A>>Igbbtepv1#?#9-P~%1CyO533wYLd)e|MgzvSex^H)PhM+YJW#4I9= zdyr|U=sp~UHC<>?07{aVmltRkcQ1#}&*h{Y0?(MGL2+TH^m<0q%U{Fcy3E@Bx{u!87uyYX!jq zwoQ(56j6Kg3xl@7^Xcj7D~6NHtE&t0_W7^ej-Ocxqv6wgnYmePoF>oP-1(gx-ky=M z^Q+40?T;T%Al{}HlsHw>ltZuf@87@1Re#5IuU1!9MlTxBFffok#UkFOn_mnDo|N}1 z!I@kbii|t&uMPwQFbFWGz?_rxd-))jW?NH_?c?xtk0%>gp|S#$;4)ciA`(FdpVaf8 zmW~Rio-<&Gg1`Nh#1#O|eUoqc@JI0o2ypQ5=t%I;5!L?X<>l9sl5Gt~Ug#@ALFOzU zc5kkotZ`d>cn6(Ki=6_>ya*%XtijZ(ebr1=0kRMCFwFRaX9>aGMG+!<{^KR5GiEIY zp>w^cAuC?x2Sb7%AsoVpTABVJSaM`R4NMFZmow^IK(fCq@!IzoMwwzekD|mVfV22r z`hCqtqaDSrD{hiVkOPX4p@kkk6b$OHtEHwEbL!&}PABIiBsfKhctxNJzy&)A3=YQZ z3Q)!F)8oQo>;l)4U=vucJt8ltm z+3(p5)XA$yp2yo$!l7ztEBE8N|JXZqj2lHDb&o%KllT3q545oJOE%Wm!}IbO2@M@? z8`Ris@!xi-I`7qk8Y<64>`;>@y$AU-)`&*1zwjvB9+HPqG5ef(yo zr+tU$>VBGL!VAy5{`==oDsR}#(2%61WnSE1MhaM?z)SEcfbPX~CGzK_gGXXvVR`Db z&8DfZFAssx-bp!@4pQG9m@AAm`P858BK#*C^lz`BRl0$uChzR1xYm^xr%-|2CWqY0+??Z3V6J|#3_S7h8qlyh z6if`7mV-tG^c+`@&f`k14p?L@am&Pwvzh}D^__}`k|i)pWw;o)!c}bZ4Zl)Cu|o{O zxDfByx*(rZaUynfc(|z~kg@&u4dS4ZD;w`4&v{eH#kwn}<^atj&}^TcodNMX%Hbhs zryR=^jtEWhBKT^EyrE$9$+Zg!3UVCL(kZtYuRx3!1I_NDpg>6C88Z>cX*O5(tGOK? zACI9+1{7(K^1;WJQ&beOd;RVGd-Qkj-huC}u$|=V>FH745Q6=vubKt8(};M#LtsWp znGuH>IB5M1lTlXK>?@(K?#V=jTFhEhVTc&G zJ-)zl0gG{kaubNY-ogJbDr0sLjm6vR+Jg3EO*U4<1PWm(2M?0s^_;tq3A6 z|A(|PFSwH-Y0ZLWKFq-76%^7wEpJ#UtS38dmc?fXPkj0;4rLT$@tr?byo^c$5H@{T zakW^qnum)YlRVHbuI7Jb#Y+MN7C+YP?XUHmlv}O2hsLKg?$YQmslBeMWm?M1@cux@ zmW%nz%3-8-_kcyA+b*+lDzL*faD&mfGnT`ZtF7^ahz33L%-|8G+F7k=FF(7ZnDm4n*cw+g24y|zfsZI@XJ)Knk-`N87 z5B01_HRZTyl<|M^BS$zy1GoP!8D^|5w$pTXb)Fc?O};U9TDirrqTe%Gv05r#X1X*? zq`c51-Z1xIS#(F{Czc!%!LSP5#Boy>?G7~kSO+a%TxpowFD9^Bs5Y)jQPlr?;;AjF z!4Q4#bD`_wXpzwlot=N8T@tQ)1CP<40UEU=f=o!xaPHCqG#gY@7zG8BBO)+9=Y1*3 z&JKjH{UIUYao0oWlA>Pi9UUQPfK^6PB{QjDstwS7i3mh>UibYw?CXzTn0$5cgcy6f z3$jg7KF>odXsyGnN;Y2;hk)R3N)^&roin4fwDi@nHz^y0?kh2dU?)l_kblFtcK7hm ze563DvDgWQU|moHsdzMIs+r<&5s0T3dsuDuOIi?Um>Ab(|urT@aw0MY+GrfG5Tc2un(wTeif=r1=Q%v9mMcn+xO`PM-#Qp%jyh{X|>P})95zk zqtb=VbKGG&wgrdlqnvR@wq-R6t^VfQY-)E;ewkWIOEvw^~>c5Vu{u<5AUkZv&|~H z@$O5{$B}XNFSB)!I4-a6_+MSg)mfoQD`^WARO)&D#A}rd=DO)~vnm^l`R=;s7l(tk zdrW73iuZBHx}AOe>(!iIM`z$HrC2QCU-RJ+^{zM$zdOg6Vpl7X?LjDWOXOWa%{PQg zwghzD%3gCqB`F`@)+BOpWf7L;e6vLVWNuGY{Isu;2V-nP;k4iOAQW|%+Cle@TjRI8 z-Tyj<{Tc#8U-&g#(VlJvP!9gF&8xE#9yR8?BYuNzAy!LJ_$?^m#+Xa? ziqiLDp#Z{WXUmCpWYVetKOW6K{IL(?mtdoSJj#x+KtD&7bKA`1UX!^%y*2N zu`T{xk|aEL<+NK0|08hOAc98eVPc=EZ6<0z?MD9aT~oXAHBa4?b~rzW149547%#v8r(VJg1n+yI4mxmhQsx+ZvYe_ANS0G=`k#ibV;4UKxXNBKig*uMrkkbeHnn;0df@>wDiwp4jb(}MWNr+eIyfpyhGhA z6;zrS#-C^?ueSKxMq#Fv=0=3QeuK4#yJ_*=WBuvz_&yzbG3C@~|K~f?D%GPRO%qjN zesqLR{Q<0HdB5ngD?fB-(|UOEgnmCVSv*VO(x(f*e~|2O_Oq7KfSlghWRUiT*30jn zUo#uND%bWo%J^xU+dqnwPM>JMcloxYGx+X%A<2$DHUH$d*t`z)a>WkCNJqVYNWW1z z_{At~SZRI-Dt6flw{rR|>;;17@7!kHjZSSug=>6&k1dy;@#Uo+2Xo)|Camzd(4Ia! zSj^a_N)G4ZZ~l>6<A_I+V(Q=PsNgVvf5Lr7D(0{k)j)J z9?ke1+)j-Ca4`4$rnBjT!B~8C@@uJRhfz!Ez+6SMcXmi_(?>+cw*8&%yo^~9O9{Vh zFwK2`ASa;n*m(phO}gzaWeuOr?yY>?uF%jj{8`*9Zn?ow`+uuNe&tifr81e5W5jnjJox*;~EyxWB0`D))=aNA})D z4tw9<9SIy}0Sy}to|)OOw6uG@zF z@v$rJ^9zP_3i#jl-K)2{Uv5>rKJEO;UsjW!6jD+bU6^5@u)Y1}(r%qg%RM%^70E-< z;}E6d#LlG2o3_;MS5Cbr<>({tB(4*mr>=cQcA;Be8Yb^ObIBG}a69GoU)1MkM>)G6ae<%=S}n6$W`lL~o5Zv@iB z8%H`=#Wxwvt}Y_5w#F-)+=dw*V%D>t~2 zSs%KoaPG}}y5kv|!(o@>^7G0@?K(Ijm2BF>oy$6>{ov-3P^_l0<(NFBwqQfc=vrjq zl(8TMi;(_%nWL20ai8K}dp7f_CQr6EFN;c}Etmg%5bF<^JNT%suiulXGK1WOO6EsS z>bhmQG!yHw8Z6ATDI%6kpKM+0Hi)BdA=c3+TCeB3LnFi|-c^}GCpJ}`*q@QqITTjO zghtj`dmcS*VAcLlOR-$&U7;DT;>}gorqGABU`va=zt2z9#_84E1QNrryu03srqntf zs!V2oqt5cMv=tiHBTb6;VcfA5xbuXW$M0JDxYhU2MVc;hF*;`$A)+V z)=q`(<@MT>$nKnsYmvvt2!4vsWon0aaeb44apXJD)r5wwifV(FwSF-JxBB600OSx^ z8$N#yh0eCEoWmcO!9eQLNhM8>+S*-PR~I&g+RQB%E8xCMg;+=5X}VwsV8u=`@A1*m z5`e_ayJP9ubj#jClT9M(`0!2jH%F@-Bj~dXaK)!O zEG&NHx1(J$dq5KXg577Ayd=zKIX1%1&c}sa;C37haQb zx-yLS$LXq_9b<1S_g8P~0B(Z)S^Tm>zpZ@+`ZAqUhW%0M)h0z76-Y>k1 zDX9(lZCSnX?Vs}rE?eV9so|zi=#KUd-Rrgyk72!%# zQJ*4drM&T==NEHiw7qddsWIeZ25e#@UQC^JzDI z!=b2I1icq2rRaqi^Lu`pHf5RWm=y7Pe*r9}{*xz;tE;i>?kM+gNyu7%(TN{dyK;K1 zdz09CziqB&pSy0prlf9*t$kxCdUH8E_0O}v(QwNiWzl9jwpYnbJlN=XVPUv4dUoJh zN$s9|dP;q21=71sJIuxC;SQW_`h~w69b7w&#qQ0ntP=K@3C;iP=eFyw1Dov$FI??S zN0%EL9wBvOI?FsJcN6c$6IwPD`8Yar7Cc|ZM7|0rUUjJo-G921$K&IVvu`LYs8{`FY zJMJzBEb#8#yLV&K)2H(W&+ZZ${s6WM6fPizQhu7Fo;ke6nesb;yvIW>mJXVHuk7rW zf4oDo87q4SU04Ld3T6swYHEOQ9RwaTKx{$FU3>#4zgS7>kG3|>`9jFLkei#!TL22* zLbQ0p?-$6!gV>A}iPldA$Ko=qFkEdDPoGW()vg_W)w;j>i}u;;FC|TPO?|9vte!5D zN2FMiMf>fEdL)bQt|Ps-^4X>JMrzfo+9kdgYtBP!Hq30*%D4CxNF-)-LA*}F!G7Y{ z>1Bg_)>Jl1w+yvue||EN<|K?cxRg^%lf~wcw2BTEXhfQn8-X zyg*0mdrcI#$@ghu6ZwqQ(b3tgb%@a8%1y27cCw_B!ZnNHw=>?!A1m>>pXC1(`K1rY zB`#1SB~ypp6sgd9jWVRyZ`{W#WoP81@lU*|3{F-PMY?79r=&Ki`Ro;19T`1N?4o23 zrMT(u&Bh|X6Y6d6f-wG%!5O;++&Oo;*)z3Yt5s=g%siTNQ#9((taz`(lcjfU!A2#O z$EBhE_W`X+6QyCMCMbte=j)X3UF>B;&VpYci+u%8B|Mjxhnxa8b z*&=|y7dQS#xq&Ku#J3Tb+S4xwC!N11^Vaq-Xi^aH(wYCU<<<4s*uou6-TYaZoFqF;ibNe!1KHI)n?DWTBy z1$1Ntr8otEz+oUNWo5+#Q$KTabLf(Cj?D=b?{_^kd?VCwbroH&1RWh-8=~7LCP@)8 ziqOA)^Ty?k>(KO&lmCdX52IpVKChiSi3qe++DhLqWri%5AJ%yd5~!H=628{kZ=ZCJ zx3L`0HEqRUP~^s!uR|a9^JCq)S@5_XJ}33gA-Iz})%r7xWWJ-1YGXn;$#qA^-5QT5 z*XZq5W+8KiBcYM_q~XR#p@ar6@marc?mIGy42w@CSo~|(wn^*Grf;&WreD(CdzD|Z zv%D;9XV$`tG+4Uvaq%UueX6&*j>hD)>E)J9U%dod!%=pb#hZH8^l~8josoPx)i`bp_ zUo}kmG7FI^exDO^5pJGevOfq#Kgp@*4luRF+an=l$x2|m>8#|XyWpCi&v#FW+FhDZ zYG=hX)yj`barfe`?)lbm?$2>e?$z}nXW#J)!NTLjviTji%3l?ssQiL48XOk#zwj)+ zH?=)dpj;S2YuRMqT9&L^c>nAp%k{-&%`eY6H1lUw%Qog`Sondf!fPM%9o1yYPCufb z_KH*FxVJpTD^4?XIM|}APh}b-5pzHEDT<-ybsJOl6zIb_Z_jm5`m^xQXEMO>amx># z`T|{yO_ht=2RUw>e@jyqM`mU`-9ra&jn6z_Gwwl8g1H{hI+E-b-L=(%TTpuzp$^N<(G36Iv%?% zvPl_V=d-X<>h^xWwo>s*!NO$O)p=~HQ9Dbc;W$FyeYrLvuKuPC!)2Kv*U$&0o4RvG z&MBJ9kV|4d*Pga3HSw8;47yH<6~mRXpLwTdPB#+cmr}0~zs6(nJC`(i0?V~I%Fott zyBkM?cKgNuJ)3GJCTj54bw7yfDs9T>G_scNnS63q#8~HE#mLV79*yn&LVmd5CJA}O z`@z7B#t8hvQ7-kE0KJ^t=8zBey0JG+JjPk?d7RF zNv^SQ+Bik2}Qgq~qnzSkzhUFOm|` zxx3pls~!9^V=}Gtdm_<5jgR{WU84}LA${UcP!kHz@_<7rI=|_6wA5wbnR$RI8qfTiClh=i&y(N;d3`#As zjGYsD{nw)7f8Hdi6-*I}dEyyW->c}M&&>{`MVZ(L@A~?eo3=Y7*xv>dZ`3pf&po)E zTZ}sX(#LDyXEe1Yx~+7wrnOlpmP20gGU^2u!SE{$Y%V8}^4lyunA^0?4G)ti-mArR ze&+cblait$WkBeZklqy-^AyE>U_`TTTNH(>drB^q6H`x%y-r$7m+tPpW(W0H)34&S zxYF%b{zu&VHTJRu!eK<>59m?2sk!ey@4GKE{XLHVow)w|r~msMQpndG&Memh>Q^o}VkHH*Vpied;Y6aIypQT{WP4hVY`V?@ zbsHl}f^ml2Rt8KG7I1NTld`SitCcage`i;fkmnR)<;OA178Y4p$~-V*h>|pU{c>Z1 zyxoX1Vfji}VCY|v`iiuZHA|B7l&hV?A{}(=fdJtFt)eMZP{cv%*0u>g&B)9aqEuKK34M@x_eAgVDX~84dG5mxVT4;=Crhz-a+G1)m|Ku-4!K4lH&qx}o zr)S=w>ER6+$K)j~v^L0b^YP{s6`Uq67_s>us~&koB=M1RZ0(KnbPx5li0a{uRxc0` z{cay@d-bUQrHb9d+H)??d3SF=wqe%kjJ}6@ygYH2ALRI~qs%LBREaI{+)o3!>=bFz zekT9<-pSKyj5Q`0UxzEzO4N|ecWiF1K58M8@A%Ta2brev(|EG&dRS$BdKIM;F_*1S zIt%*CvkO68&B*Lyv(2i#+BYBLzMW7-rfGYJ&~q|y-63Se>9K@KDkA_bAdeRmJ0p}= zQL&tB4YIrxTB(Pj=KR8fUX9)J9j<_uClI)I=-3bmxC4Nu%y>zdA6>obR{$Ujz$DBq zEHLYA<^3I+hSyvalQ`c&HEvfX^)PjIZtfjq0<7)n*B|tINRDh_s1vR2%3N=9z(XAn0X>GTPy0}a_Gk>IV6B1p`*pkq=huhTs>W9>H-$`MU$+g)|rF+lXV|V*L z@93^G_p4flpZzD_XDSMk<-7ICYYM?ByRD5%!vc>8Y<5^-Mm&=kd8^HV_`e^(W z+i%+X?52JbDP5fI7$Xej@QqFSSm%{opxbmh-8F%siDxuDBcq0%o`-hA2?9W%09_7Z zemgQ@*Uib^z-v`a*BFwPK)6PI0*z60VXoMpVBj9 zz*PepL0wl@plk3*g*`Ej(*k2#{MbYse~JND&!AdB#Qt-fGviDObLt2NTIJcic-)>) zK=Mbf(aSV9BpeiaE|j-JX=s&s8Y6#h_c$8vbqZiiSX`g|X>%{|3uiHJ*R`nCHmPP! z^4!}AjTE_}3umz*F)mJ#_P<^wXSEy};(x~7e%(sBOr*{~A|0ejHr%JYwl1w`+Vg{M z<(8TAgP@?FK2dkqvgB~O1to4#{cp_^G}Ye!92#!p;^2q|!rDr^DWM3N1u9u4*bnuE zux0`<3Y&?le3h(y1a8dt>ioaS;5AfkfKL><0!?#LK574{N$REE?kx8plNL7KJmZ!KJP9M2NWwO8j9eA#;o}P8l z>NguO$ySHTlX4Li&|G~Sw{PFp)YLrmz=Z*PFrfQ@0WyFn83v?k`I?QCF83|-phE`x z#IoAj1eF%QTl@P<-CAG6KR`p7I9Bd^-(T$tw=Ej#$M``*b$@g;o|C7EAE&uKWr)jE z#W2i|eb$GT_X~D20r>)CCqD&j<{EMbtp+xZU`zLbD^n}6!(!J%_QpeX5GnhL0DWX; zzJom%xc%L|y`=wpNGw2!W@l%YS^WMa)@ku8sRfAoE--?@9a!z{?qcr{_df(6>VKs7 zo}S#VhUjo`a1h~TZ*R}$UoE1n$8rtrd}aSClTJM2>qAB3&X zF$Wdu%EyKV5!h_@YTjO7H-%-)M%*F<=#a+}?j=aYo)8c4c%M1|GKZOigR&iVtsUru zggybB6dptX36{KO{BA@uy!X)ze96+W0bB|sz}@X(xPa*nATu%khL5j#a-eJT+Ai1P z!%c2z4}uI^VimD%1h66S)F766_X)tyq1XbpZ7v^0_zW11Zf=ZJRG(FNJYdn*)Rbo9 zZ!zfyd4zpoKmi8mk-qbFZGh;(iau=M0CU5*O>Rz35MmYOIsSmg(#H07RCF{J0LuW& zhUlGGTMOB3G%Dw{f%_@eey_-o_3c{%kWN%OUDyNGjF^}hkC2eZ_Y#`)3(1@&ceuE? zAPmH2WQfyIAjQ(DY3YZjv^e}j9xdrph9zI(!)E6HpnO!QnAtfwTqdo7(~GHeau8QI z{jR-Xg6t`q2i_1BNh(L3%d(G5yI6lDFWFmO{{D>531EE41Bih2KI&53%Z-9^#AEvE zhUbFeRn>zDS#+z!v38nww~_9V?xv5;(kXp!mjm_T;p4T~>b3N0xeFJCA+fWZu((>s zhIRuRq;kEVO>&Y}gs}rn3be0evh@7?uo)um^4)70bZRu_XtvpQ=3NoiCHZZ*(o{NW z{cUJ+vd|?$7>AfxPEGA0?Ck*GIdCNayc^gd5CWSp1jk1GJZJ^?n}&mfqw03Yw>!^) za2qJ8GGC^{6~M#Ce@ICQ%mvcLP2ZEsK~JWjfF)HqFIMHO`uQX;EaCghQg|R|4R&3f z%&166+y>>p^&%z_&%9i#f|6W^5taxGXRC&@A$kTf%)4>V@wHPA&b$HQWy(upnVp%2 zE&0pRvoReW2RsX0Z28WIZZW_iUs(7a^Z^bIGHyh8kB=wqD_ytrqbS8o93-g&lZ?S5 z0r2xa>#v^>(D_o}MAbNxvFEj+?FJhr@llSGhn}JeAK9n@!vRFHK*$LKVo#qwE%QEe z;^yHYCMVCy%R@=|En{cLZda3nP{$Ay3>&v$U}OyW@`VPtB0zEgfP&%g--ks+WLH$g z0?4Saae$k~fLJcZ}qeDFZY7P#?&efcH@JbH!Wf($G&{72#g=#N)6HW(?k zUjy^Iv`}A2}2&$<4B@9UI2J^tjq)nWGTF@*Z|+z(9oc2PfOjt z3A&cxaUzGf>{41@`~YAV$c@3TRhgEtG2PW8CZJOQ#%g$e2qhqOA8dgxM1~2(50FXG zF)|L%%&0)|1z`+M$m#6+%Xn};?HwKPy<6e^fOl7G)1yB=Jp4X@Q^%WpgyDB0%B|B= zcX;1~s9Tn zaCdl;p1Hopmqeu&iv^%_y61X+SvlfGAOi@(L8ETJ1nvb%fd4LxKH}-=@0Tss9v&Ud zd%;cJUM&CYS<*p$)%le#8K&&l<{bH)R^SXsNRW1QhpjYQv7O7#bdi}1!!4xi?snr-3I#t@a^4# z8FWFn1#Ecd)G=FtF%VnQ8yS$8het={-e>y*Nx=X0{re~Q?wKP!Mhaj?!r-Yu&4mhh zPBOVb`ohR4y$TcCG-|+#7w-Mw_;|icJTWB9uzo-bAjlkmRDwVVuue+yAj!(ez;zw7 zsaAcboTCm~LIK_8lEvCtgI2%=1H8OJt}cxoHhgg(KHM@)6TQ5ipYrD9s{B^0bN{7X&dPqN0NFx8NQAk)$chLgWJ~LrhZO zilYZHV=blx?D;I%UahLB>F-kfG7e&vaD$1hUjkiMxqflxgE`0-(C!5w{Ca$CXwoVw z4(_~OgF6@4LalxgDKW8$yE_p$05||>_C1xAjZ03JgJ#0JCohZ$mP^(^wq+^N7_%{V za?2GgBh#T^+-zd&>IEm0=n6bkDAw%Bg`nplQ@!ifd{+!@COsCccmSf^KQItk&zC+B zyQa(f8-&_6VBwH71B(u!@C+T!Q{my|&3++7-7X6o0j(c%`Vk<WUc$`A z_Ox(B9i+!V`9w=AVR31>%y&x2TMSFXj{o`86b6<7CrRY#l`lxr0M`N-YFuKXETBCp zqC-G39E9YVnVDNQj`}V<0orT{_caH=fkj1ZVkdR|j+dur%zTi-C zbO!SS_ku747&L&7lSa@2Nnwe$gGlDf095M0+Pko1xZHR$jZXSLJlqsCwSZSDNF9yZ zP8L2MWPI|SNe@{PtS7vDKmh`1FI?->z#o7EhKDNYbNz>l^i)O{Anict^>3S*fSzt) z&s{P_77kb)m_L9V30x6qCV^#x!YbJN!ro+ zIP~L#1h)U~p`8Zcz2W)cHU~yRb>$D}U&Mp8|BHdE1yGeSU07ZKm^WlgO!4xlj`fhi zDCcRc5xKDe)4|K$k1&l9v(10SNdzO9p!42W-}ED7kTf*x?p=5hZSGk7;)?ib+G4}U z#m(&xnm)za5Np7w4o^;ii?I#V#z1^RB8k>!#$Yo0E1DgnN)&%eAc}oVZV6Y^SH8|^3x9iymF1o^ITwZ;c`$-NB z5prYS6H|4Pds#71aSfCd1I`c+4=>Ob^&tcY$Vz}TD^rPq;C|_7Z>CfTLQDdF1f-bh z2-h%Z6(8l=KjomeA(>Vq_%ezi909kxh@= zR&WEfU?87RWs1R`R|d-jj=Cb32x2Z^lY(Oc8k{1d#!p~6V7dU}&CbgMG1NW?Dj-z^ zmcjNgX3S=f=z)v~1^?ew0RsBmp$X5R>uX>C7AlHplmvNcPfsDCv?%aDupQ`HPY!f@ zK$S%iExVRi5(=A3Ko;+DI4H}^%1X=39OgFTlUQEPm6J6UKVqFW*qOrTtbE@YtbSwh zvBoWsgGOAHM~@!V50An)?faXJXY%suoQQ0MeU#4&R0U1P+##6(@H*HaOS~f34j42f ziU+wfso+OpX%T`T#1=?B5VtTX392H*mBhfryrYBe0sA0_M_3h1f=FK4V!5GKBqS*a z5#_JZsUT!Ol%oL2HZCr%6s$MF55Rcvz!9hx?lzw(!4E-5_&`pAxU}Ht<34`Obty^# zS9dGZ*WXQ^4^9M?+TsbkJLDb^mj|MZfGywW;#f^p6(N8pmZ35iFNvDj05ua_Wzu5_ zUicmm2;unf6&V6+p96FWQh*$@UraTVN^mp)KLy|^@vx!9@tTDDyxAGg3y1lgQlKTK?nSjU=Sh9L<;9SmKwQh;(4$+xwas z-xMIBfv^8Z5nn53B^92TOA0E~u*gVy$gFtz;OODv!wCScnKelnl{!9W&D@V5aH=CBC2gB?0PU8j$*uHi&*h2zzref+ zI_dC5`P0;vjyyqW?+5%2K0bz^x|6k?ofY5*%_%PjZoyXI`xhy+9QcjL+=m7chi4V0 ztgsgke-xL5l#C4E_`&dCA+EARp)HkS>Cxzpa>j!j6|31Ws)W+ah_Juy`S1L49HUvz3QUGTJ!i48SL{bB;fZ`kx3 zu>OVsy#s~~2uzPWYP`=$>U=oBIDVA@Q#C>+3$Ej!wVwxN(f98pA#D<_uGRi)5Mrmp zBO>U;#WR3suuSe2DWA<}*g^q$qr1as)Z3b#p63nYIaO&>5@N^Y(Z45& zUDQ)?!Sc5K!@|%YGljE~`Z{U|^yF|AfVKxpDSTyc7jDMp=5&yG&q4eF$>afdh^aDJ zF;F!8_dke-q;$zigE0MziDLQ(3X7bk^a*kjRfwc+<*g+>vL_y9#X6X((u+ zi4z8*5y4wett!W1PkjNxJo25}cX97iTeJc%Z6`$b_$X?ETfpIs&e8A#_-BO zVw&5unoZ&?goay?jae@4nJ*)*fMcQ-gn{_@r=Zq2b_$eX(4r&T$wo*^(v4(dFp`u{7?Xb7l6 z+FD>gCwzDfdL6-{UdMrr&FSy|m$v?+1z{b^o6}CfKin=pPP8?ioSX#LW4Y9ma6cCp zJOa2y8K7CLuI968fC35rFF+NUrwX~Y;;v^krfmp&gvXoMPBQ(ZlOa^Z107vix|T!W_wR!#XF zE+ACRK)D5R*Lj~+3~{yJfgQANNTWO!V`Q0FSXx2HX1*OQ z$83rqSrCzq|1$$$8xLY=`uZe%5S#npgux2cz@bP&OWTFGchr-6NKs@v${`@ zEBWscRNhDPLeDh`{rJL_h$R z*jM--fwgadm<93!kiR42Gcq)U)$C7v?14!api2PZ4Q_R12c(Ly8hyKjV0D@1|NTT@ za77S@vl&#g*)%}61(73`8Wkgc;;91|&{s_sARKDzIN09@wLoq&Q*S3|KlnK zF+c)Hk6^)7{N}8GXX1#4hUV7l)>c|fXIwJkS_HO2MF4uTKpMtm(*S&T;Pcib7z2~E zpq3t3a~ZzxTvt~okkud8ztzphzfBWXb@u&fj--SW@kSL$_u?OaGbC?_KIg!-@pJQ#4KSU1Yr)S zOw7#i`YI`0I=Z@{{VQ3yxia8CLcOTr76GS*-VlpLBlI&MwGPuRd$0Wb-EpdeG&+nm3AtjDc}8j0l)_n3JC|agWPA|p}2!Qw&YHs zW!5X6m26J1{2FB=o}W`7x~L4zKj3&YS%4K|GI8J3M+Vj45VKXmbxT4=2=@C4fx*u3 zy9@KCuA?ItNu&&9ZEVk_&Ln8h|(e5!gvd3&HEPd;dRX10dJVX>1hT)P?L0v6`-}%@U6YH>WQkD+a<7 z_~T<0FVXe49uP+N-ACMx&Ha8ZFu#I=@Tw|a=-stijDr791NskYR@V1W zGVt*65s>f`VZ?v@IP_l=D!?BNtR~i|)DjrJO-fNDf8hfmELaXIaHGSB3<{dMg-$37 zF|TSm7vOILNNrF-nK~zAD3!lk{AO_Hh2N##mw#=klQ%p#8P{Idd!zjQU0F3`*VI@y zevU4iH#9N)Le#l|%~!|#&%y>B&3CZAPH8FX?T^?`qllmADC#ZP?~4*(T(Q2KVm#Z% z!5=K3ay#ETjVrz3y2|iPv$q-YoAub9s5$HF)piwWqA>fSkA@mm!VZT<;OE@U zsnWIUjljm=#LpQdt#kd$(KqMLN%vSzvt}-l?&0ca#1cy!oGl#Yh_sztpYe?OKfWBN z^p4wUJR@_=9T)zl?JWQ?=LFGAOZxQ56lRF2qFx{2*FZVc6Nr=$YC#Zf{;(rQ-A*p| z>=_kwB;h*apkD4T=l(P`L98_aZz}BjArg`8$I!xnb}g8cyzImIYG{WH0}}+SBOn<4 zI2sR!B1Dg&i5QaMf}YL7$#EBr2=_Fh-!Gl_v7$(MXh?GvWq)bW>{;m*acQaz!`HAE z3#FG2jn7Y6*sm8k&hiNR7DhV{ei{3uiFz>jUN@E=Ou4;wR8p=uU+`Vu;*d^h@uo}YwVo<_TUL2AfKJe!xAJnc}C zKMlz%-F9FAM^^yM&!GPibFtG*8QqC{?yz~}Dd=;~3+uRugc8vK5){mL(5G%U%+fAo zW@36V_(hrw#!WV|^+`!YFg$D{wQr!N>5)(E_nWiBWP##Zr-Zb}mea>V=({?)i=air`t?qXSyubdT68883Y&rrSI7Z%xL zpZ<+^nZW1@t}B191o zkx&stP#R1OT1r|$8fgh7R1_2iM5IeVKbn& zz1aV{@B6y0Ip-K-&auf`|Lo1f^VZv=+hO8eK|eyY*F{_wiWW8|f3${0c?>9Q|2gk$ zr?gkCC_Es=Q@v?r&}E&=*fXNT#VK%fDg2(vw7*gPrLc6L?Ny_bu5ra>%`W!`WS0|1 zn$)#p*oJwwMiW8;MYd-g`%A)gE91o@6Aa#MFLX0yFtzj$pVPA4?zBo~ZB*r5`KtSRb%CnVQe4xcJ<<2!@a31@laS@3 zzQ8nJrVFmgDE*KdAj_$3jJ{5Tv@h^As7v^|jv(`2*({knjZtQ80w=9l|2r1|uqf)J zvT>VJfpUbB#R;bHp|BOih*Kc0R*3HgrY)UPZwI^#FrLP_g0l6~cR zgIiBb4omAFPqL&QX5+O=CN)3XpC5h7=Fu*RXy!?iz4YGm?k;n^yKD4+YHp@3vSo-U z9@*)|wl%MPVE&cMDi`Z#eXSCEe~)T5=g|$>Cq#z@L*$54!s#iEn9qIv^VEfZt60M8 z{BrZWtV_*liG6n_6I(Q#++bD{UHY;=zePGfrhdMBprp^vd0jHGz1Y2XV`x{PGtanm zv@+!%hurKjma`j-vNIb(+783(hUYJdY)w4w-eXx%WSFU@7<{6sS+^lRMuh$OilL(z z6Oxl?wAO+c#ia9^pFgRI0F5asDW!qy!M%gM8c7_@uc%E55* zs)zN$d!g7T+m2h6ZCOV$h0dIMMmEG5xvn_#iz>F`b5YbtymoIFqNNEf~0GoEBtxX4agFEwpzUKP!)mO>0{^T)e!lF1O>;Ps8&$J-Rm; zLT<#Kf7iS6yCnULxLX26N~+3J-Z@w>)F=Vtu&T%C_@Lzw;labCRKI`-C}Gn zi`ZH%+oA3gx+Z|9S8`CU7XRV%aJ1?zoRGRd%m(A~xwD^|Do)U2RBr0so*?NmwGy6fOfbAq5 z5U?-5_!$Y^ND%Na!8JVm0=>jOX2cxTY}3O)Q}!3xe)&Za20DO^j?8N4yHBb#a&J<} zt5 zs@Z8N!q0yQ1dpEHaN<~N;*rCL_dBH@J$x7-f^-7e>pZrXKgP=qz53Qfj{*sHPN8r8 zNc{828_<>y-<}NcJ*iFPr{-E^DiJ47IqP5{Ez?i2yYaVlpl5!=-o4J=A^W{OI9@ZB zJl+}6@?1WybS9{LxcQ%Zw+D|zl+#f@JtEE(N2*OkrcY`d5%Q$&`6Y(?O~YR&D4yJU z(PLQgv31~KLExWw9{SSrduVsP5q8P@q@2W0Y1A~hAa!nh>7T1FO7E9`P~bg3e$^!N zgHvw>jajRJS$&o^$EiPTyli1YHcoyL-rsaCUwL~nhbpJiTf(4RrwK#(_N~PRTI9_U zUy9?`xo|jli=^~J1W4l8Lg$MwB;v~MpNrbDb4zS`Y1ge~`2*_`C`1O*RTS>oA0+JN3rWR`(~2 z-;d4Ozkl~mjQxMUmDoJ~9V7X{ouCvXbDQ;-X?20ICBY^W2s{dPxOSAp6zb?>(tqmX zWivqL5Vvf8m(0PIcYqh>j+F}jVoKXYBrqyk4#O-4?*;&jb?rD=_p1G?aTW$*T*YLO z%pfbE;y?q@>cVMf^5V`H@HQY2Q0sGP=2P3&=x3zeulffA+cCY`|1b(fi`TSgjtdGp z$YfQXr6a>Td4MON`?+G87L(#`-~LA;n&;09Kyc720P*jQW@l!e6%mnwgb<}-`dpo8 z)GuQKeL$cH5rj7Sh{eB5ZGDhg?*}??IpT+Yya4-O;?DudGQpi#Y-`Rt!>}pF9Vr=Xn?kVfn|(p&~V%|IXq)3nQIV z41+8|!NE~UNz&tVAj0s|iJ)%S`FE%cCLUmPh+9+BZ6X}H&}rxZ1jDPe9#5SIWrob( zV_171qN#cDDx3D!d;o|E3@f9_`SsY0&F*p0JxiI`R8nxzKCO~GAt*@+e#_7`V9LmO z6vN~U1ufBL_{c6$CZPZ?S-P32FV{$;+(*pCj4y(kFOFseX%YDstfePEhHoE_I;i9S z3X+@dHY#3tfw=n<1G7@l(!wk+7G`Fc7htXUHH6{Gp-$FC4!h_3$A^8i%Dg4xc7?t6<{RE|p$7cn;8JwAVmQ z)m~tiLck{MI-%l%v2ZAciJEEv%m6FFI1bS6WnL_> znC*@F?GqqUfNG`c!jK#JcRJ*7kRrd|&+$Ar0ci$75E>Jsr*@BvnfWO(ljB=tA17<} zGsj{e8hH5_T}}b4l%ryffio`K>(ES+fm^`YiQdmq>xlKEASxrf?|rKQz)N~YvWJ(_hwoM{P7(k~$c5o-sLlO>J-*I#lfe`eKrzhd(y5)eQ{? zA+^Ga0a>+2-~6aHiDr-l&H-A$OM*@0A)Fu+o^+#Ax5QgD^b*!2|O1X%7Gi zVTB;+2UsD9<@C&+g{|B%QaOPzZ|l$@f&+|chb1IZ(cWU!pw+Jk?;~L@U%z(sD%>LJ zPtCtnL;BJPjm}xRa-4wx@CXdw zBMO1DXP-2Whbo8i21#*h6$V1luxCLPM4cbFAh<#jRu~BUg3-f&@paCFjNa^guepST z9;q?KLx74qCk^Nnxmfy@z=PHoA-BM4#Enfi?=3c}1jvhdl7oGvuK3fbw{rVq4?F$<2?Wf7aDz399S=iR0#yw`<$%?QHB1D<5dt{zm-pk=ZJiy?d+XjZsK;9>Sx|zT#0++>`2X@(+710-M(^eeULE3SdNQJ&P zT-fdac!Z34vDdZwq{28ltI=rvmm9-`a_U>Bp07X{6#V`@Vfeiy@N=xYd*of@dv}Fg zc<|Nqg7wCVC1H<>y_Jb$5fW1K8Fm~f!!wpwSC<5?f`2x~u8Zr;^b~=y!)!pbrI_{< z9)^z@ZV`b;|9bRES^o!cU??4NWoC~E+6O!HSGsXyCrxr0U>M0FV8%#fo}yWhA(kY+abFzlJoVqf7bFuE&2$x(Y?xr zg@txZ4m!lGHT3lbDM<{DYF32%QJiRil=*r1_^x6O9GKf&p|T{%jNzH*=3#MKIq@z| zCoHCZ+k&!UF^FZLXehm#JD$jm+zXHs?h!=4d-4ibJ8Bvco>M)4PQRe%GSTFi@F3vP zFHCiGoQ=!yL}zfB>&vn^8Fyc@U`wfk{OWg%?cd($h$w z-gu?ucoQpuHNSNdPyirKSjH&}x#jLbY(xo!38WJD?x7{$hm4GD7DB~P*vy9)7mE=g zD6~Nvr))xPku|HVsQ4VeIZ3(K!o3CY2kRQ2qm@dPjd6+Nzklz%3+ImIKOKJ;#BS^w zf|)(`*?dsFqZ{_t3$HypckCr5z9Ot5y0tP0l9_`>>E)hpVA+7Wf};^c@=jRR1t;+& ztuT+*7iztpqQ@Y5%&A=seYA6lc;@ASN4QMzbms&FfF{1&S#N5)Z}(0DbesFA z`7{sDT)3wCUv1pg8=(F`a1%b;-@oDo>7lRF;VrNl!UKl{6=&~YrT6JT<(I2xL`B1p zqoUBq4~@9s%Z%uXEC+P(eLFqo@&`CP-*|g-f8Wxv_WLnRaz>Z|yuVHwLH3L#PPk7i z1FxxRhEg+gpX__RKS`ewxdTKO(DXcQoghEmV8nL>ivbS{+RZ%~S0-vf&k)ooAgB>> zm>lx#BqS;xXsSH=H}yDP^H&H578o4PUWjAMdIIreAzFJ2nl%eBT>w_#&>~nEnI9-Zz8?D&r%(y1wg-aYUcwlJv=U_w1SlTM_B|e zcSvJ#CgX-mNl8IP_Bo~Kd$}Qns_J2=Fpi&jv~$kVUX(FZ#-L5tBufqa0;H?F`RijE zwsQm52wM8vx0|kSb-)?2Gk+vgFX?t5ftTO?1%XA-Zu%$~{kus2n!PBnDl6#CKeSFb zY|K?6aZx-Lb8rEAj*&=r#^bE4F90~B*pH>@ffS%E`vE<`D?rQIAY5K{>YoduV`MCj zlb-oDh5f7p_6btIR7=RI8x2p;k-?%5oEc>GZ-b2u?%sV;;kLKW*wVax{vQorUxIW` z)a_s86u{1^p`jts$1)kJkcNTkg1iJ-vRG3qNbsJP^MA!5%x37lo-~jNcZnx zkq!CW7*fFb;_L;50D03noUhbUoaJ4aNd7OFb=`1s5;dp`EyWB}ug{97@Ts{dUXhCs zYy{K)+}LMXiI{3=VxmCUw1b0#5cHCekleU&1G?CQkVFGy0Cs@~(eNf0F>9VAz~}Az ziue3qhW$^Ek;z|G)xCL3itI5HvC3;}EL;Sypu|N|EN)~5&`Dv0+i2z>jw$Gg!c*tK z$l3^XKhRY8yPgKFU~W)jTibVJtys#Dwam##@&_O{L1dqwEu*kr`(p&PI?b)q(5t~d zilDiJ91E~Y$-UC4v`WT7uyV+6we-(J@KX*yf0hKH2F@!Q#XfSg?_^BOJ?!Y1VU_eJn(eZ#mlifVOGi+dLwbTZ z(umQK-XJhWPJ2p};nFZ1`Q385_4B_HRUD$wlR#`%Sy>4p`oIKBYiH-{&MCH&C-?hS zT|L%kU~m5%F9LEQ;p{9%PzpGJas=J02f+u#xqJ8S9a`@faxRI$y}}lPe52r=<@BR} zQ-SxL#XXq=p&RuCB~>{w!I}}yN)?zN4lo1?D)N#sBP(gdVZ0jEfY@r4tQ9;ORfSk~ zs{~LyKu-vC1zynSl!aUBX9U3~IgpB7hOpOeSgP;iiAGpLWx}LpdN4!sUn|IEe_INq zreQ7W2l^llDIHyq*U+e`6kFoaLM;X*wcg%gX&f~$B$Lq4=yDG?`FAQ~j?!^;*u})cQN6v5h^WWA zAYfj}{HlS3g>W_y)E*0U!q9i$x+k-bXAtlF0sbFK7V3l0jewto@Bp7ksBe8kLlbQh zRTD6h`fkVLF8aLYfzZDin(_xw@dN5Ug7O;KxVQM007B<|th`CW3~8)LER|lE)8F0R z+Kl8Efyy5!?)r3rHME0ShAcGUfzTXekJl86LR4qoc++$7N;+ zNbPzY-0z;ffyG5gb7BItz7oXW4_fjrNH$_BF>-u3i%Hi@%g7W@)gHU}uL9HDq*`0ye(n|>(8T)s1^(GXUy@ciUpxW>Wxmz6>Ch7ymU%0LaRGJYqc4j+pg zEa6vmvSz_bon5hYvvo#B24U2FQIbh_>S$=!XQ)`zSpdX6H!(Ad&C5edSd0~&m((7>b?3)0o&pvQ4Gp;Go#=b=p2 zx4Rx32*(r=?Cx=HHX@wg1mc1q&j)PY+|whLiFvYvs*05-#gH4uS zcp9-1y|=2{cr|5kTVlb^J%Dat)Qv z1>Pf`SdetDzd<4!hbhpRujdwzv#^}x;$lOAhW%H(l$CPwt@6G!xd)JUK&o?!;Y!VM z=;cnFI3b4=W*3FX7l`O!B7CbdSPAF{gza>m5|A1Y@WQ)iiJtrKjDrNFuB1EYb2=gQ zhlnH?jb+HqKEu<~=Q<-ZH#bGng^ixOFhwS4c@U`~nF)7ZGr~iD4Si%SOL-zX$1se1 zzpUsYHO@*x<-fJDYV<-7Vn!L610`D%B{Ft){N_cAv_LaSVrVaOUL^?Ga0;X7$K$R! z2V(ZFg~dTY5t!W~pAaMU#~G?TB6OWVJqdm8ld7tleZOn@pCIk;EOy&SBE_#ANCpJa zr{23pi$#e92S|!j8NUk-gpFBu@gaOXA-ti90Afz+8=U2}tZZ!Q$Ur~_zk)CglB7Na z4JhiRg>xY0#<>Go&FTn$$xU_j&LRrV=XV;g-7sZ_sjWtfQv=e`h|Ng@BX&0KDt?z*p<@J9~KB+TXA7D?=cG4J(a>zwWf7zXer08BXY zXMcFIBrkqA4NWb&9U(AB&1;t58FSFi7jzQ<9z1S*ccm9Yfl)84W3J*pLcI(u|0x8i z{R^wpmMGP7t6>6kmJa{O33&v@AeD94Tx=x>g8*a@L`LU+%nQN2k}&KBFr(4wi%|F? zDx)xf_64ys=OOvO2cg|XGyQ#*j{!KWxNOgCL*)Gp*aDQh1JGBZ)^zB|Lm6KV-90Qg zcN+JMFpjNUevt~Jd{0@!?L<$`0T93wAj~=KL zmEnATu%9q`8SxkgqkbNA$bhf0@d-}K1YjyM+?cd`Xy^o@DIAZ|U{I2(ivtdFNnmnF zHFBKD{|c!t^Pq-A)_6Ck6H}S>0V_lfKW*ivv=KNOdE6a}cIaFQ_$i?UiHC>zg%D4) zjSvGAlNd%qLP|<-*M{VaUqmJ0m(IDMJ23LZz6G?^n`sYS&9WM5YwRTcu8$HgCssF| z4=@Oovy08`2hIuAHyR5ha2!2rozSzl56sQYHRA10nR+&9BQ#_9(4Csl$gnRm7p*sd z&Uiv<+oo($)KuWIunK~04>k2$%nrQf{s%}2@H}DR5JW?$_fW8-P2yst0rQ9uBv+_` zfbJ4B@lYP1Bi7tL`BqF6Rw^)JB=>|XK%qRp$^Ja>JOtA?@k2!%ZbQlFH3nsFL*x~a z*)O{Y$Q#`1%0lr2xO=k~*2Lup3baTdXd1JXWp6Ao00Z_SCyoB_Sh2JD-lE7yG~7>iZ@ z7e^|?Y2eWR;?U40wMsxXntW=|@@A*}1jp{KlCH)@+ZQyWfWlFqqCs&r^&~#$LrMxo z!moH6GUkz(zj^qbOhZaQqJ%34!lk72i@aVOSQL&Tg18^Oq$nJrw8L!svw&^9o6!{< z-G~TJ00eP#;)t>ssW}`fGb&xehVYM_i8X+C6H@vM?39;li~(!)!7~uqaG-9N89!n4 zT)oHw86F70L1^?KT2?I`wnAeHL_9l=L6~SWDdFTR?vXkW3grm^07Q0&3>;}p=w5g320qi!dm&oJzLg*RN}kg`=Xlm$3E?Xkt)z`nIKmdl0OLz~|BS0X**!Z$D91>?* zfKwW|7R-q*2?ukGv3uaAfw@}`;*X z=SC9~y11SP8lgiB@5EtEs0q-qi}pQ;1O*-DhsYm0A$`Zd@KHivFT``GW_QK0+vgMl#@vPU?+V**_R^lRY@vNXc{Cx}K-j3LX6vpI3C z`%~68RG@E63;$6L4G9hXh%5GDQryQ(`wws?MaB1!c;1@dRJl9z9M z#$BhW{?t-5qMo0nh@s5G8li>&F4%2+xV$gzt!ZbrCxjCa+cNizjx|Ob@&(H&Y!h0V zLPMqSs6g!$jkjiHXE$|p967aj+(rm}uh?Zc<595TmqYp3Q)ZB15fd8=hn9cPs)n_K z79>FFw;=LE&rM11cBHotKpcP$=&1Mr*<|Kw5R`eu^%s$Wg&`WqM2IEXknwoK;Ro&g zM*wT!G=cj1B*RS}{$N3Z92#IBgLpO?wwB*lP96WitMl`d_*a!ZbFyR&U7|NfbcBr~ z=p)p;<>PidBYT)N@JfpHdiK{IR*fdRKrJoQa$uf=&_W>5!UV}D} zzpW_6#f&IG5CcJ6m5uq_sVb`nm)R3zKQ3t=;yZ9Uff`Jed}9>@WM zH&Y*+%Ml!`(_8ju9aDUg6T%-ZUh~^qRNCsNXK~iEpN!qIABHX|R|J)LkzEKKsyyWB z*gtr>q4$HuNW@rdy4BmE8ossq$r%2JEEBwgJH||s3`DwZ2M3O7xw$c1Ja}D&O3AmK zQ^tST9cx7njTVGnZ&Opag6N(LLKUt90uE>h;^yasg!M1&cK~W2f`Ayt0dWOgoXz8e zeTjZgNQ%L;Viyv906%%ey2Kk7jv$D-{vajgB@~rht=siIPVR#84|g2hlK#CEJXO@_ z!&an18N<;gf9VgEFl{Q)&Qr&(QOjTacvE5b?wB?j%CzG}+@>?Eo&0*ft6O*OTsnAF zPo=-G-uHT_^t7n26dRNYUFw%m&;oDAv8tPP2Ti4);@9FjfZ@epm9MO?6HrcQ?Fk5Q zdiuO<4&u_b5+=fv9TkwP2&M|SijWTF52g-K($X%u>#k`{1MWiqHk*Jzu6{dM$Zel& zRzdcyb0INr{y0UX*Y;lY9`WH2;NU(PQ@ua__eTNY7a!k`?HFFZFXv#0m1;Q))&n5e5!!xt)7<Zl#n1zI@gfnj!%y)Zwfa|3>X4G6 zd_{VUv?VEdJ!S;KTCv`P^jAh?_${4N9?#190hpnhcnL$E1mihJB&f;B$*^I8mw{XJ z_|@pfyBX~(@TsT|{;Y!joZYafa9sSQ;__SBg?Y<^z%Ly+ax2HIJGl+EYdHU;t?EoK zXj{yG7MFZyJzy@k&#=dPKvX+}_m6Gz(&iMmf7JaR?GnGWDYdf32Z_R=RS#T+T%*3R zb38xGB&$*HVE)ZQdop3uaJ%S-drBUF-+rHGZN8?{;MwpiW zIvqR~%97Zb?(WZ^cDH9;khodcQZj;VY-mXZwTupEkGDQPrGHzn;Pv&pHANOG7r-(E z9}d*U#oJr!q}dORtvnQ{uYGnv7^A*MsFg4-91tZO;tA&4NYB8*fBy6d?FgUPcvj4Z z;5ml@Dq><{@KePmMIY1dy?fvJ`R%!g1P`eJ0VYAoDsU9rAmCIxs$;{hTprwMYFgU) zW?At$bhhC!V4t9e!Q~Oni-QB=(W)8xfF+8P%MJ#lq4kEaN^)}SG~I8>xKXDGEY5jj=8q`R>nRLl|@e90p zNwh3(s<7ws@j)Z%2`|<`fy#H1hSWA4RMg}>J4(T4Z;2gwbA+^gm1ZTR>m&!?uGkFW zh62ie^!pmJ$pc-58&5O8eKS*haq&+qr}&|;oI|XKucs-Umxv3Pgcd~O6~fa2_h|jZ zJapC3nwy)$yK^o@L)-%5Uvw{*iN|l|T4(E2lq@M4HNqn7# zhQ>Y;lH*)l$s<`FQ9m>7@)dr_!i#J^u0;vv5!22iGxIZ@%k%T`pV@3IElaUwq&~@^ zN5(oNrK~@<@6G2!1nf~x?jVNS7;th!p^IGfoEd)Gh73xR)s2Pv7-JcY+i?{^Xf=Y# z+fR*`1x=x1iZ{_bC*G2LVzj*XW8dMPH(Q$4?SD4K;>~v}r77L9pg0>vWY}%VE089{ zHSLl8>{;W7O0#uqy(rb|F88~ahsh?JcYb^H{@H?tUk)|HXy*wPv%CUwvm-R>F=2ge zkN7<1h>tWX8hp7{%z%VYMnOYE3OqUhTv1&IgsUXAEFDaYK~o@ovrbL_LI{jYM0JCH87DRWE`(?gI1S_?Uoj^ImDZex2Q<}DIXp6I~E7#D);HwNRRC0~iBg0KMKMO5nq;D^=94!=LHE7$ESZH|w8 zDVVg_$+1$&Iy+V8^wELeePi=}+lJBj^ku&gx3Ws!R|*>qkJkrcN>(hp-!O9BkJFd$ zOSm?=rG7K1*0_{cfJB^|B9u|$)9!{ywI3XxKCLC~FcItIcan*|u&YtUUm=qBu7}si zx@gt=Yb%2>)_oUU>Q3z@fGx{FQ4qRxupjaBVGu{yZ~&Zf*hO*RUm+p%C?1gf=%n5G zUR(Q3Cru+gcgt`owM4z$mIo&ry5b0)lD~i7!YPS9W2`{zR1_jeBHxCD{J_S?q#=>f zHfKDAx+I{CDyHwQ{wzk@5+x&}m%ICQO?RtypP|r|ADKd;ZoaPRMmEVdW9=`7?6Aq6 z$SRuT4>?s;C`rmY4vsaKh!>j)X(SuhZjp!FS&Js^HY*BIz9d0J?Rg;j5-GT`S;goRM|bT8!YZ}(In3IHya*Y?uoo?8Lj6{KlXdd zV~BtUXuKg+`T*}G@N2s+rf3z-&dv411PV_X;w(kp5e?viwMnUQ6}JllgCx2A6b>cJ zc!t>hz6U?>efxmc9i*eXfq|(+ux2APM&ph_$kCo-uC3{Y_S67B6gzW}?r!PsY9h5{ z#_o+$NzsBy@xaK4a>AhvE<0#=lLf0KG0zR`#>2zjSc#*5rn^HVJdbG3J7X3@sWgAL zP1QQ(<)2)TqavfmV!SeS1eJPl1W0<(we_V9RM4 zg7;LkU`Bp-Yb&f@e&70|pgSKH{4x?leDrs|QSenI!j*1)rX$>mqnIF&Z!`Y2lF3D* zHS*=@m*`w6e@Th20)z*^Sw_=caYCku7?A98&tq?lVBy{BDRz2{>fv$YRJgpL-S6r+ z^qr{76t<`{(jcH1d04ie+Nrq-+VBh)Cf`FM{Ivn+4*J>Q?V0wPYON z%t%i+W-AmJ)~RR^R=UT&&WX^&mz+0p1lP~Jt}34Zb`gt{iHQm3cP4DFa^FFff}_uv z%M4MzsVSw}9zx}ZP{r|mgSP?p*{_~2LLdUBJ zGdceI0l#0K_!lqw&!0ZA{QtjsKpg73JrEUO&HzX$q>uQeDBZwqdNGQsEogg699aDK zQ@5t5Gujhd9{&A?ff;$~JxWUTYbpQ!_ljLJ4UCc=lKuDV@fHmq8)P#H6NHEJ-`|;g zeEhc%(f|6HT>P;8BUqAaX>GaJ%To{63~7KO!W*MAGlAwGLW>&a^}j8B4q3zhe9AsF zW7j-HbD7I?}zgleW=Dc5M(k*L?nAu2D`4(1MUwE-ccKxL>_y2w{ zmcv#;VQo#kHy_O&jwh)VNV*_*Y`dHMlMsWCZ^X3#07T$tkb=Rbbmx;xu6qgOHf;as z&KpxJ#7dz7+7roraK*#DDvS>IF3?KuSuo)I@FP&3ukmEALvC8H6^)jfUv<~uMkc?{ zfYs^g*t3_r89sg-jk0%Z%+@4zd_&?lLgw6_7x3;BOImGbWVcB{COZZSt9-|W-j&u|!Qr50p%871c27I~HW>EM!iVC|cS1#@JxBVRhk zIkzW|$^5D-u#U~>rF@=p#>aq(u72+J;=2;T|9L=INyeZJI8un>sMIAcXgyGmwB#A! zO!*?O@hm=m3`H#AK=G^yKEw#E-YY8hooC^W2ou>l;f(TC`@krpu0(Q1*6!~&jc>YV z*BaekW#OfWz3mrJF|FulJLi5=S?Rby&8y7g1N5s~R1<`z{Qs64f(9>NT^yWt zYiSPqXrOhKiS9{7ElsPxw53qk7|t@~1R5|Yh*EN4p_rp({;spR3d=haeuVILILHq@M7v9dVjrqstbp$H0jYzg%IKhph+^QB?Cdl)8K1Ny_1IzxIDV3}@O2Me{Vy%-&MP{?a=&hO8@J}S&pBCVzX$r z`Tx8QH7Q@7_Wyd(|K+jz_j~_ezBwvkf`}^yf*m4GT1kfMR;%FsaHzxA?zhl;7f;X? z*f?;fO}>&hdDv4zQHd3msprUi!H68hfsmM?mp4034RRDq+*Qo`OTMz&`n{$GxZErgf9br`;g%)%{6D)e}hCaXTZb%9U3)+aD3PZ)vL>W z;6RYerj1@R&)b;Z{zoOTJfc`9C(pKGP$+GJ_yDc2Nes9Adg8Uih0CP}ZYlXa6Qyro zGa->VsX^uP%44-5z_i_&%>DOJYf{8JHT|N#gwPS)M5h_+nkC7i{?Cf~(|QwLEE@C4 z|1PL zEHxUtpU<#6V6h}NI%?q44TGicCO2M6f9Q2msN&3u$P1SdUS+pETbTFikeF2b7N?|d z&|=@k;PT3b4@yj8Z9&dAdnbCW+s@qoWhxm&?XTD;@<9C*cQyOqP`2V7tC8&Yc2?@u zHC2^5b{j3RN$+a@G-t=WIXZcOUHrkFuU;D+H|rj#iG*-xY`BgXV%q|gqwx#PI_RGJ_Sik$HPo^oI z>|l$N>g=!mN8@kRJ+03zx_X z(t3{9*P2g@BqYT*@zK7?_hDNcFzV>vE7l(II$r4JnysLd+W9Cg-wPreYlq&qql=Uf z6Us}1;^PTO{uPf@W#!)ycc_oJ2a4*fM+H{vaYD&}YI5)*uXZJDQ ze@dtE*~9mp^$Q<;>m1Zgrk`?;EtKTY@qJ*(ufFVcLdB~0kIMMr*ue&31&973*XQLG zQSS|`1=_1w6b!7ScX9VbtWy856E>oqk@Xv>7NrosRCdtr%U3V*nOR908ewr&@3ihL zzPZKN;Uw?I(d0_`Xs!o4w7)gh=h{tL9UT$bm!K6ZbjERRL_nG5!btz;*RKxj|I&IT z@_6hSUs}f}aclvfb9%ma)wc3X`P(nKq`!R?q2@3-7xd=UzOVJNmxTM2Y#&CrsVUV7 z4>Ar_?v1`VtMGlp;p8CgWOQnJ`bc@+Wb3MwT6jg&8TFGLLJ=X?i_4ZxBnEsVB%3=U zMi;Bfh|Vx3pYk7!IJ+_DZErlRe?)PzuXKM(vwqp@qrswX50!Sc|IsrqR-fflXkofr zr&%j6vn0RK9r8x4kl6aOU!d>AbgD9CyB*)eb$9vMg#-~^J5g6!(c31hz9WO;4K8gz z{^TW7J(6U;?j2w;Dw)#2UFXR{Z@^>JF7s?)piy}!ecO^xXfo{9c*<#eix!plqwgsljg9<*e(5sZmn}cYR--Oy_(7cLp30)$bpF#^ z)dRe-+ewa23+Ks<#>=w5ai{UI_!Dd0xu{`yteBDH9?PM$Q7+-Sd9v7^$K2C)y{GV(y7EpJwJnr?wPqC}7`B=3#bAT5ucy}?EIIQbaI z`hVEY$PO-&Yv0au+OaH_|1zcZO5pp5U0liX2DIFNOm7;uJ~pE4KVWEh_Aa$6SJjaXr{cz>!|N@NcD~W$eEfmp zw0M!%DDgMS#yQ)TZb7dob1mJmz|q`$>uAPYrxPDnvLcnVlnCu^39ls$3hMTi&8aOb zo}sD0JxozC)0_Wemp3uxJ>DNu_QQ@sPhmYJFYDo*sg%Tjv&P)#rw%){-rZS1_C;Yw z=H9(smg2Qhj$4gdUpsog{ZAJGH=Kt<9|$lU2rUhBu$r`I zlXmb^4^a1l{HvAP;M4XE6on)8$d{pcrl~2~D9n=1t7d!dnt0+@r!WH6<9Fr^V z$*l`RgA|sU%Lg(iY*|jbocZ!O{{6?Pq4CG&QIALKy7-K_ZpPT&Zh14X_Bc-7bbas? z+wvnP2fJD;w`Jqo88yKHH6{tgY@4GrBKGy&Qfhx_Vr<#NxBAOhE;p5SA5G=|pqX*- zgU50JS7~T&5D&}Dy&+PQ?@1OPcplvY=KX$hr1{z28mB0FGqo3~*(`U`$7u4eA5IWf z2-{d|6e2sbw^4-I!>njsZfW?`Qc#!xZxc_zQ2OYNQ+l>Eq81x*Q}-)-rRrN24ZC8Q zF0Bf$o@%c#==5r`9y|NH@{BZ?kKPZzj&0^?xRdeou7|<*Co(6l zx>NPVGM{aj8LBd$LO8GcVk^R9d(@Y$ejq$qNI$7fTD5w)i^urHK>tKiCEZ%JX{=QE*Ea#$i8pJ)qV^lt`s!Blm~{z+Kep#6 zo_1>%%9`s=yk|4f7JeWs<=$%cRYi9{Rw}pVWGCSc+p+3~O6}q2?a#6}Ud^$XeN=Fl z(Rf^+FeISFxw;-SH}(MUdqqDJapTr!hF|yk8)6TWjrF`*>PDjv!{;Zy-3b-ei(d}k zk6@>o9-z7CyH7UV_rUCwC5uYVgEulfO|g~d`Mf+&eCcEeJGq0&ZckEUgn_nt^-muL zOVLVVJ&T1a>VZ)K&R%zzEbbg@i9FM7&iJEe zC;cgzC8zwioqPX8O6C-cq>VkUo{ZrvC^)Pe;A9tGM^mWQ{jJ*1IxjZdrMBtam0q6d zP1lW;ep5FJhUyS{=SzE}DAS(P-xA25xb9Vu$;#Cg65n)mB&qB2TK#Ezn{xAYv7!)u zv~3o;YNvJE5J$UfypV}*7^#T6v(<86ZFg9WP`r|C3*-bZTS+zukCjCc23$z3JP6LTj32=f}<)9`x~99P2#k zzh}nru^LV27(yhEv&wVW=rTd-&)xhTJWX9FdPwyF2 zOB3qr?>~IUKtuehck`-i!tooOYeKDMT0yQp7fQumi3kj zyvw{>!7h%ZSJrJJHQmkLgsxKR$@pc~ayJ!SQSZn!`jM3*Qo~McWf5;HV;WTVg;8^? zA&cLde`eRO>WaLAZ=JlKZYz1bD;b^ZTyIRia!BG#mzLAFlu6?0$zKsO z3fuPQ$h^PY2zEEVA-usWexKMv$(6$b5t0uPK-X;`eNJ5~m8EUpOwt`fuewryXfu zIoDRTux45B)gOOW*xLP}eoIABn}@IcyniWYm#S37Xi7uT6=7VJWCZhagvgRo+R*g9 zrtcwR9g!^jq9T5#2_C%5DsGG8S3#PNJsc#RY~Nz^mTJEml=1up#bTtwx^1RWs~>TN zNbSpzwZ`HH!qYBB=f7QGSE6x9jF_X_d}JGKGQ*s>#&y_YwnNu-tS#-#gHAjBv6bcT zq7I$1Jvru$#nSY9W$(Ps5^#-kUygGsSo)JUrMfh<{mLq@Ih4ONE?(*V&{5sir$>+Q zowd~If0vw(!;>lT>FDZDa_T3eP$sS{5UkMp!t>LzGGA0wX7y6Vzfz{tJpbK zvYnoDENB&{Sn2gW(JyqG(Ufv9Vff5yU@qzPvz`uPB)cpt8AP@#+!e!}6M~}RzNLOn z?9P34-u!_6!g`2Y*n!)=KXR>m+#NIZ_w&ElsCh%v>l3hcUR_h!%?_=S*ua@l6IGiY`4m?M{5@gS$P zUS*EB+)GlLJ$a!dt^RqQY38N|)3N-91D`)|{PGqbIMnizmW$oqq(?(S+McOIUq$z4 zKF|FdcCkHn!u({#LGnMAB7f0urFx!zHPA}s9Tj~v<+fn{qRG$FK@Ra*UVQ_a0y{>Q z+$;PWmpgek!?H|Q$3%l^ovT`gHcHwPZfVW)JR>gr9$PyxJ`u84lTl}pI3Z8Iz~|b; za)0KeUR~3SgJa9N9_>GTpB3EZ#_tJtGdlSR=bz90aw}|8w7&XA)bV@ABzxB1o=GsU zx;sqf711R~&9EKBAWYSm3uUshoT|^w*hn72>RHIoscTz~^v@VCk``H6=?gwBX)seC z&+(nRthSbhD6Bx3%j-C&vftP=OJ0J)i4teN0QKo3^^qj(->&J=6%{t#E}F4cxy5nv zQ~BhdFM~r~o!zybO&ec%Z+-Q%o~ox-F?+1P*Rp~WL$#Q^3$q3b^@g@H*A}S+3iWvR z93a&$DGC29{eg4ptXb{#RI}#mh4$*A;q);o z?$3{-pUka<%`@W#eP)V#uLbqEzH8Rcs_n`Pj_Wz2vsP%ZpHIu)h4xqG8BdQA{Ze|~ zT=PlVsENubySY)X>8Ee#&c3BLD-1fsA9J^%>PzXrXkP$}!4@OqVKpZ$amOK>bMaDL zivwiE+8aU{BT`qUthnv6{zQokau|PQNbLMW*?c{7B+rLCwd92NHE+=;84GkR<{g-_ zG5BWd7}a&v3*xM6v-9zug~BuP&&cDvu0Qw~LpwX0X?Lf@V&_fm?aS*1z4~Pxc^u+r zM&y+D6PG-4UmZUaRA5E^BW`gddX?1T!@FRUyGY>loA9*fwIMC%_$=7XlRNF?M^Cu~HpL62zU`T6kqZyIRHn|Jk?taJ{eog7 z-5Y}*iI0X2eIIWPR%cNZU5>l-Saq)Ds2P3kyF;`!aq5M=Ob;z-ug!QxoFwwTz+llC zC}nZ?SZu{y8!c08;kj22BBl&xyuDMuez^2du`%69%&nm(bDPwzfWw3KTe1${s&3Px zMuD0ewyJwR^z}|Y3O8x-?mTXOzkFbkY|4UHjpomm^UC_}rmSlRPcI}?UbLd#Du3pw zTp`vzDH1lm@AbZqB5CA-i(n5u#DD?h)>ga4fdHHuQ>@3Cv6DaFG2z_7EJ6zA%Rv$_})6iA0q+qS& z9?%@uEpf_<_tm(#zmn^O@9N^{2mURyT|cAb72_M4?aHY;G+o{*nb-DvP4x8Vt&-+t zTi&hZJ%8zez3~Qzk(Y$@JX+D$-dnP<##f+x>Qg*b@5KCfnVTorV<|L~J-%Ll zN~Fzyv6MZExx3D?pk>DBO2_P2+l4oUwj@OrT*IZ8k{a~P^xC9lEjAOFEUXo_NwarY zOjg&m?vjJYn)Scx%XueO4*88Tfg`nTNcE709ku z?#W1KAp7)w^pM;*?bCpeX91sCoubvOr0Wk%j`#Rd*cRQ`P9>^d*1M~q#K+1?ZFG4b z$ue7Y%=5wxtDld0sHubZzkXdjdnVrFw5RZ5B#*_zH|*UKNvwmVbyt7ho@Psy*X=q` zT>aEFDX64~F~!kBn0URU{ArnYs;KCb9g$j-t7A&B+`ST)R9SBtJ*5^b-F$Y&BzGy9 zovx{x$!7X_Xqwom&*Dk_-&9)P>T|KM#Jrql{nhT|8p6M|7m~VKK>3FKzLiiezGuivF>w)+u4?;f6OYKJfc7i*c+Ig)t=w zWtZH|?D)j^#yOI>Ojx`^(?ra`zV*($ZOXlJ-5>UjjU>r8XSWn)Mq3_Aema`w|4sJ% zw^a?5M`9}nqLU-)-Wv4id@0*QO?~2Azni)tr9=3X{J+e|hJlgez~RM>h25t<75&Fb;saYmQknriQSi&HtVc8l?1OH*wx+M)y}J3{IL*3$+31w6P%PkxeNcTR5q z^x#rsZlA$9%Dz3raf@+=nfB`|lt=VVbX<3DIrH+v%Zme2Zw=B)BQ=k1&(mG8D<=O$ z7gaE@n>uO7HW3xG5L5p7mbdSF$Z#Fl@HQl^}+J-{_DNn++()~xMC>x*tak{r>SFo~o=Eq-$jm18_9%i7E zC7se@E1ug=!7o&|zV2B_eORhGxn59t#5EweHr;OdV8`f=%wQs+3r!1?nTt|WDF$8h z8q;dM`{b%N=7haoEXFyPuhxywBbrGt?YVZP4qjaR;QP&oI9?J zQ(oA-T{jg?e)X}|^&bXix{U=7^5RWNN7jnQ8HOY`OQ-VmTJAi0Ofllys%$+`_9Inq za(JuJoJXhSsL<{R&3)rF+b{b0Wry?IPtSfAmeGl%_u+~Bsjumm+>>N#zibp*Qe5WB zyXP$Hg_owFripI4{h73U%{O#Kn~8ym?d%qFp zbtCMbyi=j29O%DQ@|gCVksLM2hp{*Bw}PLsEt006R&?y*HjDmobM004O{r~ljq`BvSXm2UMD z-GI%vl^RF0Tm$g(8=clSq+N$Od8H9F`Fy#rJlGk0?XD_K@$^+<-~i;7)hbbMn80JPalf}n*5!nF4wczG!C*Zr}+vV>q9HPlJ^{R@3ks;p1N{@(&rwSS^ZPsLtr1Rh^i z^BoaS>{gUo#-!Hp8!rOQYo_O~H2WW+xFjQ4Y<}?%dN5wyJwh(~+x|&CXcZd0{W?s! zd3&ii$E+DP5-=TD<}rhCA8S8uQqO>V9qJ?vqkJj;g2KF^$MTZhW39pVEYCYMNJ>(C ze1CQagrLr)a`VaOsxzykMZN6pHwS9ALoyRotxnp;j$NSqcg~iT3P=oQ<61sQw zGfv#EWj?HuY0O+CpIA8$7Dz^euU9;enDl!QxEg$S=ZmA}mcYeH9Esay0Bc=i&&FHKkvE>{?13*-HYzI_+j6xqyGyGW0Y(nzcH>JI~S>a zIkQxE8H^!aBr{vua=dZ>aFHlmuHn_oI<2n8#YaJSB^~n&PmLePBBA|y1C3XA{dWy_ z6D9~$t?B<=)vx#8${>ZWfb){Z&*J*N%mwY zm}z%}J{U_Pe;!2JT_)H&YKfky(=L0=8lLC0HlsuO>vT3})e#+jDUhQ80^NKjyWxSe z*0Pze&OVn9-qk58zGB;}F?sp~!^HQfchl@sKD_A$gU!kn>fDjS;`|A+X6`+=w1o{7b+ zN}u?mm-&0{iTM{X%QExbrHocKXs_g@{Up1wsyeFeiuH9+rdaS1r8EXFV1*f@Hg*+! zE^xIv?c?@zEv4T(?^vidF6v!@V-o$I)q2rIu=K|o8c*;T{opB2KOXXv z{J}SE(w0Rx1&b5S^y$rm4STq%1)V3K+H8;I$ks(2jE&L0G%gZ3rCqB&Bdr3*kSA9! zU7-@cZ(1*HJGSGys${PdVZb-vxHf7y`Pibi_o&*8k{bAZ{&KX^N%o;T+ux77PAmJd zau%gPXbJVLM}-N&W^ngKrTy6FO9x-fX)AA@i3UEWNw>_4tF?4D>hx!JV<2Mg4es0T z|0ZJ7Wqu}maqkK8=>Be)*fA_F6`#4Y?=|@cU#5nbLbch@(vWD0nZ@9AY*W6MORuI1 zSlMH*LvRBNW!OWFP;``d9K}S_&Hd7yM*CB<`Vl80$y`jE(yG~H-jb6+RUU|Zl2<7V z>W@uxCc#d=cN&+NmK|rU%dM+O-(eN(e)$&_K~@ZUc0xA)#heZ5l&df*G5lw{qo7lo z>6vq~&1o{$CP=#0si1`VX98s3&1{tP^%O{ZCI9Mz&1ZF{nbGa^vqk zR>gePAQ0yJYZ;b~NS-ns&MGxVfxzVDwGoE5z~#Dj8&QyurQ&&?7tapg!97#?P(iq_ zWUepcH%-uCx0}w_1z32NLVGuo{!#XNEM@av>mmwHC|`~T~;gOe%W;M%utwLiXpf3I&G zhY3ttYtnI0=J8`;JcbOO`<5`LoDD)P18cI=kQhn`9^Bf~^UQrHQMP^o{^#cF`Qq}u z?vu2A$tA}TACa&s?)}-1NO6*}CF43`$rHCA^m=Q+1V`x$8ao(D(Zoc*R_BG%=4@g+ ztdH$FhCZvxo0o;MIg1sxTp$qD2$I{QumjLidHzIL9WOh0Mng%9Li(lv7o6!^J!K(9 zlr9kCKxn(!Jgl6ENq+d6Efgf~M1A`6*Gk@?N70v2$&~MG3WqSx8iND9^pRUC3$SYW zS)sl^70F_HW{mzy9pc;MxqMD6^Jg^}FL+*(6^$C9tyCsQXvn4c#FV44N;nt!Za#bE!Qa1LX8%ARN{iY@e zQkIYh$~VqS-o}MjdwUK!6nXK83Xy^kx5{hYd>p&0!B_RY&7XpSIkHwDPrM;>D*N$a z=Xu!Wv!#xi-h_5~}?Z5dv*ey`*QmEQ+Q5%+YUO zfBdL5P)+_Zz*wn-9V_wJ5=u%F5qmp5bLCBt)`+hEW{75hG_#SOo>xpvl5+X0Q5y~} zuIQ9(5f`b7`%Xl$q#j5C1%z#l!Xiq@U?ra|nSh(%_1=y%N`2}z!M=?&P}1SP9f9jDresn_o}2i(V1dlxzG7f5_8o8WkJ zHZq?*npWXW#yQok2z8>N_T_?#m7n?9(mc{-;zqSYe5K)Qo(456?)tpNAq+p#JVjJg7q8kX zn}9-@TuFBTWAVb~d0iI#K0CQEGZml#O~8)DCauMrspzS7gWD^OQnOMu+;nd;L=fv@N1CTK zA)f88-kps!JAF3F?~WxD#DY;PJcz#pIcanv(i2w1&AV-}eqpm?RCGifSP7>Jk@b`U z{g~m3&%%)KXQ6(gdV1Kzgs!K$4>e>GhQ)FT+&R9q{IXxkC^`W+&$0OYkN1aGCB&i3 zD8j{R1|kcnxYxyAKawrN&AI`Z7gpZfZ-9P9f*qvM{4i_E`VlC#IthoAD|X>&BBW&7oOG zt~Edx-rw!4==hw!j4r6l`2xima$*+l1DZ)75lSAt+@(Vk8n223%0Di*(tAR`R=BDk z!?FsDsyeFq!Plhaqp`s2@6^%s?N$7yS~Aw_wSUX8{=pA#W8Jy49R7ow{@)<*e|G=> zq!s^f?D_`ai2~#fJ~Xd@daAj(4)huAzh(?9b4l%nf#H|o;Tkj{fQbTmt(f=k-%H0U z{tx&W(^_`yg4BjkZvXZ-oxgm95YGOcp)wh-$xjEbMvWVl%)v zcp7ppf9tN4SW_7d4EJ+hj{&nBUwQP|P;ennCzP$}9bsaXu;6qfkHmK>HMo$1+chea zZ`~zw8`GFY+J?&y{g0Jd!t~OaB%7W2lv)~4I2lrNhguP|FHhsPHT7GLE4}WHmPuFW zk>Pb~)~&vCNb-7OGlZRph9| zCS8-d|0#n0q>n%95~fH|L+Muc>Rvw>D0HNHIzHB zfddYaAh>@MS|L66&K^xv|kHs&uH zZ!0>zbgo%l6=yya->b14j)U9vnL~2N71ofpcEg9Mz@74vz2H$^Z$ff0M($ZvB;Evi z(vdf3>YJZwYov`Tq#@fJ4aAFU8@zkRS9*CUkMc@vAs`@M?E%<;qGn#PjWQO(Ahc};$Tt@=r zu7W~8eS@7}oX&4`Gy#E!m?49xb2kRxz15CB(p(12LRP1b8EFHdwl-PLYa@4?liYm% zbT4k2S2o?xv-9QTx+3iv+>F!ad-b5VXzS~|h*&$@Q=<#w4~#Z=GurNLJ8oGEkr2u= zeprLb%d(a_UI*C96j-~uvIuTzt-YDmS;-LjdF70q64b(Z>TCB)0oIb=BPTY5g??oQ z$4#%D?p_j1H)(H)@II%i?(xgVFL9>#ibQvc`ZrIbTT=JHo-`IM6kT0}(w0GQT4Z*n z%yZsMpaupOxFqU!%W%;wnL8M5&!D^f{>0B!V%`==f0|I6I@Ee3S(-F@iO&1@HJ`~T zgvFUXOxUC+vY${-&jL@BgO~d>xOZ_}o#q87)P4_9Dl(AwzWuO-c7eJmKppt|I-goO zqb;PrWPZ&QgKU=6?{Z~2OyOUsaTv}VYmeqPSlgWX`WnrlYlp}0KIQyymzW-9V3gT` zF8g6iaJP+d&qs(|?F{ncN{FnA24{_TmAw+++q5d$oL3@nITn|-tD);x*V4bk2B;i= zkCo2FGA;+E?T2~CLmqf|Wy@t{tKc(b=feohasNb3QTN=Kt5C!?eDXy7lxAY6QlLjfrI zBw)9Fq`##!Yhj660GgtW8L_+YA3=wg*tSp5C!H`oXA8*63!ALTFgcbq6mPYuA;46t7IMiUlCZO0ssI2 diff --git a/localization/initial_pose_button_panel/package.xml b/localization/initial_pose_button_panel/package.xml deleted file mode 100644 index f0b4d41bc4f51..0000000000000 --- a/localization/initial_pose_button_panel/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - initial_pose_button_panel - 0.1.0 - The initial_pose_button_panel package - Yamato ANDO - Masahiro Sakamoto - Apache License 2.0 - - Yamato ANDO - - ament_cmake_auto - autoware_cmake - - geometry_msgs - libqt5-core - libqt5-widgets - qtbase5-dev - rviz_common - tier4_localization_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/localization/initial_pose_button_panel/plugins/plugin_description.xml b/localization/initial_pose_button_panel/plugins/plugin_description.xml deleted file mode 100644 index eea08b60d03e1..0000000000000 --- a/localization/initial_pose_button_panel/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - initial button. - - - diff --git a/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp b/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp deleted file mode 100644 index 654095641c7f4..0000000000000 --- a/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp +++ /dev/null @@ -1,123 +0,0 @@ -// Copyright 2020 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 "initial_pose_button_panel.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace tier4_localization_rviz_plugin -{ -InitialPoseButtonPanel::InitialPoseButtonPanel(QWidget * parent) : rviz_common::Panel(parent) -{ - topic_label_ = new QLabel("PoseWithCovarianceStamped "); - topic_label_->setAlignment(Qt::AlignCenter); - - topic_edit_ = new QLineEdit("/sensing/gnss/pose_with_covariance"); - connect(topic_edit_, SIGNAL(textEdited(QString)), SLOT(editTopic())); - - initialize_button_ = new QPushButton("Wait for subscribe topic"); - initialize_button_->setEnabled(false); - connect(initialize_button_, SIGNAL(clicked(bool)), SLOT(pushInitializeButton())); - - status_label_ = new QLabel("Not Initialize"); - status_label_->setAlignment(Qt::AlignCenter); - status_label_->setStyleSheet("QLabel { background-color : gray;}"); - - QSizePolicy q_size_policy(QSizePolicy::Expanding, QSizePolicy::Expanding); - initialize_button_->setSizePolicy(q_size_policy); - - auto * topic_layout = new QHBoxLayout; - topic_layout->addWidget(topic_label_); - topic_layout->addWidget(topic_edit_); - - auto * v_layout = new QVBoxLayout; - v_layout->addLayout(topic_layout); - v_layout->addWidget(initialize_button_); - v_layout->addWidget(status_label_); - - setLayout(v_layout); -} -void InitialPoseButtonPanel::onInitialize() -{ - rclcpp::Node::SharedPtr raw_node = - this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - pose_cov_sub_ = raw_node->create_subscription( - topic_edit_->text().toStdString(), 10, - std::bind(&InitialPoseButtonPanel::callbackPoseCov, this, std::placeholders::_1)); - - client_ = raw_node->create_client( - "/localization/initialize"); -} - -void InitialPoseButtonPanel::callbackPoseCov( - const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg) -{ - pose_cov_msg_ = *msg; - initialize_button_->setText("Pose Initializer Let's GO!"); - initialize_button_->setEnabled(true); -} - -void InitialPoseButtonPanel::editTopic() -{ - pose_cov_sub_.reset(); - rclcpp::Node::SharedPtr raw_node = - this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - pose_cov_sub_ = raw_node->create_subscription( - topic_edit_->text().toStdString(), 10, - std::bind(&InitialPoseButtonPanel::callbackPoseCov, this, std::placeholders::_1)); - initialize_button_->setText("Wait for subscribe topic"); - initialize_button_->setEnabled(false); -} - -void InitialPoseButtonPanel::pushInitializeButton() -{ - // lock button - initialize_button_->setEnabled(false); - - status_label_->setStyleSheet("QLabel { background-color : dodgerblue;}"); - status_label_->setText("Initializing..."); - - std::thread thread([this] { - auto req = std::make_shared(); - req->pose_with_covariance = pose_cov_msg_; - - client_->async_send_request( - req, [this]([[maybe_unused]] rclcpp::Client< - tier4_localization_msgs::srv::PoseWithCovarianceStamped>::SharedFuture result) { - status_label_->setStyleSheet("QLabel { background-color : lightgreen;}"); - status_label_->setText("OK!!!"); - - // unlock button - initialize_button_->setEnabled(true); - }); - }); - - thread.detach(); -} - -} // end namespace tier4_localization_rviz_plugin - -PLUGINLIB_EXPORT_CLASS(tier4_localization_rviz_plugin::InitialPoseButtonPanel, rviz_common::Panel) diff --git a/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp b/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp deleted file mode 100644 index 44defe637b7df..0000000000000 --- a/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright 2020 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. - -#pragma once - -#ifndef INITIAL_POSE_BUTTON_PANEL_HPP_ -#define INITIAL_POSE_BUTTON_PANEL_HPP_ - -#include -#include -#include -#include - -#include -#ifndef Q_MOC_RUN - -#include -#include -#include -#endif -#include -#include - -namespace tier4_localization_rviz_plugin -{ -class InitialPoseButtonPanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit InitialPoseButtonPanel(QWidget * parent = nullptr); - void onInitialize() override; - void callbackPoseCov(const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg); - -public Q_SLOTS: - void editTopic(); - void pushInitializeButton(); - -protected: - rclcpp::Subscription::SharedPtr pose_cov_sub_; - - rclcpp::Client::SharedPtr client_; - - QLabel * topic_label_; - QLineEdit * topic_edit_; - QPushButton * initialize_button_; - QLabel * status_label_; - - geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_msg_; -}; - -} // end namespace tier4_localization_rviz_plugin - -#endif // INITIAL_POSE_BUTTON_PANEL_HPP_ From 58d8e8e2d5ed60499437bac4b92c9daa5dad6a86 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 12 Aug 2023 13:00:03 +0900 Subject: [PATCH 153/266] feat(dynamic_avoidance): object polygon based drivable area generation (#4598) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 5 +- .../dynamic_avoidance_module.cpp | 61 ++++++++++++++++++- .../dynamic_avoidance/manager.cpp | 4 ++ 3 files changed, 67 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 1f54786df83d7..dd0e06fffb255 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -74,6 +74,7 @@ struct DynamicAvoidanceParameters double max_oncoming_crossing_object_angle{0.0}; // drivable area generation + std::string polygon_generation_method{}; double lat_offset_from_obstacle{0.0}; double max_lat_offset_to_avoid{0.0}; double max_time_for_lat_shift{0.0}; @@ -335,7 +336,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; - std::optional calcDynamicObstaclePolygon( + std::optional calcEgoPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object) const; + std::optional calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; void printIgnoreReason(const std::string & obj_uuid, const std::string & reason) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 7f69397cb3cf5..b69e95875c5fb 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -274,7 +274,15 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() // create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; for (const auto & object : target_objects_) { - const auto obstacle_poly = calcDynamicObstaclePolygon(object); + const auto obstacle_poly = [&]() { + if (parameters_->polygon_generation_method == "ego_path_base") { + return calcEgoPathBasedDynamicObstaclePolygon(object); + } + if (parameters_->polygon_generation_method == "object_path_base") { + return calcObjectPathBasedDynamicObstaclePolygon(object); + } + throw std::logic_error("The polygon_generation_method's string is invalid."); + }(); if (obstacle_poly) { obstacles_for_drivable_area.push_back( {object.pose, obstacle_poly.value(), object.is_collision_left}); @@ -836,7 +844,8 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( } // NOTE: object does not have const only to update min_bound_lat_offset. -std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( +std::optional +DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { if (!object.lon_offset_to_avoid || !object.lat_offset_to_avoid) { @@ -896,4 +905,52 @@ std::optional DynamicAvoidanceModule::calcDynam boost::geometry::correct(obj_poly); return obj_poly; } + +std::optional +DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object) const +{ + const auto obj_path = *std::max_element( + object.predicted_paths.begin(), object.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + + // calculate left and right bound + std::vector obj_left_bound_points; + std::vector obj_right_bound_points; + for (size_t i = 0; i < obj_path.path.size(); ++i) { + const double lon_offset = [&]() { + if (i == 0) return -object.shape.dimensions.x / 2.0 - parameters_->lat_offset_from_obstacle; + if (i == obj_path.path.size() - 1) + return object.shape.dimensions.x / 2.0 + parameters_->lat_offset_from_obstacle; + return 0.0; + }(); + + const auto & obj_pose = obj_path.path.at(i); + obj_left_bound_points.push_back( + tier4_autoware_utils::calcOffsetPose( + obj_pose, lon_offset, + object.shape.dimensions.y / 2.0 + parameters_->lat_offset_from_obstacle, 0.0) + .position); + obj_right_bound_points.push_back( + tier4_autoware_utils::calcOffsetPose( + obj_pose, lon_offset, + -object.shape.dimensions.y / 2.0 - parameters_->lat_offset_from_obstacle, 0.0) + .position); + } + + // create obj_polygon from inner/outer bound points + tier4_autoware_utils::Polygon2d obj_poly; + for (const auto & bound_point : obj_right_bound_points) { + const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); + obj_poly.outer().push_back(obj_poly_point); + } + std::reverse(obj_left_bound_points.begin(), obj_left_bound_points.end()); + for (const auto & bound_point : obj_left_bound_points) { + const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); + obj_poly.outer().push_back(obj_poly_point); + } + + boost::geometry::correct(obj_poly); + return obj_poly; +} } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index e378d43f6497c..3b2e2caf92e6f 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -81,6 +81,8 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( { // drivable_area_generation std::string ns = "dynamic_avoidance.drivable_area_generation."; + p.polygon_generation_method = + node->declare_parameter(ns + "polygon_generation_method"); p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); p.max_lat_offset_to_avoid = node->declare_parameter(ns + "max_lat_offset_to_avoid"); p.max_time_for_lat_shift = @@ -178,6 +180,8 @@ void DynamicAvoidanceModuleManager::updateModuleParams( { // drivable_area_generation const std::string ns = "dynamic_avoidance.drivable_area_generation."; + updateParam( + parameters, ns + "polygon_generation_method", p->polygon_generation_method); updateParam(parameters, ns + "lat_offset_from_obstacle", p->lat_offset_from_obstacle); updateParam(parameters, ns + "max_lat_offset_to_avoid", p->max_lat_offset_to_avoid); updateParam( From 9ac3a7cdebc73b8d459f285dc25f5c48ce9557be Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 12 Aug 2023 23:27:35 +0900 Subject: [PATCH 154/266] feat(obstacle_avoidance_planner): faster optimization by sparser re-formulation (#4600) * feat(obstacle_avoidance_planner): re-formulate for faster QP Signed-off-by: Takayuki Murooka * minor change Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../mpt_optimizer.hpp | 3 +- .../state_equation_generator.hpp | 1 + .../src/mpt_optimizer.cpp | 211 ++++++++---------- .../src/state_equation_generator.cpp | 43 ++-- 4 files changed, 116 insertions(+), 142 deletions(-) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index ca51c791b8f0c..eabbf695496a3 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -237,6 +237,7 @@ class MPTOptimizer // previous data int prev_mat_n_ = 0; int prev_mat_m_ = 0; + int prev_solution_status_ = 0; std::shared_ptr> prev_ref_points_ptr_{nullptr}; std::shared_ptr> prev_optimized_traj_points_ptr_{nullptr}; @@ -295,7 +296,7 @@ class MPTOptimizer const std::vector & ref_points) const; std::optional> calcMPTPoints( - std::vector & ref_points, const Eigen::VectorXd & U, + std::vector & ref_points, const Eigen::VectorXd & optimized_variables, const StateEquationGenerator::Matrix & mpt_matrix) const; void publishDebugTrajectories( diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp index d4f70e8e09227..b6f4eadb682fd 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp @@ -31,6 +31,7 @@ class StateEquationGenerator public: struct Matrix { + Eigen::MatrixXd A; Eigen::MatrixXd B; Eigen::VectorXd W; }; diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 81b5974ac3deb..74711ed886ff0 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -497,15 +497,15 @@ std::vector MPTOptimizer::optimizeTrajectory( const auto const_mat = calcConstraintMatrix(mpt_mat, ref_points); // 6. optimize steer angles - const auto optimized_steer_angles = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); - if (!optimized_steer_angles) { + const auto optimized_variables = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); + if (!optimized_variables) { RCLCPP_INFO_EXPRESSION( logger_, enable_debug_info_, "return std::nullopt since could not solve qp"); return get_prev_optimized_traj_points(); } // 7. convert to points with validation - const auto mpt_traj_points = calcMPTPoints(ref_points, *optimized_steer_angles, mpt_mat); + const auto mpt_traj_points = calcMPTPoints(ref_points, *optimized_variables, mpt_mat); if (!mpt_traj_points) { RCLCPP_WARN(logger_, "return std::nullopt since lateral or yaw error is too large."); return get_prev_optimized_traj_points(); @@ -1160,13 +1160,14 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const bool is_goal_contained = geometry_utils::isSamePoint(ref_points.back(), traj_points.back()); // update Q - Eigen::SparseMatrix Q_sparse_mat(D_x * N_ref, D_x * N_ref); std::vector> Q_triplet_vec; for (size_t i = 0; i < N_ref; ++i) { const auto adaptive_error_weight = [&]() -> std::array { @@ -1198,51 +1199,50 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( Q_triplet_vec.push_back( Eigen::Triplet(i * D_x + 1, i * D_x + 1, adaptive_yaw_error_weight)); } + Eigen::SparseMatrix Q_sparse_mat(N_x, N_x); Q_sparse_mat.setFromTriplets(Q_triplet_vec.begin(), Q_triplet_vec.end()); // update R - Eigen::SparseMatrix R_sparse_mat(D_v, D_v); std::vector> R_triplet_vec; for (size_t i = 0; i < N_ref - 1; ++i) { const double adaptive_steer_weight = interpolation::lerp( mpt_param_.steer_input_weight, mpt_param_.avoidance_steer_input_weight, ref_points.at(i).normalized_avoidance_cost); - R_triplet_vec.push_back( - Eigen::Triplet(D_x + D_u * i, D_x + D_u * i, adaptive_steer_weight)); + R_triplet_vec.push_back(Eigen::Triplet(D_u * i, D_u * i, adaptive_steer_weight)); } + Eigen::SparseMatrix R_sparse_mat(N_u, N_u); addSteerWeightR(R_triplet_vec, ref_points); R_sparse_mat.setFromTriplets(R_triplet_vec.begin(), R_triplet_vec.end()); - ValueMatrix m; - m.Q = Q_sparse_mat; - m.R = R_sparse_mat; - time_keeper_ptr_->toc(__func__, " "); - return m; + return ValueMatrix{Q_sparse_mat, R_sparse_mat}; } MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( - const StateEquationGenerator::Matrix & mpt_mat, const ValueMatrix & val_mat, + [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat, const ValueMatrix & val_mat, const std::vector & ref_points) const { time_keeper_ptr_->tic(__func__); - const size_t N_ref = ref_points.size(); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); - const size_t D_xn = D_x * N_ref; - const size_t D_v = D_x + (N_ref - 1) * D_u; + + const size_t N_ref = ref_points.size(); const size_t N_slack = getNumberOfSlackVariables(); + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; + const size_t N_s = N_ref * N_slack; + + const size_t N_v = N_x + N_u + N_s; + // generate T matrix and vector to shift optimization center // NOTE: Z is defined as time-series vector of shifted deviation - // error where Z = sparse_T_mat * (B * U + W) + T_vec - Eigen::SparseMatrix sparse_T_mat(D_xn, D_xn); - Eigen::VectorXd T_vec = Eigen::VectorXd::Zero(D_xn); + // error where Z = sparse_T_mat * X + T_vec std::vector> triplet_T_vec; + Eigen::VectorXd T_vec = Eigen::VectorXd::Zero(N_x); const double offset = mpt_param_.optimization_center_offset; - for (size_t i = 0; i < N_ref; ++i) { const double alpha = ref_points.at(i).alpha; @@ -1252,38 +1252,26 @@ MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( T_vec(i * D_x) = -offset * std::sin(alpha); } + Eigen::SparseMatrix sparse_T_mat(N_x, N_x); sparse_T_mat.setFromTriplets(triplet_T_vec.begin(), triplet_T_vec.end()); - const Eigen::MatrixXd B = sparse_T_mat * mpt_mat.B; - const Eigen::MatrixXd QB = val_mat.Q * B; - const Eigen::MatrixXd R = val_mat.R; - - // calculate H, and extend it for slack variables // NOTE: min J(v) = min (v'Hv + v'g) - Eigen::MatrixXd H = Eigen::MatrixXd::Zero(D_v, D_v); - H.triangularView() = B.transpose() * QB + R; - H.triangularView() = H.transpose(); - - Eigen::MatrixXd extended_H = Eigen::MatrixXd::Zero(D_v + N_ref * N_slack, D_v + N_ref * N_slack); - extended_H.block(0, 0, D_v, D_v) = H; + Eigen::MatrixXd H_x = Eigen::MatrixXd::Zero(N_x, N_x); + H_x.triangularView() = + Eigen::MatrixXd(sparse_T_mat.transpose() * val_mat.Q * sparse_T_mat); + H_x.triangularView() = H_x.transpose(); - // calculate g, and extend it for slack variables - Eigen::VectorXd g = (sparse_T_mat * mpt_mat.W + T_vec).transpose() * QB; - /* - Eigen::VectorXd extended_g(D_v + N_ref * N_slack); + Eigen::MatrixXd H = Eigen::MatrixXd::Zero(N_v, N_v); + H.block(0, 0, N_x, N_x) = H_x; + H.block(N_x, N_x, N_u, N_u) = val_mat.R; - extended_g.segment(0, D_v) = g; - if (N_slack > 0) { - extended_g.segment(D_v, N_ref * N_slack) = - mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_ref * N_slack); - } - */ - Eigen::VectorXd extended_g(D_v + N_ref * N_slack); - extended_g << g, mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_ref * N_slack); + Eigen::VectorXd g = Eigen::VectorXd::Zero(N_v); + g.segment(0, N_x) = T_vec.transpose() * val_mat.Q * sparse_T_mat; + g.segment(N_x + N_u, N_s) = mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_s); ObjectiveMatrix obj_matrix; - obj_matrix.hessian = extended_H; - obj_matrix.gradient = extended_g; + obj_matrix.hessian = H; + obj_matrix.gradient = g; time_keeper_ptr_->toc(__func__, " "); return obj_matrix; @@ -1300,15 +1288,19 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); + const size_t N_x = N_ref * D_x; const size_t N_u = (N_ref - 1) * D_u; - const size_t D_v = D_x + N_u; - const size_t N_collision_check = vehicle_circle_longitudinal_offsets_.size(); // NOTE: The number of one-step slack variables. // The number of all slack variables will be N_ref * N_slack. const size_t N_slack = getNumberOfSlackVariables(); + const size_t N_v = N_x + N_u + (mpt_param_.soft_constraint ? N_ref * N_slack : 0); + + const size_t N_collision_check = vehicle_circle_longitudinal_offsets_.size(); + // calculate indices of fixed points std::vector fixed_points_indices; for (size_t i = 0; i < N_ref; ++i) { @@ -1319,6 +1311,7 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( // calculate rows and cols of A size_t A_rows = 0; + A_rows += N_x; if (mpt_param_.soft_constraint) { // NOTE: 3 means expecting slack variable constraints to be larger than lower bound, // smaller than upper bound, and positive. @@ -1332,22 +1325,23 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( A_rows += N_u; } - const size_t A_cols = [&] { - if (mpt_param_.soft_constraint) { - return D_v + N_ref * N_slack; // initial state + steer angles + soft variables - } - return D_v; // initial state + steer angles - }(); - - Eigen::MatrixXd A = Eigen::MatrixXd::Zero(A_rows, A_cols); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(A_rows, N_v); Eigen::VectorXd lb = Eigen::VectorXd::Constant(A_rows, -autoware::common::osqp::INF); Eigen::VectorXd ub = Eigen::VectorXd::Constant(A_rows, autoware::common::osqp::INF); size_t A_rows_end = 0; + // 1. State equation + A.block(0, 0, N_x, N_x) = Eigen::MatrixXd::Identity(N_x, N_x) - mpt_mat.A; + A.block(0, N_x, N_x, N_u) = -mpt_mat.B; + lb.segment(0, N_x) = mpt_mat.W; + ub.segment(0, N_x) = mpt_mat.W; + A_rows_end += N_x; + + // 2. collision free // CX = C(Bv + w) + C \in R^{N_ref, N_ref * D_x} for (size_t l_idx = 0; l_idx < N_collision_check; ++l_idx) { // create C := [cos(beta) | l cos(beta)] - Eigen::SparseMatrix C_sparse_mat(N_ref, N_ref * D_x); + Eigen::SparseMatrix C_sparse_mat(N_ref, N_x); std::vector> C_triplet_vec; Eigen::VectorXd C_vec = Eigen::VectorXd::Zero(N_ref); @@ -1362,10 +1356,6 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( } C_sparse_mat.setFromTriplets(C_triplet_vec.begin(), C_triplet_vec.end()); - // calculate CB, and CW - const Eigen::MatrixXd CB = C_sparse_mat * mpt_mat.B; - const Eigen::VectorXd CW = C_sparse_mat * mpt_mat.W + C_vec; - // calculate bounds const double bounds_offset = vehicle_info_.vehicle_width_m / 2.0 - vehicle_circle_radiuses_.at(l_idx); @@ -1373,36 +1363,30 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( // soft constraints if (mpt_param_.soft_constraint) { - size_t A_offset_cols = D_v; const size_t A_blk_rows = 3 * N_ref; - // A := [C * B | O | ... | O | I | O | ... - // -C * B | O | ... | O | I | O | ... + // A := [C | O | ... | O | I | O | ... + // -C | O | ... | O | I | O | ... // O | O | ... | O | I | O | ... ] - Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, A_cols); - A_blk.block(0, 0, N_ref, D_v) = CB; - A_blk.block(N_ref, 0, N_ref, D_v) = -CB; + Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, N_v); + A_blk.block(0, 0, N_ref, N_x) = C_sparse_mat; + A_blk.block(N_ref, 0, N_ref, N_x) = -C_sparse_mat; - size_t local_A_offset_cols = A_offset_cols; - if (!mpt_param_.l_inf_norm) { - local_A_offset_cols += N_ref * l_idx; - } + const size_t local_A_offset_cols = N_x + N_u + (!mpt_param_.l_inf_norm ? N_ref * l_idx : 0); A_blk.block(0, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); A_blk.block(N_ref, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); A_blk.block(2 * N_ref, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); - // lb := [lower_bound - CW - // CW - upper_bound + // lb := [lower_bound - C + // C - upper_bound // O ] Eigen::VectorXd lb_blk = Eigen::VectorXd::Zero(A_blk_rows); - lb_blk.segment(0, N_ref) = -CW + part_lb; - lb_blk.segment(N_ref, N_ref) = CW - part_ub; - - A_offset_cols += N_ref * N_slack; + lb_blk.segment(0, N_ref) = -C_vec + part_lb; + lb_blk.segment(N_ref, N_ref) = C_vec - part_ub; - A.block(A_rows_end, 0, A_blk_rows, A_cols) = A_blk; + A.block(A_rows_end, 0, A_blk_rows, N_v) = A_blk; lb.segment(A_rows_end, A_blk_rows) = lb_blk; A_rows_end += A_blk_rows; @@ -1412,33 +1396,31 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( if (mpt_param_.hard_constraint) { const size_t A_blk_rows = N_ref; - Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, A_cols); - A_blk.block(0, 0, N_ref, N_ref) = CB; + Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, N_v); + A_blk.block(0, 0, N_ref, N_ref) = C_sparse_mat; - A.block(A_rows_end, 0, A_blk_rows, A_cols) = A_blk; - lb.segment(A_rows_end, A_blk_rows) = part_lb - CW; - ub.segment(A_rows_end, A_blk_rows) = part_ub - CW; + A.block(A_rows_end, 0, A_blk_rows, N_v) = A_blk; + lb.segment(A_rows_end, A_blk_rows) = part_lb - C_vec; + ub.segment(A_rows_end, A_blk_rows) = part_ub - C_vec; A_rows_end += A_blk_rows; } } - // fixed points constraint + // 3. fixed points constraint // X = B v + w where point is fixed for (const size_t i : fixed_points_indices) { - A.block(A_rows_end, 0, D_x, D_v) = mpt_mat.B.block(i * D_x, 0, D_x, D_v); + A.block(A_rows_end, D_x * i, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); - lb.segment(A_rows_end, D_x) = - ref_points[i].fixed_kinematic_state->toEigenVector() - mpt_mat.W.segment(i * D_x, D_x); - ub.segment(A_rows_end, D_x) = - ref_points[i].fixed_kinematic_state->toEigenVector() - mpt_mat.W.segment(i * D_x, D_x); + lb.segment(A_rows_end, D_x) = ref_points.at(i).fixed_kinematic_state->toEigenVector(); + ub.segment(A_rows_end, D_x) = ref_points.at(i).fixed_kinematic_state->toEigenVector(); A_rows_end += D_x; } - // steer limit + // 4. steer angle limit if (mpt_param_.steer_limit_constraint) { - A.block(A_rows_end, D_x, N_u, N_u) = Eigen::MatrixXd::Identity(N_u, N_u); + A.block(A_rows_end, N_x, N_u, N_u) = Eigen::MatrixXd::Identity(N_u, N_u); // TODO(murooka) use curvature by stabling optimization // Currently, when using curvature, the optimization result is weird with sample_map. @@ -1468,13 +1450,13 @@ void MPTOptimizer::addSteerWeightR( std::vector> & R_triplet_vec, const std::vector & ref_points) const { - const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_u = (N_ref - 1) * D_u; // add steering rate : weight for (u(i) - u(i-1))^2 - for (size_t i = D_x; i < D_v - 1; ++i) { + for (size_t i = 0; i < N_u - 1; ++i) { R_triplet_vec.push_back(Eigen::Triplet(i, i, mpt_param_.steer_rate_weight)); R_triplet_vec.push_back(Eigen::Triplet(i + 1, i, -mpt_param_.steer_rate_weight)); R_triplet_vec.push_back(Eigen::Triplet(i, i + 1, -mpt_param_.steer_rate_weight)); @@ -1490,10 +1472,12 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const size_t N_slack = getNumberOfSlackVariables(); - const size_t D_un = D_v + N_ref * N_slack; + const size_t N_v = N_x + N_u + N_ref * N_slack; // for manual warm start, calculate initial solution const auto u0 = [&]() -> std::optional { @@ -1522,7 +1506,9 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const autoware::common::osqp::CSC_Matrix P_csc = autoware::common::osqp::calCSCMatrixTrapezoidal(H); const autoware::common::osqp::CSC_Matrix A_csc = autoware::common::osqp::calCSCMatrix(A); - if (mpt_param_.enable_warm_start && prev_mat_n_ == H.rows() && prev_mat_m_ == A.rows()) { + if ( + prev_solution_status_ == 1 && mpt_param_.enable_warm_start && prev_mat_n_ == H.rows() && + prev_mat_m_ == A.rows()) { RCLCPP_INFO_EXPRESSION(logger_, enable_debug_info_, "warm start"); osqp_solver_ptr_->updateCscP(P_csc); osqp_solver_ptr_->updateQ(f); @@ -1546,6 +1532,7 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( // check solution status const int solution_status = std::get<3>(result); + prev_solution_status_ = solution_status; if (solution_status != 1) { osqp_solver_ptr_->logUnsolvedStatus("[MPT]"); return std::nullopt; @@ -1565,15 +1552,15 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( RCLCPP_WARN(logger_, "optimization failed: result contains NaN values"); return std::nullopt; } - const Eigen::VectorXd optimized_steer_angles = - Eigen::Map(&optimization_result[0], D_un); + const Eigen::VectorXd optimized_variables = + Eigen::Map(&optimization_result[0], N_v); time_keeper_ptr_->toc(__func__, " "); if (u0) { // manual warm start - return static_cast(optimized_steer_angles + *u0); + return static_cast(optimized_variables + *u0); } - return optimized_steer_angles; + return optimized_variables; } Eigen::VectorXd MPTOptimizer::calcInitialSolutionForManualWarmStart( @@ -1649,30 +1636,30 @@ MPTOptimizer::updateMatrixForManualWarmStart( } std::optional> MPTOptimizer::calcMPTPoints( - std::vector & ref_points, const Eigen::VectorXd & U, - const StateEquationGenerator::Matrix & mpt_mat) const + std::vector & ref_points, const Eigen::VectorXd & optimized_variables, + [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat) const { time_keeper_ptr_->tic(__func__); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const size_t N_slack = getNumberOfSlackVariables(); - const Eigen::VectorXd steer_angles = U.segment(0, D_v); - const Eigen::VectorXd slack_variables = U.segment(D_v, N_ref * N_slack); - - // predict time-series states from optimized control inputs - const Eigen::VectorXd X = state_equation_generator_.predict(mpt_mat, steer_angles); + const Eigen::VectorXd states = optimized_variables.segment(0, N_x); + const Eigen::VectorXd steer_angles = optimized_variables.segment(N_x, N_u); + const Eigen::VectorXd slack_variables = optimized_variables.segment(N_x + N_u, N_ref * N_slack); // calculate trajectory points from optimization result std::vector traj_points; for (size_t i = 0; i < N_ref; ++i) { auto & ref_point = ref_points.at(i); - const double lat_error = X(i * D_x); - const double yaw_error = X(i * D_x + 1); + const double lat_error = states(i * D_x); + const double yaw_error = states(i * D_x + 1); // validate optimization result if (mpt_param_.enable_optimization_validation) { @@ -1688,7 +1675,7 @@ std::optional> MPTOptimizer::calcMPTPoints( if (i == N_ref - 1) { ref_point.optimized_input = 0.0; } else { - ref_point.optimized_input = steer_angles(D_x + i * D_u); + ref_point.optimized_input = steer_angles(i * D_u); } std::vector tmp_slack_variables; diff --git a/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp b/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp index a6eaf7ffdd2ac..7460ce9c1f764 100644 --- a/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp +++ b/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp @@ -25,31 +25,27 @@ StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( { time_keeper_ptr_->tic(__func__); - const size_t N_ref = ref_points.size(); const size_t D_x = vehicle_model_ptr_->getDimX(); const size_t D_u = vehicle_model_ptr_->getDimU(); - const size_t D_v = D_x + D_u * (N_ref - 1); + + const size_t N_ref = ref_points.size(); + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; // matrices for whole state equation - Eigen::MatrixXd B = Eigen::MatrixXd::Zero(D_x * N_ref, D_v); - Eigen::VectorXd W = Eigen::VectorXd::Zero(D_x * N_ref); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(N_x, N_x); + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(N_x, N_u); + Eigen::VectorXd W = Eigen::VectorXd::Zero(N_x); // matrices for one-step state equation Eigen::MatrixXd Ad(D_x, D_x); Eigen::MatrixXd Bd(D_x, D_u); Eigen::MatrixXd Wd(D_x, 1); - // calculate one-step state equation considering kinematics N_ref times - for (size_t i = 0; i < N_ref; ++i) { - if (i == 0) { - B.block(0, 0, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); - continue; - } - - const int idx_x_i = i * D_x; - const int idx_x_i_prev = (i - 1) * D_x; - const int idx_u_i_prev = (i - 1) * D_u; + A.block(0, 0, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); + // calculate one-step state equation considering kinematics N_ref times + for (size_t i = 1; i < N_ref; ++i) { // get discrete kinematics matrix A, B, W const auto & p = ref_points.at(i - 1); @@ -59,24 +55,13 @@ StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( // p.delta_arc_length); vehicle_model_ptr_->calculateStateEquationMatrix(Ad, Bd, Wd, 0.0, p.delta_arc_length); - B.block(idx_x_i, 0, D_x, D_x) = Ad * B.block(idx_x_i_prev, 0, D_x, D_x); - B.block(idx_x_i, D_x + idx_u_i_prev, D_x, D_u) = Bd; - - for (size_t j = 0; j < i - 1; ++j) { - size_t idx_u_j = j * D_u; - B.block(idx_x_i, D_x + idx_u_j, D_x, D_u) = - Ad * B.block(idx_x_i_prev, D_x + idx_u_j, D_x, D_u); - } - - W.segment(idx_x_i, D_x) = Ad * W.block(idx_x_i_prev, 0, D_x, 1) + Wd; + A.block(i * D_x, (i - 1) * D_x, D_x, D_x) = Ad; + B.block(i * D_x, (i - 1) * D_u, D_x, D_u) = Bd; + W.segment(i * D_x, D_x) = Wd; } - Matrix mat; - mat.B = B; - mat.W = W; - time_keeper_ptr_->toc(__func__, " "); - return mat; + return Matrix{A, B, W}; } Eigen::VectorXd StateEquationGenerator::predict( From d8efc136d2c10c75106d798e3a0c119452439a03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 13 Aug 2023 01:47:49 +0900 Subject: [PATCH 155/266] feat(obstacle_avoidance_planner): add depth argument in plotter (#4605) Signed-off-by: Takayuki Murooka --- .../scripts/calculation_time_plotter.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py index 042c2ff5f0345..eb4e028f5245d 100755 --- a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py +++ b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py @@ -28,6 +28,7 @@ def __init__(self, args): super().__init__("calculation_cost_analyzer") self.functions_name = args.functions.split(",") + self.depth = args.depth self.calculation_cost_hist = [] self.sub_calculation_cost = self.create_subscription( @@ -67,7 +68,7 @@ def CallbackCalculationCost(self, msg): if not is_found: self.y_vec[f_idx].append(None) - if len(self.y_vec[f_idx]) > 100: + if len(self.y_vec[f_idx]) > self.depth: self.y_vec[f_idx].popleft() x_vec = list(range(len(self.y_vec[f_idx]))) @@ -99,7 +100,13 @@ def CallbackCalculationCost(self, msg): "-f", "--functions", type=str, - default="onPath, getModelPredictiveTrajectory, getEBTrajectory", + default="onPath, optimizeTrajectory, publishDebugMarkerOfOptimization, solveOsqp", + ) + parser.add_argument( + "-d", + "--depth", + type=float, + default=500, ) args = parser.parse_args() From d4782c44377e1f3fb4187bcad120f0f8e167c219 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 13:21:32 +0900 Subject: [PATCH 156/266] feat(route_handler): support shoulder lane in getLeft(Right)Lanelet (#4604) Signed-off-by: kosuke55 --- planning/route_handler/src/route_handler.cpp | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 4e009836b53d4..26d226a6746e2 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -942,6 +942,16 @@ bool RouteHandler::isBijectiveConnection( boost::optional RouteHandler::getRightLanelet( const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const { + // right road lanelet of shoulder lanelet + if (isShoulderLanelet(lanelet)) { + for (const auto & road_lanelet : road_lanelets_) { + if (lanelet::geometry::rightOf(road_lanelet, lanelet)) { + return road_lanelet; + } + } + return boost::none; + } + // routable lane const auto & right_lane = routing_graph_ptr_->right(lanelet); if (right_lane) { @@ -999,6 +1009,16 @@ bool RouteHandler::getLeftLaneletWithinRoute( boost::optional RouteHandler::getLeftLanelet( const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const { + // left road lanelet of shoulder lanelet + if (isShoulderLanelet(lanelet)) { + for (const auto & road_lanelet : road_lanelets_) { + if (lanelet::geometry::leftOf(road_lanelet, lanelet)) { + return road_lanelet; + } + } + return boost::none; + } + // routable lane const auto & left_lane = routing_graph_ptr_->left(lanelet); if (left_lane) { From c2b7b7dd2b65a4b30521d9a60bca5116f62b11eb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 19:02:24 +0900 Subject: [PATCH 157/266] chore(scenario_selector): fix typo (#4613) chore(scneario_selector): fix typo Signed-off-by: kosuke55 --- .../src/scenario_selector_node/scenario_selector_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index cffb490464de0..1d5c7b44dcc45 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -197,7 +197,7 @@ void ScenarioSelectorNode::onMap( void ScenarioSelectorNode::onRoute( const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg) { - // When the route id is the same (e.g. reporting with modified goal) keep the current scenario. + // When the route id is the same (e.g. rerouting with modified goal) keep the current scenario. // Otherwise, reset the scenario. if (!route_handler_ || route_handler_->getRouteUuid() != msg->uuid) { current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; From 7f02d6a7adf7451cd1808bd658d4d1e70a2b7b1e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 19:02:37 +0900 Subject: [PATCH 158/266] fix(start_planner): fix geometric parallel parking lane ids (#4603) * fix(start_planner): fix geometric parallel parking lane ids Signed-off-by: kosuke55 * fix stop path drivable lanes Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.hpp | 2 +- .../start_planner/start_planner_module.cpp | 38 ++++++++++++--- .../geometric_parallel_parking.cpp | 48 ++++++++++++------- 3 files changed, 64 insertions(+), 24 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 1405e3cd1f10e..3214de2c37bd7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -143,7 +143,7 @@ class StartPlannerModule : public SceneModuleInterface const std::vector & start_pose_candidates, const Pose & goal_pose, const std::string search_priority); PathWithLaneId generateStopPath() const; - lanelet::ConstLanelets getPathLanes(const PathWithLaneId & path) const; + lanelet::ConstLanelets getPathRoadLanes(const PathWithLaneId & path) const; std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); static bool isOverlappedWithLane( diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 32398c7944435..fb471a4675fa7 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -534,19 +534,23 @@ PathWithLaneId StartPlannerModule::generateStopPath() const return path; } -lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & path) const +lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId & path) const { + const auto & route_handler = planner_data_->route_handler; + const auto & lanelet_layer = route_handler->getLaneletMapPtr()->laneletLayer; + std::vector lane_ids; for (const auto & p : path.points) { for (const auto & id : p.lane_ids) { + if (route_handler->isShoulderLanelet(lanelet_layer.get(id))) { + continue; + } if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) { lane_ids.push_back(id); } } } - const auto & lanelet_layer = planner_data_->route_handler->getLaneletMapPtr()->laneletLayer; - lanelet::ConstLanelets path_lanes; path_lanes.reserve(lane_ids.size()); for (const auto & id : lane_ids) { @@ -561,7 +565,22 @@ lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & p std::vector StartPlannerModule::generateDrivableLanes( const PathWithLaneId & path) const { - return utils::generateDrivableLanesWithShoulderLanes(getPathLanes(path), status_.pull_out_lanes); + const auto path_road_lanes = getPathRoadLanes(path); + + if (!path_road_lanes.empty()) { + return utils::generateDrivableLanesWithShoulderLanes( + getPathRoadLanes(path), status_.pull_out_lanes); + } + + // if path_road_lanes is empty, use only pull_out_lanes as drivable lanes + std::vector drivable_lanes; + for (const auto & lane : status_.pull_out_lanes) { + DrivableLanes drivable_lane; + drivable_lane.right_lane = lane; + drivable_lane.left_lane = lane; + drivable_lanes.push_back(drivable_lane); + } + return drivable_lanes; } void StartPlannerModule::updatePullOutStatus() @@ -702,10 +721,15 @@ bool StartPlannerModule::hasFinishedPullOut() const const auto current_pose = planner_data_->self_odometry->pose.pose; // check that ego has passed pull out end point - const auto path_lanes = getPathLanes(getFullPath()); - const auto arclength_current = lanelet::utils::getArcCoordinates(path_lanes, current_pose); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + + const auto arclength_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose); const auto arclength_pull_out_end = - lanelet::utils::getArcCoordinates(path_lanes, status_.pull_out_path.end_pose); + lanelet::utils::getArcCoordinates(current_lanes, status_.pull_out_path.end_pose); // offset to not finish the module before engage constexpr double offset = 0.1; diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp index 678e19e616f26..4f8c7ff9a94b4 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp @@ -368,7 +368,8 @@ std::vector GeometricParallelParking::planOneTrial( { clearPaths(); - const auto common_params = planner_data_->parameters; + const auto & common_params = planner_data_->parameters; + const auto & route_handler = planner_data_->route_handler; const Pose arc_end_pose = calcOffsetPose(goal_pose, end_pose_offset, 0, 0); const double self_yaw = tf2::getYaw(start_pose.orientation); @@ -435,34 +436,49 @@ std::vector GeometricParallelParking::planOneTrial( PathWithLaneId path_turn_left = generateArcPath( Cl, R_E_l, -M_PI_2, normalizeRadian(-M_PI_2 + theta_l), arc_path_interval, is_forward, is_forward); - path_turn_left.header = planner_data_->route_handler->getRouteHeader(); + path_turn_left.header = route_handler->getRouteHeader(); PathWithLaneId path_turn_right = generateArcPath( Cr, R_E_r, normalizeRadian(psi + M_PI_2 + theta_l), M_PI_2, arc_path_interval, !is_forward, is_forward); - path_turn_right.header = planner_data_->route_handler->getRouteHeader(); + path_turn_right.header = route_handler->getRouteHeader(); - auto setLaneIds = [lanes](PathPointWithLaneId & p) { - for (const auto & lane : lanes) { - p.lane_ids.push_back(lane.id()); + // Need to add straight path to last right_turning for parking in parallel + if (std::abs(end_pose_offset) > 0) { + PathPointWithLaneId straight_point{}; + straight_point.point.pose = goal_pose; + // setLaneIds(straight_point); + path_turn_right.points.push_back(straight_point); + } + + // Populate lane ids for a given path. + // It checks if each point in the path is within a lane + // and if its ID hasn't been added yet, it appends the ID to the container. + std::vector path_lane_ids; + const auto populateLaneIds = [&](const auto & path) { + for (const auto & p : path.points) { + for (const auto & lane : lanes) { + if ( + lanelet::utils::isInLanelet(p.point.pose, lane) && + std::find(path_lane_ids.begin(), path_lane_ids.end(), lane.id()) == path_lane_ids.end()) { + path_lane_ids.push_back(lane.id()); + } + } } }; - auto setLaneIdsToPath = [setLaneIds](PathWithLaneId & path) { + populateLaneIds(path_turn_left); + populateLaneIds(path_turn_right); + + // Set lane ids to each point in a given path. + // It assigns the accumulated lane ids from path_lane_ids to each point's lane_ids member. + const auto setLaneIdsToPath = [&](PathWithLaneId & path) { for (auto & p : path.points) { - setLaneIds(p); + p.lane_ids = path_lane_ids; } }; setLaneIdsToPath(path_turn_left); setLaneIdsToPath(path_turn_right); - // Need to add straight path to last right_turning for parking in parallel - if (std::abs(end_pose_offset) > 0) { - PathPointWithLaneId straight_point{}; - straight_point.point.pose = goal_pose; - setLaneIds(straight_point); - path_turn_right.points.push_back(straight_point); - } - // generate arc path vector paths_.push_back(path_turn_left); paths_.push_back(path_turn_right); From e0e9fcfd601b6ccde71a75d4e04898e5f92f049e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 14 Aug 2023 08:36:16 +0900 Subject: [PATCH 159/266] fix(avoidance): fix dying with empty lanes (#4606) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/avoidance/utils.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index ed38cc663bc84..c88fc377dc473 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -855,6 +855,10 @@ void filterTargetObjects( using lanelet::geometry::toArcCoordinates; using lanelet::utils::to2D; + if (data.current_lanelets.empty()) { + return; + } + const auto & rh = planner_data->route_handler; const auto & path_points = data.reference_path_rough.points; const auto & ego_pos = planner_data->self_odometry->pose.pose.position; From 9560d573cec741b829281029dc327d05cfac2e2b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 14 Aug 2023 14:47:47 +0900 Subject: [PATCH 160/266] feat(lane_departure_checker): add maintainer (#4611) add maintainer Signed-off-by: kyoichi-sugahara --- control/lane_departure_checker/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index d4e845ec97d82..1059e86cadc6d 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -5,6 +5,7 @@ 0.1.0 The lane_departure_checker package Kyoichi Sugahara + Makoto Kurihara Apache License 2.0 ament_cmake_auto From e8dd2255f3a07aa4cd21d4596d22a7145ec1a9ef Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 14 Aug 2023 17:48:50 +0900 Subject: [PATCH 161/266] fix(behavior_path_planner): change skip updataData() process condition (#4573) change skip condition Signed-off-by: kyoichi-sugahara --- .../src/scene_module/side_shift/side_shift_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 8e169309dfb00..4e9680cee4d59 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -185,7 +185,7 @@ void SideShiftModule::updateData() } } - if (current_state_ != ModuleStatus::RUNNING) { + if (current_state_ != ModuleStatus::RUNNING && current_state_ != ModuleStatus::IDLE) { return; } From bd7e95f00d65ae1023dc06dc82455c121b1e879f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 14 Aug 2023 19:18:33 +0900 Subject: [PATCH 162/266] feat(map_based_prediction): plan paths of objects outside the lanelets. (#4618) * add publisher of calculation time Signed-off-by: Takayuki Murooka * plan path of objects outside the lane Signed-off-by: Takayuki Murooka * minor change Signed-off-by: Takayuki Murooka * fix CI Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../map_based_prediction_node.hpp | 7 ++- perception/map_based_prediction/package.xml | 1 + .../src/map_based_prediction_node.cpp | 62 +++++++++++++------ 3 files changed, 49 insertions(+), 21 deletions(-) diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 6a0bb29e9fb2d..5903706123169 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -31,6 +32,7 @@ #include #include #include +#include #include #include @@ -106,6 +108,7 @@ using autoware_auto_perception_msgs::msg::TrackedObject; using autoware_auto_perception_msgs::msg::TrackedObjectKinematics; using autoware_auto_perception_msgs::msg::TrackedObjects; using tier4_autoware_utils::StopWatch; +using tier4_debug_msgs::msg::StringStamped; class MapBasedPredictionNode : public rclcpp::Node { @@ -116,6 +119,7 @@ class MapBasedPredictionNode : public rclcpp::Node // ROS Publisher and Subscriber rclcpp::Publisher::SharedPtr pub_objects_; rclcpp::Publisher::SharedPtr pub_debug_markers_; + rclcpp::Publisher::SharedPtr pub_calculation_time_; rclcpp::Subscription::SharedPtr sub_objects_; rclcpp::Subscription::SharedPtr sub_map_; @@ -179,8 +183,7 @@ class MapBasedPredictionNode : public rclcpp::Node LaneletsData getCurrentLanelets(const TrackedObject & object); bool checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object, - const lanelet::BasicPoint2d & search_point); + const std::pair & lanelet, const TrackedObject & object); float calculateLocalLikelihood( const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const; void updateObjectData(TrackedObject & object); diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 33abfe814c498..0765490502ec4 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -23,6 +23,7 @@ tf2_geometry_msgs tf2_ros tier4_autoware_utils + tier4_debug_msgs unique_identifier_msgs visualization_msgs diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 9292476e80c8e..66a15f28bdd1b 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -40,6 +40,8 @@ namespace map_based_prediction { +namespace +{ /** * @brief First order Low pass filtering * @@ -586,6 +588,15 @@ ObjectClassification::_label_type changeLabelForPrediction( } } +StringStamped createStringStamped(const rclcpp::Time & now, const double data) +{ + StringStamped msg; + msg.stamp = now; + msg.data = std::to_string(data); + return msg; +} +} // namespace + MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) : Node("map_based_prediction", node_options), debug_accumulated_time_(0.0) { @@ -649,6 +660,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ pub_objects_ = this->create_publisher("objects", rclcpp::QoS{1}); pub_debug_markers_ = this->create_publisher("maneuver", rclcpp::QoS{1}); + pub_calculation_time_ = create_publisher("~/debug/calculation_time", 1); } PredictedObjectKinematics MapBasedPredictionNode::convertToPredictedKinematics( @@ -691,6 +703,7 @@ void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg) void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects) { + stop_watch_.tic(); // Guard for map pointer and frame transformation if (!lanelet_map_ptr_) { return; @@ -869,6 +882,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // Publish Results pub_objects_->publish(output); pub_debug_markers_->publish(debug_markers); + const auto calculation_time_msg = createStringStamped(now(), stop_watch_.toc()); + pub_calculation_time_->publish(calculation_time_msg); } PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( @@ -1076,39 +1091,48 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob return {}; } - LaneletsData closest_lanelets; + LaneletsData object_lanelets; + std::optional> closest_lanelet{std::nullopt}; for (const auto & lanelet : surrounding_lanelets) { // Check if the close lanelets meet the necessary condition for start lanelets and - // Check if similar lanelet is inside the closest lanelet - if ( - !checkCloseLaneletCondition(lanelet, object, search_point) || - isDuplicated(lanelet, closest_lanelets)) { + // Check if similar lanelet is inside the object lanelet + if (!checkCloseLaneletCondition(lanelet, object) || isDuplicated(lanelet, object_lanelets)) { continue; } - LaneletData closest_lanelet; - closest_lanelet.lanelet = lanelet.second; - closest_lanelet.probability = calculateLocalLikelihood(lanelet.second, object); - closest_lanelets.push_back(closest_lanelet); + // Memorize closest lanelet + // NOTE: The object may be outside the lanelet. + if (!closest_lanelet || lanelet.first < closest_lanelet->first) { + closest_lanelet = lanelet; + } + + // Check if the obstacle is inside of this lanelet + constexpr double epsilon = 1e-3; + if (lanelet.first < epsilon) { + const auto object_lanelet = + LaneletData{lanelet.second, calculateLocalLikelihood(lanelet.second, object)}; + object_lanelets.push_back(object_lanelet); + } } - return closest_lanelets; + if (!object_lanelets.empty()) { + return object_lanelets; + } + if (closest_lanelet) { + return LaneletsData{LaneletData{ + closest_lanelet->second, calculateLocalLikelihood(closest_lanelet->second, object)}}; + } + return LaneletsData{}; } bool MapBasedPredictionNode::checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object, - const lanelet::BasicPoint2d & search_point) + const std::pair & lanelet, const TrackedObject & object) { // Step1. If we only have one point in the centerline, we will ignore the lanelet if (lanelet.second.centerline().size() <= 1) { return false; } - // Step2. Check if the obstacle is inside of this lanelet - if (!lanelet::geometry::inside(lanelet.second, search_point)) { - return false; - } - // If the object is in the objects history, we check if the target lanelet is // inside the current lanelets id or following lanelets const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); @@ -1124,7 +1148,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( } } - // Step3. Calculate the angle difference between the lane angle and obstacle angle + // Step2. Calculate the angle difference between the lane angle and obstacle angle const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); const double lane_yaw = lanelet::utils::getLaneletAngle( lanelet.second, object.kinematics.pose_with_covariance.pose.position); @@ -1132,7 +1156,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); const double abs_norm_delta = std::fabs(normalized_delta_yaw); - // Step4. Check if the closest lanelet is valid, and add all + // Step3. Check if the closest lanelet is valid, and add all // of the lanelets that are below max_dist and max_delta_yaw const double object_vel = object.kinematics.twist_with_covariance.twist.linear.x; const bool is_yaw_reversed = From 0ae23d4474bc465dbb97f26b2d7cd73f6e8c6001 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 14 Aug 2023 22:06:54 +0900 Subject: [PATCH 163/266] feat(lane_change): ignore front parked objects (#4591) Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- .../scene_module/lane_change/normal.hpp | 4 + .../utils/lane_change/utils.hpp | 6 - .../src/scene_module/lane_change/normal.cpp | 115 +++++++++++++++++- .../src/utils/lane_change/utils.cpp | 82 ------------- 4 files changed, 116 insertions(+), 91 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index a6a6d12a5642b..948a2cc4fbb2a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -143,6 +143,10 @@ class NormalLaneChange : public LaneChangeBase const double front_decel, const double rear_decel, std::unordered_map & debug_data) const; + LaneChangeTargetObjectIndices filterObject( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const lanelet::ConstLanelets & target_backward_lanes) const; + rclcpp::Logger logger_ = rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()); }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index dc8298720239c..266c52918c567 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -186,12 +186,6 @@ boost::optional getLeadingStaticObjectIdx( std::optional createPolygon( const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist); -LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, - const Pose & current_pose, const RouteHandler & route_handler, - const LaneChangeParameters & lane_change_parameters); - ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 2f7c39f94604e..29cefe110d9e4 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -604,9 +604,7 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( route_handler, target_lanes, current_pose, backward_length); // filter objects to get target object index - const auto target_obj_index = utils::lane_change::filterObject( - objects, current_lanes, target_lanes, target_backward_lanes, current_pose, route_handler, - *lane_change_parameters_); + const auto target_obj_index = filterObject(current_lanes, target_lanes, target_backward_lanes); LaneChangeTargetObjects target_objects; target_objects.current_lane.reserve(target_obj_index.current_lane.size()); @@ -637,6 +635,117 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( return target_objects; } +LaneChangeTargetObjectIndices NormalLaneChange::filterObject( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const lanelet::ConstLanelets & target_backward_lanes) const +{ + const auto current_pose = getEgoPose(); + const auto current_vel = getEgoVelocity(); + const auto & route_handler = *getRouteHandler(); + const auto & common_parameters = planner_data_->parameters; + const auto & objects = *planner_data_->dynamic_object; + const auto & object_check_min_road_shoulder_width = + lane_change_parameters_->object_check_min_road_shoulder_width; + const auto & object_shiftable_ratio_threshold = + lane_change_parameters_->object_shiftable_ratio_threshold; + + // Guard + if (objects.objects.empty()) { + return {}; + } + + // Get path + const auto path = + route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + const auto target_path = + route_handler.getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + + const auto current_polygon = + utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + const auto target_polygon = + utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + const auto target_backward_polygon = utils::lane_change::createPolygon( + target_backward_lanes, 0.0, std::numeric_limits::max()); + + // minimum distance to lane changing start point + const double t_prepare = common_parameters.lane_change_prepare_duration; + const double a_min = lane_change_parameters_->min_longitudinal_acc; + const double min_dist_to_lane_changing_start = std::max( + current_vel * t_prepare, current_vel * t_prepare + 0.5 * a_min * t_prepare * t_prepare); + + LaneChangeTargetObjectIndices filtered_obj_indices; + for (size_t i = 0; i < objects.objects.size(); ++i) { + const auto & object = objects.objects.at(i); + const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; + const auto extended_object = + utils::lane_change::transform(object, common_parameters, *lane_change_parameters_); + + // ignore specific object types + if (!utils::lane_change::isTargetObjectType(object, *lane_change_parameters_)) { + continue; + } + + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); + + // calc distance from the current ego position + double max_dist_ego_to_obj = std::numeric_limits::lowest(); + double min_dist_ego_to_obj = std::numeric_limits::max(); + for (const auto & polygon_p : obj_polygon.outer()) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const double dist_ego_to_obj = + motion_utils::calcSignedArcLength(path.points, current_pose.position, obj_p); + max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); + min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj); + } + + // ignore static object that are behind the ego vehicle + if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { + continue; + } + + // check if the object intersects with target lanes + if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { + // ignore static parked object that are in front of the ego vehicle in target lanes + bool is_parked_object = utils::lane_change::isParkedObject( + target_path, route_handler, extended_object, object_check_min_road_shoulder_width, + object_shiftable_ratio_threshold); + if (is_parked_object && min_dist_ego_to_obj > min_dist_to_lane_changing_start) { + continue; + } + + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with target backward lanes + if ( + target_backward_polygon && + boost::geometry::intersects(target_backward_polygon.value(), obj_polygon)) { + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with current lanes + if ( + current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && + max_dist_ego_to_obj >= 0.0) { + // check only the objects that are in front of the ego vehicle + filtered_obj_indices.current_lane.push_back(i); + continue; + } + + // ignore all objects that are behind the ego vehicle and not on the current and target + // lanes + if (max_dist_ego_to_obj < 0.0) { + continue; + } + + filtered_obj_indices.other_lane.push_back(i); + } + + return filtered_obj_indices; +} + PathWithLaneId NormalLaneChange::getTargetSegment( const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, const double lane_changing_length, diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index b3688fdb1310e..c22c07c0e80c5 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -1078,88 +1078,6 @@ std::optional createPolygon( return lanelet::utils::to2D(polygon_3d).basicPolygon(); } -LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, - const Pose & current_pose, const RouteHandler & route_handler, - const LaneChangeParameters & lane_change_parameter) -{ - // Guard - if (objects.objects.empty()) { - return {}; - } - - // Get path - const auto path = - route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - - const auto current_polygon = - createPolygon(current_lanes, 0.0, std::numeric_limits::max()); - const auto target_polygon = createPolygon(target_lanes, 0.0, std::numeric_limits::max()); - const auto target_backward_polygon = - createPolygon(target_backward_lanes, 0.0, std::numeric_limits::max()); - - LaneChangeTargetObjectIndices filtered_obj_indices; - for (size_t i = 0; i < objects.objects.size(); ++i) { - const auto & object = objects.objects.at(i); - const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; - - // ignore specific object types - if (!isTargetObjectType(object, lane_change_parameter)) { - continue; - } - - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - - // calc distance from the current ego position - double max_dist_ego_to_obj = std::numeric_limits::lowest(); - for (const auto & polygon_p : obj_polygon.outer()) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const double dist_ego_to_obj = - motion_utils::calcSignedArcLength(path.points, current_pose.position, obj_p); - max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); - } - - // ignore static object that are behind the ego vehicle - if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { - continue; - } - - // check if the object intersects with target lanes - if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - - // check if the object intersects with target backward lanes - if ( - target_backward_polygon && - boost::geometry::intersects(target_backward_polygon.value(), obj_polygon)) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - - // check if the object intersects with current lanes - if ( - current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && - max_dist_ego_to_obj >= 0.0) { - // check only the objects that are in front of the ego vehicle - filtered_obj_indices.current_lane.push_back(i); - continue; - } - - // ignore all objects that are behind the ego vehicle and not on the current and target - // lanes - if (max_dist_ego_to_obj < 0.0) { - continue; - } - - filtered_obj_indices.other_lane.push_back(i); - } - - return filtered_obj_indices; -} - ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters) From 48d5336778850ff48a37b299438087c50333a28b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 15 Aug 2023 02:07:41 +0900 Subject: [PATCH 164/266] fix(behavior_path_planner): add guard to combineDrivableLanes (#4626) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/utils.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 47729bab4d11f..8cc94bd6b46fa 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3247,9 +3247,11 @@ std::vector combineDrivableLanes( } // NOTE: If original_drivable_lanes_vec is shorter than new_drivable_lanes_vec, push back remained // new_drivable_lanes_vec. - updated_drivable_lanes_vec.insert( - updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, - new_drivable_lanes_vec.end()); + if (new_drivable_lanes_idx + 1 < new_drivable_lanes_vec.size()) { + updated_drivable_lanes_vec.insert( + updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, + new_drivable_lanes_vec.end()); + } return updated_drivable_lanes_vec; } From 90930e5ac033b7e312c10baa0cca29d740f9ebda Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 15 Aug 2023 09:39:36 +0900 Subject: [PATCH 165/266] docs(traffic_light_multi_camera_fusion): fix broken table display (#4621) * docs(traffic_light_multi_camera_fusion): fix broken table display Signed-off-by: Tomohito Ando * style(pre-commit): autofix --------- Signed-off-by: Tomohito Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_multi_camera_fusion/README.md | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/perception/traffic_light_multi_camera_fusion/README.md b/perception/traffic_light_multi_camera_fusion/README.md index 2f225f1540f63..f7ee294cda147 100644 --- a/perception/traffic_light_multi_camera_fusion/README.md +++ b/perception/traffic_light_multi_camera_fusion/README.md @@ -9,12 +9,13 @@ ## Input topics -For every camera, the following three topics are subscribed: -| Name | Type | | -| ---------------------------------------| -------------------------------------------------------|----------------------------------------------------| -| `~//camera_info` | sensor_msgs::CameraInfo |camera info from traffic_light_map_based_detector | -| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray |detection roi from traffic_light_fine_detector | -| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray |classification result from traffic_light_classifier | +For every camera, the following three topics are subscribed: + +| Name | Type | Description | +| -------------------------------------- | ---------------------------------------------- | --------------------------------------------------- | +| `~//camera_info` | sensor_msgs::CameraInfo | camera info from traffic_light_map_based_detector | +| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray | detection roi from traffic_light_fine_detector | +| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray | classification result from traffic_light_classifier | You don't need to configure these topics manually. Just provide the `camera_namespaces` parameter and the node will automatically extract the `` and create the subscribers. From e1472ea4b8886377e205b520c511f4427b5a08f8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 15 Aug 2023 10:51:18 +0900 Subject: [PATCH 166/266] fix(behavior_path_planner): fix simultaneous execution (#4622) Signed-off-by: kosuke55 --- .../scene_module/goal_planner/manager.hpp | 6 +++ .../scene_module/scene_module_interface.hpp | 20 -------- .../scene_module_manager_interface.hpp | 34 ++----------- .../scene_module/start_planner/manager.hpp | 4 ++ .../start_planner/start_planner_module.hpp | 13 +---- .../utils/goal_planner/util.hpp | 5 ++ .../goal_planner/goal_planner_module.cpp | 30 +++++------ .../src/scene_module/goal_planner/manager.cpp | 29 +++++++++++ .../scene_module/start_planner/manager.cpp | 51 +++++++++++++++++-- .../start_planner/start_planner_module.cpp | 12 ----- .../src/utils/goal_planner/util.cpp | 22 ++++++++ 11 files changed, 133 insertions(+), 93 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp index 592a578f7fc72..c410999b2aaa9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp @@ -40,8 +40,14 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface void updateModuleParams(const std::vector & parameters) override; + bool isSimultaneousExecutableAsApprovedModule() const override; + + bool isSimultaneousExecutableAsCandidateModule() const override; + private: std::shared_ptr parameters_; + + bool left_side_parking_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 9f53defac2827..d1579ef40e9a7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -284,26 +284,6 @@ class SceneModuleInterface rclcpp::Logger getLogger() const { return logger_; } - void setIsSimultaneousExecutableAsApprovedModule(const bool enable) - { - is_simultaneously_executable_as_approved_module_ = enable; - } - - bool isSimultaneousExecutableAsApprovedModule() const - { - return is_simultaneously_executable_as_approved_module_; - } - - void setIsSimultaneousExecutableAsCandidateModule(const bool enable) - { - is_simultaneously_executable_as_candidate_module_ = enable; - } - - bool isSimultaneousExecutableAsCandidateModule() const - { - return is_simultaneously_executable_as_candidate_module_; - } - private: bool existRegisteredRequest() const { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp index ee5d539b3415d..cb47c33b6901c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp @@ -100,10 +100,6 @@ class SceneModuleManagerInterface return; } - observer.lock()->setIsSimultaneousExecutableAsApprovedModule( - enable_simultaneous_execution_as_approved_module_); - observer.lock()->setIsSimultaneousExecutableAsCandidateModule( - enable_simultaneous_execution_as_candidate_module_); observer.lock()->setData(planner_data_); observer.lock()->setPreviousModuleOutput(previous_module_output); observer.lock()->onEntry(); @@ -218,36 +214,14 @@ class SceneModuleManagerInterface bool canLaunchNewModule() const { return observers_.size() < max_module_num_; } - bool isSimultaneousExecutableAsApprovedModule() const + virtual bool isSimultaneousExecutableAsApprovedModule() const { - if (observers_.empty()) { - return enable_simultaneous_execution_as_approved_module_; - } - - const auto checker = [this](const SceneModuleObserver & observer) { - if (observer.expired()) { - return enable_simultaneous_execution_as_approved_module_; - } - return observer.lock()->isSimultaneousExecutableAsApprovedModule(); - }; - - return std::all_of(observers_.begin(), observers_.end(), checker); + return enable_simultaneous_execution_as_approved_module_; } - bool isSimultaneousExecutableAsCandidateModule() const + virtual bool isSimultaneousExecutableAsCandidateModule() const { - if (observers_.empty()) { - return enable_simultaneous_execution_as_candidate_module_; - } - - const auto checker = [this](const SceneModuleObserver & observer) { - if (observer.expired()) { - return enable_simultaneous_execution_as_candidate_module_; - } - return observer.lock()->isSimultaneousExecutableAsCandidateModule(); - }; - - return std::all_of(observers_.begin(), observers_.end(), checker); + return enable_simultaneous_execution_as_candidate_module_; } void setData(const std::shared_ptr & planner_data) { planner_data_ = planner_data; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp index 9822e799b8ccf..3ee376f4111f0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp @@ -40,6 +40,10 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface void updateModuleParams(const std::vector & parameters) override; + bool isSimultaneousExecutableAsApprovedModule() const override; + + bool isSimultaneousExecutableAsCandidateModule() const override; + private: std::shared_ptr parameters_; }; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 3214de2c37bd7..e4e3468b45ff6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -96,18 +96,7 @@ class StartPlannerModule : public SceneModuleInterface { } - // set is_simultaneously_executable_ as false when backward driving. - // keep initial value to return it after finishing backward driving. - bool initial_value_simultaneously_executable_as_approved_module_; - bool initial_value_simultaneously_executable_as_candidate_module_; - void setInitialIsSimultaneousExecutableAsApprovedModule(const bool is_simultaneously_executable) - { - initial_value_simultaneously_executable_as_approved_module_ = is_simultaneously_executable; - }; - void setInitialIsSimultaneousExecutableAsCandidateModule(const bool is_simultaneously_executable) - { - initial_value_simultaneously_executable_as_candidate_module_ = is_simultaneously_executable; - }; + bool isBackFinished() const { return status_.back_finished; } private: bool canTransitSuccessState() override { return false; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp index b1f548425d48f..3dde96e813aad 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp @@ -51,6 +51,11 @@ PredictedObjects filterObjectsByLateralDistance( const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects, const double distance_thresh, const bool filter_inside); +bool isAllowedGoalModification( + const std::shared_ptr & route_handler, const bool left_side_parking); +bool checkOriginalGoalIsInShoulder( + const std::shared_ptr & route_handler, const bool left_side_parking); + // debug MarkerArray createPullOverAreaMarkerArray( const tier4_autoware_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index cb790cff2ce30..40998ae3bcd0d 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -310,7 +310,9 @@ bool GoalPlannerModule::isExecutionRequested() const const double self_to_goal_arc_length = utils::getSignedDistance(current_pose, goal_pose, current_lanes); const double request_length = - allow_goal_modification_ ? calcModuleRequestLength() : parameters_->minimum_request_length; + goal_planner_utils::isAllowedGoalModification(route_handler, left_side_parking_) + ? calcModuleRequestLength() + : parameters_->minimum_request_length; if (self_to_goal_arc_length < 0.0 || self_to_goal_arc_length > request_length) { // if current position is far from goal or behind goal, do not execute goal_planner return false; @@ -319,7 +321,7 @@ bool GoalPlannerModule::isExecutionRequested() const // if goal modification is not allowed // 1) goal_pose is in current_lanes, plan path to the original fixed goal // 2) goal_pose is NOT in current_lanes, do not execute goal_planner - if (!allow_goal_modification_) { + if (!goal_planner_utils::isAllowedGoalModification(route_handler, left_side_parking_)) { return goal_is_in_current_lanes; } @@ -405,7 +407,10 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const ModuleStatus GoalPlannerModule::updateState() { // finish module only when the goal is fixed - if (!allow_goal_modification_ && hasFinishedGoalPlanner()) { + if ( + !goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_) && + hasFinishedGoalPlanner()) { return ModuleStatus::SUCCESS; } @@ -502,7 +507,7 @@ void GoalPlannerModule::generateGoalCandidates() // calculate goal candidates const Pose goal_pose = route_handler->getGoalPose(); refined_goal_pose_ = calcRefinedGoal(goal_pose); - if (allow_goal_modification_) { + if (goal_planner_utils::isAllowedGoalModification(route_handler, left_side_parking_)) { goal_searcher_->setPlannerData(planner_data_); goal_candidates_ = goal_searcher_->search(refined_goal_pose_); } else { @@ -517,13 +522,10 @@ BehaviorModuleOutput GoalPlannerModule::plan() { generateGoalCandidates(); - if (allow_goal_modification_) { + if (goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_)) { return planWithGoalModification(); } else { - // for fixed goals, only minor path refinements are made, - // so other modules are always allowed to run. - setIsSimultaneousExecutableAsApprovedModule(true); - setIsSimultaneousExecutableAsCandidateModule(true); fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); return fixed_goal_planner_->plan(planner_data_); } @@ -836,13 +838,10 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { - if (allow_goal_modification_) { + if (goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_)) { return planWaitingApprovalWithGoalModification(); } else { - // for fixed goals, only minor path refinements are made, - // so other modules are always allowed to run. - setIsSimultaneousExecutableAsApprovedModule(true); - setIsSimultaneousExecutableAsCandidateModule(true); fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); return fixed_goal_planner_->plan(planner_data_); } @@ -1453,7 +1452,8 @@ void GoalPlannerModule::setDebugData() tier4_autoware_utils::appendMarkerArray(added, &debug_marker_); }; - if (allow_goal_modification_) { + if (goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_)) { // Visualize pull over areas const auto color = status_.has_decided_path ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index bfa1487f05411..07af2c866daa5 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -14,6 +14,9 @@ #include "behavior_path_planner/scene_module/goal_planner/manager.hpp" +#include "behavior_path_planner/utils/goal_planner/util.hpp" + +#include #include #include @@ -235,6 +238,8 @@ GoalPlannerModuleManager::GoalPlannerModuleManager( } parameters_ = std::make_shared(p); + + left_side_parking_ = parameters_->parking_policy == ParkingPolicy::LEFT_SIDE; } void GoalPlannerModuleManager::updateModuleParams( @@ -251,4 +256,28 @@ void GoalPlannerModuleManager::updateModuleParams( }); } +bool GoalPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const +{ + // enable SimultaneousExecutable whenever goal modification is not allowed + // because only minor path refinements are made for fixed goals + if (!goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_)) { + return true; + } + + return enable_simultaneous_execution_as_approved_module_; +} + +bool GoalPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() const +{ + // enable SimultaneousExecutable whenever goal modification is not allowed + // because only minor path refinements are made for fixed goals + if (!goal_planner_utils::isAllowedGoalModification( + planner_data_->route_handler, left_side_parking_)) { + return true; + } + + return enable_simultaneous_execution_as_candidate_module_; +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index bba0ffc99294a..b2e872416672e 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -105,12 +105,55 @@ void StartPlannerModuleManager::updateModuleParams( const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); if (start_planner_ptr) { start_planner_ptr->updateModuleParams(p); - start_planner_ptr->setInitialIsSimultaneousExecutableAsApprovedModule( - enable_simultaneous_execution_as_approved_module_); - start_planner_ptr->setInitialIsSimultaneousExecutableAsCandidateModule( - enable_simultaneous_execution_as_candidate_module_); } } }); } + +bool StartPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const +{ + if (observers_.empty()) { + return enable_simultaneous_execution_as_approved_module_; + } + + const auto checker = [this](const SceneModuleObserver & observer) { + if (observer.expired()) { + return enable_simultaneous_execution_as_approved_module_; + } + + const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); + + // Currently simultaneous execution with other modules is not supported while backward driving + if (!start_planner_ptr->isBackFinished()) { + return false; + } + + return enable_simultaneous_execution_as_approved_module_; + }; + + return std::all_of(observers_.begin(), observers_.end(), checker); +} + +bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() const +{ + if (observers_.empty()) { + return enable_simultaneous_execution_as_candidate_module_; + } + + const auto checker = [this](const SceneModuleObserver & observer) { + if (observer.expired()) { + return enable_simultaneous_execution_as_candidate_module_; + } + + const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); + + // Currently simultaneous execution with other modules is not supported while backward driving + if (!start_planner_ptr->isBackFinished()) { + return false; + } + return enable_simultaneous_execution_as_candidate_module_; + }; + + return std::all_of(observers_.begin(), observers_.end(), checker); +} } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index fb471a4675fa7..e4921ba293702 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -224,10 +224,6 @@ BehaviorModuleOutput StartPlannerModule::plan() }); if (status_.back_finished) { - setIsSimultaneousExecutableAsApprovedModule( - initial_value_simultaneously_executable_as_approved_module_); - setIsSimultaneousExecutableAsCandidateModule( - initial_value_simultaneously_executable_as_candidate_module_); const double start_distance = motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -241,8 +237,6 @@ BehaviorModuleOutput StartPlannerModule::plan() {start_distance, finish_distance}, SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); } else { - setIsSimultaneousExecutableAsApprovedModule(false); - setIsSimultaneousExecutableAsCandidateModule(false); const double distance = motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -361,10 +355,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() }); if (status_.back_finished) { - setIsSimultaneousExecutableAsApprovedModule( - initial_value_simultaneously_executable_as_approved_module_); - setIsSimultaneousExecutableAsCandidateModule( - initial_value_simultaneously_executable_as_candidate_module_); const double start_distance = motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -377,8 +367,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() {start_distance, finish_distance}, SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); } else { - setIsSimultaneousExecutableAsApprovedModule(false); - setIsSimultaneousExecutableAsCandidateModule(false); const double distance = motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp index cc44e7f0e012d..19b6bd27ea07c 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp @@ -180,5 +180,27 @@ MarkerArray createGoalCandidatesMarkerArray( return marker_array; } + +bool isAllowedGoalModification( + const std::shared_ptr & route_handler, const bool left_side_parking) +{ + return route_handler->isAllowedGoalModification() || + checkOriginalGoalIsInShoulder(route_handler, left_side_parking); +} + +bool checkOriginalGoalIsInShoulder( + const std::shared_ptr & route_handler, const bool left_side_parking) +{ + const Pose & goal_pose = route_handler->getGoalPose(); + + const lanelet::ConstLanelets pull_over_lanes = + goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking); + lanelet::ConstLanelet target_lane{}; + lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane); + + return route_handler->isShoulderLanelet(target_lane) && + lanelet::utils::isInLanelet(goal_pose, target_lane, 0.1); +} + } // namespace goal_planner_utils } // namespace behavior_path_planner From f35fb0e5529b1d8d93f1b28ec840b50879884e7b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 15 Aug 2023 10:51:44 +0900 Subject: [PATCH 167/266] feat(lane_departure_checker): add road_border departure checker (#4607) * temp Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * update Signed-off-by: kyoichi-sugahara * add param Signed-off-by: kyoichi-sugahara * add param Signed-off-by: kyoichi-sugahara * update README.md Signed-off-by: kyoichi-sugahara * initialize variable Signed-off-by: kyoichi-sugahara * fix bug and output error messege Signed-off-by: kyoichi-sugahara * comment put debug message Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- control/lane_departure_checker/README.md | 14 ++-- .../config/lane_departure_checker.param.yaml | 1 + .../lane_departure_checker.hpp | 8 +++ .../lane_departure_checker_node.hpp | 1 + .../lane_departure_checker.cpp | 65 +++++++++++++++++++ .../lane_departure_checker_node.cpp | 7 ++ 6 files changed, 92 insertions(+), 4 deletions(-) diff --git a/control/lane_departure_checker/README.md b/control/lane_departure_checker/README.md index e0609997737b8..5148d6a998f50 100644 --- a/control/lane_departure_checker/README.md +++ b/control/lane_departure_checker/README.md @@ -8,6 +8,7 @@ This package includes the following features: - **Lane Departure**: Check if ego vehicle is going to be out of lane boundaries based on output from control module (predicted trajectory). - **Trajectory Deviation**: Check if ego vehicle's pose does not deviate from the trajectory. Checking lateral, longitudinal and yaw deviation. +- **Road Border Departure**: Check if ego vehicle's footprint, generated from the control's output, extends beyond the road border. ## Inner-workings / Algorithms @@ -62,10 +63,15 @@ This package includes the following features: ### Node Parameters -| Name | Type | Description | Default value | -| :---------------- | :----- | :---------------------------- | :------------ | -| update_rate | double | Frequency for publishing [Hz] | 10.0 | -| visualize_lanelet | bool | Flag for visualizing lanelet | False | +| Name | Type | Description | Default value | +| :---------------------------- | :----- | :------------------------------------------------------------ | :------------ | +| update_rate | double | Frequency for publishing [Hz] | 10.0 | +| visualize_lanelet | bool | Flag for visualizing lanelet | False | +| include_right_lanes | bool | Flag for including right lanelet in borders | False | +| include_left_lanes | bool | Flag for including left lanelet in borders | False | +| include_opposite_lanes | bool | Flag for including opposite lanelet in borders | False | +| include_conflicting_lanes | bool | Flag for including conflicting lanelet in borders | False | +| road_border_departure_checker | bool | Flag for checking if the vehicle will departs the road border | False | ### Core Parameters diff --git a/control/lane_departure_checker/config/lane_departure_checker.param.yaml b/control/lane_departure_checker/config/lane_departure_checker.param.yaml index 59e25cbc5d86e..008832b1cab21 100644 --- a/control/lane_departure_checker/config/lane_departure_checker.param.yaml +++ b/control/lane_departure_checker/config/lane_departure_checker.param.yaml @@ -7,6 +7,7 @@ include_left_lanes: false include_opposite_lanes: false include_conflicting_lanes: false + road_border_departure_checker: false # Core footprint_margin_scale: 1.0 diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp index 244e75210cec3..9822fd820dc3c 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp @@ -80,6 +80,7 @@ struct Output std::map processing_time_map{}; bool will_leave_lane{}; bool is_out_of_lane{}; + bool will_cross_road_border{}; PoseDeviation trajectory_deviation{}; lanelet::ConstLanelets candidate_lanelets{}; TrajectoryPoints resampled_trajectory{}; @@ -135,6 +136,13 @@ class LaneDepartureChecker static bool willLeaveLane( const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints); + + static bool willCrossRoadBorder( + const lanelet::ConstLanelets & candidate_lanelets, + const std::vector & vehicle_footprints); + + static bool isCrossingRoadBorder( + const lanelet::BasicLineString2d & road_border, const std::vector & footprints); }; } // namespace lane_departure_checker diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp index 85fd73c63f544..f7f7bcfda7d51 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp @@ -51,6 +51,7 @@ struct NodeParam bool include_left_lanes; bool include_opposite_lanes; bool include_conflicting_lanes; + bool road_border_departure_checker; }; class LaneDepartureCheckerNode : public rclcpp::Node diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index 1a63fb3eb395b..f1d8d75452df1 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -39,6 +39,16 @@ namespace using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; +using geometry_msgs::msg::Point; + +Point fromVector2dToMsg(const Eigen::Vector2d & point) +{ + Point msg{}; + msg.x = point.x(); + msg.y = point.y(); + msg.z = 0.0; + return msg; +} double calcBrakingDistance( const double abs_velocity, const double max_deceleration, const double delay_time) @@ -57,6 +67,27 @@ bool isInAnyLane(const lanelet::ConstLanelets & candidate_lanelets, const Point2 return false; } +bool isCrossingWithRoadBorder( + const lanelet::BasicLineString2d & road_border, const std::vector & footprints) +{ + for (auto & footprint : footprints) { + for (size_t i = 0; i < footprint.size() - 1; ++i) { + auto footprint1 = footprint.at(i).to_3d(); + auto footprint2 = footprint.at(i + 1).to_3d(); + for (size_t i = 0; i < road_border.size() - 1; ++i) { + auto road_border1 = road_border.at(i); + auto road_border2 = road_border.at(i + 1); + if (tier4_autoware_utils::intersect( + tier4_autoware_utils::toMsg(footprint1), tier4_autoware_utils::toMsg(footprint2), + fromVector2dToMsg(road_border1), fromVector2dToMsg(road_border2))) { + return true; + } + } + } + } + return false; +} + LinearRing2d createHullFromFootprints(const std::vector & footprints) { MultiPoint2d combined; @@ -141,6 +172,10 @@ Output LaneDepartureChecker::update(const Input & input) output.is_out_of_lane = isOutOfLane(output.candidate_lanelets, output.vehicle_footprints.front()); output.processing_time_map["isOutOfLane"] = stop_watch.toc(true); + output.will_cross_road_border = + willCrossRoadBorder(output.candidate_lanelets, output.vehicle_footprints); + output.processing_time_map["willCrossRoadBorder"] = stop_watch.toc(true); + return output; } @@ -298,4 +333,34 @@ bool LaneDepartureChecker::isOutOfLane( return false; } + +bool LaneDepartureChecker::willCrossRoadBorder( + const lanelet::ConstLanelets & candidate_lanelets, + const std::vector & vehicle_footprints) +{ + for (const auto & candidate_lanelet : candidate_lanelets) { + const std::string r_type = + candidate_lanelet.rightBound().attributeOr(lanelet::AttributeName::Type, "none"); + if (r_type == "road_border") { + if (isCrossingWithRoadBorder( + candidate_lanelet.rightBound2d().basicLineString(), vehicle_footprints)) { + // std::cerr << "The crossed road_border's line string id: " + // << candidate_lanelet.rightBound().id() << std::endl; + return true; + } + } + const std::string l_type = + candidate_lanelet.leftBound().attributeOr(lanelet::AttributeName::Type, "none"); + if (l_type == "road_border") { + if (isCrossingWithRoadBorder( + candidate_lanelet.leftBound2d().basicLineString(), vehicle_footprints)) { + // std::cerr << "The crossed road_border's line string id: " + // << candidate_lanelet.leftBound().id() << std::endl; + return true; + } + } + } + return false; +} + } // namespace lane_departure_checker diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index ed9149cd6df2d..20d535a82bfa1 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -132,6 +132,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o node_param_.include_left_lanes = declare_parameter("include_left_lanes"); node_param_.include_opposite_lanes = declare_parameter("include_opposite_lanes"); node_param_.include_conflicting_lanes = declare_parameter("include_conflicting_lanes"); + node_param_.road_border_departure_checker = + declare_parameter("road_border_departure_checker"); // Vehicle Info const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); @@ -417,6 +419,11 @@ void LaneDepartureCheckerNode::checkLaneDeparture( msg = "vehicle is out of lane"; } + if (output_.will_cross_road_border && node_param_.road_border_departure_checker) { + level = DiagStatus::ERROR; + msg = "vehicle will cross road border"; + } + stat.summary(level, msg); } From 8dd1460f24df188172a416e1355b35bbefd87d19 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Aug 2023 11:09:44 +0900 Subject: [PATCH 168/266] feat(map_based_prediction): consider opposite lanelets path planning (#4624) * feat(map_based_prediction): consider opposite lanelets path planning Signed-off-by: Takayuki Murooka * add comment Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../map_based_prediction_node.hpp | 3 +- .../src/map_based_prediction_node.cpp | 148 ++++++++++++++---- 2 files changed, 116 insertions(+), 35 deletions(-) diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 5903706123169..f265633bd55dc 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -183,7 +183,8 @@ class MapBasedPredictionNode : public rclcpp::Node LaneletsData getCurrentLanelets(const TrackedObject & object); bool checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object); + const std::pair & lanelet, const TrackedObject & object, + const bool check_distance = true); float calculateLocalLikelihood( const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const; void updateObjectData(TrackedObject & object); diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 66a15f28bdd1b..be6327cf5c01a 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -595,6 +595,45 @@ StringStamped createStringStamped(const rclcpp::Time & now, const double data) msg.data = std::to_string(data); return msg; } + +// NOTE: These two functions are copied from the route_handler package. +lanelet::Lanelets getRightOppositeLanelets( + const std::shared_ptr & lanelet_map_ptr, + const lanelet::ConstLanelet & lanelet) +{ + const auto opposite_candidate_lanelets = + lanelet_map_ptr->laneletLayer.findUsages(lanelet.rightBound().invert()); + + lanelet::Lanelets opposite_lanelets; + for (const auto & candidate_lanelet : opposite_candidate_lanelets) { + if (candidate_lanelet.leftBound().id() == lanelet.rightBound().id()) { + continue; + } + + opposite_lanelets.push_back(candidate_lanelet); + } + + return opposite_lanelets; +} + +lanelet::Lanelets getLeftOppositeLanelets( + const std::shared_ptr & lanelet_map_ptr, + const lanelet::ConstLanelet & lanelet) +{ + const auto opposite_candidate_lanelets = + lanelet_map_ptr->laneletLayer.findUsages(lanelet.leftBound().invert()); + + lanelet::Lanelets opposite_lanelets; + for (const auto & candidate_lanelet : opposite_candidate_lanelets) { + if (candidate_lanelet.rightBound().id() == lanelet.leftBound().id()) { + continue; + } + + opposite_lanelets.push_back(candidate_lanelet); + } + + return opposite_lanelets; +} } // namespace MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) @@ -1086,47 +1125,87 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob std::vector> surrounding_lanelets = lanelet::geometry::findNearest(lanelet_map_ptr_->laneletLayer, search_point, 10); - // No Closest Lanelets - if (surrounding_lanelets.empty()) { - return {}; - } - - LaneletsData object_lanelets; - std::optional> closest_lanelet{std::nullopt}; - for (const auto & lanelet : surrounding_lanelets) { - // Check if the close lanelets meet the necessary condition for start lanelets and - // Check if similar lanelet is inside the object lanelet - if (!checkCloseLaneletCondition(lanelet, object) || isDuplicated(lanelet, object_lanelets)) { - continue; + { // Step 1. Search same directional lanelets + // No Closest Lanelets + if (surrounding_lanelets.empty()) { + return {}; } - // Memorize closest lanelet - // NOTE: The object may be outside the lanelet. - if (!closest_lanelet || lanelet.first < closest_lanelet->first) { - closest_lanelet = lanelet; + LaneletsData object_lanelets; + std::optional> closest_lanelet{std::nullopt}; + for (const auto & lanelet : surrounding_lanelets) { + // Check if the close lanelets meet the necessary condition for start lanelets and + // Check if similar lanelet is inside the object lanelet + if (!checkCloseLaneletCondition(lanelet, object) || isDuplicated(lanelet, object_lanelets)) { + continue; + } + + // Memorize closest lanelet + // NOTE: The object may be outside the lanelet. + if (!closest_lanelet || lanelet.first < closest_lanelet->first) { + closest_lanelet = lanelet; + } + + // Check if the obstacle is inside of this lanelet + constexpr double epsilon = 1e-3; + if (lanelet.first < epsilon) { + const auto object_lanelet = + LaneletData{lanelet.second, calculateLocalLikelihood(lanelet.second, object)}; + object_lanelets.push_back(object_lanelet); + } } - // Check if the obstacle is inside of this lanelet - constexpr double epsilon = 1e-3; - if (lanelet.first < epsilon) { - const auto object_lanelet = - LaneletData{lanelet.second, calculateLocalLikelihood(lanelet.second, object)}; - object_lanelets.push_back(object_lanelet); + if (!object_lanelets.empty()) { + return object_lanelets; + } + if (closest_lanelet) { + return LaneletsData{LaneletData{ + closest_lanelet->second, calculateLocalLikelihood(closest_lanelet->second, object)}}; } } - if (!object_lanelets.empty()) { - return object_lanelets; - } - if (closest_lanelet) { - return LaneletsData{LaneletData{ - closest_lanelet->second, calculateLocalLikelihood(closest_lanelet->second, object)}}; + { // Step 2. Search opposite directional lanelets + // Get opposite lanelets and calculate distance to search point. + std::vector> surrounding_opposite_lanelets; + for (const auto & surrounding_lanelet : surrounding_lanelets) { + for (const auto & left_opposite_lanelet : + getLeftOppositeLanelets(lanelet_map_ptr_, surrounding_lanelet.second)) { + const double distance = lanelet::geometry::distance2d(left_opposite_lanelet, search_point); + surrounding_opposite_lanelets.push_back(std::make_pair(distance, left_opposite_lanelet)); + } + for (const auto & right_opposite_lanelet : + getRightOppositeLanelets(lanelet_map_ptr_, surrounding_lanelet.second)) { + const double distance = lanelet::geometry::distance2d(right_opposite_lanelet, search_point); + surrounding_opposite_lanelets.push_back(std::make_pair(distance, right_opposite_lanelet)); + } + } + + std::optional> opposite_closest_lanelet{std::nullopt}; + for (const auto & lanelet : surrounding_opposite_lanelets) { + // Check if the close lanelets meet the necessary condition for start lanelets + // except for distance checking + if (!checkCloseLaneletCondition(lanelet, object, false)) { + continue; + } + + // Memorize closest lanelet + if (!opposite_closest_lanelet || lanelet.first < opposite_closest_lanelet->first) { + opposite_closest_lanelet = lanelet; + } + } + if (opposite_closest_lanelet) { + return LaneletsData{LaneletData{ + opposite_closest_lanelet->second, + calculateLocalLikelihood(opposite_closest_lanelet->second, object)}}; + } } + return LaneletsData{}; } bool MapBasedPredictionNode::checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object) + const std::pair & lanelet, const TrackedObject & object, + const bool check_distance) { // Step1. If we only have one point in the centerline, we will ignore the lanelet if (lanelet.second.centerline().size() <= 1) { @@ -1161,13 +1240,14 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( const double object_vel = object.kinematics.twist_with_covariance.twist.linear.x; const bool is_yaw_reversed = M_PI - delta_yaw_threshold_for_searching_lanelet_ < abs_norm_delta && object_vel < 0.0; - if ( - lanelet.first < dist_threshold_for_searching_lanelet_ && - (is_yaw_reversed || abs_norm_delta < delta_yaw_threshold_for_searching_lanelet_)) { - return true; + if (check_distance && dist_threshold_for_searching_lanelet_ < lanelet.first) { + return false; + } + if (!is_yaw_reversed && delta_yaw_threshold_for_searching_lanelet_ < abs_norm_delta) { + return false; } - return false; + return true; } float MapBasedPredictionNode::calculateLocalLikelihood( From eeeca38fde9235f649ae06d2459f484588c451a7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Aug 2023 11:32:34 +0900 Subject: [PATCH 169/266] perf(obstacle_avoidance_planner): smaller calculation time (#4608) * perf(obstacle_avoidance_planner): smaller calculation time Signed-off-by: Takayuki Murooka * update script Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 7 +- .../debug_marker.hpp | 2 +- .../mpt_optimizer.hpp | 1 + .../obstacle_avoidance_planner/node.hpp | 1 + .../scripts/calculation_time_plotter.py | 2 +- .../src/debug_marker.cpp | 64 +++++++++-------- .../src/mpt_optimizer.cpp | 25 ++++--- .../obstacle_avoidance_planner/src/node.cpp | 71 +++++++++++++++---- 8 files changed, 118 insertions(+), 55 deletions(-) diff --git a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml index 65b4c9fab3d21..bb64006656216 100644 --- a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml +++ b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: option: - enable_skip_optimization: false # skip model predictive trajectory + enable_skip_optimization: false # skip elastic band and model predictive trajectory enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result. enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered. @@ -9,6 +9,7 @@ debug: # flag to publish enable_pub_debug_marker: true # publish debug marker + enable_pub_extra_debug_marker: false # publish extra debug marker # flag to show enable_debug_info: false @@ -19,7 +20,7 @@ output_delta_arc_length: 0.5 # delta arc length for output trajectory [m] output_backward_traj_length: 5.0 # backward length for backward trajectory from base_link [m] - vehicle_stop_margin_outside_drivable_area: 1.5 # vehicle stop margin to let the vehicle stop before the calculated stop point if it is calculated outside the drivable area [m] . + vehicle_stop_margin_outside_drivable_area: 0.0 # vehicle stop margin to let the vehicle stop before the calculated stop point if it is calculated outside the drivable area [m] . # This margin will be realized with delta_arc_length_for_mpt_points m precision. # replanning & trimming trajectory param outside algorithm @@ -77,7 +78,7 @@ # avoidance avoidance: - max_bound_fixing_time: 3.0 # [s] + max_bound_fixing_time: 1.0 # [s] max_longitudinal_margin_for_bound_violation: 1.0 # [m] max_avoidance_cost: 0.5 # [m] avoidance_cost_margin: 0.0 # [m] diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/debug_marker.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/debug_marker.hpp index 8753699ab9d4b..ce12cbca8ddb6 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/debug_marker.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/debug_marker.hpp @@ -30,6 +30,6 @@ namespace obstacle_avoidance_planner MarkerArray getDebugMarker( const DebugData & debug_data, const std::vector & optimized_points, - const vehicle_info_util::VehicleInfo & vehicle_info); + const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker); } // namespace obstacle_avoidance_planner #endif // OBSTACLE_AVOIDANCE_PLANNER__DEBUG_MARKER_HPP_ diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index eabbf695496a3..ea2e18b099f1d 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -118,6 +118,7 @@ class MPTOptimizer void onParam(const std::vector & parameters); double getTrajectoryLength() const; + double getDeltaArcLength() const; int getNumberOfPoints() const; private: diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 97607be30de3f..f716f497b90da 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -61,6 +61,7 @@ class ObstacleAvoidancePlanner : public rclcpp::Node // flags for some functions bool enable_pub_debug_marker_; + bool enable_pub_extra_debug_marker_; bool enable_debug_info_; bool enable_outside_drivable_area_stop_; bool enable_skip_optimization_; diff --git a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py index eb4e028f5245d..daf6beea730d3 100755 --- a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py +++ b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py @@ -100,7 +100,7 @@ def CallbackCalculationCost(self, msg): "-f", "--functions", type=str, - default="onPath, optimizeTrajectory, publishDebugMarkerOfOptimization, solveOsqp", + default="onPath, calcReferencePoints, calcOptimizedSteerAngles, publishDebugMarkerOfOptimization", ) parser.add_argument( "-d", diff --git a/planning/obstacle_avoidance_planner/src/debug_marker.cpp b/planning/obstacle_avoidance_planner/src/debug_marker.cpp index ffe6444151cd4..79f3dfd2fe2e4 100644 --- a/planning/obstacle_avoidance_planner/src/debug_marker.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_marker.cpp @@ -364,16 +364,11 @@ visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray( MarkerArray getDebugMarker( const DebugData & debug_data, const std::vector & optimized_points, - const vehicle_info_util::VehicleInfo & vehicle_info) + const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker) { MarkerArray marker_array; - // mpt footprints - appendMarkerArray( - getFootprintsMarkerArray(optimized_points, vehicle_info, debug_data.mpt_visualize_sampling_num), - &marker_array); - - // bounds lines + // bounds line appendMarkerArray( getBoundsLineMarkerArray(debug_data.ref_points, vehicle_info.vehicle_width_m), &marker_array); @@ -383,13 +378,6 @@ MarkerArray getDebugMarker( debug_data.ref_points, vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num), &marker_array); - // vehicle circle line - appendMarkerArray( - getVehicleCircleLinesMarkerArray( - debug_data.ref_points, debug_data.vehicle_circle_longitudinal_offsets, - vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num, "vehicle_circle_lines"), - &marker_array); - // current vehicle circles appendMarkerArray( getCurrentVehicleCirclesMarkerArray( @@ -397,25 +385,43 @@ MarkerArray getDebugMarker( debug_data.vehicle_circle_radiuses, "current_vehicle_circles", 1.0, 0.3, 0.3), &marker_array); - // vehicle circles - appendMarkerArray( - getVehicleCirclesMarkerArray( - optimized_points, debug_data.vehicle_circle_longitudinal_offsets, - debug_data.vehicle_circle_radiuses, debug_data.mpt_visualize_sampling_num, "vehicle_circles", - 1.0, 0.3, 0.3), - &marker_array); + // NOTE: Default debug marker is limited for less calculation time + // Circles visualization is comparatively heavy. + if (publish_extra_marker) { + // vehicle circles + appendMarkerArray( + getVehicleCirclesMarkerArray( + optimized_points, debug_data.vehicle_circle_longitudinal_offsets, + debug_data.vehicle_circle_radiuses, debug_data.mpt_visualize_sampling_num, + "vehicle_circles", 1.0, 0.3, 0.3), + &marker_array); - // footprint by drivable area - if (debug_data.stop_pose_by_drivable_area) { + // mpt footprints appendMarkerArray( - getFootprintByDrivableAreaMarkerArray( - *debug_data.stop_pose_by_drivable_area, vehicle_info, "footprint_by_drivable_area", 1.0, - 0.0, 0.0), + getFootprintsMarkerArray( + optimized_points, vehicle_info, debug_data.mpt_visualize_sampling_num), &marker_array); - } - // debug text - appendMarkerArray(getPointsTextMarkerArray(debug_data.ref_points), &marker_array); + // vehicle circle line + appendMarkerArray( + getVehicleCircleLinesMarkerArray( + debug_data.ref_points, debug_data.vehicle_circle_longitudinal_offsets, + vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num, + "vehicle_circle_lines"), + &marker_array); + + // footprint by drivable area + if (debug_data.stop_pose_by_drivable_area) { + appendMarkerArray( + getFootprintByDrivableAreaMarkerArray( + *debug_data.stop_pose_by_drivable_area, vehicle_info, "footprint_by_drivable_area", 1.0, + 0.0, 0.0), + &marker_array); + } + + // debug text + appendMarkerArray(getPointsTextMarkerArray(debug_data.ref_points), &marker_array); + } return marker_array; } diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 74711ed886ff0..0a55cc8d91f8e 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -687,6 +687,8 @@ void MPTOptimizer::updateDeltaArcLength(std::vector & ref_points void MPTOptimizer::updateExtraPoints(std::vector & ref_points) const { + time_keeper_ptr_->tic(__func__); + // alpha for (size_t i = 0; i < ref_points.size(); ++i) { const auto front_wheel_pos = @@ -774,6 +776,8 @@ void MPTOptimizer::updateExtraPoints(std::vector & ref_points) c } } } + + time_keeper_ptr_->toc(__func__, " "); } void MPTOptimizer::updateBounds( @@ -1273,7 +1277,7 @@ MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( obj_matrix.hessian = H; obj_matrix.gradient = g; - time_keeper_ptr_->toc(__func__, " "); + time_keeper_ptr_->toc(__func__, " "); return obj_matrix; } @@ -1325,6 +1329,7 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( A_rows += N_u; } + // NOTE: The following takes 1 [ms] Eigen::MatrixXd A = Eigen::MatrixXd::Zero(A_rows, N_v); Eigen::VectorXd lb = Eigen::VectorXd::Constant(A_rows, -autoware::common::osqp::INF); Eigen::VectorXd ub = Eigen::VectorXd::Constant(A_rows, autoware::common::osqp::INF); @@ -1437,13 +1442,8 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( A_rows_end += N_u; } - ConstraintMatrix constraint_matrix; - constraint_matrix.linear = A; - constraint_matrix.lower_bound = lb; - constraint_matrix.upper_bound = ub; - - time_keeper_ptr_->toc(__func__, " "); - return constraint_matrix; + time_keeper_ptr_->toc(__func__, " "); + return ConstraintMatrix{A, lb, ub}; } void MPTOptimizer::addSteerWeightR( @@ -1700,6 +1700,8 @@ void MPTOptimizer::publishDebugTrajectories( const std_msgs::msg::Header & header, const std::vector & ref_points, const std::vector & mpt_traj_points) const { + time_keeper_ptr_->tic(__func__); + // reference points const auto ref_traj = trajectory_utils::createTrajectory( header, trajectory_utils::convertToTrajectoryPoints(ref_points)); @@ -1713,6 +1715,8 @@ void MPTOptimizer::publishDebugTrajectories( // mpt points const auto mpt_traj = trajectory_utils::createTrajectory(header, mpt_traj_points); debug_mpt_traj_pub_->publish(mpt_traj); + + time_keeper_ptr_->toc(__func__, " "); } std::vector MPTOptimizer::extractFixedPoints( @@ -1738,6 +1742,11 @@ double MPTOptimizer::getTrajectoryLength() const return forward_traj_length + backward_traj_length; } +double MPTOptimizer::getDeltaArcLength() const +{ + return mpt_param_.delta_arc_length; +} + int MPTOptimizer::getNumberOfPoints() const { return mpt_param_.num_points; diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index d40d271112814..6c4730e9d86f9 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -59,6 +59,17 @@ bool hasZeroVelocity(const TrajectoryPoint & traj_point) constexpr double zero_vel = 0.0001; return std::abs(traj_point.longitudinal_velocity_mps) < zero_vel; } + +std::vector calcSegmentLengthVector(const std::vector & points) +{ + std::vector segment_length_vector; + for (size_t i = 0; i < points.size() - 1; ++i) { + const double segment_length = + tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i + 1)); + segment_length_vector.push_back(segment_length); + } + return segment_length_vector; +} } // namespace ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & node_options) @@ -94,6 +105,8 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // parameter for debug marker enable_pub_debug_marker_ = declare_parameter("option.debug.enable_pub_debug_marker"); + enable_pub_extra_debug_marker_ = + declare_parameter("option.debug.enable_pub_extra_debug_marker"); // parameter for debug info enable_debug_info_ = declare_parameter("option.debug.enable_debug_info"); @@ -145,6 +158,8 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::onParam( // parameters for debug marker updateParam(parameters, "option.debug.enable_pub_debug_marker", enable_pub_debug_marker_); + updateParam( + parameters, "option.debug.enable_pub_extra_debug_marker", enable_pub_extra_debug_marker_); // parameters for debug info updateParam(parameters, "option.debug.enable_debug_info", enable_debug_info_); @@ -363,32 +378,61 @@ void ObstacleAvoidancePlanner::applyInputVelocity( const size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(input_traj_points, ego_pose, ego_nearest_param_); - return motion_utils::cropForwardPoints( + const auto cropped_points = motion_utils::cropForwardPoints( input_traj_points, ego_pose.position, ego_seg_idx, optimized_traj_length + margin_traj_length); + + if (cropped_points.size() < 2) { + return input_traj_points; + } + return cropped_points; }(); // update velocity - size_t input_traj_start_idx = 0; + const auto segment_length_vec = calcSegmentLengthVector(forward_cropped_input_traj_points); + const double mpt_delta_arc_length = mpt_optimizer_ptr_->getDeltaArcLength(); + size_t input_traj_start_idx = trajectory_utils::findEgoSegmentIndex( + forward_cropped_input_traj_points, output_traj_points.front().pose, ego_nearest_param_); for (size_t i = 0; i < output_traj_points.size(); i++) { - // crop backward for efficient calculation - const auto cropped_input_traj_points = std::vector{ - forward_cropped_input_traj_points.begin() + input_traj_start_idx, - forward_cropped_input_traj_points.end()}; + // NOTE: input_traj_start/end_idx is calculated for efficient index calculation + const size_t input_traj_end_idx = [&]() { + double sum_segment_length = 0.0; + for (size_t j = input_traj_start_idx + 1; j < segment_length_vec.size(); ++j) { + sum_segment_length += segment_length_vec.at(j); + if (mpt_delta_arc_length < sum_segment_length) { + return j + 1; + } + } + return forward_cropped_input_traj_points.size() - 1; + }(); + + const auto nearest_traj_point = [&]() { + if (input_traj_start_idx == input_traj_end_idx) { + return forward_cropped_input_traj_points.at(input_traj_start_idx); + } - const size_t nearest_seg_idx = trajectory_utils::findEgoSegmentIndex( - cropped_input_traj_points, output_traj_points.at(i).pose, ego_nearest_param_); - input_traj_start_idx = nearest_seg_idx; + // crop forward and backward for efficient calculation + const auto cropped_input_traj_points = std::vector{ + forward_cropped_input_traj_points.begin() + input_traj_start_idx, + forward_cropped_input_traj_points.begin() + input_traj_end_idx + 1}; + assert(2 <= cropped_input_traj_points.size()); + + const size_t nearest_seg_idx = trajectory_utils::findEgoSegmentIndex( + cropped_input_traj_points, output_traj_points.at(i).pose, ego_nearest_param_); + input_traj_start_idx += nearest_seg_idx; + + return cropped_input_traj_points.at(nearest_seg_idx); + }(); // calculate velocity with zero order hold - const double velocity = cropped_input_traj_points.at(nearest_seg_idx).longitudinal_velocity_mps; - output_traj_points.at(i).longitudinal_velocity_mps = velocity; + output_traj_points.at(i).longitudinal_velocity_mps = + nearest_traj_point.longitudinal_velocity_mps; } // insert stop point explicitly const auto stop_idx = motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); if (stop_idx) { - const auto input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.get()).pose; + const auto & input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.get()).pose; // NOTE: motion_utils::findNearestSegmentIndex is used instead of // trajectory_utils::findEgoSegmentIndex // for the case where input_traj_points is much longer than output_traj_points, and the @@ -499,7 +543,8 @@ void ObstacleAvoidancePlanner::publishDebugMarkerOfOptimization( // debug marker time_keeper_ptr_->tic("getDebugMarker"); - const auto debug_marker = getDebugMarker(*debug_data_ptr_, traj_points, vehicle_info_); + const auto debug_marker = + getDebugMarker(*debug_data_ptr_, traj_points, vehicle_info_, enable_pub_extra_debug_marker_); time_keeper_ptr_->toc("getDebugMarker", " "); time_keeper_ptr_->tic("publishDebugMarker"); From fbd9b27f405f7e3061c9243f014a9d42f96d84ec Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Aug 2023 11:32:53 +0900 Subject: [PATCH 170/266] feat(planning_debug_tools): capture slider handle independently of mouse cursor (#4615) Signed-off-by: Takayuki Murooka --- .../perception_reproducer.py | 2 +- .../time_manager_widget.py | 35 +++++++++++++++++-- 2 files changed, 34 insertions(+), 3 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index 36b62bc1ec5ee..4228d506d5bec 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -32,7 +32,7 @@ def __init__(self, args): self.prev_traffic_signals_msg = None # start timer callback - self.timer = self.create_timer(0.01, self.on_timer) + self.timer = self.create_timer(0.1, self.on_timer) print("Start timer callback") def on_timer(self): diff --git a/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py index c16f3560ba399..382e725b114cd 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/time_manager_widget.py @@ -23,6 +23,37 @@ from PyQt5.QtWidgets import QWidget +# With QSlider, the slider's handle cannot be captured if the mouse cursor is not the handle position when pressing the mouse. +class QJumpSlider(QSlider): + def __init__(self, slider_direction, max_value): + super(self.__class__, self).__init__(slider_direction) + + self.max_value = max_value + self.is_mouse_pressed = False + + def mouse_to_value(self, event): + x = event.pos().x() + return int(self.max_value * x / self.width()) + + def mousePressEvent(self, event): + super(self.__class__, self).mousePressEvent(event) + + if event.button() == QtCore.Qt.LeftButton: + self.setValue(self.mouse_to_value(event)) + self.is_mouse_pressed = True + + def mouseMoveEvent(self, event): + super(self.__class__, self).mouseMoveEvent(event) + if self.is_mouse_pressed: + self.setValue(self.mouse_to_value(event)) + + def mouseReleaseEvent(self, event): + super(self.__class__, self).mouseReleaseEvent(event) + + if event.button() == QtCore.Qt.LeftButton: + self.is_mouse_pressed = False + + class TimeManagerWidget(QMainWindow): def __init__(self, start_timestamp, end_timestamp): super(self.__class__, self).__init__() @@ -60,7 +91,7 @@ def setupUI(self): self.grid_layout.addWidget(self.button, 1, 0, 1, -1) # slider - self.slider = QSlider(QtCore.Qt.Horizontal) + self.slider = QJumpSlider(QtCore.Qt.Horizontal, self.max_value) self.slider.setMinimum(0) self.slider.setMaximum(self.max_value) self.slider.setValue(0) @@ -77,5 +108,5 @@ def timestamp_to_value(self, timestamp): def value_to_timestamp(self, value): return self.start_timestamp + self.slider.value() / self.max_value * ( - self.end_value - self.start_value + self.end_timestamp - self.start_timestamp ) From 629023ffbc0a529689cde45fc0d2e5d5ead529f2 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 15 Aug 2023 11:54:05 +0900 Subject: [PATCH 171/266] feat(probabilistic_occupancy_grid_map): add launch test and gtest for future debugging (#4619) * add launch test to test node I/O Signed-off-by: yoshiri * add util test Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../CMakeLists.txt | 16 ++ ...ntcloud_based_occupancy_grid_map.launch.py | 2 +- .../package.xml | 7 +- .../test/test_pointcloud_based_method.py | 246 ++++++++++++++++++ .../test/test_utils.cpp | 92 +++++++ 5 files changed, 361 insertions(+), 2 deletions(-) create mode 100644 perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py create mode 100644 perception/probabilistic_occupancy_grid_map/test/test_utils.cpp diff --git a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt index facb61d82abb0..035845772ce53 100644 --- a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt @@ -60,3 +60,19 @@ ament_auto_package( launch config ) + +# test +if(BUILD_TESTING) + # launch_testing + find_package(launch_testing_ament_cmake REQUIRED) + add_launch_test(test/test_pointcloud_based_method.py) + + # gtest + ament_add_gtest(test_utils + test/test_utils.cpp + ) + target_link_libraries(test_utils + ${PCL_LIBRARIES} + ${PROJECT_NAME}_common + ) +endif() diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index 5b6e0d1c3c242..49bf228905dcc 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -116,7 +116,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg( "updater_param_file", get_package_share_directory("probabilistic_occupancy_grid_map") - + "/config/updater.param.yaml", + + "/config/binary_bayes_filter_updater.param.yaml", ), set_container_executable, set_container_mt_executable, diff --git a/perception/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml index a6f4d46242a3f..a90ae78b03597 100644 --- a/perception/probabilistic_occupancy_grid_map/package.xml +++ b/perception/probabilistic_occupancy_grid_map/package.xml @@ -36,9 +36,14 @@ pointcloud_to_laserscan + ament_cmake_gtest ament_lint_auto autoware_lint_common - + launch + launch_ros + launch_testing + launch_testing_ament_cmake + launch_testing_ros ament_cmake diff --git a/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py b/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py new file mode 100644 index 0000000000000..6b0150dc3fa7b --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py @@ -0,0 +1,246 @@ +# Copyright 2021 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. + +import struct +import time +import unittest + +from geometry_msgs.msg import TransformStamped +import launch +import launch.actions +from launch_ros.substitutions import FindPackageShare +import launch_testing +import launch_testing.actions +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +from nav_msgs.msg import OccupancyGrid +import numpy as np +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + +PACKAGE_NAME = "probabilistic_occupancy_grid_map" +INPUT_TOPIC_RAW = "/raw" +INPUT_TOPIC_OBSTACLE = "/obstacle" + + +# test launcher +@pytest.mark.launch_test +def generate_test_description(): + """Launch file test description. + + Returns: + _type_: launch.LaunchDescription + """ + # get launch file path + launch_file_path = ( + FindPackageShare(PACKAGE_NAME).find(PACKAGE_NAME) + + "/launch/pointcloud_based_occupancy_grid_map.launch.py" + ) + launch_args = [ + ("input/obstacle_pointcloud", INPUT_TOPIC_OBSTACLE), + ("input/raw_pointcloud", INPUT_TOPIC_RAW), + ] + # action to include launch file + test_launch_file = launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource(launch_file_path), + launch_arguments=launch_args, + ) + + return launch.LaunchDescription( + [ + test_launch_file, + launch_testing.actions.ReadyToTest(), + ] + ) + + +# util functions +def get_pointcloud_msg(pts: list): + """Create ros2 point cloud message from list of points. + + Args: + pts (list): list of points [[x, y, z], ...] + + Returns: + PointCloud2: ros2 point cloud message + """ + msg = PointCloud2() + np_pts = np.array(pts, dtype=np.float32).reshape(-1, 3) + binary_pts = np_pts.tobytes() + + # set current time + now = rclpy.clock.Clock().now() + msg.header.stamp = now.to_msg() + msg.header.frame_id = "base_link" + msg.height = 1 + msg.width = np_pts.shape[0] + msg.fields = [ + PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), + ] + msg.is_bigendian = False + msg.point_step = 12 + msg.row_step = msg.point_step * msg.width + msg.is_dense = True + # msg.data = b"" + # msg_data_list = [] + # for pt in pts: + # msg_data_list.append(struct.pack('fff', pt[0], pt[1], pt[2])) + # msg.data = b"".join(msg_data_list) + msg.data = binary_pts + return msg + + +def parse_pointcloud_msg(msg: PointCloud2): + """Parse ros2 point cloud message to list of points. + + Args: + msg (PointCloud2): ros2 point cloud message + + Returns: + list: list of points [[x, y, z], ...] + """ + pts = [] + for i in range(msg.width): + offset = msg.point_step * i + x, y, z = struct.unpack("fff", msg.data[offset : offset + 12]) + pts.append([x, y, z]) + return pts + + +def generate_static_transform_msg(): + """Generate static transform message from base_link to map. + + Returns: + TransformStamped: static transform message + """ + msg = TransformStamped() + msg.header.stamp = rclpy.clock.Clock().now().to_msg() + msg.header.frame_id = "map" + msg.child_frame_id = "base_link" + msg.transform.translation.x = 0.0 + msg.transform.translation.y = 0.0 + msg.transform.translation.z = 0.0 + msg.transform.rotation.x = 0.0 + msg.transform.rotation.y = 0.0 + msg.transform.rotation.z = 0.0 + msg.transform.rotation.w = 1.0 + return msg + + +# Test Node IO +class TestNodeIO(unittest.TestCase): + @classmethod + def setUpClass(cls): + # init ROS at once + rclpy.init() + + @classmethod + def tearDownClass(cls): + # shutdown ROS at once + rclpy.shutdown() + + def setUp(self): + # called when each test started + self.node = rclpy.create_node("test_node_io") + # send static transform from map to base_link + tf_msg = generate_static_transform_msg() + self.tf_broadcaster = StaticTransformBroadcaster(self.node) + self.tf_broadcaster.sendTransform(tf_msg) + + def tearDown(self): + # called when each test finished + self.node.destroy_node() + + def callback(self, msg: OccupancyGrid): + self.msg_buffer.append(msg) + print("callback", len(self.msg_buffer)) + + # util functions + def create_pub_sub(self): + # create publisher + pub_raw = self.node.create_publisher(PointCloud2, INPUT_TOPIC_RAW, 10) + pub_obstacle = self.node.create_publisher(PointCloud2, INPUT_TOPIC_OBSTACLE, 10) + + sensor_qos = QoSProfile( + history=QoSHistoryPolicy.KEEP_LAST, + depth=10, + reliability=QoSReliabilityPolicy.BEST_EFFORT, + durability=QoSDurabilityPolicy.VOLATILE, + ) + # create subscriber + self.msg_buffer = [] + # subscribe to occupancy grid with buffer + sub = self.node.create_subscription( + OccupancyGrid, "/occupancy_grid", self.callback, qos_profile=sensor_qos + ) + return pub_raw, pub_obstacle, sub + + # test functions + def test_normal_input(self): + """Test normal input. + + input: normal pointcloud + output: normal ogm + """ + # wait for the node to be ready + time.sleep(3) + # min_height, max_height = -1.0, 2.0 + input_points = [[1.0, 1.0, 1.0], [2.0, 2.0, 2.0]] + pub_raw, pub_obstacle, sub = self.create_pub_sub() + # publish input pointcloud + pt_msg = get_pointcloud_msg(input_points) + pub_raw.publish(pt_msg) + pub_obstacle.publish(pt_msg) + # try to subscribe output pointcloud once + rclpy.spin_once(self.node, timeout_sec=3.0) + self.assertEqual(len(self.msg_buffer), 1) + + def test_null_input(self, proc_info): + """Test null input. + + input: null pointcloud + output: null ogm + """ + # wait for the node to be ready + time.sleep(3) + input_points = [] + pub_raw, pub_obstacle, sub = self.create_pub_sub() + # publish input pointcloud + pt_msg = get_pointcloud_msg(input_points) + pub_raw.publish(pt_msg) + pub_obstacle.publish(pt_msg) + # try to subscribe output pointcloud once + rclpy.spin_once(self.node, timeout_sec=3.0) + + # check if process is successfully terminated + nodes = self.node.get_node_names() + self.assertIn("occupancy_grid_map_node", nodes) + self.assertEqual(len(self.msg_buffer), 1) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # check exit code + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp b/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp new file mode 100644 index 0000000000000..3b1edca14e146 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp @@ -0,0 +1,92 @@ +// Copyright 2023 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 + +#include +// pcl +#include + +#include +#include + +// autoware +#include "utils/utils.hpp" + +#include + +// create pointcloud function +pcl::PointCloud createPCLPointCloudWithIteratedHeight(const size_t width) +{ + pcl::PointCloud pcl_cloud; + pcl_cloud.width = width; + pcl_cloud.height = 1; // assume height is 1 + pcl_cloud.points.resize(pcl_cloud.width * pcl_cloud.height); + for (size_t i = 0; i < pcl_cloud.points.size(); ++i) { + pcl_cloud.points[i].x = 1.0; + pcl_cloud.points[i].y = 1.0; + pcl_cloud.points[i].z = static_cast(i); + } + pcl_cloud.header.frame_id = "base_link"; + return pcl_cloud; +} + +// mock buffer to avoid tf2_ros::Buffer::lookupTransform() error +class MockBuffer : public tf2_ros::Buffer +{ +public: + MockBuffer() : Buffer(std::make_shared(RCL_ROS_TIME)) {} + + // override lookupTransform() to avoid error + geometry_msgs::msg::TransformStamped lookupTransform( + const std::string & target_frame, const std::string & source_frame, + const tf2::TimePoint & time) const override + { + (void)target_frame; + (void)source_frame; + (void)time; + geometry_msgs::msg::TransformStamped dummy_transform; + return dummy_transform; + } +}; + +// test pointcloud cropping function +TEST(TestUtils, TestCropPointcloudByHeight) +{ + // mock buffer + MockBuffer mock_buffer; + // create pointcloud with pcl + const auto pcl_cloud_10 = createPCLPointCloudWithIteratedHeight(10); + const auto pcl_cloud_0 = createPCLPointCloudWithIteratedHeight(0); + // convert to ros msg + sensor_msgs::msg::PointCloud2 ros_cloud_10; + sensor_msgs::msg::PointCloud2 ros_cloud_0; + pcl::toROSMsg(pcl_cloud_10, ros_cloud_10); + pcl::toROSMsg(pcl_cloud_0, ros_cloud_0); + + // test buffer + sensor_msgs::msg::PointCloud2 test1_output, test2_output, test3_output; + + // case1: normal input, normal output + EXPECT_NO_THROW( + utils::cropPointcloudByHeight(ros_cloud_10, mock_buffer, "base_link", 0.0, 10.0, test1_output)); + + // case2: normal input, empty output + EXPECT_NO_THROW(utils::cropPointcloudByHeight( + ros_cloud_10, mock_buffer, "base_link", -2.0, -0.1, test2_output)); + + // case3: empty input, normal output + EXPECT_NO_THROW( + utils::cropPointcloudByHeight(ros_cloud_0, mock_buffer, "base_link", 0.0, 10.0, test3_output)); +} From 3076544826f9bf9043e1b47b75cdebf46ab19832 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Tue, 15 Aug 2023 11:34:08 +0800 Subject: [PATCH 172/266] fix(documents for behavior path planner): change output_debug_marker to publish debug marker following code changes. (#4623) Signed-off-by: Owen-Liuyuxuan Co-authored-by: Owen-Liuyuxuan --- .../docs/behavior_path_planner_avoidance_design.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index 4e4d2258fc276..693d610951bbb 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -822,7 +822,7 @@ Developers can see what is going on in each process by visualizing all the avoid ![fig1](../image/avoidance/avoidance-debug-marker.png) -To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.output_debug_marker true` (no restart is needed) or simply set the `output_debug_marker` to `true` in the `avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. +To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. ### Echoing debug message to find out why the objects were ignored From bf400db7aa6a045148718ccf1ee47a6e0cf8a67c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 15 Aug 2023 14:37:11 +0900 Subject: [PATCH 173/266] feat(avoidance): reduce road shoulder margin if lateral distance is not enough to avoid (#4609) * feat(avoidance): reduce road shoulder margin if lateral distance is not enough to avoid Signed-off-by: satoshi-ota * fix(avoidance): remove std::min Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 3 ++- .../utils/avoidance/avoidance_module_data.hpp | 6 ++++- .../src/scene_module/avoidance/manager.cpp | 7 +++--- .../src/utils/avoidance/utils.cpp | 25 +++++++++++++------ 4 files changed, 28 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index ac3840baa1c4c..8666360696021 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -154,7 +154,8 @@ lateral_execution_threshold: 0.499 # [m] lateral_small_shift_threshold: 0.101 # [m] lateral_avoid_check_threshold: 0.1 # [m] - road_shoulder_safety_margin: 0.3 # [m] + soft_road_shoulder_margin: 0.8 # [m] + hard_road_shoulder_margin: 0.3 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 # avoidance distance parameters diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 94b914b65a067..dfdf4531a8d65 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -233,7 +233,11 @@ struct AvoidanceParameters // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. - double road_shoulder_safety_margin{1.0}; + double soft_road_shoulder_margin{1.0}; + + // The margin is configured so that the generated avoidance trajectory does not come near to the + // road shoulder. + double hard_road_shoulder_margin{1.0}; // Even if the obstacle is very large, it will not avoid more than this length for right direction double max_right_shift_length; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index be8c610611422..48c75b5b114e1 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -157,7 +157,8 @@ AvoidanceModuleManager::AvoidanceModuleManager( // avoidance maneuver (lateral) { std::string ns = "avoidance.avoidance.lateral."; - p.road_shoulder_safety_margin = get_parameter(node, ns + "road_shoulder_safety_margin"); + p.soft_road_shoulder_margin = get_parameter(node, ns + "soft_road_shoulder_margin"); + p.hard_road_shoulder_margin = get_parameter(node, ns + "hard_road_shoulder_margin"); p.lateral_execution_threshold = get_parameter(node, ns + "lateral_execution_threshold"); p.lateral_small_shift_threshold = get_parameter(node, ns + "lateral_small_shift_threshold"); @@ -316,8 +317,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorlateral_small_shift_threshold); updateParam( parameters, ns + "lateral_avoid_check_threshold", p->lateral_avoid_check_threshold); - updateParam( - parameters, ns + "road_shoulder_safety_margin", p->road_shoulder_safety_margin); + updateParam(parameters, ns + "soft_road_shoulder_margin", p->soft_road_shoulder_margin); + updateParam(parameters, ns + "hard_road_shoulder_margin", p->hard_road_shoulder_margin); } { diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index c88fc377dc473..7dca1219945c6 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -992,18 +992,27 @@ void filterTargetObjects( // calculate avoid_margin dynamically // NOTE: This calculation must be after calculating to_road_shoulder_distance. - const double max_avoid_margin = object_parameter.safety_buffer_lateral * o.distance_factor + - object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; - const double min_safety_lateral_distance = - object_parameter.safety_buffer_lateral + 0.5 * vehicle_width; - const auto max_allowable_lateral_distance = - o.to_road_shoulder_distance - parameters->road_shoulder_safety_margin - 0.5 * vehicle_width; + const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o.distance_factor + + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; + const auto min_avoid_margin = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width; + const auto soft_lateral_distance_limit = + o.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width; + const auto hard_lateral_distance_limit = + o.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width; const auto avoid_margin = [&]() -> boost::optional { - if (max_allowable_lateral_distance < min_safety_lateral_distance) { + // Step1. check avoidable or not. + if (hard_lateral_distance_limit < min_avoid_margin) { return boost::none; } - return std::min(max_allowable_lateral_distance, max_avoid_margin); + + // Step2. check if it should expand road shoulder margin. + if (soft_lateral_distance_limit < min_avoid_margin) { + return min_avoid_margin; + } + + // Step3. nominal case. avoid margin is limited by soft constraint. + return std::min(soft_lateral_distance_limit, max_avoid_margin); }(); if (!!avoid_margin) { From 7d740fddbe30678b6731678658f18fe187171f45 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 15 Aug 2023 16:04:54 +0900 Subject: [PATCH 174/266] fix(behavior_velocity_crosswalk_module): fix links to images (#4625) Signed-off-by: Ryohsuke Mitsudome --- planning/behavior_velocity_crosswalk_module/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_crosswalk_module/README.md index 218989482ec97..f85c472c6d856 100644 --- a/planning/behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_crosswalk_module/README.md @@ -32,7 +32,7 @@ The manager launch crosswalk scene modules when the reference path conflicts cro The crosswalk module determines a stop position at least `stop_distance_from_object` away from the object.

    - ![stop_distance_from_object](docs/stop_distance_from_object.svg){width=1000} + ![stop_distance_from_object](docs/stop_margin.svg){width=1000}
    stop margin
    @@ -44,14 +44,14 @@ The stop line is the reference point for the stopping position of the vehicle, b
    - ![stop_distance_from_crosswalk](docs/stop_distance_from_crosswalk.svg){width=700} + ![stop_distance_from_crosswalk](docs/stop_line_distance.svg){width=700}
    virtual stop point
    On the other hand, if pedestrian (bicycle) is crossing **wide** crosswalks seen in scramble intersections, and the pedestrian position is more than `far_object_threshold` meters away from the stop line, the actual stop position is determined to be `stop_distance_from_object` and pedestrian position, not at the stop line.
    - ![far_object_threshold](docs/far_object_threshold.svg){width=1000} + ![far_object_threshold](docs/stop_line_margin.svg){width=1000}
    stop at wide crosswalk
    From a7ed060ea235bcfe5f3e9d53a43ddd6e533ddbe0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 15 Aug 2023 16:12:10 +0900 Subject: [PATCH 175/266] fix(avoidance): add gurard to generateTotalShiftLine (#4628) * fix(avoidance): add gurard to generateTotalShiftLine Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * style(pre-commit): autofix * Revert "style(pre-commit): autofix" This reverts commit e142f521ccf2f77fac1767b5eefa1da95a08ea0c. * Revert "Update planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp" This reverts commit 174c90319fd10dbb75ea9824316f12ab2fc527a4. * fix from suggenstion Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/scene_module/avoidance/avoidance_module.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index a763bab7897fb..990a5ea35818a 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1094,7 +1094,10 @@ void AvoidanceModule::generateTotalShiftLine( // overwrite shift with current_ego_shift until ego pose. const auto current_shift = helper_.getEgoLinearShift(); - for (size_t i = 0; i <= avoidance_data_.ego_closest_path_index; ++i) { + for (size_t i = 0; i < sl.shift_line.size(); ++i) { + if (avoidance_data_.ego_closest_path_index < i) { + break; + } sl.shift_line.at(i) = current_shift; sl.shift_line_grad.at(i) = 0.0; } From 1dea0643044fc0846e9d1df8712ad2ea3cc9572a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 15 Aug 2023 18:02:21 +0900 Subject: [PATCH 176/266] chore(ci): disable spell-check-partial for control directory (#4631) enable_spell-check-partial_for_control_directory Signed-off-by: kyoichi-sugahara --- .cspell-partial.json | 1 + 1 file changed, 1 insertion(+) diff --git a/.cspell-partial.json b/.cspell-partial.json index a3c4ca455d444..7d41451bd840a 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -3,6 +3,7 @@ "**/perception/**", "**/planning/**", "**/sensing/**", + "**/control/**", "perception/bytetrack/lib/**" ], "ignoreRegExpList": [], From 7bc09bc5e297dfac68f185b0be74348ce761dcdb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 15 Aug 2023 18:32:01 +0900 Subject: [PATCH 177/266] fix(avoidance): add guard for empty path in updateData (#4633) Signed-off-by: kosuke55 --- .../src/scene_module/avoidance/avoidance_module.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 990a5ea35818a..8523bed5d4c2d 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -2460,6 +2460,10 @@ void AvoidanceModule::updateData() debug_data_ = DebugData(); avoidance_data_ = calcAvoidancePlanningData(debug_data_); + if (avoidance_data_.reference_path.points.empty()) { + // an empty path will kill further processing + return; + } utils::avoidance::updateRegisteredObject( registered_objects_, avoidance_data_.target_objects, parameters_); From ba8e22eda72adc62a09701b57a2ff75d2e427b20 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 15 Aug 2023 19:30:39 +0900 Subject: [PATCH 178/266] feat(control_validator): measure predicted path deviation from trajectory (#4549) * add feature for getting predicted path deviation from trajectory Signed-off-by: kyoichi-sugahara * fix for build success Signed-off-by: kyoichi-sugahara * fix topic name Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * cut off extra length on predicted path Signed-off-by: kyoichi-sugahara * cut off extra length on predicted path Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * minor refactor Signed-off-by: kyoichi-sugahara * change function name Signed-off-by: kyoichi-sugahara * add control validator Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * add max_deviation calculation Signed-off-by: kyoichi-sugahara * refactor Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * update launch Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * change maintainer Signed-off-by: kyoichi-sugahara * refactor Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * feat(dynamic_avoidance): object polygon based drivable area generation (#4598) Signed-off-by: Takayuki Murooka * update Signed-off-by: kyoichi-sugahara * update README Signed-off-by: kyoichi-sugahara * fix typo Signed-off-by: kyoichi-sugahara * apply clang-tidy check Signed-off-by: kyoichi-sugahara * Update control/control_validator/include/control_validator/utils.hpp Co-authored-by: Takamasa Horibe * remove debug code Signed-off-by: kyoichi-sugahara * add maintainer Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Signed-off-by: Takayuki Murooka Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takayuki Murooka Co-authored-by: Takamasa Horibe --- control/control_validator/CMakeLists.txt | 46 ++++ control/control_validator/README.md | 58 +++++ .../config/control_validator.param.yaml | 14 ++ .../image/control_validator.drawio.svg | 155 +++++++++++++ .../image/trajectory_deviation.drawio.svg | 112 +++++++++ .../control_validator/control_validator.hpp | 100 +++++++++ .../control_validator/debug_marker.hpp | 61 +++++ .../include/control_validator/utils.hpp | 55 +++++ .../launch/control_validator.launch.xml | 16 ++ .../msg/ControlValidatorStatus.msg | 9 + control/control_validator/package.xml | 41 ++++ .../src/control_validator.cpp | 212 ++++++++++++++++++ .../control_validator/src/debug_marker.cpp | 101 +++++++++ control/control_validator/src/utils.cpp | 164 ++++++++++++++ .../launch/control.launch.py | 21 ++ 15 files changed, 1165 insertions(+) create mode 100644 control/control_validator/CMakeLists.txt create mode 100644 control/control_validator/README.md create mode 100644 control/control_validator/config/control_validator.param.yaml create mode 100644 control/control_validator/image/control_validator.drawio.svg create mode 100644 control/control_validator/image/trajectory_deviation.drawio.svg create mode 100644 control/control_validator/include/control_validator/control_validator.hpp create mode 100644 control/control_validator/include/control_validator/debug_marker.hpp create mode 100644 control/control_validator/include/control_validator/utils.hpp create mode 100644 control/control_validator/launch/control_validator.launch.xml create mode 100644 control/control_validator/msg/ControlValidatorStatus.msg create mode 100644 control/control_validator/package.xml create mode 100644 control/control_validator/src/control_validator.cpp create mode 100644 control/control_validator/src/debug_marker.cpp create mode 100644 control/control_validator/src/utils.cpp diff --git a/control/control_validator/CMakeLists.txt b/control/control_validator/CMakeLists.txt new file mode 100644 index 0000000000000..fab942c4dc001 --- /dev/null +++ b/control/control_validator/CMakeLists.txt @@ -0,0 +1,46 @@ +cmake_minimum_required(VERSION 3.22) +project(control_validator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(control_validator_helpers SHARED + src/utils.cpp + src/debug_marker.cpp +) + +# control validator +ament_auto_add_library(control_validator_component SHARED + include/control_validator/control_validator.hpp + src/control_validator.cpp +) +target_link_libraries(control_validator_component control_validator_helpers) +rclcpp_components_register_node(control_validator_component + PLUGIN "control_validator::ControlValidator" + EXECUTABLE control_validator_node +) + +rosidl_generate_interfaces( + ${PROJECT_NAME} + "msg/ControlValidatorStatus.msg" + DEPENDENCIES builtin_interfaces +) + +# to use a message defined in the same package +if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) + rosidl_target_interfaces(control_validator_component + ${PROJECT_NAME} "rosidl_typesupport_cpp") +else() + rosidl_get_typesupport_target( + cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(control_validator_component "${cpp_typesupport_target}") +endif() + +# if(BUILD_TESTING) +# endif() + +ament_auto_package( + INSTALL_TO_SHARE + config + launch +) diff --git a/control/control_validator/README.md b/control/control_validator/README.md new file mode 100644 index 0000000000000..3d78721a0a040 --- /dev/null +++ b/control/control_validator/README.md @@ -0,0 +1,58 @@ +# Control Validator + +The `control_validator` is a module that checks the validity of the output of the control component. The status of the validation can be viewed in the `/diagnostics` topic. + +![control_validator](./image/control_validator.drawio.svg) + +## Supported features + +The following features are supported for the validation and can have thresholds set by parameters: + +- **Deviation check between reference trajectory and predicted trajectory** : invalid when the largest deviation between the predicted trajectory and reference trajectory is greater than the given threshold. + +![trajectory_deviation](./image/trajectory_deviation.drawio.svg) + +Other features are to be implemented. + +## Inputs/Outputs + +### Inputs + +The `control_validator` takes in the following inputs: + +| Name | Type | Description | +| ------------------------------ | ------------------------------------- | ------------------------------------------------------------------------------ | +| `~/input/kinematics` | nav_msgs/Odometry | ego pose and twist | +| `~/input/reference_trajectory` | autoware_auto_control_msgs/Trajectory | reference trajectory which is outputted from planning module to to be followed | +| `~/input/predicted_trajectory` | autoware_auto_control_msgs/Trajectory | predicted trajectory which is outputted from control module | + +### Outputs + +It outputs the following: + +| Name | Type | Description | +| ---------------------------- | ---------------------------------------- | ------------------------------------------------------------------------- | +| `~/output/validation_status` | control_validator/ControlValidatorStatus | validator status to inform the reason why the trajectory is valid/invalid | +| `/diagnostics` | diagnostic_msgs/DiagnosticStatus | diagnostics to report errors | + +## Parameters + +The following parameters can be set for the `control_validator`: + +### System parameters + +| Name | Type | Description | Default value | +| :--------------------------- | :--- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| `publish_diag` | bool | if true, diagnostics msg is published. | true | +| `diag_error_count_threshold` | int | the Diag will be set to ERROR when the number of consecutive invalid trajectory exceeds this threshold. (For example, threshold = 1 means, even if the trajectory is invalid, the Diag will not be ERROR if the next trajectory is valid.) | true | +| `display_on_terminal` | bool | show error msg on terminal | true | + +### Algorithm parameters + +#### Thresholds + +The input trajectory is detected as invalid if the index exceeds the following thresholds. + +| Name | Type | Description | Default value | +| :---------------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :------------ | +| `thresholds.max_distance_deviation` | double | invalid threshold of the max distance deviation between the predicted path and the reference trajectory [m] | 1.0 | diff --git a/control/control_validator/config/control_validator.param.yaml b/control/control_validator/config/control_validator.param.yaml new file mode 100644 index 0000000000000..7bbe6a466799b --- /dev/null +++ b/control/control_validator/config/control_validator.param.yaml @@ -0,0 +1,14 @@ +/**: + ros__parameters: + + publish_diag: true # if true, diagnostic msg is published + + # If the number of consecutive invalid trajectory exceeds this threshold, the Diag will be set to ERROR. + # (For example, threshold = 1 means, even if the trajectory is invalid, Diag will not be ERROR if + # the next trajectory is valid.) + diag_error_count_threshold: 0 + + display_on_terminal: true # show error msg on terminal + + thresholds: + max_distance_deviation: 1.0 diff --git a/control/control_validator/image/control_validator.drawio.svg b/control/control_validator/image/control_validator.drawio.svg new file mode 100644 index 0000000000000..1b226cbd3ec85 --- /dev/null +++ b/control/control_validator/image/control_validator.drawio.svg @@ -0,0 +1,155 @@ + + + + + + +
    +
    control_validator
    +
    +
    +
    + + + + +
    +
    Predicted trajectory
    +
    +
    +
    + + + + +
    +
    ego_kinematics
    +
    +
    +
    + + + + +
    +
    DiagnosticStatus
    +
    +
    +
    + + + + +
    +
    ControlValidatorStatus
    +
    +
    +
    + + + +
    +
    + + Predicted trajectory to +
    + be validated +
    +
    +
    +
    +
    + + + +
    +
    + Used for the validation +
    +
    +
    +
    + + + +
    +
    + To send validation result to the system: OK/ERROR +
    +
    +
    +
    + + + +
    +
    + To show the result and the reason for other modules/users +
    +
    +
    +
    + + + + +
    +
    Planning trajectory
    +
    +
    +
    + + + +
    +
    + + Reference trajectory to be followed + +
    +
    +
    +
    +
    +
    diff --git a/control/control_validator/image/trajectory_deviation.drawio.svg b/control/control_validator/image/trajectory_deviation.drawio.svg new file mode 100644 index 0000000000000..cdad355c5bb1e --- /dev/null +++ b/control/control_validator/image/trajectory_deviation.drawio.svg @@ -0,0 +1,112 @@ + + + + + + + +
    +
    +
    + ego +
    +
    +
    +
    + ego +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +
    + Reference Trajectory +
    +
    +
    +
    + Reference Trajectory +
    +
    + + + + +
    +
    +
    + Predicted Trajectory +
    +
    +
    +
    + Predicted Trajectory +
    +
    + + + + + + + +
    +
    +
    + max distance deviation +
    +
    +
    +
    + max distance deviation +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/control/control_validator/include/control_validator/control_validator.hpp b/control/control_validator/include/control_validator/control_validator.hpp new file mode 100644 index 0000000000000..48b7eba7412a2 --- /dev/null +++ b/control/control_validator/include/control_validator/control_validator.hpp @@ -0,0 +1,100 @@ +// Copyright 2023 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 CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_ +#define CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_ + +#include "control_validator/debug_marker.hpp" +#include "control_validator/msg/control_validator_status.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include +#include + +#include +#include +#include + +#include +#include + +namespace control_validator +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using control_validator::msg::ControlValidatorStatus; +using diagnostic_updater::DiagnosticStatusWrapper; +using diagnostic_updater::Updater; +using nav_msgs::msg::Odometry; + +struct ValidationParams +{ + double max_distance_deviation_threshold; +}; + +class ControlValidator : public rclcpp::Node +{ +public: + explicit ControlValidator(const rclcpp::NodeOptions & options); + + void onReferenceTrajectory(const Trajectory::ConstSharedPtr msg); + void onPredictedTrajectory(const Trajectory::ConstSharedPtr msg); + + bool checkValidMaxDistanceDeviation(const Trajectory & predicted_trajectory); + +private: + void setupDiag(); + + void setupParameters(); + + bool isDataReady(); + + void validate(const Trajectory & trajectory); + + void publishPredictedTrajectory(); + void publishDebugInfo(); + void displayStatus(); + + void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg); + + rclcpp::Subscription::SharedPtr sub_kinematics_; + rclcpp::Subscription::SharedPtr sub_reference_traj_; + rclcpp::Subscription::SharedPtr sub_predicted_traj_; + rclcpp::Publisher::SharedPtr pub_status_; + rclcpp::Publisher::SharedPtr pub_markers_; + + // system parameters + bool publish_diag_ = true; + int diag_error_count_threshold_ = 0; + bool display_on_terminal_ = true; + + Updater diag_updater_{this}; + + ControlValidatorStatus validation_status_; + ValidationParams validation_params_; // for thresholds + + vehicle_info_util::VehicleInfo vehicle_info_; + + bool isAllValid(const ControlValidatorStatus & status); + + Trajectory::ConstSharedPtr current_reference_trajectory_; + Trajectory::ConstSharedPtr current_predicted_trajectory_; + + Odometry::ConstSharedPtr current_kinematics_; + + std::shared_ptr debug_pose_publisher_; +}; +} // namespace control_validator + +#endif // CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_ diff --git a/control/control_validator/include/control_validator/debug_marker.hpp b/control/control_validator/include/control_validator/debug_marker.hpp new file mode 100644 index 0000000000000..794912e085949 --- /dev/null +++ b/control/control_validator/include/control_validator/debug_marker.hpp @@ -0,0 +1,61 @@ +// 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 CONTROL_VALIDATOR__DEBUG_MARKER_HPP_ +#define CONTROL_VALIDATOR__DEBUG_MARKER_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include +#include + +class ControlValidatorDebugMarkerPublisher +{ +public: + explicit ControlValidatorDebugMarkerPublisher(rclcpp::Node * node); + + void pushPoseMarker( + const autoware_auto_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns, + int id = 0); + void pushPoseMarker(const geometry_msgs::msg::Pose & pose, const std::string & ns, int id = 0); + void pushVirtualWall(const geometry_msgs::msg::Pose & pose); + void pushWarningMsg(const geometry_msgs::msg::Pose & pose, const std::string & msg); + void publish(); + + void clearMarkers(); + +private: + rclcpp::Node * node_; + visualization_msgs::msg::MarkerArray marker_array_; + visualization_msgs::msg::MarkerArray marker_array_virtual_wall_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Publisher::SharedPtr virtual_wall_pub_; + std::map marker_id_; + + int getMarkerId(const std::string & ns) + { + if (marker_id_.count(ns) == 0) { + marker_id_[ns] = 0.0; + } + return marker_id_[ns]++; + } +}; + +#endif // CONTROL_VALIDATOR__DEBUG_MARKER_HPP_ diff --git a/control/control_validator/include/control_validator/utils.hpp b/control/control_validator/include/control_validator/utils.hpp new file mode 100644 index 0000000000000..39ec316dbe437 --- /dev/null +++ b/control/control_validator/include/control_validator/utils.hpp @@ -0,0 +1,55 @@ +// Copyright 2023 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 CONTROL_VALIDATOR__UTILS_HPP_ +#define CONTROL_VALIDATOR__UTILS_HPP_ + +#include +#include + +#include + +#include +#include +#include + +namespace control_validator +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using geometry_msgs::msg::Pose; +using motion_utils::convertToTrajectory; +using motion_utils::convertToTrajectoryPointArray; +using TrajectoryPoints = std::vector; + +void shiftPose(Pose & pose, double longitudinal); + +void insertPointInPredictedTrajectory( + TrajectoryPoints & modified_trajectory, const geometry_msgs::msg::Pose & reference_pose, + const TrajectoryPoints & predicted_trajectory); + +TrajectoryPoints reverseTrajectoryPoints(const TrajectoryPoints & trajectory); + +bool removeFrontTrajectoryPoint( + const TrajectoryPoints & trajectory_points, TrajectoryPoints & modified_trajectory_points, + const TrajectoryPoints & predicted_trajectory_points); + +Trajectory alignTrajectoryWithReferenceTrajectory( + const Trajectory & trajectory, const Trajectory & predicted_trajectory); + +double calcMaxLateralDistance( + const Trajectory & trajectory, const Trajectory & predicted_trajectory); +} // namespace control_validator + +#endif // CONTROL_VALIDATOR__UTILS_HPP_ diff --git a/control/control_validator/launch/control_validator.launch.xml b/control/control_validator/launch/control_validator.launch.xml new file mode 100644 index 0000000000000..9727e06e60523 --- /dev/null +++ b/control/control_validator/launch/control_validator.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/control/control_validator/msg/ControlValidatorStatus.msg b/control/control_validator/msg/ControlValidatorStatus.msg new file mode 100644 index 0000000000000..242bede4ece89 --- /dev/null +++ b/control/control_validator/msg/ControlValidatorStatus.msg @@ -0,0 +1,9 @@ +builtin_interfaces/Time stamp + +# states +bool is_valid_max_distance_deviation + +# values +float64 max_distance_deviation + +int64 invalid_count diff --git a/control/control_validator/package.xml b/control/control_validator/package.xml new file mode 100644 index 0000000000000..c46c2d237b605 --- /dev/null +++ b/control/control_validator/package.xml @@ -0,0 +1,41 @@ + + + + control_validator + 0.1.0 + ros node for control_validator + Kyoichi Sugahara + Takamasa Horibe + Makoto Kurihara + Apache License 2.0 + + Kyoichi Sugahara + Takamasa Horibe + Makoto Kurihara + + ament_cmake_auto + autoware_cmake + rosidl_default_generators + + autoware_auto_planning_msgs + diagnostic_updater + geometry_msgs + motion_utils + nav_msgs + rclcpp + rclcpp_components + tier4_autoware_utils + vehicle_info_util + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + rosidl_default_runtime + rosidl_interface_packages + + + ament_cmake + + diff --git a/control/control_validator/src/control_validator.cpp b/control/control_validator/src/control_validator.cpp new file mode 100644 index 0000000000000..c301b26575d99 --- /dev/null +++ b/control/control_validator/src/control_validator.cpp @@ -0,0 +1,212 @@ +// Copyright 2023 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 "control_validator/control_validator.hpp" + +#include "control_validator/utils.hpp" + +#include +#include + +#include +#include +#include + +namespace control_validator +{ +using diagnostic_msgs::msg::DiagnosticStatus; + +ControlValidator::ControlValidator(const rclcpp::NodeOptions & options) +: Node("control_validator", options) +{ + using std::placeholders::_1; + + sub_kinematics_ = create_subscription( + "~/input/kinematics", 1, + [this](const Odometry::ConstSharedPtr msg) { current_kinematics_ = msg; }); + sub_reference_traj_ = create_subscription( + "~/input/reference_trajectory", 1, + std::bind(&ControlValidator::onReferenceTrajectory, this, _1)); + sub_predicted_traj_ = create_subscription( + "~/input/predicted_trajectory", 1, + std::bind(&ControlValidator::onPredictedTrajectory, this, _1)); + + pub_status_ = create_publisher("~/output/validation_status", 1); + pub_markers_ = create_publisher("~/output/markers", 1); + + debug_pose_publisher_ = std::make_shared(this); + + setupParameters(); + + if (publish_diag_) { + setupDiag(); + } +} + +void ControlValidator::setupParameters() +{ + publish_diag_ = declare_parameter("publish_diag"); + diag_error_count_threshold_ = declare_parameter("diag_error_count_threshold"); + display_on_terminal_ = declare_parameter("display_on_terminal"); + + { + auto & p = validation_params_; + const std::string t = "thresholds."; + p.max_distance_deviation_threshold = declare_parameter(t + "max_distance_deviation"); + } + + try { + vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + } catch (...) { + RCLCPP_ERROR(get_logger(), "failed to get vehicle info. use default value."); + vehicle_info_.front_overhang_m = 0.5; + vehicle_info_.wheel_base_m = 4.0; + } +} + +void ControlValidator::setStatus( + DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg) +{ + if (is_ok) { + stat.summary(DiagnosticStatus::OK, "validated."); + } else if (validation_status_.invalid_count < diag_error_count_threshold_) { + const auto warn_msg = msg + " (invalid count is less than error threshold: " + + std::to_string(validation_status_.invalid_count) + " < " + + std::to_string(diag_error_count_threshold_) + ")"; + stat.summary(DiagnosticStatus::WARN, warn_msg); + } else { + stat.summary(DiagnosticStatus::ERROR, msg); + } +} + +void ControlValidator::setupDiag() +{ + auto & d = diag_updater_; + d.setHardwareID("control_validator"); + + std::string ns = "control_validation_"; + d.add(ns + "max_distance_deviation", [&](auto & stat) { + setStatus( + stat, validation_status_.is_valid_max_distance_deviation, + "control output is deviated from trajectory"); + }); +} + +bool ControlValidator::isDataReady() +{ + const auto waiting = [this](const auto s) { + RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for %s", s); + return false; + }; + + if (!current_kinematics_) { + return waiting("current_kinematics_"); + } + if (!current_reference_trajectory_) { + return waiting("current_reference_trajectory_"); + } + if (!current_predicted_trajectory_) { + return waiting("current_predicted_trajectory_"); + } + return true; +} + +void ControlValidator::onReferenceTrajectory(const Trajectory::ConstSharedPtr msg) +{ + current_reference_trajectory_ = msg; + + return; +} + +void ControlValidator::onPredictedTrajectory(const Trajectory::ConstSharedPtr msg) +{ + current_predicted_trajectory_ = msg; + + if (!isDataReady()) return; + + debug_pose_publisher_->clearMarkers(); + + validate(*current_predicted_trajectory_); + + diag_updater_.force_update(); + + // for debug + publishDebugInfo(); + displayStatus(); +} + +void ControlValidator::publishDebugInfo() +{ + validation_status_.stamp = get_clock()->now(); + pub_status_->publish(validation_status_); + + if (!isAllValid(validation_status_)) { + geometry_msgs::msg::Pose front_pose = current_kinematics_->pose.pose; + shiftPose(front_pose, vehicle_info_.front_overhang_m + vehicle_info_.wheel_base_m); + debug_pose_publisher_->pushVirtualWall(front_pose); + debug_pose_publisher_->pushWarningMsg(front_pose, "INVALID CONTROL"); + } + debug_pose_publisher_->publish(); +} + +void ControlValidator::validate(const Trajectory & predicted_trajectory) +{ + if (predicted_trajectory.points.size() < 2) { + RCLCPP_ERROR(get_logger(), "predicted_trajectory size is less than 2. Cannot validate."); + return; + } + + auto & s = validation_status_; + + s.is_valid_max_distance_deviation = checkValidMaxDistanceDeviation(predicted_trajectory); + + s.invalid_count = isAllValid(s) ? 0 : s.invalid_count + 1; +} + +bool ControlValidator::checkValidMaxDistanceDeviation(const Trajectory & predicted_trajectory) +{ + validation_status_.max_distance_deviation = + calcMaxLateralDistance(*current_reference_trajectory_, predicted_trajectory); + if ( + validation_status_.max_distance_deviation > + validation_params_.max_distance_deviation_threshold) { + return false; + } + return true; +} + +bool ControlValidator::isAllValid(const ControlValidatorStatus & s) +{ + return s.is_valid_max_distance_deviation; +} + +void ControlValidator::displayStatus() +{ + if (!display_on_terminal_) return; + + const auto warn = [this](const bool status, const std::string & msg) { + if (!status) { + RCLCPP_WARN(get_logger(), "%s", msg.c_str()); + } + }; + + const auto & s = validation_status_; + + warn(s.is_valid_max_distance_deviation, "planning trajectory is too far from ego!!"); +} + +} // namespace control_validator + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(control_validator::ControlValidator) diff --git a/control/control_validator/src/debug_marker.cpp b/control/control_validator/src/debug_marker.cpp new file mode 100644 index 0000000000000..c94c22c807648 --- /dev/null +++ b/control/control_validator/src/debug_marker.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 "control_validator/debug_marker.hpp" + +#include +#include + +#include +#include +#include + +using visualization_msgs::msg::Marker; + +ControlValidatorDebugMarkerPublisher::ControlValidatorDebugMarkerPublisher(rclcpp::Node * node) +: node_(node) +{ + debug_viz_pub_ = + node_->create_publisher("~/debug/marker", 1); + + virtual_wall_pub_ = + node_->create_publisher("~/virtual_wall", 1); +} + +void ControlValidatorDebugMarkerPublisher::clearMarkers() +{ + marker_array_.markers.clear(); + marker_array_virtual_wall_.markers.clear(); +} + +void ControlValidatorDebugMarkerPublisher::pushPoseMarker( + const autoware_auto_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns, int id) +{ + pushPoseMarker(p.pose, ns, id); +} + +void ControlValidatorDebugMarkerPublisher::pushPoseMarker( + const geometry_msgs::msg::Pose & pose, const std::string & ns, int id) +{ + using tier4_autoware_utils::createMarkerColor; + + // append arrow marker + std_msgs::msg::ColorRGBA color; + if (id == 0) // Red + { + color = createMarkerColor(1.0, 0.0, 0.0, 0.999); + } + if (id == 1) // Green + { + color = createMarkerColor(0.0, 1.0, 0.0, 0.999); + } + if (id == 2) // Blue + { + color = createMarkerColor(0.0, 0.0, 1.0, 0.999); + } + Marker marker = tier4_autoware_utils::createDefaultMarker( + "map", node_->get_clock()->now(), ns, getMarkerId(ns), Marker::ARROW, + tier4_autoware_utils::createMarkerScale(0.2, 0.1, 0.3), color); + marker.lifetime = rclcpp::Duration::from_seconds(0.2); + marker.pose = pose; + + marker_array_.markers.push_back(marker); +} + +void ControlValidatorDebugMarkerPublisher::pushWarningMsg( + const geometry_msgs::msg::Pose & pose, const std::string & msg) +{ + visualization_msgs::msg::Marker marker = tier4_autoware_utils::createDefaultMarker( + "map", node_->get_clock()->now(), "warning_msg", 0, Marker::TEXT_VIEW_FACING, + tier4_autoware_utils::createMarkerScale(0.0, 0.0, 1.0), + tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.999)); + marker.lifetime = rclcpp::Duration::from_seconds(0.2); + marker.pose = pose; + marker.text = msg; + marker_array_virtual_wall_.markers.push_back(marker); +} + +void ControlValidatorDebugMarkerPublisher::pushVirtualWall(const geometry_msgs::msg::Pose & pose) +{ + const auto now = node_->get_clock()->now(); + const auto stop_wall_marker = + motion_utils::createStopVirtualWallMarker(pose, "control_validator", now, 0); + tier4_autoware_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); +} + +void ControlValidatorDebugMarkerPublisher::publish() +{ + debug_viz_pub_->publish(marker_array_); + virtual_wall_pub_->publish(marker_array_virtual_wall_); +} diff --git a/control/control_validator/src/utils.cpp b/control/control_validator/src/utils.cpp new file mode 100644 index 0000000000000..88b8431b07af0 --- /dev/null +++ b/control/control_validator/src/utils.cpp @@ -0,0 +1,164 @@ +// Copyright 2023 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 "control_validator/utils.hpp" + +#include +#include +#include + +#include +#include +#include +#include + +namespace control_validator +{ + +void shiftPose(Pose & pose, double longitudinal) +{ + const auto yaw = tf2::getYaw(pose.orientation); + pose.position.x += std::cos(yaw) * longitudinal; + pose.position.y += std::sin(yaw) * longitudinal; +} + +void insertPointInPredictedTrajectory( + TrajectoryPoints & modified_trajectory, const Pose & reference_pose, + const TrajectoryPoints & predicted_trajectory) +{ + const auto point_to_interpolate = + motion_utils::calcInterpolatedPoint(convertToTrajectory(predicted_trajectory), reference_pose); + modified_trajectory.insert(modified_trajectory.begin(), point_to_interpolate); +} + +TrajectoryPoints reverseTrajectoryPoints(const TrajectoryPoints & trajectory_points) +{ + TrajectoryPoints reversed_trajectory_points(trajectory_points.size()); + std::reverse_copy( + trajectory_points.begin(), trajectory_points.end(), + std::back_inserter(reversed_trajectory_points)); + return reversed_trajectory_points; +} + +bool removeFrontTrajectoryPoint( + const TrajectoryPoints & trajectory_points, TrajectoryPoints & modified_trajectory_points, + const TrajectoryPoints & predicted_trajectory_points) +{ + bool predicted_trajectory_point_removed = false; + for (const auto & point : predicted_trajectory_points) { + if ( + motion_utils::calcLongitudinalOffsetToSegment(trajectory_points, 0, point.pose.position) < + 0.0) { + modified_trajectory_points.erase(modified_trajectory_points.begin()); + + predicted_trajectory_point_removed = true; + } else { + break; + } + } + + return predicted_trajectory_point_removed; +} + +Trajectory alignTrajectoryWithReferenceTrajectory( + const Trajectory & trajectory, const Trajectory & predicted_trajectory) +{ + const auto last_seg_length = motion_utils::calcSignedArcLength( + trajectory.points, trajectory.points.size() - 2, trajectory.points.size() - 1); + + // If no overlapping between trajectory and predicted_trajectory, return empty trajectory + // predicted_trajectory: p1------------------pN + // trajectory: t1------------------tN + // OR + // predicted_trajectory: p1------------------pN + // trajectory: t1------------------tN + const bool & is_p_n_before_t1 = + motion_utils::calcLongitudinalOffsetToSegment( + trajectory.points, 0, predicted_trajectory.points.back().pose.position) < 0.0; + const bool & is_p1_behind_t_n = motion_utils::calcLongitudinalOffsetToSegment( + trajectory.points, trajectory.points.size() - 2, + predicted_trajectory.points.front().pose.position) - + last_seg_length > + 0.0; + const bool is_no_overlapping = (is_p_n_before_t1 || is_p1_behind_t_n); + + if (is_no_overlapping) { + return Trajectory(); + } + + auto modified_trajectory_points = convertToTrajectoryPointArray(predicted_trajectory); + auto predicted_trajectory_points = convertToTrajectoryPointArray(predicted_trajectory); + auto trajectory_points = convertToTrajectoryPointArray(trajectory); + + // If first point of predicted_trajectory is in front of start of trajectory, erase points which + // are in front of trajectory start point and insert pNew along the predicted_trajectory + // predicted_trajectory:     p1-----p2-----p3----//------pN + // trajectory: t1--------//------tN + // ↓ + // predicted_trajectory:      tNew--p3----//------pN + // trajectory: t1--------//------tN + auto predicted_trajectory_point_removed = removeFrontTrajectoryPoint( + trajectory_points, modified_trajectory_points, predicted_trajectory_points); + + if (predicted_trajectory_point_removed) { + insertPointInPredictedTrajectory( + modified_trajectory_points, trajectory_points.front().pose, predicted_trajectory_points); + } + + // If last point of predicted_trajectory is behind of end of trajectory, erase points which are + // behind trajectory last point and insert pNew along the predicted_trajectory + // predicted_trajectory:     p1-----//------pN-2-----pN-1-----pN + // trajectory: t1-----//-----tN-1--tN + // ↓ + // predicted_trajectory: p1-----//------pN-2-pNew + // trajectory: t1-----//-----tN-1--tN + + auto reversed_predicted_trajectory_points = reverseTrajectoryPoints(predicted_trajectory_points); + auto reversed_trajectory_points = reverseTrajectoryPoints(trajectory_points); + auto reversed_modified_trajectory_points = reverseTrajectoryPoints(modified_trajectory_points); + + auto reversed_predicted_trajectory_point_removed = removeFrontTrajectoryPoint( + reversed_trajectory_points, reversed_modified_trajectory_points, + reversed_predicted_trajectory_points); + + if (reversed_predicted_trajectory_point_removed) { + insertPointInPredictedTrajectory( + reversed_modified_trajectory_points, reversed_trajectory_points.front().pose, + reversed_predicted_trajectory_points); + } + + return convertToTrajectory(reverseTrajectoryPoints(reversed_modified_trajectory_points)); +} + +double calcMaxLateralDistance( + const Trajectory & reference_trajectory, const Trajectory & predicted_trajectory) +{ + const auto alined_predicted_trajectory = + alignTrajectoryWithReferenceTrajectory(reference_trajectory, predicted_trajectory); + double max_dist = 0; + for (const auto & point : alined_predicted_trajectory.points) { + const auto p0 = tier4_autoware_utils::getPoint(point); + // find nearest segment + const size_t nearest_segment_idx = + motion_utils::findNearestSegmentIndex(reference_trajectory.points, p0); + double temp_dist = + motion_utils::calcLateralOffset(reference_trajectory.points, p0, nearest_segment_idx); + if (temp_dist > max_dist) { + max_dist = temp_dist; + } + } + return max_dist; +} + +} // namespace control_validator diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 8cb9c726fcb05..a673eb08c222f 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -49,6 +49,8 @@ def launch_setup(context, *args, **kwargs): vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"] with open(LaunchConfiguration("lane_departure_checker_param_path").perform(context), "r") as f: lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(LaunchConfiguration("control_validator_param_path").perform(context), "r") as f: + control_validator_param = yaml.safe_load(f)["/**"]["ros__parameters"] with open( LaunchConfiguration("operation_mode_transition_manager_param_path").perform(context), "r" ) as f: @@ -112,6 +114,23 @@ def launch_setup(context, *args, **kwargs): parameters=[nearest_search_param, lane_departure_checker_param, vehicle_info_param], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # control validator checker + control_validator_component = ComposableNode( + package="control_validator", + plugin="control_validator::ControlValidator", + name="control_validator", + remappings=[ + ("~/input/kinematics", "/localization/kinematic_state"), + ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ( + "~/input/predicted_trajectory", + "/control/trajectory_follower/lateral/predicted_trajectory", + ), + ("~/output/validation_status", "~/validation_status"), + ], + parameters=[control_validator_param], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) # shift decider shift_decider_component = ComposableNode( @@ -295,6 +314,7 @@ def launch_setup(context, *args, **kwargs): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ controller_component, + control_validator_component, lane_departure_component, shift_decider_component, vehicle_cmd_gate_component, @@ -338,6 +358,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("lon_controller_param_path") add_launch_arg("vehicle_cmd_gate_param_path") add_launch_arg("lane_departure_checker_param_path") + add_launch_arg("control_validator_param_path") add_launch_arg("operation_mode_transition_manager_param_path") add_launch_arg("shift_decider_param_path") add_launch_arg("obstacle_collision_checker_param_path") From 1d397240a20d79b1cfd88dfef0452a0071141329 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 15 Aug 2023 21:32:50 +0900 Subject: [PATCH 179/266] fix(planner_manager): don't back waiting approval besides last one in approved modules (#4588) * fix(planner_manager): back waiting approval only when it's last module Signed-off-by: satoshi-ota * fix(avoidance): lock output path Signed-off-by: satoshi-ota * fix(avoidance): remove unnecessary process Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 1 - .../behavior_path_planner/planner_manager.hpp | 2 +- .../scene_module/scene_module_interface.hpp | 10 ++++++ .../utils/avoidance/avoidance_module_data.hpp | 3 -- .../src/planner_manager.cpp | 34 +++++++++++++------ .../avoidance/avoidance_module.cpp | 20 ++++------- .../src/scene_module/avoidance/manager.cpp | 1 - 7 files changed, 41 insertions(+), 30 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 8666360696021..60f587002f72c 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -145,7 +145,6 @@ time_horizon: 10.0 # [s] safety_check_backward_distance: 100.0 # [m] safety_check_hysteresis_factor: 2.0 # [-] - safety_check_ego_offset: 1.0 # [m] # For avoidance maneuver avoidance: diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index f1292c2db7811..29857590d4eda 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -126,10 +126,10 @@ class PlannerManager */ void reset() { + std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->reset(); }); approved_module_ptrs_.clear(); candidate_module_ptrs_.clear(); root_lanelet_ = boost::none; - std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->reset(); }); resetProcessingTime(); } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index d1579ef40e9a7..3405ae446615d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -161,7 +161,9 @@ class SceneModuleInterface clearWaitingApproval(); removeRTCStatus(); + publishRTCStatus(); unlockNewModuleLaunch(); + unlockOutputPath(); steering_factor_interface_ptr_->clearSteeringFactors(); stop_reason_ = StopReason(); @@ -220,6 +222,10 @@ class SceneModuleInterface */ virtual void setData(const std::shared_ptr & data) { planner_data_ = data; } + void lockOutputPath() { is_locked_output_path_ = true; } + + void unlockOutputPath() { is_locked_output_path_ = false; } + bool isWaitingApproval() const { return is_waiting_approval_ || current_state_ == ModuleStatus::WAITING_APPROVAL; @@ -340,6 +346,8 @@ class SceneModuleInterface bool is_locked_new_module_launch_{false}; + bool is_locked_output_path_{false}; + protected: /** * @brief State transition condition ANY -> SUCCESS @@ -507,6 +515,8 @@ class SceneModuleInterface BehaviorModuleOutput getPreviousModuleOutput() const { return previous_module_output_; } + bool isOutputPathLocked() const { return is_locked_output_path_; } + void lockNewModuleLaunch() { is_locked_new_module_launch_ = true; } void unlockNewModuleLaunch() { is_locked_new_module_launch_ = false; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index dfdf4531a8d65..bb846d2aa70d0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -201,9 +201,6 @@ struct AvoidanceParameters // transit hysteresis (unsafe to safe) double safety_check_hysteresis_factor; - // don't output new candidate path if the offset between ego and path is larger than this. - double safety_check_ego_offset; - // keep target velocity in yield maneuver double yield_velocity; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 6558bd7110f10..c09df4151ca35 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -129,6 +129,9 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da return BehaviorModuleOutput{}; }(); + std::for_each( + manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); }); + generateCombinedDrivableArea(result_output, data); return result_output; @@ -449,6 +452,16 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrlockOutputPath(); + }); + approved_module_ptrs_.back()->unlockOutputPath(); + /** * execute all approved modules. */ @@ -468,21 +481,22 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrisWaitingApproval(); }; const auto itr = std::find_if( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), waiting_approval_modules); + approved_module_ptrs_.rbegin(), approved_module_ptrs_.rend(), waiting_approval_modules); - if (itr != approved_module_ptrs_.end()) { - clearCandidateModules(); - candidate_module_ptrs_.push_back(*itr); + if (itr != approved_module_ptrs_.rend()) { + const auto is_last_module = std::distance(approved_module_ptrs_.rbegin(), itr) == 0; + if (is_last_module) { + clearCandidateModules(); + candidate_module_ptrs_.push_back(*itr); + + debug_info_.emplace_back(*itr, Action::MOVE, "Back To Waiting Approval"); + + approved_module_ptrs_.pop_back(); + } - std::for_each( - std::next(itr), approved_module_ptrs_.end(), [this](auto & m) { deleteExpiredModules(m); }); std::for_each( manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); }); - - debug_info_.emplace_back(*itr, Action::MOVE, "Back To Waiting Approval"); } - - approved_module_ptrs_.erase(itr, approved_module_ptrs_.end()); } /** diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 8523bed5d4c2d..3fb333036da26 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -480,18 +480,14 @@ void AvoidanceModule::fillEgoStatus( const auto can_yield_maneuver = canYieldManeuver(data); - const size_t ego_seg_idx = - planner_data_->findEgoSegmentIndex(helper_.getPreviousSplineShiftPath().path.points); - const auto offset = std::abs(motion_utils::calcLateralOffset( - helper_.getPreviousSplineShiftPath().path.points, getEgoPosition(), ego_seg_idx)); - - // don't output new candidate path if the offset between the ego and previous output path is - // larger than threshold. - // TODO(Satoshi OTA): remove this workaround - if (offset > parameters_->safety_check_ego_offset) { + /** + * If the output path is locked by outside of this module, don't update output path. + */ + if (isOutputPathLocked()) { data.safe_new_sl.clear(); data.candidate_path = helper_.getPreviousSplineShiftPath(); - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. canceling candidate path..."); + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 500, "this module is locked now. keep current path."); return; } @@ -2172,8 +2168,6 @@ BehaviorModuleOutput AvoidanceModule::plan() generateExtendedDrivableArea(output); setDrivableLanes(output.drivable_area_info.drivable_lanes); - // updateRegisteredRTCStatus(spline_shift_path.path); - return output; } @@ -2515,8 +2509,6 @@ void AvoidanceModule::initVariables() void AvoidanceModule::initRTCStatus() { - removeRTCStatus(); - clearWaitingApproval(); left_shift_array_.clear(); right_shift_array_.clear(); uuid_map_.at("left") = generateUUID(); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 48c75b5b114e1..a6db07f35327c 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -151,7 +151,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( get_parameter(node, ns + "safety_check_backward_distance"); p.safety_check_hysteresis_factor = get_parameter(node, ns + "safety_check_hysteresis_factor"); - p.safety_check_ego_offset = get_parameter(node, ns + "safety_check_ego_offset"); } // avoidance maneuver (lateral) From 31e10cd105116e4f18da567dd5315f189716bc4e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 16 Aug 2023 09:50:38 +0900 Subject: [PATCH 180/266] fix(start_planner): fix path when goal is out of current lanes (#4636) * fix(start_planner): fix path when goal is not preffered lanes Signed-off-by: kosuke55 * add calcEndArcLength Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/utils/start_planner/util.cpp Co-authored-by: Kyoichi Sugahara * Update planning/behavior_path_planner/src/utils/start_planner/util.cpp * Update planning/behavior_path_planner/src/utils/start_planner/util.cpp * Update planning/behavior_path_planner/src/utils/start_planner/util.cpp * fix build Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Kyoichi Sugahara --- .../utils/start_planner/util.hpp | 8 +++++++ .../geometric_parallel_parking.cpp | 14 +++++------- .../utils/start_planner/shift_pull_out.cpp | 13 +++++------ .../src/utils/start_planner/util.cpp | 22 +++++++++++++++++++ 4 files changed, 41 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp index 6c7c6804ba6bb..63e374e074a5a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp @@ -28,6 +28,7 @@ #include #include +#include #include namespace behavior_path_planner::start_planner_utils @@ -47,6 +48,13 @@ lanelet::ConstLanelets getPullOutLanes( const std::shared_ptr & planner_data, const double backward_length); Pose getBackedPose( const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance); +/** + * @brief calculate end arc length to generate reference path considering the goal position + * @return a pair of s_end and terminal_is_goal + */ +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose); } // namespace behavior_path_planner::start_planner_utils #endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp index 4f8c7ff9a94b4..a5ccfc9517771 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp @@ -15,6 +15,7 @@ #include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner/utils/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -272,13 +273,10 @@ bool GeometricParallelParking::planPullOut( // get road center line path from pull_out end to goal, and combine after the second arc path const double s_start = getArcCoordinates(road_lanes, *end_pose).length; - const double s_goal = getArcCoordinates(road_lanes, goal_pose).length; - const double road_lanes_length = std::accumulate( - road_lanes.begin(), road_lanes.end(), 0.0, [](const double sum, const auto & lane) { - return sum + lanelet::utils::getLaneletLength2d(lane); - }); - const bool goal_is_behind = s_goal < s_start; - const double s_end = goal_is_behind ? road_lanes_length : s_goal; + const auto path_end_info = start_planner_utils::calcEndArcLength( + s_start, planner_data_->parameters.forward_path_length, road_lanes, goal_pose); + const double s_end = path_end_info.first; + const bool path_terminal_is_goal = path_end_info.second; PathWithLaneId road_center_line_path = planner_data_->route_handler->getCenterLinePath(road_lanes, s_start, s_end, true); @@ -305,7 +303,7 @@ bool GeometricParallelParking::planPullOut( paths.back().points = motion_utils::removeOverlapPoints(paths.back().points); // if the end point is the goal, set the velocity to 0 - if (!goal_is_behind) { + if (path_terminal_is_goal) { paths.back().points.back().point.longitudinal_velocity_mps = 0.0; } diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index 54f19ff121b55..cbe06fa66c306 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -150,13 +150,10 @@ std::vector ShiftPullOut::calcPullOutPaths( // generate road lane reference path const auto arc_position_start = getArcCoordinates(road_lanes, start_pose); const double s_start = std::max(arc_position_start.length - backward_path_length, 0.0); - const auto arc_position_goal = getArcCoordinates(road_lanes, goal_pose); - - // if goal is behind start pose, use path with forward_path_length - const bool goal_is_behind = arc_position_goal.length < s_start; - const double s_forward_length = s_start + forward_path_length; - const double s_end = - goal_is_behind ? s_forward_length : std::min(arc_position_goal.length, s_forward_length); + const auto path_end_info = + start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const double s_end = path_end_info.first; + const bool path_terminal_is_goal = path_end_info.second; constexpr double RESAMPLE_INTERVAL = 1.0; PathWithLaneId road_lane_reference_path = utils::resamplePathWithSpline( @@ -276,7 +273,7 @@ std::vector ShiftPullOut::calcPullOutPaths( } } // if the end point is the goal, set the velocity to 0 - if (!goal_is_behind) { + if (path_terminal_is_goal) { shifted_path.path.points.back().point.longitudinal_velocity_mps = 0.0; } diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 8ef659b7df7b0..9ee0491ca017e 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -118,4 +118,26 @@ lanelet::ConstLanelets getPullOutLanes( /*forward_length*/ std::numeric_limits::max(), /*forward_only_in_route*/ true); } + +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose) +{ + const double s_forward_length = s_start + forward_path_length; + // use forward length if the goal pose is not in the lanelets + if (!utils::isInLanelets(goal_pose, road_lanes)) { + return {s_forward_length, false}; + } + + const double s_goal = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + + // If the goal is behind the start or beyond the forward length, use forward length. + if (s_goal < s_start || s_goal >= s_forward_length) { + return {s_forward_length, false}; + } + + // path end is goal + return {s_goal, true}; +} + } // namespace behavior_path_planner::start_planner_utils From 0b79f4d9a45abdb50631085a2097d131d446955f Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 16 Aug 2023 16:00:36 +0900 Subject: [PATCH 181/266] refactor(control_validator): changing the frequency of error (#4640) changing the frequency of error output Signed-off-by: kyoichi-sugahara --- control/control_validator/src/control_validator.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/control/control_validator/src/control_validator.cpp b/control/control_validator/src/control_validator.cpp index c301b26575d99..59b798a786722 100644 --- a/control/control_validator/src/control_validator.cpp +++ b/control/control_validator/src/control_validator.cpp @@ -194,10 +194,11 @@ bool ControlValidator::isAllValid(const ControlValidatorStatus & s) void ControlValidator::displayStatus() { if (!display_on_terminal_) return; + rclcpp::Clock clock{RCL_ROS_TIME}; - const auto warn = [this](const bool status, const std::string & msg) { + const auto warn = [this, &clock](const bool status, const std::string & msg) { if (!status) { - RCLCPP_WARN(get_logger(), "%s", msg.c_str()); + RCLCPP_WARN_THROTTLE(get_logger(), clock, 1000, "%s", msg.c_str()); } }; From 8c5c20b9ce3c4b8e23c2b81ad94725e3185aa1d8 Mon Sep 17 00:00:00 2001 From: ito-san <57388357+ito-san@users.noreply.github.com> Date: Wed, 16 Aug 2023 17:12:37 +0900 Subject: [PATCH 182/266] fix(system_monitor): extend command line to display (#4553) Signed-off-by: ito-san --- .../process_monitor/diag_task.hpp | 129 +++++------------- .../src/process_monitor/process_monitor.cpp | 26 ++-- 2 files changed, 45 insertions(+), 110 deletions(-) diff --git a/system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp b/system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp index 183f86baa2a08..15702852a0e50 100644 --- a/system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp +++ b/system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp @@ -24,6 +24,25 @@ #include +/** + * @brief Struct for storing process information + */ +struct ProcessInfo +{ + std::string processId; + std::string userName; + std::string priority; + std::string niceValue; + std::string virtualImage; + std::string residentSize; + std::string sharedMemSize; + std::string processStatus; + std::string cpuUsage; + std::string memoryUsage; + std::string cpuTime; + std::string commandName; +}; + class DiagTask : public diagnostic_updater::DiagnosticTask { public: @@ -46,18 +65,18 @@ class DiagTask : public diagnostic_updater::DiagnosticTask if (level_ != DiagStatus::OK) { stat.add("content", content_); } else { - stat.add("COMMAND", command_); - stat.add("%CPU", cpu_); - stat.add("%MEM", mem_); - stat.add("PID", pid_); - stat.add("USER", user_); - stat.add("PR", pr_); - stat.add("NI", ni_); - stat.add("VIRT", virt_); - stat.add("RES", res_); - stat.add("SHR", shr_); - stat.add("S", s_); - stat.add("TIME+", time_); + stat.add("COMMAND", info_.commandName); + stat.add("%CPU", info_.cpuUsage); + stat.add("%MEM", info_.memoryUsage); + stat.add("PID", info_.processId); + stat.add("USER", info_.userName); + stat.add("PR", info_.priority); + stat.add("NI", info_.niceValue); + stat.add("VIRT", info_.virtualImage); + stat.add("RES", info_.residentSize); + stat.add("SHR", info_.sharedMemSize); + stat.add("S", info_.processStatus); + stat.add("TIME+", info_.cpuTime); } stat.summary(level_, message_); } @@ -85,95 +104,17 @@ class DiagTask : public diagnostic_updater::DiagnosticTask } /** - * @brief set process id - * @param [in] pid process id - */ - void setProcessId(const std::string & pid) { pid_ = pid; } - - /** - * @brief set user name - * @param [in] user user name - */ - void setUserName(const std::string & user) { user_ = user; } - - /** - * @brief set priority - * @param [in] pr priority - */ - void setPriority(const std::string & pr) { pr_ = pr; } - - /** - * @brief set nice value - * @param [in] ni nice value - */ - void setNiceValue(const std::string & ni) { ni_ = ni; } - - /** - * @brief set virtual image - * @param [in] virt virtual image - */ - void setVirtualImage(const std::string & virt) { virt_ = virt; } - - /** - * @brief set resident size - * @param [in] res resident size + * @brief Set process information + * @param [in] info Process information */ - void setResidentSize(const std::string & res) { res_ = res; } - - /** - * @brief set shared mem size - * @param [in] shr shared mem size - */ - void setSharedMemSize(const std::string & shr) { shr_ = shr; } - - /** - * @brief set process status - * @param [in] s process status - */ - void setProcessStatus(const std::string & s) { s_ = s; } - - /** - * @brief set CPU usage - * @param [in] cpu CPU usage - */ - void setCPUUsage(const std::string & cpu) { cpu_ = cpu; } - - /** - * @brief set memory usage - * @param [in] mem memory usage - */ - void setMemoryUsage(const std::string & mem) { mem_ = mem; } - - /** - * @brief set CPU time - * @param [in] time CPU time - */ - void setCPUTime(const std::string & time) { time_ = time; } - - /** - * @brief set Command name/line - * @param [in] command Command name/line - */ - void setCommandName(const std::string & command) { command_ = command; } + void setProcessInformation(const struct ProcessInfo & info) { info_ = info; } private: int level_; //!< @brief Diagnostics error level std::string message_; //!< @brief Diagnostics status message std::string error_command_; //!< @brief Error command std::string content_; //!< @brief Error content - - std::string pid_; //!< @brief Process Id - std::string user_; //!< @brief User Name - std::string pr_; //!< @brief Priority - std::string ni_; //!< @brief Nice value - std::string virt_; //!< @brief Virtual Image (kb) - std::string res_; //!< @brief Resident size (kb) - std::string shr_; //!< @brief Shared Mem size (kb) - std::string s_; //!< @brief Process Status - std::string cpu_; //!< @brief CPU usage - std::string mem_; //!< @brief Memory usage - std::string time_; //!< @brief CPU Time - std::string command_; //!< @brief Command name/line + struct ProcessInfo info_; //!< @brief Struct for storing process information }; #endif // SYSTEM_MONITOR__PROCESS_MONITOR__DIAG_TASK_HPP_ diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/system_monitor/src/process_monitor/process_monitor.cpp index f78fc00c430dc..2ce1738ecd960 100644 --- a/system/system_monitor/src/process_monitor/process_monitor.cpp +++ b/system/system_monitor/src/process_monitor/process_monitor.cpp @@ -451,27 +451,21 @@ void ProcessMonitor::getTopratedProcesses( return; } - std::vector list; std::string line; int index = 0; while (std::getline(is_out, line) && !line.empty()) { - boost::trim_left(line); - boost::split(list, line, boost::is_space(), boost::token_compress_on); + std::istringstream stream(line); + + ProcessInfo info; + stream >> info.processId >> info.userName >> info.priority >> info.niceValue >> + info.virtualImage >> info.residentSize >> info.sharedMemSize >> info.processStatus >> + info.cpuUsage >> info.memoryUsage >> info.cpuTime; + + std::getline(stream, info.commandName); tasks->at(index)->setDiagnosticsStatus(DiagStatus::OK, "OK"); - tasks->at(index)->setProcessId(list[0]); - tasks->at(index)->setUserName(list[1]); - tasks->at(index)->setPriority(list[2]); - tasks->at(index)->setNiceValue(list[3]); - tasks->at(index)->setVirtualImage(list[4]); - tasks->at(index)->setResidentSize(list[5]); - tasks->at(index)->setSharedMemSize(list[6]); - tasks->at(index)->setProcessStatus(list[7]); - tasks->at(index)->setCPUUsage(list[8]); - tasks->at(index)->setMemoryUsage(list[9]); - tasks->at(index)->setCPUTime(list[10]); - tasks->at(index)->setCommandName(list[11]); + tasks->at(index)->setProcessInformation(info); ++index; } } @@ -521,7 +515,7 @@ void ProcessMonitor::onTimer() std::ostringstream os; // Get processes - bp::child c("top -bn1 -o %CPU -w 128", bp::std_out > is_out, bp::std_err > is_err); + bp::child c("top -bcn1 -o %CPU -w 256", bp::std_out > is_out, bp::std_err > is_err); c.wait(); if (c.exit_code() != 0) { From 6f85580dc65d1521e6f2d5afa84902b55f4f209d Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 17 Aug 2023 09:58:09 +0900 Subject: [PATCH 183/266] fix(traffic_light_arbiter): use the shape as a key to find the highest confidence signal (#4635) Signed-off-by: Tomohito Ando --- .../traffic_light_arbiter/src/traffic_light_arbiter.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp index 217430ee72d81..3baefaa43163a 100644 --- a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -147,14 +147,14 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim const auto get_highest_confidence_elements = [](const std::vector & elements_and_priority_vector) { - using Key = std::tuple; + using Key = Element::_shape_type; std::map highest_score_element_and_priority_map; std::vector highest_score_elements_vector; for (const auto & elements_and_priority : elements_and_priority_vector) { const auto & element = elements_and_priority.first; const auto & element_priority = elements_and_priority.second; - const auto key = std::make_tuple(element.color, element.shape); + const auto key = element.shape; auto [iter, success] = highest_score_element_and_priority_map.try_emplace(key, elements_and_priority); const auto & iter_element = iter->second.first; From ce01013faecf670f89e9d105483451bf1fb49084 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 17 Aug 2023 13:30:14 +0900 Subject: [PATCH 184/266] feat(avoidance): create detection area from latest generated path (#4525) * feat(avoidance): create detection area from latest generated path Signed-off-by: satoshi-ota * refactor(avoidance): remove unused marker utils Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 2 - .../marker_utils/avoidance/debug.hpp | 3 - .../marker_utils/utils.hpp | 2 +- .../utils/avoidance/avoidance_module_data.hpp | 35 +----- .../utils/avoidance/utils.hpp | 6 + .../src/marker_utils/avoidance/debug.cpp | 56 --------- .../src/marker_utils/utils.cpp | 4 +- .../avoidance/avoidance_module.cpp | 14 +-- .../src/scene_module/avoidance/manager.cpp | 4 - .../src/scene_module/lane_change/manager.cpp | 4 - .../src/utils/avoidance/utils.cpp | 107 ++++++++++++++++++ 11 files changed, 122 insertions(+), 115 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 60f587002f72c..e06393495fa1b 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -4,8 +4,6 @@ avoidance: resample_interval_for_planning: 0.3 # [m] resample_interval_for_output: 4.0 # [m] - detection_area_right_expand_dist: 0.0 # [m] - detection_area_left_expand_dist: 1.0 # [m] drivable_area_right_bound_offset: 0.0 # [m] drivable_area_left_bound_offset: 0.0 # [m] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp index 9e9ad5361fed8..ac24591a0a283 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp @@ -49,9 +49,6 @@ using visualization_msgs::msg::MarkerArray; MarkerArray createEgoStatusMarkerArray( const AvoidancePlanningData & data, const Pose & p_ego, std::string && ns); -MarkerArray createSafetyCheckMarkerArray( - const AvoidanceState & state, const Pose & pose, const DebugData & data); - MarkerArray createAvoidLineMarkerArray( const AvoidLineArray & shift_points, std::string && ns, const float & r, const float & g, const float & b, const double & w); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp index 6894edaece828..b3cb53ec18349 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp @@ -122,7 +122,7 @@ MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3 MarkerArray createPolygonMarkerArray( const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r, - const float & g, const float & b); + const float & g, const float & b, const float & w = 0.3); MarkerArray createObjectsMarkerArray( const PredictedObjects & objects, std::string && ns, const int64_t & lane_id, const float & r, diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index bb846d2aa70d0..ef956fb7950dd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -79,12 +79,6 @@ struct AvoidanceParameters // computational cost for latter modules. double resample_interval_for_output = 3.0; - // lanelet expand length for right side to find avoidance target vehicles - double detection_area_right_expand_dist = 0.0; - - // lanelet expand length for left side to find avoidance target vehicles - double detection_area_left_expand_dist = 1.0; - // enable avoidance to be perform only in lane with same direction bool use_adjacent_lane{true}; @@ -513,35 +507,15 @@ struct ShiftLineData std::vector> shift_line_history; }; -/* - * Data struct for longitudinal margin - */ -struct MarginData -{ - Pose pose{}; - - bool enough_lateral_margin{true}; - - double longitudinal_distance{std::numeric_limits::max()}; - - double longitudinal_margin{std::numeric_limits::lowest()}; - - double vehicle_width; - - double base_link2front; - - double base_link2rear; -}; -using MarginDataArray = std::vector; - /* * Debug information for marker array */ struct DebugData { - std::shared_ptr expanded_lanelets; std::shared_ptr current_lanelets; + geometry_msgs::msg::Polygon detection_area; + lanelet::ConstLineStrings3d bounds; AvoidLineArray current_shift_lines; // in path shifter @@ -576,14 +550,9 @@ struct DebugData // shift path std::vector proposed_spline_shift; - bool exist_adjacent_objects{false}; - // future pose PathWithLaneId path_with_planned_velocity; - // margin - MarginDataArray margin_data_array; - // avoidance require objects ObjectDataArray unavoidable_objects; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 8c229b4f26949..5f1ccbcc9aedf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include namespace behavior_path_planner::utils::avoidance @@ -160,6 +161,11 @@ ExtendedPredictedObject transform( std::vector getSafetyCheckTargetObjects( const AvoidancePlanningData & data, const std::shared_ptr & planner_data, const std::shared_ptr & parameters, const bool is_right_shift); + +std::pair separateObjectsByPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const AvoidancePlanningData & data, const std::shared_ptr & parameters, + DebugData & debug); } // namespace behavior_path_planner::utils::avoidance #endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp index 061cb10883f6c..94073ad467326 100644 --- a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp @@ -222,62 +222,6 @@ MarkerArray createEgoStatusMarkerArray( return msg; } -MarkerArray createSafetyCheckMarkerArray( - const AvoidanceState & state, const Pose & pose, const DebugData & data) -{ - const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - MarkerArray msg; - - if (data.exist_adjacent_objects) { - auto marker = createDefaultMarker( - "map", current_time, "safety_alert", 0L, Marker::CYLINDER, createMarkerScale(0.2, 0.2, 2.0), - createMarkerColor(1.0, 1.0, 0.0, 0.8)); - - marker.color = state == AvoidanceState::YIELD ? createMarkerColor(1.0, 0.0, 0.0, 0.8) - : createMarkerColor(1.0, 1.0, 0.0, 0.8); - - marker.pose = calcOffsetPose(pose, 0.0, 1.5, 1.0); - msg.markers.push_back(marker); - - marker.pose = calcOffsetPose(pose, 0.0, -1.5, 1.0); - marker.id++; - msg.markers.push_back(marker); - } - - if (state == AvoidanceState::YIELD) { - return msg; - } - - { - auto marker = createDefaultMarker( - "map", current_time, "safety_longitudinal_margin", 0L, Marker::CUBE, - createMarkerScale(3.0, 1.5, 1.5), createMarkerColor(1.0, 1.0, 1.0, 0.1)); - - for (const auto & m : data.margin_data_array) { - if (m.enough_lateral_margin) { - continue; - } - - constexpr double max_x = 10.0; - - const auto offset = 0.5 * (m.base_link2front + m.base_link2rear) - m.base_link2rear; - const auto diff = m.longitudinal_distance - m.longitudinal_margin; - const auto scale_x = std::min(max_x, 2.0 * (m.base_link2front + m.base_link2rear + diff)); - - const auto ratio = std::clamp(diff / max_x, 0.0, 1.0); - - marker.pose = calcOffsetPose(m.pose, offset, 0.0, 0.0); - marker.pose.position.z += 1.0; - marker.scale = createMarkerScale(scale_x, 2.0 * m.vehicle_width, 2.0); - marker.color = createMarkerColor(1.0 - ratio, ratio, 0.0, 0.1); - marker.id++; - msg.markers.push_back(marker); - } - } - - return msg; -} - MarkerArray createAvoidLineMarkerArray( const AvoidLineArray & shift_lines, std::string && ns, const float & r, const float & g, const float & b, const double & w) diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 80fea95b03caa..d8c87b6d1b291 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -314,11 +314,11 @@ MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3 MarkerArray createPolygonMarkerArray( const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r, - const float & g, const float & b) + const float & g, const float & b, const float & w) { Marker marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, static_cast(lane_id), Marker::LINE_STRIP, - createMarkerScale(0.3, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); + createMarkerScale(w, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 3fb333036da26..10a6307b263b4 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -266,12 +266,9 @@ void AvoidanceModule::fillAvoidanceTargetObjects( using utils::avoidance::getTargetLanelets; // Separate dynamic objects based on whether they are inside or outside of the expanded lanelets. - const auto expanded_lanelets = getTargetLanelets( - planner_data_, data.current_lanelets, parameters_->detection_area_left_expand_dist, - parameters_->detection_area_right_expand_dist * (-1.0)); - const auto [object_within_target_lane, object_outside_target_lane] = - utils::separateObjectsByLanelets(*planner_data_->dynamic_object, expanded_lanelets); + utils::avoidance::separateObjectsByPath( + helper_.getPreviousSplineShiftPath().path, planner_data_, data, parameters_, debug); for (const auto & object : object_outside_target_lane.objects) { ObjectData other_object; @@ -298,7 +295,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects( // debug { debug.current_lanelets = std::make_shared(data.current_lanelets); - debug.expanded_lanelets = std::make_shared(expanded_lanelets); std::vector debug_info_array; const auto append = [&](const auto & o) { @@ -2654,6 +2650,7 @@ void AvoidanceModule::updateDebugMarker( using marker_utils::createLaneletsAreaMarkerArray; using marker_utils::createObjectsMarkerArray; using marker_utils::createPathMarkerArray; + using marker_utils::createPolygonMarkerArray; using marker_utils::createPoseMarkerArray; using marker_utils::createShiftGradMarkerArray; using marker_utils::createShiftLengthMarkerArray; @@ -2663,7 +2660,6 @@ void AvoidanceModule::updateDebugMarker( using marker_utils::avoidance_marker::createOtherObjectsMarkerArray; using marker_utils::avoidance_marker::createOverhangFurthestLineStringMarkerArray; using marker_utils::avoidance_marker::createPredictedVehiclePositions; - using marker_utils::avoidance_marker::createSafetyCheckMarkerArray; using marker_utils::avoidance_marker::createUnsafeObjectsMarkerArray; using marker_utils::avoidance_marker::makeOverhangToRoadShoulderMarkerArray; using tier4_autoware_utils::appendMarkerArray; @@ -2699,10 +2695,8 @@ void AvoidanceModule::updateDebugMarker( helper_.getPreviousLinearShiftPath().path, "prev_linear_shift", 0, 0.5, 0.4, 0.6)); add(createPoseMarkerArray(data.reference_pose, "reference_pose", 0, 0.9, 0.3, 0.3)); - add(createSafetyCheckMarkerArray(data.state, getEgoPose(), debug)); - add(createLaneletsAreaMarkerArray(*debug.current_lanelets, "current_lanelet", 0.0, 1.0, 0.0)); - add(createLaneletsAreaMarkerArray(*debug.expanded_lanelets, "expanded_lanelet", 0.8, 0.8, 0.0)); + add(createPolygonMarkerArray(debug.detection_area, "detection_area", 0L, 0.16, 1.0, 0.69, 0.1)); add(createOtherObjectsMarkerArray( data.other_objects, AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD)); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index a6db07f35327c..606869eb4007f 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -50,10 +50,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( get_parameter(node, ns + "resample_interval_for_planning"); p.resample_interval_for_output = get_parameter(node, ns + "resample_interval_for_output"); - p.detection_area_right_expand_dist = - get_parameter(node, ns + "detection_area_right_expand_dist"); - p.detection_area_left_expand_dist = - get_parameter(node, ns + "detection_area_left_expand_dist"); p.enable_bound_clipping = get_parameter(node, ns + "enable_bound_clipping"); p.enable_cancel_maneuver = get_parameter(node, ns + "enable_cancel_maneuver"); p.enable_force_avoidance_for_stopped_vehicle = diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 0f770efb542c7..5dc2a1ee9837c 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -193,10 +193,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( get_parameter(node, ns + "resample_interval_for_planning"); p.resample_interval_for_output = get_parameter(node, ns + "resample_interval_for_output"); - p.detection_area_right_expand_dist = - get_parameter(node, ns + "detection_area_right_expand_dist"); - p.detection_area_left_expand_dist = - get_parameter(node, ns + "detection_area_left_expand_dist"); p.enable_force_avoidance_for_stopped_vehicle = get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); } diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 7dca1219945c6..3f47b97aa0adf 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -142,6 +142,59 @@ double calcSignedArcLengthToFirstNearestPoint( return signed_length_on_traj - signed_length_src_offset + signed_length_dst_offset; } + +geometry_msgs::msg::Polygon createVehiclePolygon( + const vehicle_info_util::VehicleInfo & vehicle_info, const double offset) +{ + const auto & i = vehicle_info; + const auto & front_m = i.max_longitudinal_offset_m; + const auto & width_m = i.vehicle_width_m / 2.0 + offset; + const auto & back_m = i.rear_overhang_m; + + geometry_msgs::msg::Polygon polygon{}; + + polygon.points.push_back(createPoint32(front_m, -width_m, 0.0)); + polygon.points.push_back(createPoint32(front_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-back_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-back_m, -width_m, 0.0)); + + return polygon; +} + +Polygon2d createOneStepPolygon( + const geometry_msgs::msg::Pose & p_front, const geometry_msgs::msg::Pose & p_back, + const geometry_msgs::msg::Polygon & base_polygon) +{ + Polygon2d one_step_polygon{}; + + { + geometry_msgs::msg::Polygon out_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(p_front); + tf2::doTransform(base_polygon, out_polygon, geometry_tf); + + for (const auto & p : out_polygon.points) { + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); + } + } + + { + geometry_msgs::msg::Polygon out_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(p_back); + tf2::doTransform(base_polygon, out_polygon, geometry_tf); + + for (const auto & p : out_polygon.points) { + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); + } + } + + Polygon2d hull_polygon{}; + boost::geometry::convex_hull(one_step_polygon, hull_polygon); + boost::geometry::correct(hull_polygon); + + return hull_polygon; +} } // namespace bool isOnRight(const ObjectData & obj) @@ -1557,4 +1610,58 @@ std::vector getSafetyCheckTargetObjects( return target_objects; } + +std::pair separateObjectsByPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const AvoidancePlanningData & data, const std::shared_ptr & parameters, + DebugData & debug) +{ + PredictedObjects target_objects; + PredictedObjects other_objects; + + double max_offset = 0.0; + for (const auto & object_parameter : parameters->object_parameters) { + const auto p = object_parameter.second; + const auto offset = p.envelope_buffer_margin + p.safety_buffer_lateral + p.avoid_margin_lateral; + max_offset = std::max(max_offset, offset); + } + + const auto detection_area = + createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset); + const auto ego_idx = planner_data->findEgoIndex(path.points); + + Polygon2d attention_area; + for (size_t i = 0; i < path.points.size() - 1; ++i) { + const auto & p_ego_front = path.points.at(i).point.pose; + const auto & p_ego_back = path.points.at(i + 1).point.pose; + + const auto distance_from_ego = calcSignedArcLength(path.points, ego_idx, i); + if (distance_from_ego > parameters->object_check_forward_distance) { + break; + } + + const auto ego_one_step_polygon = createOneStepPolygon(p_ego_front, p_ego_back, detection_area); + + std::vector unions; + boost::geometry::union_(attention_area, ego_one_step_polygon, unions); + if (!unions.empty()) { + attention_area = unions.front(); + boost::geometry::correct(attention_area); + } + } + + debug.detection_area = toMsg(attention_area, data.reference_pose.position.z); + + const auto objects = planner_data->dynamic_object->objects; + std::for_each(objects.begin(), objects.end(), [&](const auto & object) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); + if (boost::geometry::disjoint(obj_polygon, attention_area)) { + other_objects.objects.push_back(object); + } else { + target_objects.objects.push_back(object); + } + }); + + return std::make_pair(target_objects, other_objects); +} } // namespace behavior_path_planner::utils::avoidance From 49f9d9db375a3ca1c33d0ee40cd60897e23f3912 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 17 Aug 2023 13:32:52 +0900 Subject: [PATCH 185/266] fix(avoidance): fix trimmed shift line alignment (#4632) * fix(avoidance): fix trimmed shift line alignment Signed-off-by: satoshi-ota * fix(avoidance): fill shift line gap Signed-off-by: satoshi-ota * fixup! fix(avoidance): fix trimmed shift line alignment --------- Signed-off-by: satoshi-ota --- .../avoidance/avoidance_module.hpp | 2 + .../avoidance/avoidance_module.cpp | 61 ++++++++++++++++--- 2 files changed, 55 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 55ecee17b9778..436fbed76cf5e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -329,6 +329,8 @@ class AvoidanceModule : public SceneModuleInterface AvoidLineArray applyPreProcessToRawShiftLines( AvoidLineArray & current_raw_shift_points, DebugData & debug) const; + AvoidLineArray getFillGapShiftLines(const AvoidLineArray & shift_lines) const; + /* * @brief merge negative & positive shift lines. * @param original shift lines. diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 10a6307b263b4..88bc583345966 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -700,6 +700,8 @@ void AvoidanceModule::updateRegisteredRawShiftLines() AvoidLineArray AvoidanceModule::applyPreProcessToRawShiftLines( AvoidLineArray & raw_shift_lines, DebugData & debug) const { + const auto fill_gap_shift_lines = getFillGapShiftLines(raw_shift_lines); + /** * Use all registered points. For the current points, if the similar one of the current * points are already registered, will not use it. @@ -729,6 +731,8 @@ AvoidLineArray AvoidanceModule::applyPreProcessToRawShiftLines( * Add gap filled shift lines so that merged shift lines connect smoothly. */ fillShiftLineGap(raw_shift_lines); + raw_shift_lines.insert( + raw_shift_lines.end(), fill_gap_shift_lines.begin(), fill_gap_shift_lines.end()); debug.gap_filled = raw_shift_lines; /** @@ -974,10 +978,6 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( al_avoid.end_longitudinal = o.longitudinal - offset; al_avoid.id = getOriginalShiftLineUniqueId(); al_avoid.object = o; - - if (is_valid_shift_line(al_avoid)) { - avoid_lines.push_back(al_avoid); - } } AvoidLine al_return; @@ -997,10 +997,11 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( o.longitudinal + offset + std::min(feasible_return_distance, return_remaining_distance); al_return.id = getOriginalShiftLineUniqueId(); al_return.object = o; + } - if (is_valid_shift_line(al_return)) { - avoid_lines.push_back(al_return); - } + if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { + avoid_lines.push_back(al_avoid); + avoid_lines.push_back(al_return); } o.is_avoidable = true; @@ -1216,6 +1217,38 @@ AvoidLineArray AvoidanceModule::extractShiftLinesFromLine(ShiftLineData & shift_ return merged_avoid_lines; } +AvoidLineArray AvoidanceModule::getFillGapShiftLines(const AvoidLineArray & shift_lines) const +{ + AvoidLineArray ret{}; + + if (shift_lines.empty()) { + return ret; + } + + const auto calc_gap_shift_line = [&](const auto & line1, const auto & line2) { + AvoidLine gap_filled_line{}; + gap_filled_line.start_shift_length = line1.end_shift_length; + gap_filled_line.start_longitudinal = line1.end_longitudinal; + gap_filled_line.end_shift_length = line2.start_shift_length; + gap_filled_line.end_longitudinal = line2.start_longitudinal; + gap_filled_line.id = getOriginalShiftLineUniqueId(); + + return gap_filled_line; + }; + + // fill gap among shift lines. + for (size_t i = 0; i < shift_lines.size() - 1; i += 2) { + if (shift_lines.at(i).end_longitudinal > shift_lines.at(i + 1).start_longitudinal) { + continue; + } + ret.push_back(calc_gap_shift_line(shift_lines.at(i), shift_lines.at(i + 1))); + } + + utils::avoidance::fillAdditionalInfoFromLongitudinal(avoidance_data_, ret); + + return ret; +} + void AvoidanceModule::fillShiftLineGap(AvoidLineArray & shift_lines) const { using utils::avoidance::setEndData; @@ -2343,12 +2376,16 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat std::abs(candidates.at(i).getRelativeLength()) > parameters_->lateral_small_shift_threshold) { if (has_large_shift) { - break; + return; } has_large_shift = true; } + if (!isComfortable(AvoidLineArray{candidates.at(i)})) { + return; + } + subsequent.push_back(candidates.at(i)); } }; @@ -2357,10 +2394,18 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat const auto get_subsequent_shift = [&, this](size_t i) { AvoidLineArray subsequent{candidates.at(i)}; + if (!isComfortable(subsequent)) { + return subsequent; + } + if (candidates.size() == i + 1) { return subsequent; } + if (!isComfortable(AvoidLineArray{candidates.at(i + 1)})) { + return subsequent; + } + if ( std::abs(candidates.at(i).getRelativeLength()) < parameters_->lateral_small_shift_threshold) { const auto has_large_shift = From e1a86f941aa9dd8d07c56e517c987d5911cfa07c Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 17 Aug 2023 14:08:56 +0900 Subject: [PATCH 186/266] refactor(behavior_path_planner): create path_safety_checker directory (#4644) * create safety_check directory Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * rename directory name safety_check to path_safety_checker Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * change directory name Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/behavior_path_planner/CMakeLists.txt | 2 +- .../docs/behavior_path_planner_safety_check.md | 6 +++--- .../extended_polygons.drawio.svg | 0 .../front_object.drawio.svg | 0 .../safety_check_flow.drawio.svg | 0 .../scene_module/avoidance/avoidance_module.hpp | 2 +- .../include/behavior_path_planner/utils/avoidance/utils.hpp | 2 +- .../utils/lane_change/lane_change_module_data.hpp | 2 +- .../behavior_path_planner/utils/lane_change/utils.hpp | 2 +- .../utils/{ => path_safety_checker}/safety_check.hpp | 6 +++--- .../include/behavior_path_planner/utils/utils.hpp | 2 +- .../behavior_path_planner/src/utils/lane_change/utils.cpp | 2 +- .../src/utils/{ => path_safety_checker}/safety_check.cpp | 2 +- .../behavior_path_planner/test/test_lane_change_utils.cpp | 2 +- planning/behavior_path_planner/test/test_safety_check.cpp | 2 +- 15 files changed, 16 insertions(+), 16 deletions(-) rename planning/behavior_path_planner/image/{safety_check => path_safety_checker}/extended_polygons.drawio.svg (100%) rename planning/behavior_path_planner/image/{safety_check => path_safety_checker}/front_object.drawio.svg (100%) rename planning/behavior_path_planner/image/{safety_check => path_safety_checker}/safety_check_flow.drawio.svg (100%) rename planning/behavior_path_planner/include/behavior_path_planner/utils/{ => path_safety_checker}/safety_check.hpp (95%) rename planning/behavior_path_planner/src/utils/{ => path_safety_checker}/safety_check.cpp (99%) diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 8bb4947c56e3b..162dd855a577a 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -30,7 +30,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/turn_signal_decider.cpp src/utils/utils.cpp src/utils/path_utils.cpp - src/utils/safety_check.cpp + src/utils/path_safety_checker/safety_check.cpp src/utils/avoidance/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md b/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md index 2d8ec7a6b2de3..30e2093cb465e 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md @@ -22,7 +22,7 @@ Currently the yaw angle of each point of predicted paths of a target object does The flow of the safety check algorithm is described in the following explanations. -![safety_check_flow](../image/safety_check/safety_check_flow.drawio.svg) +![safety_check_flow](../image/path_safety_checker/safety_check_flow.drawio.svg) Here we explain each step of the algorithm flow. @@ -38,7 +38,7 @@ With the interpolated pose obtained in the step.1, we check if the object and eg After the overlap check, it starts to perform the safety check for the broader range. In this step, it judges if ego or target object is in front of the other vehicle. We use arc length of the front point of each object along the given path to judge which one is in front of the other. In the following example, target object (red rectangle) is running in front of the ego vehicle (black rectangle). -![front_object](../image/safety_check/front_object.drawio.svg) +![front_object](../image/path_safety_checker/front_object.drawio.svg) #### 4. Calculate RSS distance @@ -54,7 +54,7 @@ where $V_{front}$, $v_{rear}$ are front and rear vehicle velocity respectively a In this step, we compute extended ego and target object polygons. The extended polygons can be described as: -![extended_polygons](../image/safety_check/extended_polygons.drawio.svg) +![extended_polygons](../image/path_safety_checker/extended_polygons.drawio.svg) As the picture shows, we expand the rear object polygon. For the longitudinal side, we extend it with the RSS distance, and for the lateral side, we extend it by the lateral margin diff --git a/planning/behavior_path_planner/image/safety_check/extended_polygons.drawio.svg b/planning/behavior_path_planner/image/path_safety_checker/extended_polygons.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/safety_check/extended_polygons.drawio.svg rename to planning/behavior_path_planner/image/path_safety_checker/extended_polygons.drawio.svg diff --git a/planning/behavior_path_planner/image/safety_check/front_object.drawio.svg b/planning/behavior_path_planner/image/path_safety_checker/front_object.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/safety_check/front_object.drawio.svg rename to planning/behavior_path_planner/image/path_safety_checker/front_object.drawio.svg diff --git a/planning/behavior_path_planner/image/safety_check/safety_check_flow.drawio.svg b/planning/behavior_path_planner/image/path_safety_checker/safety_check_flow.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/safety_check/safety_check_flow.drawio.svg rename to planning/behavior_path_planner/image/path_safety_checker/safety_check_flow.drawio.svg diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 436fbed76cf5e..b2ed205680b45 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -19,7 +19,7 @@ #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner/utils/avoidance/helper.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 5f1ccbcc9aedf..27128e92ab971 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -17,7 +17,7 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 88ddeba83b8c8..7a3e96aa3fa3d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -15,7 +15,7 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "lanelet2_core/geometry/Lanelet.h" #include "autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index 266c52918c567..5fa22a8935bf2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -19,7 +19,7 @@ #include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/utils.hpp" #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp rename to planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index d2671ff32a787..55bac83442e84 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__SAFETY_CHECK_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__SAFETY_CHECK_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" @@ -147,4 +147,4 @@ bool checkCollision( } // namespace behavior_path_planner::utils::safety_check -#endif // BEHAVIOR_PATH_PLANNER__UTILS__SAFETY_CHECK_HPP_ +#endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index e56360922b56c..088a0f0bd795b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -19,7 +19,7 @@ #include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_following/module_data.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include "motion_utils/motion_utils.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index c22c07c0e80c5..0e68862f12a5a 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -17,9 +17,9 @@ #include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" #include "behavior_path_planner/utils/utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/safety_check.cpp rename to planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 01d10b2aeec1e..23c2951d30a38 100644 --- a/planning/behavior_path_planner/src/utils/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" #include "interpolation/linear_interpolation.hpp" diff --git a/planning/behavior_path_planner/test/test_lane_change_utils.cpp b/planning/behavior_path_planner/test/test_lane_change_utils.cpp index 21538de073d35..3a809509641f4 100644 --- a/planning/behavior_path_planner/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_planner/test/test_lane_change_utils.cpp @@ -11,7 +11,7 @@ // 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 "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" #include diff --git a/planning/behavior_path_planner/test/test_safety_check.cpp b/planning/behavior_path_planner/test/test_safety_check.cpp index 47c619c310f4d..4058956ceff3f 100644 --- a/planning/behavior_path_planner/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/test/test_safety_check.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "behavior_path_planner/marker_utils/utils.hpp" -#include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" #include From 2da561f4959fc3185c0525ad76c05aa7f4605e1a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 17 Aug 2023 17:10:55 +0900 Subject: [PATCH 187/266] feat(intersection): consider object velocity direction (#4651) * feat(intersection): consider object velocity direction Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/scene_intersection.cpp | 11 ++++++++--- .../src/util.cpp | 6 ++++-- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index dcfa3b0fce71f..6bfe1c83d370a 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -800,8 +800,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); const bool is_over_default_stop_line = util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); - const double vel = std::fabs(planner_data_->current_velocity->twist.linear.x); - const bool keep_detection = (vel < planner_param_.collision_detection.keep_detection_vel_thr); + const double vel_norm = std::hypot( + planner_data_->current_velocity->twist.linear.x, + planner_data_->current_velocity->twist.linear.y); + const bool keep_detection = + (vel_norm < planner_param_.collision_detection.keep_detection_vel_thr); // if ego is over the pass judge line and not stopped if (is_peeking_) { // do nothing @@ -871,7 +874,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( target_objects.objects.begin(), target_objects.objects.end(), std::back_inserter(parked_attention_objects), [thresh = planner_param_.occlusion.ignore_parked_vehicle_speed_threshold](const auto & object) { - return std::fabs(object.kinematics.initial_twist_with_covariance.twist.linear.x) <= thresh; + return std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y) <= thresh; }); const bool is_occlusion_cleared = (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !tl_arrow_solid_on) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 178df99ba7b02..f0343891c6051 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -923,8 +923,10 @@ bool checkStuckVehicleInIntersection( if (!isTargetStuckVehicleType(object)) { continue; // not target vehicle type } - const auto obj_v = std::fabs(object.kinematics.initial_twist_with_covariance.twist.linear.x); - if (obj_v > stuck_vehicle_vel_thr) { + const auto obj_v_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + if (obj_v_norm > stuck_vehicle_vel_thr) { continue; // not stop vehicle } From 420af00840a577b45283f53e2d3ee2fce9b3b052 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 17 Aug 2023 17:11:33 +0900 Subject: [PATCH 188/266] feat(occlusion spot): consider object velocity direction (#4650) Signed-off-by: Takayuki Murooka --- .../src/occlusion_spot_utils.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index 0a172c7f5544b..21a8cce93a1be 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -186,15 +186,19 @@ bool isVehicle(const PredictedObject & obj) bool isStuckVehicle(const PredictedObject & obj, const double min_vel) { if (!isVehicle(obj)) return false; - const auto & obj_vel = obj.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::abs(obj_vel) <= min_vel; + const auto & obj_vel_norm = std::hypot( + obj.kinematics.initial_twist_with_covariance.twist.linear.x, + obj.kinematics.initial_twist_with_covariance.twist.linear.y); + return obj_vel_norm <= min_vel; } bool isMovingVehicle(const PredictedObject & obj, const double min_vel) { if (!isVehicle(obj)) return false; - const auto & obj_vel = obj.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::abs(obj_vel) > min_vel; + const auto & obj_vel_norm = std::hypot( + obj.kinematics.initial_twist_with_covariance.twist.linear.x, + obj.kinematics.initial_twist_with_covariance.twist.linear.y); + return obj_vel_norm > min_vel; } std::vector extractVehicles( From 4d66811c1745c4bdba4e7bb0d0cd9c98b0962f11 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 17 Aug 2023 17:12:01 +0900 Subject: [PATCH 189/266] feat(obstacle_velocity_limiter): consider object velocity direction (#4649) * feat(obstacle_velocity_limiter): consider object velocity direction Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/obstacle_velocity_limiter/src/obstacles.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_velocity_limiter/src/obstacles.cpp b/planning/obstacle_velocity_limiter/src/obstacles.cpp index 417ff6b7783e2..7f6d1cc965319 100644 --- a/planning/obstacle_velocity_limiter/src/obstacles.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacles.cpp @@ -64,9 +64,10 @@ multipolygon_t createObjectPolygons( { multipolygon_t polygons; for (const auto & object : objects.objects) { - if ( - object.kinematics.initial_twist_with_covariance.twist.linear.x >= min_velocity || - object.kinematics.initial_twist_with_covariance.twist.linear.x <= -min_velocity) { + const double obj_vel_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + if (min_velocity <= obj_vel_norm) { polygons.push_back(createObjectPolygon( object.kinematics.initial_pose_with_covariance.pose, object.shape.dimensions, buffer)); } From b5f83d04ed0420a6780017a631f68b51a5c2aa10 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 17 Aug 2023 17:15:08 +0900 Subject: [PATCH 190/266] feat(obstacle_cruise_planner): consider object velocity direction (#4647) * feat(obstacle_cruise_planner): consider object velocity direction Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * chore: spell fix --------- Signed-off-by: Takayuki Murooka Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- planning/obstacle_cruise_planner/src/node.cpp | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index ab2092a3120ca..70c0c687b2514 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -100,12 +100,13 @@ std::pair projectObstacleVelocityToTrajectory( { const size_t object_idx = motion_utils::findNearestIndex(traj_points, obstacle.pose.position); - const double object_yaw = tf2::getYaw(obstacle.pose.orientation); + const double object_vel_norm = std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y); + const double object_vel_yaw = std::atan2(obstacle.twist.linear.y, obstacle.twist.linear.x); const double traj_yaw = tf2::getYaw(traj_points.at(object_idx).pose.orientation); return std::make_pair( - obstacle.twist.linear.x * std::cos(object_yaw - traj_yaw), - obstacle.twist.linear.x * std::sin(object_yaw - traj_yaw)); + object_vel_norm * std::cos(object_vel_yaw - traj_yaw), + object_vel_norm * std::sin(object_vel_yaw - traj_yaw)); } double calcObstacleMaxLength(const Shape & shape) @@ -818,7 +819,9 @@ ObstacleCruisePlannerNode::createCollisionPointsForOutsideCruiseObstacle( return std::nullopt; } - if (std::abs(obstacle.twist.linear.x) < p.outside_obstacle_min_velocity_threshold) { + if ( + std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y) < + p.outside_obstacle_min_velocity_threshold) { RCLCPP_INFO_EXPRESSION( get_logger(), enable_debug_info_, "[Cruise] Ignore outside obstacle (%s) since the obstacle velocity is low.", @@ -919,8 +922,8 @@ ObstacleCruisePlannerNode::createCollisionPointForStopObstacle( // NOTE: Dynamic obstacles for stop are crossing ego's trajectory with high speed, // and the collision between ego and obstacles are within the margin threshold. const bool is_obstacle_crossing = isObstacleCrossing(traj_points, obstacle); - const double has_high_speed = - p.crossing_obstacle_velocity_threshold < std::abs(obstacle.twist.linear.x); + const double has_high_speed = p.crossing_obstacle_velocity_threshold < + std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y); if (is_obstacle_crossing && has_high_speed) { // Get highest confidence predicted path const auto resampled_predicted_path = resampleHighestConfidencePredictedPath( @@ -995,7 +998,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl } return true; } - // check if entrying slow down + // check if entering slow down if (is_lat_dist_low) { const int count = slow_down_condition_counter_.increaseCounter(obstacle.uuid); if (p.successive_num_to_entry_slow_down_condition <= count) { @@ -1016,7 +1019,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl const auto obstacle_poly = obstacle.toPolygon(); // calculate collision points with trajectory with lateral stop margin - // NOTE: For additional margin, hysteresis is not devided by two. + // NOTE: For additional margin, hysteresis is not divided by two. const auto traj_polys_with_lat_margin = polygon_utils::createOneStepPolygons( traj_points, vehicle_info_, p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down); From e9dfe5cf3740c81a4d2848eecd25494b300e9ac7 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Thu, 17 Aug 2023 12:24:57 +0300 Subject: [PATCH 191/266] feat(pid_longitudinal_controller): take into account the current acceleration to calculate delayed pose (#4616) * feat(pid_longitudinal_controller): take into account the current acceleration to calculate delayed pose Signed-off-by: Berkay Karaman * Update for reverse driving Signed-off-by: Berkay Karaman * update for wrong calculation Signed-off-by: Berkay Karaman * update Signed-off-by: Berkay Karaman --------- Signed-off-by: Berkay Karaman --- .../longitudinal_controller_utils.hpp | 7 +- .../src/longitudinal_controller_utils.cpp | 16 +++- .../src/pid_longitudinal_controller.cpp | 2 +- .../test_longitudinal_controller_utils.cpp | 78 +++++++++++++++---- 4 files changed, 82 insertions(+), 21 deletions(-) diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp index 5584e1e79e971..8685d6264993b 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp +++ b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp @@ -72,11 +72,12 @@ double getPitchByTraj( double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint & p_to); /** - * @brief calculate vehicle pose after time delay by moving the vehicle at current velocity for - * delayed time + * @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and + * acceleration for delayed time */ Pose calcPoseAfterTimeDelay( - const Pose & current_pose, const double delay_time, const double current_vel); + const Pose & current_pose, const double delay_time, const double current_vel, + const double current_acc); /** * @brief apply linear interpolation to orientation diff --git a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 8cbf02b90ce51..70cdbcaf17bd2 100644 --- a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -129,11 +129,23 @@ double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint } Pose calcPoseAfterTimeDelay( - const Pose & current_pose, const double delay_time, const double current_vel) + const Pose & current_pose, const double delay_time, const double current_vel, + const double current_acc) { + if (delay_time <= 0.0) { + return current_pose; + } + + // check time to stop + const double time_to_stop = -current_vel / current_acc; + + const double delay_time_calculation = + time_to_stop > 0.0 && time_to_stop < delay_time ? time_to_stop : delay_time; // simple linear prediction const double yaw = tf2::getYaw(current_pose.orientation); - const double running_distance = delay_time * current_vel; + const double running_distance = delay_time_calculation * current_vel + 0.5 * current_acc * + delay_time_calculation * + delay_time_calculation; const double dx = running_distance * std::cos(yaw); const double dy = running_distance * std::sin(yaw); diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 23c4bcc857cd4..337a63bc7dc76 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -626,7 +626,7 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd( Motion target_motion{}; if (m_control_state == ControlState::DRIVE) { const auto target_pose = longitudinal_utils::calcPoseAfterTimeDelay( - current_pose, m_delay_compensation_time, current_vel); + current_pose, m_delay_compensation_time, current_vel, current_acc); const auto target_interpolated_point = calcInterpolatedTargetValue(m_trajectory, target_pose); target_motion = Motion{ target_interpolated_point.longitudinal_velocity_mps, diff --git a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp b/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp index ef38533376446..d9fc404ce6abe 100644 --- a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp +++ b/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp @@ -197,25 +197,30 @@ TEST(TestLongitudinalControllerUtils, calcPoseAfterTimeDelay) quaternion_tf.setRPY(0.0, 0.0, 0.0); current_pose.orientation = tf2::toMsg(quaternion_tf); - // With a delay and/or a velocity of 0.0 there is no change of position + // With a delay acceleration and/or a velocity of 0.0 there is no change of position double delay_time = 0.0; double current_vel = 0.0; + double current_acc = 0.0; Pose delayed_pose = - longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x, abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); delay_time = 1.0; current_vel = 0.0; - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + current_acc = 0.0; + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x, abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); delay_time = 0.0; current_vel = 1.0; - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + current_acc = 0.0; + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x, abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); @@ -223,46 +228,89 @@ TEST(TestLongitudinalControllerUtils, calcPoseAfterTimeDelay) // With both delay and velocity: change of position delay_time = 1.0; current_vel = 1.0; - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + current_acc = 0.0; + + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x + current_vel * delay_time, abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); + // With all, acceleration, delay and velocity: change of position + delay_time = 1.0; + current_vel = 1.0; + current_acc = 1.0; + + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); + EXPECT_NEAR( + delayed_pose.position.x, + current_pose.position.x + current_vel * delay_time + + 0.5 * current_acc * delay_time * delay_time, + abs_err); + EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); + EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); + // Vary the yaw quaternion_tf.setRPY(0.0, 0.0, M_PI); current_pose.orientation = tf2::toMsg(quaternion_tf); - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); - EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x - current_vel * delay_time, abs_err); + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); + EXPECT_NEAR( + delayed_pose.position.x, + current_pose.position.x - current_vel * delay_time - + 0.5 * current_acc * delay_time * delay_time, + abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); quaternion_tf.setRPY(0.0, 0.0, M_PI_2); current_pose.orientation = tf2::toMsg(quaternion_tf); - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x, abs_err); - EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y + current_vel * delay_time, abs_err); + EXPECT_NEAR( + delayed_pose.position.y, + current_pose.position.y + current_vel * delay_time + + 0.5 * current_acc * delay_time * delay_time, + abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); quaternion_tf.setRPY(0.0, 0.0, -M_PI_2); current_pose.orientation = tf2::toMsg(quaternion_tf); - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x, abs_err); - EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y - current_vel * delay_time, abs_err); + EXPECT_NEAR( + delayed_pose.position.y, + current_pose.position.y - current_vel * delay_time - + 0.5 * current_acc * delay_time * delay_time, + abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); // Vary the pitch : no effect /!\ NOTE: bug with roll of +-PI/2 which rotates the yaw by PI quaternion_tf.setRPY(0.0, M_PI_4, 0.0); current_pose.orientation = tf2::toMsg(quaternion_tf); - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); - EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x + current_vel * delay_time, abs_err); + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); + EXPECT_NEAR( + delayed_pose.position.x, + current_pose.position.x + current_vel * delay_time + + 0.5 * current_acc * delay_time * delay_time, + abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); // Vary the roll : no effect quaternion_tf.setRPY(M_PI_2, 0.0, 0.0); current_pose.orientation = tf2::toMsg(quaternion_tf); - delayed_pose = longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel); - EXPECT_NEAR(delayed_pose.position.x, current_pose.position.x + current_vel * delay_time, abs_err); + delayed_pose = + longitudinal_utils::calcPoseAfterTimeDelay(current_pose, delay_time, current_vel, current_acc); + EXPECT_NEAR( + delayed_pose.position.x, + current_pose.position.x + current_vel * delay_time + + 0.5 * current_acc * delay_time * delay_time, + abs_err); EXPECT_NEAR(delayed_pose.position.y, current_pose.position.y, abs_err); EXPECT_NEAR(delayed_pose.position.z, current_pose.position.z, abs_err); } From bb14a402b64c65612be23dc17de215fd6a98a1d2 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 17 Aug 2023 18:52:39 +0900 Subject: [PATCH 192/266] fix(intersection): refactor first stop timeout (#4457) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 6bfe1c83d370a..f67bf45d55d73 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -895,7 +895,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool approached_stop_line = (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); const bool over_stop_line = (dist_stopline < 0.0); - const bool is_stopped = planner_data_->isVehicleStopped(); + const bool is_stopped = + planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time); if (over_stop_line) { before_creep_state_machine_.setState(StateMachine::State::GO); } @@ -913,8 +914,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } else { if (is_stopped && approached_stop_line) { // start waiting at the first stop line - before_creep_state_machine_.setStateWithMarginTime( - StateMachine::State::GO, logger_.get_child("occlusion state_machine"), *clock_); + before_creep_state_machine_.setState(StateMachine::State::GO); } is_peeking_ = true; return IntersectionModule::FirstWaitBeforeOcclusion{ From 81a1e5397c82efeee35e94bdd95224d46efaed87 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 17 Aug 2023 19:07:00 +0900 Subject: [PATCH 193/266] fix(intersection): guard invalid access (#4655) Signed-off-by: satoshi-ota --- .../src/scene_intersection.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index f67bf45d55d73..7f56afde2f4ea 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1130,6 +1130,10 @@ bool IntersectionModule::checkCollision( const auto trimmed_ego_polygon = getPolygonFromArcLength(ego_lane_with_next_lanes, start_arc_length, end_arc_length); + if (trimmed_ego_polygon.empty()) { + continue; + } + Polygon2d polygon{}; for (const auto & p : trimmed_ego_polygon) { polygon.outer().emplace_back(p.x(), p.y()); From 1b103869cabcfdabf353d806db7de5e57cdc13fe Mon Sep 17 00:00:00 2001 From: Kasper Mecklenburg <30662532+kaspermeck-arm@users.noreply.github.com> Date: Thu, 17 Aug 2023 05:49:00 -0700 Subject: [PATCH 194/266] refactor(joy_controller): rework parameters (#3992) * refactor(joy_controller): rework parameters Updated adding a schema according to new ROS node config coding guidelines. Signed-off-by: kaspermeck-arm Change-Id: Icf76852cd102bf70a27f7d4111f1b52de087a00d * refactor(joy_controller): rework parameters Updated adding a schema according to new ROS node config coding guidelines. Signed-off-by: kaspermeck-arm Change-Id: Icf76852cd102bf70a27f7d4111f1b52de087a00d * Apply suggestions from code review Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> * Added quotes for default values Signed-off-by: kaspermeck-arm Change-Id: Ib754b9400003c0871ee1dd9bda8db07215852a78 --------- Signed-off-by: kaspermeck-arm Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- .../config/joy_controller.param.yaml | 1 + .../schema/joy_controller.schema.json | 118 ++++++++++++++++++ 2 files changed, 119 insertions(+) create mode 100644 control/joy_controller/schema/joy_controller.schema.json diff --git a/control/joy_controller/config/joy_controller.param.yaml b/control/joy_controller/config/joy_controller.param.yaml index 8796e026b0e69..8d48948a2d133 100644 --- a/control/joy_controller/config/joy_controller.param.yaml +++ b/control/joy_controller/config/joy_controller.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + joy_type: DS4 update_rate: 10.0 accel_ratio: 3.0 brake_ratio: 5.0 diff --git a/control/joy_controller/schema/joy_controller.schema.json b/control/joy_controller/schema/joy_controller.schema.json new file mode 100644 index 0000000000000..c67c575a6bd41 --- /dev/null +++ b/control/joy_controller/schema/joy_controller.schema.json @@ -0,0 +1,118 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Joy Controller node", + "type": "object", + "definitions": { + "joy_controller": { + "type": "object", + "properties": { + "joy_type": { + "type": "string", + "description": "Joy controller type", + "default": "DS4", + "enum": ["P65", "DS4", "G29"] + }, + "update_rate": { + "type": "number", + "description": "Update rate to publish control commands", + "default": "10.0", + "exclusiveMinimum": 0 + }, + "accel_ratio": { + "type": "number", + "description": "Ratio to calculate acceleration (commanded acceleration is ratio * operation)", + "default": "3.0" + }, + "brake_ratio": { + "type": "number", + "description": "Ratio to calculate deceleration (commanded acceleration is -ratio * operation)", + "default": "5.0" + }, + "steer_ratio": { + "type": "number", + "description": "Ratio to calculate deceleration (commanded steer is ratio * operation)", + "default": "0.5" + }, + "steering_angle_velocity": { + "type": "number", + "description": "Steering angle velocity for operation", + "default": "0.1" + }, + "accel_sensitivity": { + "type": "number", + "description": "Sensitivity to calculate acceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity))", + "default": "1.0", + "maximum": 1.0, + "exclusiveMinimum": 0.0 + }, + "brake_sensitivity": { + "type": "number", + "description": "Sensitivity to calculate deceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity))", + "default": "1.0", + "maximum": 1.0, + "exclusiveMinimum": 0.0 + }, + "control_command": { + "type": "object", + "properties": { + "velocity_gain": { + "type": "number", + "description": "Ratio to calculate velocity by acceleration", + "default": "3.0" + }, + "max_forward_velocity": { + "type": "number", + "description": "Absolute max velocity to go forward", + "default": "20.0", + "minimum": 0 + }, + "max_backward_velocity": { + "type": "number", + "description": "Absolute max velocity to go backward", + "default": "3.0", + "minimum": 0 + }, + "backward_accel_ratio": { + "type": "number", + "description": "Ratio to calculate deceleration (commanded acceleration is -ratio * operation)", + "default": "1.0" + } + }, + "required": [ + "velocity_gain", + "max_forward_velocity", + "max_backward_velocity", + "backward_accel_ratio" + ], + "additionalProperties": false + } + }, + "required": [ + "joy_type", + "update_rate", + "accel_ratio", + "brake_ratio", + "steer_ratio", + "steering_angle_velocity", + "accel_sensitivity", + "brake_sensitivity", + "control_command" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/joy_controller" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 4df5f8affb95a0743ca5a2d394c8792473f78efb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 18 Aug 2023 01:56:27 +0900 Subject: [PATCH 195/266] fix(start_planner): fix blinker direction (#4363) * fix(start_planner): fix blinker direction Signed-off-by: kosuke55 * fix Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index e4921ba293702..4e27f57b39e7b 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -814,10 +814,17 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const if (path.points.empty()) { return {}; } - const auto closest_idx = motion_utils::findNearestIndex(path.points, start_pose.position); - const auto lane_id = path.points.at(closest_idx).lane_ids.front(); - const auto lane = planner_data_->route_handler->getLaneletMapPtr()->laneletLayer.get(lane_id); - const double lateral_offset = lanelet::utils::getLateralDistanceToCenterline(lane, start_pose); + + // calculate lateral offset from pull out target lane center line + lanelet::ConstLanelet closest_road_lane; + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto road_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + lanelet::utils::query::getClosestLanelet(road_lanes, start_pose, &closest_road_lane); + const double lateral_offset = + lanelet::utils::getLateralDistanceToCenterline(closest_road_lane, start_pose); if (distance_from_end < 0.0 && lateral_offset > parameters_->th_turn_signal_on_lateral_offset) { turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; From 02ba0c64ac4d18fb1c3ad18b2c95b9911b56a1e2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 18 Aug 2023 08:41:39 +0900 Subject: [PATCH 196/266] fix(planning_debug_tools): fix the bug of perception_replayer with detected objects publishing (#4653) Signed-off-by: Takayuki Murooka --- .../scripts/perception_replayer/perception_replayer.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py index 329058cc95c35..b45357c7bd8b2 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py @@ -84,7 +84,9 @@ def on_timer(self): return ego_odom = self.find_ego_odom_by_timestamp(self.bag_timestamp) - log_ego_pose = ego_odom[1].pose.pose + if not ego_odom: + return + log_ego_pose = ego_odom.pose.pose translate_objects_coordinate(self.ego_pose, log_ego_pose, objects_msg) self.objects_pub.publish(objects_msg) From f398db4efac09a1674f2f54b1cb8540fe8486f61 Mon Sep 17 00:00:00 2001 From: ito-san <57388357+ito-san@users.noreply.github.com> Date: Fri, 18 Aug 2023 09:07:22 +0900 Subject: [PATCH 197/266] fix(system_monitor): high-memory process are not provided in MEM order (#4654) * fix(process_monitor): high-memory process are not being provided in %MEM order Signed-off-by: ito-san * changed option from 'g' to 'n' Signed-off-by: ito-san --------- Signed-off-by: ito-san --- system/system_monitor/src/process_monitor/process_monitor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/system_monitor/src/process_monitor/process_monitor.cpp index 2ce1738ecd960..f8ee314e5a0ef 100644 --- a/system/system_monitor/src/process_monitor/process_monitor.cpp +++ b/system/system_monitor/src/process_monitor/process_monitor.cpp @@ -401,7 +401,7 @@ void ProcessMonitor::getHighMemoryProcesses(const std::string & output) bp::pipe err_pipe{err_fd[0], err_fd[1]}; bp::ipstream is_err{std::move(err_pipe)}; - bp::child c("sort -r -k 10", bp::std_out > p2, bp::std_err > is_err, bp::std_in < p1); + bp::child c("sort -r -k 10 -n", bp::std_out > p2, bp::std_err > is_err, bp::std_in < p1); c.wait(); if (c.exit_code() != 0) { is_err >> os.rdbuf(); From 555142135f940a8d4860399629899ec7a101a52b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 18 Aug 2023 11:08:26 +0900 Subject: [PATCH 198/266] refactor(behavior_path_planner): separete function in utils to objects_filtering (#4658) * separate utils function to object_filtering Signed-off-by: kyoichi-sugahara * chenge call side of util functions Signed-off-by: kyoichi-sugahara * refactor Signed-off-by: kyoichi-sugahara * add explanation for parameters Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- planning/behavior_path_planner/CMakeLists.txt | 1 + .../scene_module/lane_change/normal.hpp | 8 +- .../utils/avoidance/utils.hpp | 9 +- .../lane_change/lane_change_module_data.hpp | 7 +- .../utils/lane_change/utils.hpp | 9 +- .../path_safety_checker/objects_filtering.hpp | 179 +++++++++ .../path_safety_checker_parameters.hpp | 174 +++++++++ .../path_safety_checker/safety_check.hpp | 50 +-- .../behavior_path_planner/utils/utils.hpp | 36 +- .../avoidance/avoidance_module.cpp | 7 +- .../lane_change/avoidance_by_lane_change.cpp | 4 +- .../src/scene_module/lane_change/normal.cpp | 12 +- .../start_planner/start_planner_module.cpp | 9 +- .../src/utils/goal_planner/goal_searcher.cpp | 7 +- .../path_safety_checker/objects_filtering.cpp | 353 ++++++++++++++++++ .../path_safety_checker/safety_check.cpp | 4 +- .../start_planner/geometric_pull_out.cpp | 8 +- .../utils/start_planner/shift_pull_out.cpp | 7 +- .../behavior_path_planner/src/utils/utils.cpp | 101 ----- .../test/test_safety_check.cpp | 7 +- 20 files changed, 775 insertions(+), 217 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp create mode 100644 planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 162dd855a577a..fac0e921c1072 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -31,6 +31,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/utils/utils.cpp src/utils/path_utils.cpp src/utils/path_safety_checker/safety_check.cpp + src/utils/path_safety_checker/objects_filtering.cpp src/utils/avoidance/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 948a2cc4fbb2a..9a6a12427d783 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -26,10 +26,10 @@ namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathWithLaneId; -using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; -using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; -using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; -using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; +using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 27128e92ab971..6b7830147ebf9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -17,6 +17,7 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include @@ -28,10 +29,10 @@ namespace behavior_path_planner::utils::avoidance { using behavior_path_planner::PlannerData; -using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; -using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; -using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; -using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; +using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; bool isOnRight(const ObjectData & obj); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 7a3e96aa3fa3d..721c5b00f6e33 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -15,6 +15,7 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "lanelet2_core/geometry/Lanelet.h" @@ -132,9 +133,9 @@ struct LaneChangeTargetObjectIndices struct LaneChangeTargetObjects { - std::vector current_lane{}; - std::vector target_lane{}; - std::vector other_lane{}; + std::vector current_lane{}; + std::vector target_lane{}; + std::vector other_lane{}; }; enum class LaneChangeModuleType { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index 5fa22a8935bf2..f59e0170bdf14 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -19,6 +19,7 @@ #include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -43,10 +44,10 @@ 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::PathWithLaneId; -using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; -using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; -using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; -using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; +using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp new file mode 100644 index 0000000000000..b4575eb4d3b7e --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp @@ -0,0 +1,179 @@ +// Copyright 2023 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 BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ + +#include "behavior_path_planner/data_manager.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" + +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +namespace behavior_path_planner::utils::path_safety_checker +{ + +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::PathPointWithLaneId; + +/** + * @brief Filters objects based on various criteria. + * + * @param objects The predicted objects to filter. + * @param route_handler + * @param current_lanes + * @param current_pose The current pose of ego vehicle. + * @param params The filtering parameters. + * @return PredictedObjects The filtered objects. + */ +PredictedObjects filterObjects( + const std::shared_ptr & objects, + const std::shared_ptr & route_handler, const lanelet::ConstLanelets & current_lanes, + const geometry_msgs::msg::Point & current_pose, + const std::shared_ptr & params); + +/** + * @brief Filter objects based on their velocity. + * + * @param objects The predicted objects to filter. + * @param lim_v Velocity limit for filtering. + * @return PredictedObjects The filtered objects. + */ +PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v); + +/** + * @brief Filter objects based on a velocity range. + * + * @param objects The predicted objects to filter. + * @param min_v Minimum velocity for filtering. + * @param max_v Maximum velocity for filtering. + * @return PredictedObjects The filtered objects. + */ +PredictedObjects filterObjectsByVelocity( + const PredictedObjects & objects, double min_v, double max_v); + +/** + * @brief Filter objects based on their position relative to a current_pose. + * + * @param objects The predicted objects to filter. + * @param path_points Points on the path. + * @param current_pose Current pose of the reference (e.g., ego vehicle). + * @param forward_distance Maximum forward distance for filtering. + * @param backward_distance Maximum backward distance for filtering. + */ +void filterObjectsByPosition( + PredictedObjects & objects, const std::vector & path_points, + const geometry_msgs::msg::Point & current_pose, const double forward_distance, + const double backward_distance); +/** + * @brief Filters the provided objects based on their classification. + * + * @param objects The predicted objects to be filtered. + * @param target_object_types The types of objects to retain after filtering. + */ +void filterObjectsByClass( + PredictedObjects & objects, const ObjectTypesToCheck & target_object_types); + +/** + * @brief Separate index of the obstacles into two part based on whether the object is within + * lanelet. + * @return Indices of objects pair. first objects are in the lanelet, and second others are out of + * lanelet. + */ +std::pair, std::vector> separateObjectIndicesByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets); + +/** + * @brief Separate the objects into two part based on whether the object is within lanelet. + * @return Objects pair. first objects are in the lanelet, and second others are out of lanelet. + */ +std::pair separateObjectsByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets); + +/** + * @brief Get the predicted path from an object. + * + * @param obj The extended predicted object. + * @param is_use_all_predicted_path Flag to determine whether to use all predicted paths or just the + * one with maximum confidence. + * @return std::vector The predicted path(s) from the object. + */ +std::vector getPredictedPathFromObj( + const ExtendedPredictedObject & obj, const bool & is_use_all_predicted_path); + +/** + * @brief Create a predicted path based on ego vehicle parameters. + * + * @param ego_predicted_path_params Parameters for ego's predicted path. + * @param path_points Points on the path. + * @param vehicle_pose Current pose of the ego-vehicle. + * @param current_velocity Current velocity of the vehicle. + * @param ego_seg_idx Index of the ego segment. + * @return std::vector The predicted path. + */ +std::vector createPredictedPath( + const std::shared_ptr & ego_predicted_path_params, + const std::vector & path_points, + const geometry_msgs::msg::Pose & vehicle_pose, const double current_velocity, size_t ego_seg_idx); + +/** + * @brief Checks if the centroid of a given object is within the provided lanelets. + * + * @param object The predicted object to check. + * @param target_lanelets The lanelets to check against. + * @return bool True if the object's centroid is within the lanelets, otherwise false. + */ +bool isCentroidWithinLanelets( + const PredictedObject & object, const lanelet::ConstLanelets & target_lanelets); + +/** + * @brief Transforms a given object into an extended predicted object. + * + * @param object The predicted object to transform. + * @param safety_check_time_horizon The time horizon for safety checks. + * @param safety_check_time_resolution The time resolution for safety checks. + * @return ExtendedPredictedObject The transformed object. + */ +ExtendedPredictedObject transform( + const PredictedObject & object, const double safety_check_time_horizon, + const double safety_check_time_resolution); + +/** + * @brief Creates target objects on a lane based on provided parameters. + * + * @param current_lanes + * @param route_handler + * @param filtered_objects The filtered objects. + * @param params The filtering parameters. + * @return TargetObjectsOnLane The target objects on the lane. + */ +TargetObjectsOnLane createTargetObjectsOnLane( + const lanelet::ConstLanelets & current_lanes, const std::shared_ptr & route_handler, + const PredictedObjects & filtered_objects, + const std::shared_ptr & params); + +} // namespace behavior_path_planner::utils::path_safety_checker + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp new file mode 100644 index 0000000000000..519f589f561ee --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -0,0 +1,174 @@ +// Copyright 2023 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 BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__PATH_SAFETY_CHECKER_PARAMETERS_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__PATH_SAFETY_CHECKER_PARAMETERS_HPP_ + +#include + +#include +#include + +#include + +namespace behavior_path_planner::utils::path_safety_checker +{ + +using geometry_msgs::msg::Pose; +using tier4_autoware_utils::Polygon2d; + +struct PoseWithVelocity +{ + Pose pose; + double velocity{0.0}; + + PoseWithVelocity(const Pose & pose, const double velocity) : pose(pose), velocity(velocity) {} +}; + +struct PoseWithVelocityStamped : public PoseWithVelocity +{ + double time{0.0}; + + PoseWithVelocityStamped(const double time, const Pose & pose, const double velocity) + : PoseWithVelocity(pose, velocity), time(time) + { + } +}; + +struct PoseWithVelocityAndPolygonStamped : public PoseWithVelocityStamped +{ + Polygon2d poly; + + PoseWithVelocityAndPolygonStamped( + const double time, const Pose & pose, const double velocity, const Polygon2d & poly) + : PoseWithVelocityStamped(time, pose, velocity), poly(poly) + { + } +}; + +struct PredictedPathWithPolygon +{ + float confidence{0.0}; + std::vector path; +}; + +struct ExtendedPredictedObject +{ + unique_identifier_msgs::msg::UUID uuid; + geometry_msgs::msg::PoseWithCovariance initial_pose; + geometry_msgs::msg::TwistWithCovariance initial_twist; + geometry_msgs::msg::AccelWithCovariance initial_acceleration; + autoware_auto_perception_msgs::msg::Shape shape; + std::vector predicted_paths; +}; + +/** + * @brief Specifies which object class should be checked. + */ +struct ObjectTypesToCheck +{ + bool check_car{true}; ///< Check for cars. + bool check_truck{true}; ///< Check for trucks. + bool check_bus{true}; ///< Check for buses. + bool check_trailer{true}; ///< Check for trailers. + bool check_unknown{true}; ///< Check for unknown object types. + bool check_bicycle{true}; ///< Check for bicycles. + bool check_motorcycle{true}; ///< Check for motorcycles. + bool check_pedestrian{true}; ///< Check for pedestrians. +}; + +/** + * @brief Configuration for which lanes should be checked for objects. + */ +struct ObjectLaneConfiguration +{ + bool check_current_lane{}; ///< Check the current lane. + bool check_right_lane{}; ///< Check the right lane. + bool check_left_lane{}; ///< Check the left lane. + bool check_shoulder_lane{}; ///< Check the shoulder lane. + bool check_other_lane{}; ///< Check other lanes. +}; + +/** + * @brief Contains objects on lanes type. + */ +struct TargetObjectsOnLane +{ + std::vector on_current_lane{}; ///< Objects on the current lane. + std::vector on_right_lane{}; ///< Objects on the right lane. + std::vector on_left_lane{}; ///< Objects on the left lane. + std::vector on_shoulder_lane{}; ///< Objects on the shoulder lane. + std::vector on_other_lane{}; ///< Objects on other lanes. +}; + +/** + * @brief Parameters related to the RSS (Responsibility-Sensitive Safety) model. + */ +struct RSSparams +{ + double rear_vehicle_reaction_time{0.0}; ///< Reaction time of the rear vehicle. + double rear_vehicle_safety_time_margin{0.0}; ///< Safety time margin for the rear vehicle. + double lateral_distance_max_threshold{0.0}; ///< Maximum threshold for lateral distance. + double longitudinal_distance_min_threshold{ + 0.0}; ///< Minimum threshold for longitudinal distance. + double longitudinal_velocity_delta_time{0.0}; ///< Delta time for longitudinal velocity. +}; + +/** + * @brief Parameters for generating the ego vehicle's predicted path. + */ +struct EgoPredictedPathParams +{ + double acceleration; ///< Acceleration value. + double time_horizon; ///< Time horizon for prediction. + double time_resolution; ///< Time resolution for prediction. + double min_slow_speed; ///< Minimum slow speed. + double delay_until_departure; ///< Delay before departure. + double target_velocity; ///< Target velocity. +}; + +/** + * @brief Parameters for filtering objects. + */ +struct ObjectsFilteringParams +{ + double safety_check_time_horizon; ///< Time horizon for object's prediction. + double safety_check_time_resolution; ///< Time resolution for object's prediction. + double object_check_forward_distance; ///< Forward distance for object checks. + double object_check_backward_distance; ///< Backward distance for object checks. + double ignore_object_velocity_threshold; ///< Velocity threshold for ignoring objects. + ObjectTypesToCheck object_types_to_check; ///< Specifies which object types to check. + ObjectLaneConfiguration object_lane_configuration; ///< Configuration for which lanes to check. + bool include_opposite_lane; ///< Include the opposite lane in checks. + bool invert_opposite_lane; ///< Invert the opposite lane in checks. + bool check_all_predicted_path; ///< Check all predicted paths. + bool use_all_predicted_path; ///< Use all predicted paths. + bool use_predicted_path_outside_lanelet; ///< Use predicted paths outside of lanelets. +}; + +/** + * @brief Parameters for safety checks. + */ +struct SafetyCheckParams +{ + bool enable_safety_check; ///< Enable safety checks. + double backward_lane_length; ///< Length of the backward lane for path generation. + double forward_path_length; ///< Length of the forward path lane for path generation. + RSSparams rss_params; ///< Parameters related to the RSS model. + bool publish_debug_marker{false}; ///< Option to publish debug markers. +}; + +} // namespace behavior_path_planner::utils::path_safety_checker + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__PATH_SAFETY_CHECKER_PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index 55bac83442e84..edfec6a7db579 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -17,6 +17,7 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -36,7 +37,7 @@ #include #include -namespace behavior_path_planner::utils::safety_check +namespace behavior_path_planner::utils::path_safety_checker { using autoware_auto_perception_msgs::msg::PredictedObject; @@ -49,51 +50,6 @@ using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using vehicle_info_util::VehicleInfo; -struct PoseWithVelocity -{ - Pose pose; - double velocity{0.0}; - - PoseWithVelocity(const Pose & pose, const double velocity) : pose(pose), velocity(velocity) {} -}; - -struct PoseWithVelocityStamped : public PoseWithVelocity -{ - double time{0.0}; - - PoseWithVelocityStamped(const double time, const Pose & pose, const double velocity) - : PoseWithVelocity(pose, velocity), time(time) - { - } -}; - -struct PoseWithVelocityAndPolygonStamped : public PoseWithVelocityStamped -{ - Polygon2d poly; - - PoseWithVelocityAndPolygonStamped( - const double time, const Pose & pose, const double velocity, const Polygon2d & poly) - : PoseWithVelocityStamped(time, pose, velocity), poly(poly) - { - } -}; - -struct PredictedPathWithPolygon -{ - float confidence{0.0}; - std::vector path; -}; - -struct ExtendedPredictedObject -{ - unique_identifier_msgs::msg::UUID uuid; - geometry_msgs::msg::PoseWithCovariance initial_pose; - geometry_msgs::msg::TwistWithCovariance initial_twist; - geometry_msgs::msg::AccelWithCovariance initial_acceleration; - autoware_auto_perception_msgs::msg::Shape shape; - std::vector predicted_paths; -}; - namespace bg = boost::geometry; bool isTargetObjectFront( @@ -145,6 +101,6 @@ bool checkCollision( const BehaviorPathPlannerParameters & common_parameters, const double front_object_deceleration, const double rear_object_deceleration, CollisionCheckDebug & debug); -} // namespace behavior_path_planner::utils::safety_check +} // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 088a0f0bd795b..784258e31b265 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -19,6 +19,7 @@ #include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_following/module_data.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include "motion_utils/motion_utils.hpp" @@ -66,16 +67,19 @@ using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; -using behavior_path_planner::utils::safety_check::ExtendedPredictedObject; -using behavior_path_planner::utils::safety_check::PoseWithVelocityAndPolygonStamped; -using behavior_path_planner::utils::safety_check::PoseWithVelocityStamped; -using behavior_path_planner::utils::safety_check::PredictedPathWithPolygon; using drivable_area_expansion::DrivableAreaExpansionParameters; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; using geometry_msgs::msg::Twist; using geometry_msgs::msg::Vector3; +using path_safety_checker::ExtendedPredictedObject; +using path_safety_checker::ObjectTypesToCheck; +using path_safety_checker::PoseWithVelocityAndPolygonStamped; +using path_safety_checker::PoseWithVelocityStamped; +using path_safety_checker::PredictedPathWithPolygon; +using path_safety_checker::SafetyCheckParams; +using path_safety_checker::TargetObjectsOnLane; using route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; @@ -199,27 +203,6 @@ double calcLongitudinalDistanceFromEgoToObjects( const Pose & ego_pose, double base_link2front, double base_link2rear, const PredictedObjects & dynamic_objects); -/** - * @brief Separate index of the obstacles into two part based on whether the object is within - * lanelet. - * @return Indices of objects pair. first objects are in the lanelet, and second others are out of - * lanelet. - */ -std::pair, std::vector> separateObjectIndicesByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets); - -/** - * @brief Separate the objects into two part based on whether the object is within lanelet. - * @return Objects pair. first objects are in the lanelet, and second others are out of lanelet. - */ -std::pair separateObjectsByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets); - -PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v); - -PredictedObjects filterObjectsByVelocity( - const PredictedObjects & objects, double min_v, double max_v); - // drivable area generation lanelet::ConstLanelets transformToLanelets(const DrivableLanes & drivable_lanes); lanelet::ConstLanelets transformToLanelets(const std::vector & drivable_lanes); @@ -391,9 +374,6 @@ lanelet::ConstLanelets calcLaneAroundPose( const double dist_threshold = std::numeric_limits::max(), const double yaw_threshold = std::numeric_limits::max()); -std::vector getPredictedPathFromObj( - const ExtendedPredictedObject & obj, const bool & is_use_all_predicted_path); - bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold); double calcMinimumLaneChangeLength( diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 88bc583345966..2a806bcb24cfe 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -17,6 +17,7 @@ #include "behavior_path_planner/marker_utils/avoidance/debug.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -1895,11 +1896,11 @@ bool AvoidanceModule::isSafePath( avoidance_data_, planner_data_, parameters_, is_right_shift.value()); for (const auto & object : safety_check_target_objects) { - const auto obj_predicted_paths = - utils::getPredictedPathFromObj(object, parameters_->check_all_predicted_path); + const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( + object, parameters_->check_all_predicted_path); for (const auto & obj_path : obj_predicted_paths) { CollisionCheckDebug collision{}; - if (!utils::safety_check::checkCollision( + if (!utils::path_safety_checker::checkCollision( shifted_path.path, ego_predicted_path, object, obj_path, p, p.expected_front_deceleration, p.expected_rear_deceleration, collision)) { return false; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp index 0db16c4c1d4ca..841fc9092e279 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp @@ -15,6 +15,7 @@ #include "behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp" #include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include @@ -136,7 +137,8 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( const auto p = std::dynamic_pointer_cast(avoidance_parameters_); const auto [object_within_target_lane, object_outside_target_lane] = - utils::separateObjectsByLanelets(*planner_data_->dynamic_object, data.current_lanelets); + utils::path_safety_checker::separateObjectsByLanelets( + *planner_data_->dynamic_object, data.current_lanelets); // Assume that the maximum allocation for data.other object is the sum of // objects_within_target_lane and object_outside_target_lane. The maximum allocation for diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 29cefe110d9e4..77c5e78d3db50 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -16,6 +16,7 @@ #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -1372,18 +1373,19 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( for (const auto & obj : collision_check_objects) { auto current_debug_data = assignDebugData(obj); current_debug_data.second.ego_predicted_path.push_back(debug_predicted_path); - const auto obj_predicted_paths = - utils::getPredictedPathFromObj(obj, lane_change_parameters_->use_all_predicted_path); + const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( + obj, lane_change_parameters_->use_all_predicted_path); for (const auto & obj_path : obj_predicted_paths) { - if (!utils::safety_check::checkCollision( + if (!utils::path_safety_checker::checkCollision( path, ego_predicted_path, obj, obj_path, common_parameters, front_decel, rear_decel, current_debug_data.second)) { path_safety_status.is_safe = false; updateDebugInfo(current_debug_data, path_safety_status.is_safe); const auto & obj_pose = obj.initial_pose.pose; const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, obj.shape); - path_safety_status.is_object_coming_from_rear |= !utils::safety_check::isTargetObjectFront( - path, current_pose, common_parameters.vehicle_info, obj_polygon); + path_safety_status.is_object_coming_from_rear |= + !utils::path_safety_checker::isTargetObjectFront( + path, current_pose, common_parameters.vehicle_info, obj_polygon); } } updateDebugInfo(current_debug_data, path_safety_status.is_safe); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 4e27f57b39e7b..860cdac31640d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -15,9 +15,9 @@ #include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" #include "behavior_path_planner/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/start_planner/util.hpp" -#include "behavior_path_planner/utils/utils.hpp" #include #include @@ -631,9 +631,10 @@ std::vector StartPlannerModule::searchPullOutStartPoses() // filter pull out lanes stop objects const auto [pull_out_lane_objects, others] = - utils::separateObjectsByLanelets(*planner_data_->dynamic_object, status_.pull_out_lanes); - const auto pull_out_lane_stop_objects = - utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_->th_moving_object_velocity); + utils::path_safety_checker::separateObjectsByLanelets( + *planner_data_->dynamic_object, status_.pull_out_lanes); + const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( + pull_out_lane_objects, parameters_->th_moving_object_velocity); // lateral shift to current_pose const double distance_from_center_line = arc_position_pose.distance; diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index 9daee39433d97..1e57dcc319dc5 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -15,6 +15,7 @@ #include "behavior_path_planner/utils/goal_planner/goal_searcher.hpp" #include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "lanelet2_extension/utility/utilities.hpp" @@ -69,7 +70,8 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose) parameters_.goal_search_interval); const auto [shoulder_lane_objects, others] = - utils::separateObjectsByLanelets(*(planner_data_->dynamic_object), pull_over_lanes); + utils::path_safety_checker::separateObjectsByLanelets( + *(planner_data_->dynamic_object), pull_over_lanes); std::vector original_search_poses{}; // for search area visualizing size_t goal_id = 0; @@ -151,7 +153,8 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_); const auto [shoulder_lane_objects, others] = - utils::separateObjectsByLanelets(*(planner_data_->dynamic_object), pull_over_lanes); + utils::path_safety_checker::separateObjectsByLanelets( + *(planner_data_->dynamic_object), pull_over_lanes); constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( goal_pose, planner_data_->parameters.vehicle_width, shoulder_lane_objects, diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp new file mode 100644 index 0000000000000..33afe0fe6642f --- /dev/null +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp @@ -0,0 +1,353 @@ +// Copyright 2023 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 "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" + +#include "behavior_path_planner/utils/utils.hpp" + +namespace behavior_path_planner::utils::path_safety_checker +{ + +PredictedObjects filterObjects( + const std::shared_ptr & objects, + const std::shared_ptr & route_handler, const lanelet::ConstLanelets & current_lanes, + const geometry_msgs::msg::Point & current_pose, + const std::shared_ptr & params) +{ + // Guard + if (objects->objects.empty()) { + return PredictedObjects(); + } + + const double ignore_object_velocity_threshold = params->ignore_object_velocity_threshold; + const double object_check_forward_distance = params->object_check_forward_distance; + const double object_check_backward_distance = params->object_check_backward_distance; + const ObjectTypesToCheck & target_object_types = params->object_types_to_check; + + PredictedObjects filtered_objects; + + filtered_objects = filterObjectsByVelocity(*objects, ignore_object_velocity_threshold); + + filterObjectsByClass(filtered_objects, target_object_types); + + const auto path = route_handler->getCenterLinePath( + current_lanes, object_check_backward_distance, object_check_forward_distance); + + filterObjectsByPosition( + filtered_objects, path.points, current_pose, object_check_forward_distance, + object_check_backward_distance); + + return filtered_objects; +} + +PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v) +{ + return filterObjectsByVelocity(objects, -lim_v, lim_v); +} + +PredictedObjects filterObjectsByVelocity( + const PredictedObjects & objects, double min_v, double max_v) +{ + PredictedObjects filtered; + filtered.header = objects.header; + for (const auto & obj : objects.objects) { + const auto v_norm = std::hypot( + obj.kinematics.initial_twist_with_covariance.twist.linear.x, + obj.kinematics.initial_twist_with_covariance.twist.linear.y); + if (min_v < v_norm && v_norm < max_v) { + filtered.objects.push_back(obj); + } + } + return filtered; +} + +void filterObjectsByPosition( + PredictedObjects & objects, const std::vector & path_points, + const geometry_msgs::msg::Point & current_pose, const double forward_distance, + const double backward_distance) +{ + // Create a new container to hold the filtered objects + PredictedObjects filtered; + filtered.header = objects.header; + + // Reserve space in the vector to avoid reallocations + filtered.objects.reserve(objects.objects.size()); + + for (const auto & obj : objects.objects) { + const double dist_ego_to_obj = motion_utils::calcSignedArcLength( + path_points, current_pose, obj.kinematics.initial_pose_with_covariance.pose.position); + + if (-backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance) { + filtered.objects.push_back(obj); + } + } + + // Replace the original objects with the filtered list + objects.objects = std::move(filtered.objects); + return; +} + +void filterObjectsByClass( + PredictedObjects & objects, const ObjectTypesToCheck & target_object_types) +{ + using autoware_auto_perception_msgs::msg::ObjectClassification; + + PredictedObjects filtered_objects; + + for (auto & object : objects.objects) { + const auto t = utils::getHighestProbLabel(object.classification); + const auto is_object_type = + ((t == ObjectClassification::CAR && target_object_types.check_car) || + (t == ObjectClassification::TRUCK && target_object_types.check_truck) || + (t == ObjectClassification::BUS && target_object_types.check_bus) || + (t == ObjectClassification::TRAILER && target_object_types.check_trailer) || + (t == ObjectClassification::UNKNOWN && target_object_types.check_unknown) || + (t == ObjectClassification::BICYCLE && target_object_types.check_bicycle) || + (t == ObjectClassification::MOTORCYCLE && target_object_types.check_motorcycle) || + (t == ObjectClassification::PEDESTRIAN && target_object_types.check_pedestrian)); + + // If the object type matches any of the target types, add it to the filtered list + if (is_object_type) { + filtered_objects.objects.push_back(object); + } + } + + // Replace the original objects with the filtered list + objects = std::move(filtered_objects); + + return; +} + +std::pair, std::vector> separateObjectIndicesByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets) +{ + if (target_lanelets.empty()) { + return {}; + } + + std::vector target_indices; + std::vector other_indices; + + for (size_t i = 0; i < objects.objects.size(); i++) { + // create object polygon + const auto & obj = objects.objects.at(i); + // create object polygon + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj); + bool is_filtered_object = false; + for (const auto & llt : target_lanelets) { + // create lanelet polygon + const auto polygon2d = llt.polygon2d().basicPolygon(); + if (polygon2d.empty()) { + // no lanelet polygon + continue; + } + Polygon2d lanelet_polygon; + for (const auto & lanelet_point : polygon2d) { + lanelet_polygon.outer().emplace_back(lanelet_point.x(), lanelet_point.y()); + } + lanelet_polygon.outer().push_back(lanelet_polygon.outer().front()); + // check the object does not intersect the lanelet + if (!boost::geometry::disjoint(lanelet_polygon, obj_polygon)) { + target_indices.push_back(i); + is_filtered_object = true; + break; + } + } + + if (!is_filtered_object) { + other_indices.push_back(i); + } + } + + return std::make_pair(target_indices, other_indices); +} + +std::pair separateObjectsByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets) +{ + PredictedObjects target_objects; + PredictedObjects other_objects; + + const auto [target_indices, other_indices] = + separateObjectIndicesByLanelets(objects, target_lanelets); + + target_objects.objects.reserve(target_indices.size()); + other_objects.objects.reserve(other_indices.size()); + + for (const size_t i : target_indices) { + target_objects.objects.push_back(objects.objects.at(i)); + } + + for (const size_t i : other_indices) { + other_objects.objects.push_back(objects.objects.at(i)); + } + + return std::make_pair(target_objects, other_objects); +} + +std::vector getPredictedPathFromObj( + const ExtendedPredictedObject & obj, const bool & is_use_all_predicted_path) +{ + if (!is_use_all_predicted_path) { + const auto max_confidence_path = std::max_element( + obj.predicted_paths.begin(), obj.predicted_paths.end(), + [](const auto & path1, const auto & path2) { return path1.confidence < path2.confidence; }); + if (max_confidence_path != obj.predicted_paths.end()) { + return {*max_confidence_path}; + } + } + + return obj.predicted_paths; +} + +// TODO(Sugahara): should consider delay before departure +std::vector createPredictedPath( + const std::shared_ptr & ego_predicted_path_params, + const std::vector & path_points, + const geometry_msgs::msg::Pose & vehicle_pose, const double current_velocity, size_t ego_seg_idx) +{ + if (path_points.empty()) { + return {}; + } + + const double min_slow_down_speed = ego_predicted_path_params->min_slow_speed; + const double acceleration = ego_predicted_path_params->acceleration; + const double time_horizon = ego_predicted_path_params->time_horizon; + const double time_resolution = ego_predicted_path_params->time_resolution; + + std::vector predicted_path; + const auto vehicle_pose_frenet = + convertToFrenetPoint(path_points, vehicle_pose.position, ego_seg_idx); + + for (double t = 0.0; t < time_horizon + 1e-3; t += time_resolution) { + const double velocity = std::max(current_velocity + acceleration * t, min_slow_down_speed); + const double length = current_velocity * t + 0.5 * acceleration * t * t; + const auto pose = + motion_utils::calcInterpolatedPose(path_points, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); + } + + return predicted_path; +} + +bool isCentroidWithinLanelets( + const PredictedObject & object, const lanelet::ConstLanelets & target_lanelets) +{ + if (target_lanelets.empty()) { + return false; + } + + const auto & object_pos = object.kinematics.initial_pose_with_covariance.pose.position; + lanelet::BasicPoint2d object_centroid(object_pos.x, object_pos.y); + + for (const auto & llt : target_lanelets) { + if (boost::geometry::within(object_centroid, llt.polygon2d().basicPolygon())) { + return true; + } + } + + return false; +} + +ExtendedPredictedObject transform( + const PredictedObject & object, const double safety_check_time_horizon, + const double safety_check_time_resolution) +{ + ExtendedPredictedObject extended_object; + extended_object.uuid = object.object_id; + extended_object.initial_pose = object.kinematics.initial_pose_with_covariance; + extended_object.initial_twist = object.kinematics.initial_twist_with_covariance; + extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; + extended_object.shape = object.shape; + + const auto obj_velocity = extended_object.initial_twist.twist.linear.x; + + extended_object.predicted_paths.resize(object.kinematics.predicted_paths.size()); + for (size_t i = 0; i < object.kinematics.predicted_paths.size(); ++i) { + const auto & path = object.kinematics.predicted_paths[i]; + extended_object.predicted_paths[i].confidence = path.confidence; + + // Create path based on time horizon and resolution + for (double t = 0.0; t < safety_check_time_horizon + 1e-3; t += safety_check_time_resolution) { + const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); + if (obj_pose) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(*obj_pose, object.shape); + extended_object.predicted_paths[i].path.emplace_back( + t, *obj_pose, obj_velocity, obj_polygon); + } + } + } + + return extended_object; +} + +TargetObjectsOnLane createTargetObjectsOnLane( + const lanelet::ConstLanelets & current_lanes, const std::shared_ptr & route_handler, + const PredictedObjects & filtered_objects, const std::shared_ptr & params) +{ + const auto & object_lane_configuration = params->object_lane_configuration; + const bool include_opposite = params->include_opposite_lane; + const bool invert_opposite = params->invert_opposite_lane; + const double safety_check_time_horizon = params->safety_check_time_horizon; + const double safety_check_time_resolution = params->safety_check_time_resolution; + + lanelet::ConstLanelets all_left_lanelets; + lanelet::ConstLanelets all_right_lanelets; + + // Define lambda functions to update left and right lanelets + const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto left_lanelets = route_handler->getAllLeftSharedLinestringLanelets( + target_lane, include_opposite, invert_opposite); + all_left_lanelets.insert(all_left_lanelets.end(), left_lanelets.begin(), left_lanelets.end()); + }; + + const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto right_lanelets = route_handler->getAllRightSharedLinestringLanelets( + target_lane, include_opposite, invert_opposite); + all_right_lanelets.insert( + all_right_lanelets.end(), right_lanelets.begin(), right_lanelets.end()); + }; + + // Update left and right lanelets for each current lane + for (const auto & current_lane : current_lanes) { + update_left_lanelets(current_lane); + update_right_lanelets(current_lane); + } + + TargetObjectsOnLane target_objects_on_lane{}; + const auto append_objects_on_lane = [&](auto & lane_objects, const auto & check_lanes) { + std::for_each( + filtered_objects.objects.begin(), filtered_objects.objects.end(), [&](const auto & object) { + if (isCentroidWithinLanelets(object, check_lanes)) { + lane_objects.push_back( + transform(object, safety_check_time_horizon, safety_check_time_resolution)); + } + }); + }; + + // TODO(Sugahara): Consider shoulder and other lane objects + if (object_lane_configuration.check_current_lane) { + append_objects_on_lane(target_objects_on_lane.on_current_lane, current_lanes); + } + if (object_lane_configuration.check_left_lane) { + append_objects_on_lane(target_objects_on_lane.on_left_lane, all_left_lanelets); + } + if (object_lane_configuration.check_right_lane) { + append_objects_on_lane(target_objects_on_lane.on_right_lane, all_right_lanelets); + } + + return target_objects_on_lane; +} + +} // namespace behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 23c2951d30a38..ee23ecc005142 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -19,7 +19,7 @@ #include "motion_utils/trajectory/trajectory.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" -namespace behavior_path_planner::utils::safety_check +namespace behavior_path_planner::utils::path_safety_checker { void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) { @@ -303,4 +303,4 @@ bool checkCollision( return true; } -} // namespace behavior_path_planner::utils::safety_check +} // namespace behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 5eac8291f0e1a..721ffd3064840 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -14,6 +14,7 @@ #include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -69,9 +70,10 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p // collision check with stop objects in pull out lanes const auto arc_path = planner_.getArcPath(); const auto [pull_out_lane_objects, others] = - utils::separateObjectsByLanelets(*(planner_data_->dynamic_object), pull_out_lanes); - const auto pull_out_lane_stop_objects = - utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_.th_moving_object_velocity); + utils::path_safety_checker::separateObjectsByLanelets( + *(planner_data_->dynamic_object), pull_out_lanes); + const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( + pull_out_lane_objects, parameters_.th_moving_object_velocity); if (utils::checkCollisionBetweenPathFootprintsAndObjects( vehicle_footprint_, arc_path, pull_out_lane_stop_objects, diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index cbe06fa66c306..08dcc0254deb1 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -14,6 +14,7 @@ #include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -64,9 +65,9 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) // extract stop objects in pull out lane for collision check const auto [pull_out_lane_objects, others] = - utils::separateObjectsByLanelets(*dynamic_objects, pull_out_lanes); - const auto pull_out_lane_stop_objects = - utils::filterObjectsByVelocity(pull_out_lane_objects, parameters_.th_moving_object_velocity); + utils::path_safety_checker::separateObjectsByLanelets(*dynamic_objects, pull_out_lanes); + const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( + pull_out_lane_objects, parameters_.th_moving_object_velocity); // get safe path for (auto & pull_out_path : pull_out_paths) { diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 8cc94bd6b46fa..b1f5afc119b39 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -711,73 +711,6 @@ double calcLongitudinalDistanceFromEgoToObjects( return min_distance; } -std::pair, std::vector> separateObjectIndicesByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets) -{ - if (target_lanelets.empty()) { - return {}; - } - - std::vector target_indices; - std::vector other_indices; - - for (size_t i = 0; i < objects.objects.size(); i++) { - // create object polygon - const auto & obj = objects.objects.at(i); - // create object polygon - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj); - bool is_filtered_object = false; - for (const auto & llt : target_lanelets) { - // create lanelet polygon - const auto polygon2d = llt.polygon2d().basicPolygon(); - if (polygon2d.empty()) { - // no lanelet polygon - continue; - } - Polygon2d lanelet_polygon; - for (const auto & lanelet_point : polygon2d) { - lanelet_polygon.outer().emplace_back(lanelet_point.x(), lanelet_point.y()); - } - lanelet_polygon.outer().push_back(lanelet_polygon.outer().front()); - // check the object does not intersect the lanelet - if (!boost::geometry::disjoint(lanelet_polygon, obj_polygon)) { - target_indices.push_back(i); - is_filtered_object = true; - break; - } - } - - if (!is_filtered_object) { - other_indices.push_back(i); - } - } - - return std::make_pair(target_indices, other_indices); -} - -std::pair separateObjectsByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets) -{ - PredictedObjects target_objects; - PredictedObjects other_objects; - - const auto [target_indices, other_indices] = - separateObjectIndicesByLanelets(objects, target_lanelets); - - target_objects.objects.reserve(target_indices.size()); - other_objects.objects.reserve(other_indices.size()); - - for (const size_t i : target_indices) { - target_objects.objects.push_back(objects.objects.at(i)); - } - - for (const size_t i : other_indices) { - other_objects.objects.push_back(objects.objects.at(i)); - } - - return std::make_pair(target_objects, other_objects); -} - std::vector calcObjectsDistanceToPath( const PredictedObjects & objects, const PathWithLaneId & ego_path) { @@ -2661,25 +2594,6 @@ std::vector expandLanelets( return expanded_drivable_lanes; } -PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v) -{ - return filterObjectsByVelocity(objects, -lim_v, lim_v); -} - -PredictedObjects filterObjectsByVelocity( - const PredictedObjects & objects, double min_v, double max_v) -{ - PredictedObjects filtered; - filtered.header = objects.header; - for (const auto & obj : objects.objects) { - const auto v = std::abs(obj.kinematics.initial_twist_with_covariance.twist.linear.x); - if (min_v < v && v < max_v) { - filtered.objects.push_back(obj); - } - } - return filtered; -} - PathWithLaneId getCenterLinePathFromRootLanelet( const lanelet::ConstLanelet & root_lanelet, const std::shared_ptr & planner_data) @@ -3051,21 +2965,6 @@ lanelet::ConstLanelets calcLaneAroundPose( return current_lanes; } -std::vector getPredictedPathFromObj( - const ExtendedPredictedObject & obj, const bool & is_use_all_predicted_path) -{ - if (!is_use_all_predicted_path) { - const auto max_confidence_path = std::max_element( - obj.predicted_paths.begin(), obj.predicted_paths.end(), - [](const auto & path1, const auto & path2) { return path1.confidence < path2.confidence; }); - if (max_confidence_path != obj.predicted_paths.end()) { - return {*max_confidence_path}; - } - } - - return obj.predicted_paths; -} - bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold) { // We need at least three points to compute relative angle diff --git a/planning/behavior_path_planner/test/test_safety_check.cpp b/planning/behavior_path_planner/test/test_safety_check.cpp index 4058956ceff3f..e24f3274179fe 100644 --- a/planning/behavior_path_planner/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/test/test_safety_check.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" @@ -35,7 +36,7 @@ using tier4_autoware_utils::Polygon2d; TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { - using behavior_path_planner::utils::safety_check::createExtendedPolygon; + using behavior_path_planner::utils::path_safety_checker::createExtendedPolygon; vehicle_info_util::VehicleInfo vehicle_info; vehicle_info.max_longitudinal_offset_m = 4.0; @@ -128,7 +129,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) { - using behavior_path_planner::utils::safety_check::createExtendedPolygon; + using behavior_path_planner::utils::path_safety_checker::createExtendedPolygon; using tier4_autoware_utils::createPoint; using tier4_autoware_utils::createQuaternionFromYaw; @@ -176,7 +177,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) TEST(BehaviorPathPlanningSafetyUtilsTest, calcRssDistance) { - using behavior_path_planner::utils::safety_check::calcRssDistance; + using behavior_path_planner::utils::path_safety_checker::calcRssDistance; { const double front_vel = 5.0; From 25355b5ade08603ba9e492666bd30d0cfdbe8b00 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 18 Aug 2023 11:50:10 +0900 Subject: [PATCH 199/266] fix(ekf_localizer): fix True to true (#4659) --- localization/ekf_localizer/config/ekf_localizer.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 322325d239004..4d3f5b9643462 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: show_debug_info: false - enable_yaw_bias_estimation: True + enable_yaw_bias_estimation: true predict_frequency: 50.0 tf_rate: 50.0 extend_state_step: 50 From 93b7d4da383b5f1e005d2db26849acbcd15e5380 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 18 Aug 2023 15:28:15 +0900 Subject: [PATCH 200/266] fix(map_loader, map_projection_loader): use component interface specs (#4585) * feat(map): use component_interface_specs in map_projection_loader Signed-off-by: kminoda * update map_loader Signed-off-by: kminoda * style(pre-commit): autofix * feat: add dummy typo Signed-off-by: kminoda * update name Signed-off-by: kminoda * fix test Signed-off-by: kminoda * fix test Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- launch/tier4_map_launch/launch/map.launch.py | 1 - .../include/map_loader/lanelet2_map_loader_node.hpp | 8 ++++++-- map/map_loader/package.xml | 2 ++ .../lanelet2_map_loader/lanelet2_map_loader_node.cpp | 11 +++++++---- .../map_projection_loader/map_projection_loader.hpp | 6 ++++-- .../launch/map_projection_loader.launch.xml | 1 - map/map_projection_loader/package.xml | 2 ++ .../src/map_projection_loader.cpp | 6 ++++-- .../test/test_node_load_local_from_yaml.test.py | 4 ++-- .../test/test_node_load_mgrs_from_yaml.test.py | 4 ++-- .../test/test_node_load_utm_from_yaml.test.py | 4 ++-- 11 files changed, 31 insertions(+), 18 deletions(-) diff --git a/launch/tier4_map_launch/launch/map.launch.py b/launch/tier4_map_launch/launch/map.launch.py index 169c53814df22..23bd2fc337c97 100644 --- a/launch/tier4_map_launch/launch/map.launch.py +++ b/launch/tier4_map_launch/launch/map.launch.py @@ -64,7 +64,6 @@ def launch_setup(context, *args, **kwargs): name="lanelet2_map_loader", remappings=[ ("output/lanelet2_map", "vector_map"), - ("input/map_projector_info", "map_projector_type"), ], parameters=[ { diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 2fb8b893d8fce..f422d3628fe2c 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -15,6 +15,8 @@ #ifndef MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ #define MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ +#include +#include #include #include @@ -41,9 +43,11 @@ class Lanelet2MapLoaderNode : public rclcpp::Node const rclcpp::Time & now); private: - void on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg); + using MapProjectorInfo = map_interface::MapProjectorInfo; - rclcpp::Subscription::SharedPtr sub_map_projector_type_; + void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); + + component_interface_utils::Subscription::SharedPtr sub_map_projector_type_; rclcpp::Publisher::SharedPtr pub_map_bin_; }; diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index 93b00cd412147..fbc2572d0bc6d 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -16,6 +16,8 @@ autoware_auto_mapping_msgs autoware_map_msgs + component_interface_specs + component_interface_utils fmt geometry_msgs lanelet2_extension diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index 42c46e2b5e96c..c935cd62b2fb6 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -51,13 +51,16 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options) : Node("lanelet2_map_loader", options) { + const auto adaptor = component_interface_utils::NodeAdaptor(this); + // subscription - sub_map_projector_type_ = create_subscription( - "input/map_projector_info", rclcpp::QoS{1}.transient_local(), - [this](const MapProjectorInfo::ConstSharedPtr msg) { on_map_projector_info(msg); }); + adaptor.init_sub( + sub_map_projector_type_, + [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); }); } -void Lanelet2MapLoaderNode::on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg) +void Lanelet2MapLoaderNode::on_map_projector_info( + const MapProjectorInfo::Message::ConstSharedPtr msg) { const auto lanelet2_filename = declare_parameter("lanelet2_map_path", ""); const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp index de19ac5dabda4..16442eb43c740 100644 --- a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp +++ b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp @@ -17,7 +17,8 @@ #include "rclcpp/rclcpp.hpp" -#include "tier4_map_msgs/msg/map_projector_info.hpp" +#include +#include #include @@ -29,7 +30,8 @@ class MapProjectionLoader : public rclcpp::Node MapProjectionLoader(); private: - rclcpp::Publisher::SharedPtr publisher_; + using MapProjectorInfo = map_interface::MapProjectorInfo; + component_interface_utils::Publisher::SharedPtr publisher_; }; #endif // MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/map_projection_loader/launch/map_projection_loader.launch.xml index 6448675c4a75f..fc625e3162911 100644 --- a/map/map_projection_loader/launch/map_projection_loader.launch.xml +++ b/map/map_projection_loader/launch/map_projection_loader.launch.xml @@ -3,7 +3,6 @@ - diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml index 84f66583ed840..823cea064515b 100644 --- a/map/map_projection_loader/package.xml +++ b/map/map_projection_loader/package.xml @@ -12,6 +12,8 @@ ament_cmake_auto autoware_cmake + component_interface_specs + component_interface_utils lanelet2_extension rclcpp rclcpp_components diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp index ccea8d7417cbc..6d1459c628e35 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -16,6 +16,8 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" +#include + #include #include @@ -64,7 +66,7 @@ MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") } // Publish the message - publisher_ = this->create_publisher( - "~/map_projector_info", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_pub(publisher_); publisher_->publish(msg); } diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py index aa0e3245565b5..721fd5f95e8f3 100644 --- a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map_projection_loader/map_projector_info", + "/map/map_projector_type", self.callback, custom_qos_profile, ) @@ -125,7 +125,7 @@ def test_node_link(self): get_package_share_directory("map_projection_loader"), YAML_FILE_PATH ) with open(map_projection_info_path) as f: - yaml_data = yaml.load(f) + yaml_data = yaml.load(f, Loader=yaml.FullLoader) # Test if message received self.assertIsNotNone( diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index ae29b4b06c61c..1805d59d54f65 100644 --- a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map_projection_loader/map_projector_info", + "/map/map_projector_type", self.callback, custom_qos_profile, ) @@ -125,7 +125,7 @@ def test_node_link(self): get_package_share_directory("map_projection_loader"), YAML_FILE_PATH ) with open(map_projection_info_path) as f: - yaml_data = yaml.load(f) + yaml_data = yaml.load(f, Loader=yaml.FullLoader) # Test if message received self.assertIsNotNone( diff --git a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py index 8da98bbb8b25d..1f92802231e37 100644 --- a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map_projection_loader/map_projector_info", + "/map/map_projector_type", self.callback, custom_qos_profile, ) @@ -125,7 +125,7 @@ def test_node_link(self): get_package_share_directory("map_projection_loader"), YAML_FILE_PATH ) with open(map_projection_info_path) as f: - yaml_data = yaml.load(f) + yaml_data = yaml.load(f, Loader=yaml.FullLoader) # Test if message received self.assertIsNotNone( From ab64a5ac477a040f24da8b04152743c32e60d212 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 18 Aug 2023 15:56:49 +0900 Subject: [PATCH 201/266] fix(avoidance): don't extend backward path if driving lane is updated (#4593) * fix(avoidance): don't extend backward path if driving lane is updated Signed-off-by: satoshi-ota * chore(avoidance): rename variables Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../avoidance/avoidance_module.hpp | 5 +- .../avoidance/avoidance_module.cpp | 210 ++++++++---------- 2 files changed, 98 insertions(+), 117 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index b2ed205680b45..fcde58756d4be 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -242,9 +242,8 @@ class AvoidanceModule : public SceneModuleInterface /** * @brief update main avoidance data for avoidance path generation based on latest planner data. - * @return avoidance data. */ - AvoidancePlanningData calcAvoidancePlanningData(DebugData & debug) const; + void fillFundamentalData(AvoidancePlanningData & data, DebugData & debug); /** * @brief fill additional data so that the module judges target objects. @@ -555,7 +554,7 @@ class AvoidanceModule : public SceneModuleInterface helper::avoidance::AvoidanceHelper helper_; - AvoidancePlanningData avoidance_data_; + AvoidancePlanningData avoid_data_; PathShifter path_shifter_; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 2a806bcb24cfe..4071edbdd5d24 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -117,30 +117,30 @@ bool AvoidanceModule::isExecutionRequested() const DEBUG_PRINT("AVOIDANCE isExecutionRequested"); // Check ego is in preferred lane - updateInfoMarker(avoidance_data_); - updateDebugMarker(avoidance_data_, path_shifter_, debug_data_); + updateInfoMarker(avoid_data_); + updateDebugMarker(avoid_data_, path_shifter_, debug_data_); // there is object that should be avoid. return true. - if (!!avoidance_data_.stop_target_object) { + if (!!avoid_data_.stop_target_object) { return true; } - if (avoidance_data_.unapproved_new_sl.empty()) { + if (avoid_data_.unapproved_new_sl.empty()) { return false; } - return !avoidance_data_.target_objects.empty(); + return !avoid_data_.target_objects.empty(); } bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return avoidance_data_.safe && avoidance_data_.comfortable; + return avoid_data_.safe && avoid_data_.comfortable; } bool AvoidanceModule::canTransitSuccessState() { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; // Change input lane. -> EXIT. if (!isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { @@ -190,73 +190,51 @@ bool AvoidanceModule::canTransitSuccessState() return false; // Keep current state. } -AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & debug) const +void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugData & debug) { - AvoidancePlanningData data; - // reference pose - const auto reference_pose = + data.reference_pose = utils::getUnshiftedEgoPose(getEgoPose(), helper_.getPreviousSplineShiftPath()); - data.reference_pose = reference_pose; - - // special for avoidance: take behind distance upt ot shift-start-point if it exist. - const auto longest_dist_to_shift_line = [&]() { - double max_dist = 0.0; - for (const auto & pnt : path_shifter_.getShiftLines()) { - max_dist = std::max(max_dist, calcDistance2d(getEgoPose(), pnt.start)); - } - for (const auto & sl : registered_raw_shift_lines_) { - max_dist = std::max(max_dist, calcDistance2d(getEgoPose(), sl.start)); - } - return max_dist; - }(); - // center line path (output of this function must have size > 1) - const auto center_path = utils::calcCenterLinePath( - planner_data_, reference_pose, longest_dist_to_shift_line, - *getPreviousModuleOutput().reference_path); - - debug.center_line = center_path; - if (center_path.points.size() < 2) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 5000, "calcCenterLinePath() must return path which size > 1"); - return data; - } + // lanelet info + data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( + *getPreviousModuleOutput().reference_path, planner_data_); // reference path - data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); + if (isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { + data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); + } else { + data.reference_path_rough = *getPreviousModuleOutput().path; + RCLCPP_WARN(getLogger(), "Previous module lane is updated. Don't use latest reference path."); + } + // resampled reference path data.reference_path = utils::resamplePathWithSpline( data.reference_path_rough, parameters_->resample_interval_for_planning); - if (data.reference_path.points.size() < 2) { - // if the resampled path has only 1 point, use original path. - data.reference_path = center_path; - } - - const size_t nearest_segment_index = - findNearestSegmentIndex(data.reference_path.points, data.reference_pose.position); - data.ego_closest_path_index = - std::min(nearest_segment_index + 1, data.reference_path.points.size() - 1); + // closest index + data.ego_closest_path_index = planner_data_->findEgoIndex(data.reference_path.points); // arclength from ego pose (used in many functions) data.arclength_from_ego = utils::calcPathArcLengthArray( data.reference_path, 0, data.reference_path.points.size(), calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); - // lanelet info - data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( - *getPreviousModuleOutput().reference_path, planner_data_); - - // keep avoidance state - data.state = avoidance_data_.state; - // target objects for avoidance fillAvoidanceTargetObjects(data, debug); - DEBUG_PRINT("target object size = %lu", data.target_objects.size()); + // lost object compensation + utils::avoidance::updateRegisteredObject(registered_objects_, data.target_objects, parameters_); + utils::avoidance::compensateDetectionLost( + registered_objects_, data.target_objects, data.other_objects); + + // sort object order by longitudinal distance + std::sort(data.target_objects.begin(), data.target_objects.end(), [](auto a, auto b) { + return a.longitudinal < b.longitudinal; + }); - return data; + // set base path + path_shifter_.setPath(data.reference_path); } void AvoidanceModule::fillAvoidanceTargetObjects( @@ -648,7 +626,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif void AvoidanceModule::updateRegisteredRawShiftLines() { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; utils::avoidance::fillAdditionalInfoFromPoint(data, registered_raw_shift_lines_); @@ -771,7 +749,7 @@ void AvoidanceModule::registerRawShiftLines(const AvoidLineArray & future) const auto old_size = registered_raw_shift_lines_.size(); auto future_with_info = future; - utils::avoidance::fillAdditionalInfoFromPoint(avoidance_data_, future_with_info); + utils::avoidance::fillAdditionalInfoFromPoint(avoid_data_, future_with_info); printShiftLines(future_with_info, "future_with_info"); printShiftLines(registered_raw_shift_lines_, "registered_raw_shift_lines_"); printShiftLines(current_raw_shift_lines_, "current_raw_shift_lines_"); @@ -966,13 +944,13 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( { const auto offset = object_parameter.safety_buffer_longitudinal + base_link2front; const auto path_front_to_ego = - avoidance_data_.arclength_from_ego.at(avoidance_data_.ego_closest_path_index); + avoid_data_.arclength_from_ego.at(avoid_data_.ego_closest_path_index); al_avoid.start_longitudinal = std::max(o.longitudinal - offset - feasible_avoid_distance, 1e-3); al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength( - avoidance_data_.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); - al_avoid.start = avoidance_data_.reference_path.points.at(al_avoid.start_idx).point.pose; + avoid_data_.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); + al_avoid.start = avoid_data_.reference_path.points.at(al_avoid.start_idx).point.pose; al_avoid.start_shift_length = helper_.getLinearShift(al_avoid.start.position); al_avoid.end_shift_length = feasible_shift_length.get(); @@ -1038,8 +1016,8 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( void AvoidanceModule::generateTotalShiftLine( const AvoidLineArray & avoid_lines, ShiftLineData & shift_line_data) const { - const auto & path = avoidance_data_.reference_path; - const auto & arcs = avoidance_data_.arclength_from_ego; + const auto & path = avoid_data_.reference_path; + const auto & arcs = avoid_data_.arclength_from_ego; const auto N = path.points.size(); auto & sl = shift_line_data; @@ -1089,7 +1067,7 @@ void AvoidanceModule::generateTotalShiftLine( // overwrite shift with current_ego_shift until ego pose. const auto current_shift = helper_.getEgoLinearShift(); for (size_t i = 0; i < sl.shift_line.size(); ++i) { - if (avoidance_data_.ego_closest_path_index < i) { + if (avoid_data_.ego_closest_path_index < i) { break; } sl.shift_line.at(i) = current_shift; @@ -1119,7 +1097,7 @@ void AvoidanceModule::generateTotalShiftLine( const auto grad_first_shift_line = (avoid_lines.front().start_shift_length - current_shift) / avoid_lines.front().start_longitudinal; - for (size_t i = avoidance_data_.ego_closest_path_index; i <= avoid_lines.front().start_idx; ++i) { + for (size_t i = avoid_data_.ego_closest_path_index; i <= avoid_lines.front().start_idx; ++i) { sl.shift_line.at(i) = helper_.getLinearShift(getPoint(path.points.at(i))); sl.shift_line_grad.at(i) = grad_first_shift_line; } @@ -1132,8 +1110,8 @@ AvoidLineArray AvoidanceModule::extractShiftLinesFromLine(ShiftLineData & shift_ using utils::avoidance::setEndData; using utils::avoidance::setStartData; - const auto & path = avoidance_data_.reference_path; - const auto & arcs = avoidance_data_.arclength_from_ego; + const auto & path = avoid_data_.reference_path; + const auto & arcs = avoid_data_.arclength_from_ego; const auto N = path.points.size(); auto & sl = shift_line_data; @@ -1174,7 +1152,7 @@ AvoidLineArray AvoidanceModule::extractShiftLinesFromLine(ShiftLineData & shift_ bool found_first_start = false; constexpr auto CREATE_SHIFT_GRAD_THR = 0.001; constexpr auto IS_ALREADY_SHIFTING_THR = 0.001; - for (size_t i = avoidance_data_.ego_closest_path_index; i < N - 1; ++i) { + for (size_t i = avoid_data_.ego_closest_path_index; i < N - 1; ++i) { const auto & p = path.points.at(i).point.pose; const auto shift = sl.shift_line.at(i); @@ -1258,7 +1236,7 @@ void AvoidanceModule::fillShiftLineGap(AvoidLineArray & shift_lines) const return; } - const auto & data = avoidance_data_; + const auto & data = avoid_data_; helper_.alignShiftLinesOrder(shift_lines, false); @@ -1328,8 +1306,8 @@ AvoidLineArray AvoidanceModule::mergeShiftLines( // debug print { - const auto & arc = avoidance_data_.arclength_from_ego; - const auto & closest = avoidance_data_.ego_closest_path_index; + const auto & arc = avoid_data_.arclength_from_ego; + const auto & closest = avoid_data_.ego_closest_path_index; const auto & sl = shift_line_data.shift_line; const auto & sg = shift_line_data.shift_line_grad; const auto & fg = shift_line_data.forward_grad; @@ -1668,7 +1646,7 @@ void AvoidanceModule::trimSharpReturn(AvoidLineArray & shift_lines, const double void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) const { constexpr double ep = 1.0e-3; - const auto & data = avoidance_data_; + const auto & data = avoid_data_; const bool has_candidate_point = !sl_candidates.empty(); const bool has_registered_point = !path_shifter_.getShiftLines().empty(); @@ -1716,8 +1694,8 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) // avoidance points: No, shift points: No -> set the ego position to the last shift point // so that the return-shift will be generated from ego position. if (!has_candidate_point && !has_registered_point) { - last_sl.end_idx = avoidance_data_.ego_closest_path_index; - last_sl.end = avoidance_data_.reference_path.points.at(last_sl.end_idx).point.pose; + last_sl.end_idx = avoid_data_.ego_closest_path_index; + last_sl.end = avoid_data_.reference_path.points.at(last_sl.end_idx).point.pose; last_sl.end_shift_length = getCurrentBaseShift(); } } @@ -1758,12 +1736,12 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) // set the return-shift from ego. DEBUG_PRINT( "return shift already exists, but they are all candidates. Add return shift for overwrite."); - last_sl.end_idx = avoidance_data_.ego_closest_path_index; - last_sl.end = avoidance_data_.reference_path.points.at(last_sl.end_idx).point.pose; + last_sl.end_idx = avoid_data_.ego_closest_path_index; + last_sl.end = avoid_data_.reference_path.points.at(last_sl.end_idx).point.pose; last_sl.end_shift_length = current_base_shift; } - const auto & arclength_from_ego = avoidance_data_.arclength_from_ego; + const auto & arclength_from_ego = avoid_data_.arclength_from_ego; const auto nominal_prepare_distance = helper_.getNominalPrepareDistance(); const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(last_sl.end_shift_length); @@ -1775,7 +1753,7 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) const auto remaining_distance = arclength_from_ego.back() - parameters_->remain_buffer_distance; // If the avoidance point has already been set, the return shift must be set after the point. - const auto last_sl_distance = avoidance_data_.arclength_from_ego.at(last_sl.end_idx); + const auto last_sl_distance = avoid_data_.arclength_from_ego.at(last_sl.end_idx); // check if there is enough distance for return. if (last_sl_distance > remaining_distance) { // tmp: add some small number (+1.0) @@ -1828,7 +1806,7 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) al.start_longitudinal = arclength_from_ego.at(al.start_idx); al.end_idx = utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); - al.end = avoidance_data_.reference_path.points.at(al.end_idx).point.pose; + al.end = avoid_data_.reference_path.points.at(al.end_idx).point.pose; al.end_longitudinal = arclength_from_ego.at(al.end_idx); al.end_shift_length = last_sl.end_shift_length; al.start_shift_length = last_sl.end_shift_length; @@ -1843,11 +1821,11 @@ void AvoidanceModule::addReturnShiftLineFromEgo(AvoidLineArray & sl_candidates) al.id = getOriginalShiftLineUniqueId(); al.start_idx = utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); - al.start = avoidance_data_.reference_path.points.at(al.start_idx).point.pose; + al.start = avoid_data_.reference_path.points.at(al.start_idx).point.pose; al.start_longitudinal = arclength_from_ego.at(al.start_idx); al.end_idx = utils::avoidance::findPathIndexFromArclength( arclength_from_ego, prepare_distance_scaled + avoid_distance_scaled); - al.end = avoidance_data_.reference_path.points.at(al.end_idx).point.pose; + al.end = avoid_data_.reference_path.points.at(al.end_idx).point.pose; al.end_longitudinal = arclength_from_ego.at(al.end_idx); al.end_shift_length = 0.0; al.start_shift_length = last_sl.end_shift_length; @@ -1893,7 +1871,7 @@ bool AvoidanceModule::isSafePath( } const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects( - avoidance_data_, planner_data_, parameters_, is_right_shift.value()); + avoid_data_, planner_data_, parameters_, is_right_shift.value()); for (const auto & object : safety_check_target_objects) { const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( @@ -1921,7 +1899,7 @@ void AvoidanceModule::generateExtendedDrivableArea(BehaviorModuleOutput & output }; const auto & route_handler = planner_data_->route_handler; - const auto & current_lanes = avoidance_data_.current_lanelets; + const auto & current_lanes = avoid_data_.current_lanelets; const auto & enable_opposite = parameters_->use_opposite_lane; std::vector drivable_lanes; @@ -2062,7 +2040,7 @@ void AvoidanceModule::generateExtendedDrivableArea(BehaviorModuleOutput & output // generate obstacle polygons current_drivable_area_info.obstacles = utils::avoidance::generateObstaclePolygonsForDrivableArea( - avoidance_data_.target_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0); + avoid_data_.target_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0); // expand hatched road markings current_drivable_area_info.enable_expanding_hatched_road_markings = parameters_->use_hatched_road_markings; @@ -2130,7 +2108,7 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig BehaviorModuleOutput AvoidanceModule::plan() { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; resetPathCandidate(); resetPathReference(); @@ -2178,16 +2156,22 @@ BehaviorModuleOutput AvoidanceModule::plan() spline_shift_path.path, parameters_->resample_interval_for_output); } - avoidance_data_.state = updateEgoState(data); + avoid_data_.state = updateEgoState(data); // update output data { updateEgoBehavior(data, spline_shift_path); - updateInfoMarker(avoidance_data_); - updateDebugMarker(avoidance_data_, path_shifter_, debug_data_); + updateInfoMarker(avoid_data_); + updateDebugMarker(avoid_data_, path_shifter_, debug_data_); + } + + if (isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { + output.path = std::make_shared(spline_shift_path.path); + } else { + output.path = getPreviousModuleOutput().path; + RCLCPP_WARN(getLogger(), "Previous module lane is updated. Do nothing."); } - output.path = std::make_shared(spline_shift_path.path); output.reference_path = getPreviousModuleOutput().reference_path; path_reference_ = getPreviousModuleOutput().reference_path; @@ -2203,7 +2187,7 @@ BehaviorModuleOutput AvoidanceModule::plan() CandidateOutput AvoidanceModule::planCandidate() const { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; CandidateOutput output; @@ -2273,7 +2257,7 @@ void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) addNewShiftLines(path_shifter_, shift_lines); - current_raw_shift_lines_ = avoidance_data_.unapproved_raw_sl; + current_raw_shift_lines_ = avoid_data_.unapproved_raw_sl; registerRawShiftLines(shift_lines); @@ -2348,9 +2332,8 @@ void AvoidanceModule::addNewShiftLines( future.push_back(sl); } - const double road_velocity = - avoidance_data_.reference_path.points.at(front_new_shift_line.start_idx) - .point.longitudinal_velocity_mps; + const double road_velocity = avoid_data_.reference_path.points.at(front_new_shift_line.start_idx) + .point.longitudinal_velocity_mps; const double shift_time = PathShifter::calcShiftTimeFromJerk( front_new_shift_line.getRelativeLength(), helper_.getLateralMaxJerkLimit(), helper_.getLateralMaxAccelLimit()); @@ -2495,30 +2478,29 @@ void AvoidanceModule::updateData() } debug_data_ = DebugData(); - avoidance_data_ = calcAvoidancePlanningData(debug_data_); - if (avoidance_data_.reference_path.points.empty()) { - // an empty path will kill further processing - return; - } - - utils::avoidance::updateRegisteredObject( - registered_objects_, avoidance_data_.target_objects, parameters_); - utils::avoidance::compensateDetectionLost( - registered_objects_, avoidance_data_.target_objects, avoidance_data_.other_objects); + avoid_data_ = AvoidancePlanningData(); - std::sort( - avoidance_data_.target_objects.begin(), avoidance_data_.target_objects.end(), - [](auto a, auto b) { return a.longitudinal < b.longitudinal; }); + // update base path and target objects. + fillFundamentalData(avoid_data_, debug_data_); - path_shifter_.setPath(avoidance_data_.reference_path); + // an empty path will kill further processing + if (avoid_data_.reference_path.points.empty()) { + return; + } // update registered shift point for new reference path & remove past objects updateRegisteredRawShiftLines(); - fillShiftLine(avoidance_data_, debug_data_); - fillEgoStatus(avoidance_data_, debug_data_); - fillDebugData(avoidance_data_, debug_data_); + // update shift line and check path safety. + fillShiftLine(avoid_data_, debug_data_); + + // update ego behavior. + fillEgoStatus(avoid_data_, debug_data_); + + // update debug data. + fillDebugData(avoid_data_, debug_data_); + // update rtc status. updateRTCData(); } @@ -2560,7 +2542,7 @@ void AvoidanceModule::initRTCStatus() void AvoidanceModule::updateRTCData() { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; updateRegisteredRTCStatus(helper_.getPreviousSplineShiftPath().path); @@ -2880,7 +2862,7 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const void AvoidanceModule::insertWaitPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; if (!data.stop_target_object) { return; @@ -2923,7 +2905,7 @@ void AvoidanceModule::insertWaitPoint( void AvoidanceModule::insertStopPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; if (data.safe) { return; @@ -2971,7 +2953,7 @@ void AvoidanceModule::insertStopPoint( void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const { const auto & p = parameters_; - const auto & data = avoidance_data_; + const auto & data = avoid_data_; if (data.target_objects.empty()) { return; @@ -2988,7 +2970,7 @@ void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const { - const auto & data = avoidance_data_; + const auto & data = avoid_data_; // do nothing if there is no avoidance target. if (data.target_objects.empty()) { From 414a2ba43dfd5427ea35eed3a929cae119908b2b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 18 Aug 2023 16:43:27 +0900 Subject: [PATCH 202/266] fix(behavior_path_planner): add fallback for splitting the dynamic drivable area into left and right bounds (#4646) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 43 ++++++++++++++++--- .../test/test_drivable_area_expansion.cpp | 13 +++--- 2 files changed, 43 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 617c3cd633cda..2b62d5e7c3b53 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -200,11 +200,39 @@ void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_ end_right.update(*inter_end, it, dist); } } - if ( // ill-formed expanded drivable area -> keep the original bounds - start_left.segment_it == da.end() || start_right.segment_it == da.end() || - end_left.segment_it == da.end() || end_right.segment_it == da.end()) { - return; + if (start_left.segment_it == da.end()) { + const auto closest_it = + std::min_element(da.begin(), da.end(), [&](const auto & a, const auto & b) { + return boost::geometry::distance(a, start_segment.first) < + boost::geometry::distance(b, start_segment.first); + }); + start_left.update(*closest_it, closest_it, 0.0); } + if (start_right.segment_it == da.end()) { + const auto closest_it = + std::min_element(da.begin(), da.end(), [&](const auto & a, const auto & b) { + return boost::geometry::distance(a, start_segment.second) < + boost::geometry::distance(b, start_segment.second); + }); + start_right.update(*closest_it, closest_it, 0.0); + } + if (end_left.segment_it == da.end()) { + const auto closest_it = + std::min_element(da.begin(), da.end(), [&](const auto & a, const auto & b) { + return boost::geometry::distance(a, end_segment.first) < + boost::geometry::distance(b, end_segment.first); + }); + end_left.update(*closest_it, closest_it, 0.0); + } + if (end_right.segment_it == da.end()) { + const auto closest_it = + std::min_element(da.begin(), da.end(), [&](const auto & a, const auto & b) { + return boost::geometry::distance(a, end_segment.second) < + boost::geometry::distance(b, end_segment.second); + }); + end_right.update(*closest_it, closest_it, 0.0); + } + // extract the expanded left and right bound from the expanded drivable area path.left_bound.clear(); path.right_bound.clear(); @@ -238,8 +266,11 @@ void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_ const auto point_cmp = [](const auto & p1, const auto & p2) { return p1.x == p2.x && p1.y == p2.y; }; - std::unique(path.left_bound.begin(), path.left_bound.end(), point_cmp); - std::unique(path.right_bound.begin(), path.right_bound.end(), point_cmp); + path.left_bound.erase( + std::unique(path.left_bound.begin(), path.left_bound.end(), point_cmp), path.left_bound.end()); + path.right_bound.erase( + std::unique(path.right_bound.begin(), path.right_bound.end(), point_cmp), + path.right_bound.end()); copy_z_over_arc_length(original_left_bound, path.left_bound); copy_z_over_arc_length(original_right_bound, path.right_bound); } diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index b02df9753e0b5..605b3b96ee9b9 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -266,7 +266,6 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) params.ego_right_offset = -2.0; } // we expect the drivable area to be expanded by 1m on each side - // BUT short paths, due to pruning at the edge of the driving area, there is no expansion drivable_area_expansion::expandDrivableArea( path, params, dynamic_objects, route_handler, path_lanes); // unchanged path points @@ -280,16 +279,16 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) ASSERT_EQ(path.left_bound.size(), 3ul); EXPECT_NEAR(path.left_bound[0].x, 0.0, eps); EXPECT_NEAR(path.left_bound[0].y, 1.0, eps); - EXPECT_NEAR(path.left_bound[1].x, 1.0, eps); - EXPECT_NEAR(path.left_bound[1].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[1].x, 0.0, eps); + EXPECT_NEAR(path.left_bound[1].y, 2.0, eps); EXPECT_NEAR(path.left_bound[2].x, 2.0, eps); - EXPECT_NEAR(path.left_bound[2].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[2].y, 2.0, eps); // expanded right bound ASSERT_EQ(path.right_bound.size(), 3ul); EXPECT_NEAR(path.right_bound[0].x, 0.0, eps); - EXPECT_NEAR(path.right_bound[0].y, -1.0, eps); - EXPECT_NEAR(path.right_bound[1].x, 1.0, eps); - EXPECT_NEAR(path.right_bound[1].y, -1.0, eps); + EXPECT_NEAR(path.right_bound[0].y, -2.0, eps); + EXPECT_NEAR(path.right_bound[1].x, 2.0, eps); + EXPECT_NEAR(path.right_bound[1].y, -2.0, eps); EXPECT_NEAR(path.right_bound[2].x, 2.0, eps); EXPECT_NEAR(path.right_bound[2].y, -1.0, eps); } From 04ca20c69ad52ecc9f449550b767fb3b11f57b7e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 18 Aug 2023 18:44:53 +0900 Subject: [PATCH 203/266] feat(behavior_path_planner): add combineLanelets (#4657) * feat(behavior_path_planner): add combineLanelets Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/utils/utils.cpp --------- Signed-off-by: kosuke55 --- .../behavior_path_planner/utils/utils.hpp | 3 +++ .../behavior_path_planner/src/utils/utils.cpp | 17 +++++++++++++++++ 2 files changed, 20 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 784258e31b265..d27d9ebbdadec 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -402,6 +402,9 @@ void makeBoundLongitudinallyMonotonic( std::optional getPolygonByPoint( const std::shared_ptr & route_handler, const lanelet::ConstPoint3d & point, const std::string & polygon_name); + +lanelet::ConstLanelets combineLanelets( + const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes); } // namespace behavior_path_planner::utils #endif // BEHAVIOR_PATH_PLANNER__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index b1f5afc119b39..dbbab9f040cfa 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3246,4 +3246,21 @@ void extractObstaclesFromDrivableArea( bound = drivable_area_processing::updateBoundary(bound, unique_polygons); } } + +lanelet::ConstLanelets combineLanelets( + const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes) +{ + lanelet::ConstLanelets combined_lanes = base_lanes; + for (const auto & added_lane : added_lanes) { + const auto it = std::find_if( + combined_lanes.begin(), combined_lanes.end(), + [&added_lane](const lanelet::ConstLanelet & lane) { return lane.id() == added_lane.id(); }); + if (it == combined_lanes.end()) { + combined_lanes.push_back(added_lane); + } + } + + return combined_lanes; +} + } // namespace behavior_path_planner::utils From 93478b72c016000afb20f8ee866e4cd065c9afe9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 18 Aug 2023 19:04:07 +0900 Subject: [PATCH 204/266] fix(avoidance): fix build error (#4667) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 4071edbdd5d24..3550b2035248a 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1223,7 +1223,7 @@ AvoidLineArray AvoidanceModule::getFillGapShiftLines(const AvoidLineArray & shif ret.push_back(calc_gap_shift_line(shift_lines.at(i), shift_lines.at(i + 1))); } - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoidance_data_, ret); + utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, ret); return ret; } From 5ed7ca387bedf3c46e616ca8bac5a29a97fe6b10 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 19 Aug 2023 01:32:05 +0900 Subject: [PATCH 205/266] feat(goal_planner): add lane ids to freespace path (#4668) Signed-off-by: kosuke55 --- .../utils/goal_planner/freespace_pull_over.hpp | 1 + .../behavior_path_planner/utils/path_utils.hpp | 3 ++- .../utils/goal_planner/freespace_pull_over.cpp | 16 ++++++++++++++-- .../src/utils/path_utils.cpp | 9 +++++++-- 4 files changed, 24 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp index 1378be5461a64..b698892907789 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp @@ -47,6 +47,7 @@ class FreespacePullOver : public PullOverPlannerBase std::unique_ptr planner_; double velocity_; bool use_back_; + bool left_side_parking_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp index bdca6a2fdf085..191cd3e10def5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp @@ -75,7 +75,8 @@ std::pair getPathTurnSignal( const BehaviorPathPlannerParameters & common_parameter); PathWithLaneId convertWayPointsToPathWithLaneId( - const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity); + const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, + const lanelet::ConstLanelets & lanelets); std::vector getReversingIndices(const PathWithLaneId & path); diff --git a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp index ebfac8a347134..f4aabb13b8916 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp @@ -25,7 +25,9 @@ namespace behavior_path_planner FreespacePullOver::FreespacePullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, const vehicle_info_util::VehicleInfo & vehicle_info) -: PullOverPlannerBase{node, parameters}, velocity_{parameters.freespace_parking_velocity} +: PullOverPlannerBase{node, parameters}, + velocity_{parameters.freespace_parking_velocity}, + left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { freespace_planning_algorithms::VehicleShape vehicle_shape( vehicle_info, parameters.vehicle_shape_margin); @@ -58,8 +60,18 @@ boost::optional FreespacePullOver::plan(const Pose & goal_pose) return {}; } + const auto road_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + /*forward_only_in_route*/ false); + const auto pull_over_lanes = + goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_); + if (road_lanes.empty() || pull_over_lanes.empty()) { + return {}; + } + const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes); + PathWithLaneId path = - utils::convertWayPointsToPathWithLaneId(planner_->getWaypoints(), velocity_); + utils::convertWayPointsToPathWithLaneId(planner_->getWaypoints(), velocity_, lanes); const auto reverse_indices = utils::getReversingIndices(path); std::vector partial_paths = utils::dividePath(path, reverse_indices); diff --git a/planning/behavior_path_planner/src/utils/path_utils.cpp b/planning/behavior_path_planner/src/utils/path_utils.cpp index d2d70b0a46dfc..d455cd66ae769 100644 --- a/planning/behavior_path_planner/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/src/utils/path_utils.cpp @@ -336,14 +336,19 @@ std::pair getPathTurnSignal( } PathWithLaneId convertWayPointsToPathWithLaneId( - const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity) + const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, + const lanelet::ConstLanelets & lanelets) { PathWithLaneId path; path.header = waypoints.header; for (const auto & waypoint : waypoints.waypoints) { PathPointWithLaneId point{}; point.point.pose = waypoint.pose.pose; - // point.lane_id = // todo + for (const auto & lane : lanelets) { + if (lanelet::utils::isInLanelet(point.point.pose, lane)) { + point.lane_ids.push_back(lane.id()); + } + } point.point.longitudinal_velocity_mps = (waypoint.is_back ? -1 : 1) * velocity; path.points.push_back(point); } From bc86f0e3216eb2fdc93640fddd468a975eb632e8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 20 Aug 2023 01:59:26 +0900 Subject: [PATCH 206/266] feat(obstacle_stop_planner): consider object velocity direction (#4648) * feat(obstacle_stop_planner): consider object velocity direction Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/adaptive_cruise_control.cpp | 27 ++++++++++++------- 1 file changed, 18 insertions(+), 9 deletions(-) diff --git a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp index bc3e07cf8dd74..fb1e93185f738 100644 --- a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -414,23 +414,27 @@ bool AdaptiveCruiseController::estimatePointVelocityFromObject( /* get object velocity, and current yaw */ bool get_obj = false; - double obj_vel; - double obj_yaw; + double obj_vel_norm; + double obj_vel_yaw; const Point collision_point_2d = convertPointRosToBoost(nearest_collision_p_ros); for (const auto & obj : object_ptr->objects) { const Polygon obj_poly = getPolygon( obj.kinematics.initial_pose_with_covariance.pose, obj.shape.dimensions, 0.0, param_.object_polygon_length_margin, param_.object_polygon_width_margin); if (boost::geometry::distance(obj_poly, collision_point_2d) <= 0) { - obj_vel = obj.kinematics.initial_twist_with_covariance.twist.linear.x; - obj_yaw = tf2::getYaw(obj.kinematics.initial_pose_with_covariance.pose.orientation); + obj_vel_norm = std::hypot( + obj.kinematics.initial_twist_with_covariance.twist.linear.x, + obj.kinematics.initial_twist_with_covariance.twist.linear.y); + obj_vel_yaw = std::atan2( + obj.kinematics.initial_twist_with_covariance.twist.linear.y, + obj.kinematics.initial_twist_with_covariance.twist.linear.x); get_obj = true; break; } } if (get_obj) { - *velocity = obj_vel * std::cos(obj_yaw - traj_yaw); + *velocity = obj_vel_norm * std::cos(obj_vel_yaw - traj_yaw); debug_values_.data.at(DBGVAL::ESTIMATED_VEL_OBJ) = *velocity; return true; } else { @@ -442,10 +446,15 @@ void AdaptiveCruiseController::calculateProjectedVelocityFromObject( const PredictedObject & object, const double traj_yaw, double * velocity) { /* get object velocity, and current yaw */ - double obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear.x; - double obj_yaw = tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation); - - *velocity = obj_vel * std::cos(tier4_autoware_utils::normalizeRadian(obj_yaw - traj_yaw)); + double obj_vel_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + double obj_vel_yaw = std::atan2( + object.kinematics.initial_twist_with_covariance.twist.linear.y, + object.kinematics.initial_twist_with_covariance.twist.linear.x); + + *velocity = + obj_vel_norm * std::cos(tier4_autoware_utils::normalizeRadian(obj_vel_yaw - traj_yaw)); debug_values_.data.at(DBGVAL::ESTIMATED_VEL_OBJ) = *velocity; } From 9dc104fd135539a67dc42fdc8d92e4df1e657d17 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 20 Aug 2023 10:31:41 +0900 Subject: [PATCH 207/266] feat(start_planner): support freespace pull out (#4610) feat(start_planner): add freespace pull out Signed-off-by: kosuke55 --- planning/behavior_path_planner/CMakeLists.txt | 1 + .../start_planner/start_planner.param.yaml | 36 ++++ .../start_planner/start_planner_module.hpp | 19 +- .../start_planner/freespace_pull_out.hpp | 53 +++++ .../start_planner/pull_out_planner_base.hpp | 1 + .../start_planner_parameters.hpp | 20 ++ .../scene_module/start_planner/manager.cpp | 80 +++++++ .../start_planner/start_planner_module.cpp | 204 +++++++++++++----- .../start_planner/freespace_pull_out.cpp | 115 ++++++++++ 9 files changed, 473 insertions(+), 56 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp create mode 100644 planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index fac0e921c1072..0352096d02b2b 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -44,6 +44,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/utils/start_planner/util.cpp src/utils/start_planner/shift_pull_out.cpp src/utils/start_planner/geometric_pull_out.cpp + src/utils/start_planner/freespace_pull_out.cpp src/utils/path_shifter/path_shifter.cpp src/utils/drivable_area_expansion/drivable_area_expansion.cpp src/utils/drivable_area_expansion/map_utils.cpp diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 60f292744025d..bea78664c65a3 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -36,3 +36,39 @@ th_turn_signal_on_lateral_offset: 1.0 intersection_search_length: 30.0 length_ratio_for_turn_signal_deactivation_near_intersection: 0.5 + # freespace planner + freespace_planner: + enable_freespace_planner: true + end_pose_search_start_distance: 20.0 + end_pose_search_end_distance: 30.0 + end_pose_search_interval: 2.0 + freespace_planner_algorithm: "astar" # options: astar, rrtstar + velocity: 1.0 + vehicle_shape_margin: 1.0 + time_limit: 3000.0 + minimum_turning_radius: 5.0 + maximum_turning_radius: 5.0 + turning_radius_size: 1 + # search configs + search_configs: + theta_size: 144 + angle_goal_range: 6.0 + curve_weight: 1.2 + reverse_weight: 1.0 + lateral_goal_range: 0.5 + longitudinal_goal_range: 2.0 + # costmap configs + costmap_configs: + obstacle_threshold: 30 + # -- A* search Configurations -- + astar: + only_behind_solutions: false + use_back: false + distance_heuristic_weight: 1.0 + # -- RRT* search Configurations -- + rrtstar: + enable_update: true + use_informed_sampling: true + max_planning_time: 150.0 + neighbor_radius: 8.0 + margin: 1.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index e4e3468b45ff6..40f0dc0289cf0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" +#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" #include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" #include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" @@ -96,7 +97,9 @@ class StartPlannerModule : public SceneModuleInterface { } + // Condition to disable simultaneous execution bool isBackFinished() const { return status_.back_finished; } + bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; } private: bool canTransitSuccessState() override { return false; } @@ -117,7 +120,15 @@ class StartPlannerModule : public SceneModuleInterface std::unique_ptr last_pull_out_start_update_time_; std::unique_ptr last_approved_pose_; - std::shared_ptr getCurrentPlanner() const; + // generate freespace pull out paths in a separate thread + std::unique_ptr freespace_planner_; + rclcpp::TimerBase::SharedPtr freespace_planner_timer_; + rclcpp::CallbackGroup::SharedPtr freespace_planner_timer_cb_group_; + // TODO(kosuke55) + // Currently, we only do lock when updating a member of status_. + // However, we need to ensure that the value does not change when referring to it. + std::mutex mutex_; + PathWithLaneId getFullPath() const; std::vector searchPullOutStartPoses(); @@ -141,7 +152,9 @@ class StartPlannerModule : public SceneModuleInterface bool hasFinishedPullOut() const; void checkBackFinished(); bool isStopped(); + bool isStuck(); bool hasFinishedCurrentPath(); + void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // check if the goal is located behind the ego in the same route segment. bool IsGoalBehindOfEgoInSameRouteSegment() const; @@ -149,6 +162,10 @@ class StartPlannerModule : public SceneModuleInterface // generate BehaviorPathOutput with stopping path and update status BehaviorModuleOutput generateStopOutput(); + // freespace planner + void onFreespacePlannerTimer(); + bool planFreespacePath(); + void setDebugData() const; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp new file mode 100644 index 0000000000000..abdf17c9c6cfe --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp @@ -0,0 +1,53 @@ +// Copyright 2023 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 BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ + +#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" + +#include +#include +#include + +#include + +#include +#include + +namespace behavior_path_planner +{ +using freespace_planning_algorithms::AbstractPlanningAlgorithm; +using freespace_planning_algorithms::AstarSearch; +using freespace_planning_algorithms::RRTStar; + +class FreespacePullOut : public PullOutPlannerBase +{ +public: + FreespacePullOut( + rclcpp::Node & node, const StartPlannerParameters & parameters, + const vehicle_info_util::VehicleInfo & vehicle_info); + + PlannerType getPlannerType() override { return PlannerType::FREESPACE; } + + boost::optional plan(Pose start_pose, Pose end_pose) override; + +protected: + std::unique_ptr planner_; + double velocity_; + bool use_back_; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp index 3a2087083b427..6e6e5111e5dd9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp @@ -40,6 +40,7 @@ enum class PlannerType { SHIFT = 1, GEOMETRIC = 2, STOP = 3, + FREESPACE = 4, }; class PullOutPlannerBase diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 9abad1a2fbec6..1e26bef0c85be 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -18,11 +18,20 @@ #include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include +#include +#include + #include #include namespace behavior_path_planner { + +using freespace_planning_algorithms::AstarParam; +using freespace_planning_algorithms::PlannerCommonParam; +using freespace_planning_algorithms::RRTStarParam; + struct StartPlannerParameters { double th_arrived_distance; @@ -56,6 +65,17 @@ struct StartPlannerParameters double backward_search_resolution; double backward_path_update_duration; double ignore_distance_from_lane_end; + // freespace planner + bool enable_freespace_planner; + std::string freespace_planner_algorithm; + double end_pose_search_start_distance; + double end_pose_search_end_distance; + double end_pose_search_interval; + double freespace_planner_velocity; + double vehicle_shape_margin; + PlannerCommonParam freespace_planner_common_parameters; + AstarParam astar_parameters; + RRTStarParam rrt_star_parameters; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index b2e872416672e..9d2da0d13f56b 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -78,6 +78,75 @@ StartPlannerModuleManager::StartPlannerModuleManager( node->declare_parameter(ns + "backward_path_update_duration"); p.ignore_distance_from_lane_end = node->declare_parameter(ns + "ignore_distance_from_lane_end"); + // freespace planner general params + { + std::string ns = "start_planner.freespace_planner."; + p.enable_freespace_planner = node->declare_parameter(ns + "enable_freespace_planner"); + p.freespace_planner_algorithm = + node->declare_parameter(ns + "freespace_planner_algorithm"); + p.end_pose_search_start_distance = + node->declare_parameter(ns + "end_pose_search_start_distance"); + p.end_pose_search_end_distance = + node->declare_parameter(ns + "end_pose_search_end_distance"); + p.end_pose_search_interval = node->declare_parameter(ns + "end_pose_search_interval"); + p.freespace_planner_velocity = node->declare_parameter(ns + "velocity"); + p.vehicle_shape_margin = node->declare_parameter(ns + "vehicle_shape_margin"); + p.freespace_planner_common_parameters.time_limit = + node->declare_parameter(ns + "time_limit"); + p.freespace_planner_common_parameters.minimum_turning_radius = + node->declare_parameter(ns + "minimum_turning_radius"); + p.freespace_planner_common_parameters.maximum_turning_radius = + node->declare_parameter(ns + "maximum_turning_radius"); + p.freespace_planner_common_parameters.turning_radius_size = + node->declare_parameter(ns + "turning_radius_size"); + p.freespace_planner_common_parameters.maximum_turning_radius = std::max( + p.freespace_planner_common_parameters.maximum_turning_radius, + p.freespace_planner_common_parameters.minimum_turning_radius); + p.freespace_planner_common_parameters.turning_radius_size = + std::max(p.freespace_planner_common_parameters.turning_radius_size, 1); + } + // freespace planner search config + { + std::string ns = "start_planner.freespace_planner.search_configs."; + p.freespace_planner_common_parameters.theta_size = + node->declare_parameter(ns + "theta_size"); + p.freespace_planner_common_parameters.angle_goal_range = + node->declare_parameter(ns + "angle_goal_range"); + p.freespace_planner_common_parameters.curve_weight = + node->declare_parameter(ns + "curve_weight"); + p.freespace_planner_common_parameters.reverse_weight = + node->declare_parameter(ns + "reverse_weight"); + p.freespace_planner_common_parameters.lateral_goal_range = + node->declare_parameter(ns + "lateral_goal_range"); + p.freespace_planner_common_parameters.longitudinal_goal_range = + node->declare_parameter(ns + "longitudinal_goal_range"); + } + // freespace planner costmap configs + { + std::string ns = "start_planner.freespace_planner.costmap_configs."; + p.freespace_planner_common_parameters.obstacle_threshold = + node->declare_parameter(ns + "obstacle_threshold"); + } + // freespace planner astar + { + std::string ns = "start_planner.freespace_planner.astar."; + p.astar_parameters.only_behind_solutions = + node->declare_parameter(ns + "only_behind_solutions"); + p.astar_parameters.use_back = node->declare_parameter(ns + "use_back"); + p.astar_parameters.distance_heuristic_weight = + node->declare_parameter(ns + "distance_heuristic_weight"); + } + // freespace planner rrtstar + { + std::string ns = "start_planner.freespace_planner.rrtstar."; + p.rrt_star_parameters.enable_update = node->declare_parameter(ns + "enable_update"); + p.rrt_star_parameters.use_informed_sampling = + node->declare_parameter(ns + "use_informed_sampling"); + p.rrt_star_parameters.max_planning_time = + node->declare_parameter(ns + "max_planning_time"); + p.rrt_star_parameters.neighbor_radius = node->declare_parameter(ns + "neighbor_radius"); + p.rrt_star_parameters.margin = node->declare_parameter(ns + "margin"); + } // validation of parameters if (p.lateral_acceleration_sampling_num < 1) { @@ -128,6 +197,11 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const return false; } + // Other modules are not needed when freespace planning + if (start_planner_ptr->isFreespacePlanning()) { + return false; + } + return enable_simultaneous_execution_as_approved_module_; }; @@ -151,6 +225,12 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() cons if (!start_planner_ptr->isBackFinished()) { return false; } + + // Other modules are not needed when freespace planning + if (start_planner_ptr->isFreespacePlanning()) { + return false; + } + return enable_simultaneous_execution_as_candidate_module_; }; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 860cdac31640d..c7541dc8af544 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -58,6 +58,34 @@ StartPlannerModule::StartPlannerModule( if (start_planners_.empty()) { RCLCPP_ERROR(getLogger(), "Not found enabled planner"); } + + if (parameters_->enable_freespace_planner) { + freespace_planner_ = std::make_unique(node, *parameters, vehicle_info_); + const auto freespace_planner_period_ns = rclcpp::Rate(1.0).period(); + freespace_planner_timer_cb_group_ = + node.create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + freespace_planner_timer_ = rclcpp::create_timer( + &node, clock_, freespace_planner_period_ns, + std::bind(&StartPlannerModule::onFreespacePlannerTimer, this), + freespace_planner_timer_cb_group_); + } +} + +void StartPlannerModule::onFreespacePlannerTimer() +{ + if (!planner_data_) { + return; + } + + if (!planner_data_->costmap) { + return; + } + + const bool is_new_costmap = + (clock_->now() - planner_data_->costmap->header.stamp).seconds() < 1.0; + if (isStuck() && is_new_costmap) { + planFreespacePath(); + } } BehaviorModuleOutput StartPlannerModule::run() @@ -200,20 +228,14 @@ BehaviorModuleOutput StartPlannerModule::plan() path = status_.backward_path; } - const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - path, generateDrivableLanes(path), planner_data_->drivable_area_expansion_parameters); - - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = target_drivable_lanes; - output.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); - output.path = std::make_shared(path); output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); path_reference_ = getPreviousModuleOutput().reference_path; + setDrivableAreaInfo(output); + const uint16_t steering_factor_direction = std::invoke([&output]() { if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { return SteeringFactor::LEFT; @@ -257,23 +279,8 @@ CandidateOutput StartPlannerModule::planCandidate() const return CandidateOutput{}; } -std::shared_ptr StartPlannerModule::getCurrentPlanner() const -{ - for (const auto & planner : start_planners_) { - if (status_.planner_type == planner->getPlannerType()) { - return planner; - } - } - return nullptr; -} - PathWithLaneId StartPlannerModule::getFullPath() const { - const auto pull_out_planner = getCurrentPlanner(); - if (pull_out_planner == nullptr) { - return PathWithLaneId{}; - } - // combine partial pull out path PathWithLaneId pull_out_path; for (const auto & partial_path : status_.pull_out_path.partial_paths) { @@ -334,17 +341,14 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() p.point.longitudinal_velocity_mps = 0.0; } - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = expanded_lanes; - output.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); - output.path = std::make_shared(stop_path); output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); path_reference_ = getPreviousModuleOutput().reference_path; + setDrivableAreaInfo(output); + const uint16_t steering_factor_direction = std::invoke([&output]() { if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { return SteeringFactor::LEFT; @@ -405,18 +409,12 @@ void StartPlannerModule::planWithPriority( const std::vector & start_pose_candidates, const Pose & goal_pose, const std::string search_priority) { - status_.is_safe = false; - status_.planner_type = PlannerType::NONE; - // check if start pose candidates are valid if (start_pose_candidates.empty()) { return; } const auto is_safe_with_pose_planner = [&](const size_t i, const auto & planner) { - // Set back_finished flag based on the current index - status_.back_finished = i == 0; - // Get the pull_out_start_pose for the current index const auto & pull_out_start_pose = start_pose_candidates.at(i); @@ -428,6 +426,7 @@ void StartPlannerModule::planWithPriority( } // use current path if back is not needed if (status_.back_finished) { + const std::lock_guard lock(mutex_); status_.is_safe = true; status_.pull_out_path = *pull_out_path; status_.pull_out_start_pose = pull_out_start_pose; @@ -447,10 +446,13 @@ void StartPlannerModule::planWithPriority( } // Update status variables with the next path information - status_.is_safe = true; - status_.pull_out_path = *pull_out_path_next; - status_.pull_out_start_pose = pull_out_start_pose_next; - status_.planner_type = planner->getPlannerType(); + { + const std::lock_guard lock(mutex_); + status_.is_safe = true; + status_.pull_out_path = *pull_out_path_next; + status_.pull_out_start_pose = pull_out_start_pose_next; + status_.planner_type = planner->getPlannerType(); + } return true; }; @@ -490,7 +492,19 @@ void StartPlannerModule::planWithPriority( } for (const auto & p : order_priority) { - if (is_safe_with_pose_planner(p.first, p.second)) break; + if (is_safe_with_pose_planner(p.first, p.second)) { + const std::lock_guard lock(mutex_); + // Set back_finished flag based on the current index + status_.back_finished = p.first == 0; + return; + } + } + + // not found safe path + if (status_.planner_type != PlannerType::FREESPACE) { + const std::lock_guard lock(mutex_); + status_.is_safe = false; + status_.planner_type = PlannerType::NONE; } } @@ -515,10 +529,6 @@ PathWithLaneId StartPlannerModule::generateStopPath() const path.points.push_back(toPathPointWithLaneId(current_pose)); path.points.push_back(toPathPointWithLaneId(moved_pose)); - // generate drivable area - const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - path, generateDrivableLanes(path), planner_data_->drivable_area_expansion_parameters); - return path; } @@ -708,6 +718,10 @@ bool StartPlannerModule::hasFinishedPullOut() const } const auto current_pose = planner_data_->self_odometry->pose.pose; + if (status_.planner_type == PlannerType::FREESPACE) { + return tier4_autoware_utils::calcDistance2d(current_pose, status_.pull_out_path.end_pose) < + parameters_->th_arrived_distance; + } // check that ego has passed pull out end point const double backward_path_length = @@ -775,6 +789,24 @@ bool StartPlannerModule::isStopped() return is_stopped; } +bool StartPlannerModule::isStuck() +{ + if (!isStopped()) { + return false; + } + + if (status_.planner_type == PlannerType::STOP) { + return true; + } + + // not found safe path + if (!status_.is_safe) { + return true; + } + + return false; +} + bool StartPlannerModule::hasFinishedCurrentPath() { const auto current_path = getCurrentPath(); @@ -921,21 +953,21 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() const PathWithLaneId stop_path = generateStopPath(); output.path = std::make_shared(stop_path); - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = generateDrivableLanes(*output.path); - output.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); + setDrivableAreaInfo(output); output.reference_path = getPreviousModuleOutput().reference_path; - status_.back_finished = true; - status_.planner_type = PlannerType::STOP; - status_.pull_out_path.partial_paths.clear(); - status_.pull_out_path.partial_paths.push_back(stop_path); - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - status_.pull_out_start_pose = current_pose; - status_.pull_out_path.start_pose = current_pose; - status_.pull_out_path.end_pose = current_pose; + { + const std::lock_guard lock(mutex_); + status_.back_finished = true; + status_.planner_type = PlannerType::STOP; + status_.pull_out_path.partial_paths.clear(); + status_.pull_out_path.partial_paths.push_back(stop_path); + const Pose & current_pose = planner_data_->self_odometry->pose.pose; + status_.pull_out_start_pose = current_pose; + status_.pull_out_path.start_pose = current_pose; + status_.pull_out_path.end_pose = current_pose; + } path_candidate_ = std::make_shared(stop_path); path_reference_ = getPreviousModuleOutput().reference_path; @@ -943,6 +975,68 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() return output; } +bool StartPlannerModule::planFreespacePath() +{ + const Pose & current_pose = planner_data_->self_odometry->pose.pose; + const auto & route_handler = planner_data_->route_handler; + + const double end_pose_search_start_distance = parameters_->end_pose_search_start_distance; + const double end_pose_search_end_distance = parameters_->end_pose_search_end_distance; + const double end_pose_search_interval = parameters_->end_pose_search_interval; + + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + + const auto current_arc_coords = lanelet::utils::getArcCoordinates(current_lanes, current_pose); + + const double s_start = std::max(0.0, current_arc_coords.length + end_pose_search_start_distance); + const double s_end = current_arc_coords.length + end_pose_search_end_distance; + + auto center_line_path = utils::resamplePathWithSpline( + route_handler->getCenterLinePath(current_lanes, s_start, s_end), end_pose_search_interval); + + for (const auto & p : center_line_path.points) { + const Pose end_pose = p.point.pose; + freespace_planner_->setPlannerData(planner_data_); + auto freespace_path = freespace_planner_->plan(current_pose, end_pose); + + if (!freespace_path) { + continue; + } + + const std::lock_guard lock(mutex_); + status_.pull_out_path = *freespace_path; + status_.pull_out_start_pose = current_pose; + status_.planner_type = freespace_planner_->getPlannerType(); + status_.is_safe = true; + status_.back_finished = true; + return true; + } + + return false; +} + +void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const +{ + if (status_.planner_type == PlannerType::FREESPACE) { + const double drivable_area_margin = planner_data_->parameters.vehicle_width; + output.drivable_area_info.drivable_margin = + planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; + } else { + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + *output.path, generateDrivableLanes(*output.path), + planner_data_->drivable_area_expansion_parameters); + + DrivableAreaInfo current_drivable_area_info; + current_drivable_area_info.drivable_lanes = target_drivable_lanes; + output.drivable_area_info = utils::combineDrivableAreaInfo( + current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); + } +} + void StartPlannerModule::setDebugData() const { using marker_utils::createPathMarkerArray; diff --git a/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp new file mode 100644 index 0000000000000..ba34901d9df6a --- /dev/null +++ b/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp @@ -0,0 +1,115 @@ +// Copyright 2023 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 "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" + +#include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner/utils/utils.hpp" + +#include + +#include +#include + +namespace behavior_path_planner +{ +FreespacePullOut::FreespacePullOut( + rclcpp::Node & node, const StartPlannerParameters & parameters, + const vehicle_info_util::VehicleInfo & vehicle_info) +: PullOutPlannerBase{node, parameters}, velocity_{parameters.freespace_planner_velocity} +{ + freespace_planning_algorithms::VehicleShape vehicle_shape( + vehicle_info, parameters.vehicle_shape_margin); + if (parameters.freespace_planner_algorithm == "astar") { + use_back_ = parameters.astar_parameters.use_back; + planner_ = std::make_unique( + parameters.freespace_planner_common_parameters, vehicle_shape, parameters.astar_parameters); + } else if (parameters.freespace_planner_algorithm == "rrtstar") { + use_back_ = true; // no option for disabling back in rrtstar + planner_ = std::make_unique( + parameters.freespace_planner_common_parameters, vehicle_shape, + parameters.rrt_star_parameters); + } +} + +boost::optional FreespacePullOut::plan(const Pose start_pose, const Pose end_pose) +{ + const auto & route_handler = planner_data_->route_handler; + const double backward_path_length = planner_data_->parameters.backward_path_length; + const double forward_path_length = planner_data_->parameters.forward_path_length; + + planner_->setMap(*planner_data_->costmap); + + const bool found_path = planner_->makePlan(start_pose, end_pose); + if (!found_path) { + return {}; + } + + const auto road_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + // find candidate paths + const auto pull_out_lanes = + start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); + const auto lanes = utils::combineLanelets(road_lanes, pull_out_lanes); + + const PathWithLaneId path = + utils::convertWayPointsToPathWithLaneId(planner_->getWaypoints(), velocity_, lanes); + + const auto reverse_indices = utils::getReversingIndices(path); + std::vector partial_paths = utils::dividePath(path, reverse_indices); + + // remove points which are near the end pose + PathWithLaneId & last_path = partial_paths.back(); + const double th_end_distance = 1.0; + for (auto it = last_path.points.begin(); it != last_path.points.end(); ++it) { + const size_t index = std::distance(last_path.points.begin(), it); + if (index == 0) continue; + const double distance = + tier4_autoware_utils::calcDistance2d(end_pose.position, it->point.pose.position); + if (distance < th_end_distance) { + last_path.points.erase(it, last_path.points.end()); + break; + } + } + + // push back generate road lane path between end pose and goal pose to last path + const auto & goal_pose = route_handler->getGoalPose(); + constexpr double offset_from_end_pose = 1.0; + const auto arc_position_end = lanelet::utils::getArcCoordinates(road_lanes, end_pose); + const double s_start = std::max(arc_position_end.length + offset_from_end_pose, 0.0); + const auto path_end_info = + start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const double s_end = path_end_info.first; + const bool path_terminal_is_goal = path_end_info.second; + + const auto road_center_line_path = route_handler->getCenterLinePath(road_lanes, s_start, s_end); + last_path = start_planner_utils::combineReferencePath(last_path, road_center_line_path); + + const double original_terminal_velocity = last_path.points.back().point.longitudinal_velocity_mps; + utils::correctDividedPathVelocity(partial_paths); + if (!path_terminal_is_goal) { + // not need to stop at terminal + last_path.points.back().point.longitudinal_velocity_mps = original_terminal_velocity; + } + + PullOutPath pull_out_path{}; + pull_out_path.partial_paths = partial_paths; + pull_out_path.start_pose = start_pose; + pull_out_path.end_pose = end_pose; + + return pull_out_path; +} +} // namespace behavior_path_planner From c665d9d44a0c0a09eaa7fe3c4a73f98d4542da80 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 20 Aug 2023 15:47:00 +0900 Subject: [PATCH 208/266] fix(start/goal_planner): set previous lane_ids if freespace path is out of lanes (#4672) Signed-off-by: kosuke55 --- .../behavior_path_planner/src/utils/path_utils.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utils/path_utils.cpp b/planning/behavior_path_planner/src/utils/path_utils.cpp index d455cd66ae769..ec14a064bf51b 100644 --- a/planning/behavior_path_planner/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/src/utils/path_utils.cpp @@ -341,14 +341,23 @@ PathWithLaneId convertWayPointsToPathWithLaneId( { PathWithLaneId path; path.header = waypoints.header; - for (const auto & waypoint : waypoints.waypoints) { + for (size_t i = 0; i < waypoints.waypoints.size(); ++i) { + const auto & waypoint = waypoints.waypoints.at(i); PathPointWithLaneId point{}; point.point.pose = waypoint.pose.pose; + // put the lane that contain waypoints in lane_ids. + bool is_in_lanes = false; for (const auto & lane : lanelets) { if (lanelet::utils::isInLanelet(point.point.pose, lane)) { point.lane_ids.push_back(lane.id()); + is_in_lanes = true; } } + // If none of them corresponds, assign the previous lane_ids. + if (!is_in_lanes && i > 0) { + point.lane_ids = path.points.at(i - 1).lane_ids; + } + point.point.longitudinal_velocity_mps = (waypoint.is_back ? -1 : 1) * velocity; path.points.push_back(point); } From f91db6b1caf8f77d78093b2b2e9a48a22ab80484 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sun, 20 Aug 2023 19:01:43 +0900 Subject: [PATCH 209/266] fix(mpc): use optimization result when polish failed (#4673) * fix(mpc): use optimization result when polish failed Signed-off-by: Takamasa Horibe * fix arg Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../src/qp_solver/qp_solver_osqp.cpp | 10 ++++------ control/mpc_lateral_controller/test/test_mpc.cpp | 3 +-- 2 files changed, 5 insertions(+), 8 deletions(-) diff --git a/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp b/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp index dba803e8f5efc..7c76d67e75aa3 100644 --- a/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp +++ b/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp @@ -72,12 +72,10 @@ bool QPSolverOSQP::solve( // polish status: successful (1), unperformed (0), (-1) unsuccessful int status_polish = std::get<2>(result); - if (status_polish == -1) { - RCLCPP_WARN(logger_, "osqp status_polish = %d (unsuccessful)", status_polish); - return false; - } - if (status_polish == 0) { - RCLCPP_WARN(logger_, "osqp status_polish = %d (unperformed)", status_polish); + if (status_polish == -1 || status_polish == 0) { + const auto s = (status_polish == 0) ? "Polish process is not performed in osqp." + : "Polish process failed in osqp."; + RCLCPP_INFO(logger_, "%s The required accuracy is met, but the solution can be inaccurate.", s); return true; } return true; diff --git a/control/mpc_lateral_controller/test/test_mpc.cpp b/control/mpc_lateral_controller/test/test_mpc.cpp index 6066cd3419ef3..6f8a6fb598058 100644 --- a/control/mpc_lateral_controller/test/test_mpc.cpp +++ b/control/mpc_lateral_controller/test/test_mpc.cpp @@ -252,9 +252,8 @@ TEST_F(MPCTest, OsqpCalculate) AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; - // with OSQP this function returns false despite finding correct solutions const auto odom = makeOdometry(pose_zero, default_velocity); - EXPECT_FALSE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } From 338d4b0cf2387ff7b126ad4903446e67a0cae850 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sun, 20 Aug 2023 23:32:03 +0900 Subject: [PATCH 210/266] feat(mpc): 1d interpolate in steering rate limit calculation (#4666) * feat(mpc): 1d interpolate in steering rate limit calculation Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * fix Signed-off-by: Takamasa Horibe * fix clamp Signed-off-by: Takamasa Horibe * remove unused funcs Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../include/mpc_lateral_controller/mpc.hpp | 8 ++ control/mpc_lateral_controller/src/mpc.cpp | 100 +++++++++++------- 2 files changed, 67 insertions(+), 41 deletions(-) diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp index 0d144726a0866..0854340ed24a5 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp @@ -379,6 +379,14 @@ class MPC const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex, const Odometry & current_kinematics) const; + /** + * @brief calculate steering rate limit along with the target trajectory + * @param reference_trajectory The reference trajectory. + * @param current_velocity current velocity of ego. + */ + VectorXd calcSteerRateLimitOnTrajectory( + const MPCTrajectory & trajectory, const double current_velocity) const; + //!< @brief logging with warn and return false template inline bool fail_warn_throttle(Args &&... args) const diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index 8e99880b68050..643f8a6f91023 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -359,9 +359,6 @@ std::pair MPC::updateStateForDelayCompensation( MatrixXd x_curr = x0_orig; double mpc_curr_time = start_time; - // for (const auto & tt : traj.relative_time) { - // std::cerr << "traj.relative_time = " << tt << std::endl; - // } for (size_t i = 0; i < m_input_buffer.size(); ++i) { double k, v = 0.0; try { @@ -573,47 +570,16 @@ std::pair MPC::executeOptimization( A(i, i - 1) = -1.0; } - const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01; - const auto get_adaptive_steer_rate_lim = [&](const double curvature, const double velocity) { - if (is_vehicle_stopped) { - return std::numeric_limits::max(); - } - - double steer_rate_lim_by_curvature = m_steer_rate_lim_map_by_curvature.back().second; - for (const auto & steer_rate_lim_info : m_steer_rate_lim_map_by_curvature) { - if (std::abs(curvature) <= steer_rate_lim_info.first) { - steer_rate_lim_by_curvature = steer_rate_lim_info.second; - break; - } - } - - double steer_rate_lim_by_velocity = m_steer_rate_lim_map_by_velocity.back().second; - for (const auto & steer_rate_lim_info : m_steer_rate_lim_map_by_velocity) { - if (std::abs(velocity) <= steer_rate_lim_info.first) { - steer_rate_lim_by_velocity = steer_rate_lim_info.second; - break; - } - } - - return std::min(steer_rate_lim_by_curvature, steer_rate_lim_by_velocity); - }; - + // steering angle limit VectorXd lb = VectorXd::Constant(DIM_U_N, -m_steer_lim); // min steering angle VectorXd ub = VectorXd::Constant(DIM_U_N, m_steer_lim); // max steering angle - VectorXd lbA(DIM_U_N); - VectorXd ubA(DIM_U_N); - for (int i = 0; i < DIM_U_N; ++i) { - const double adaptive_steer_rate_lim = - get_adaptive_steer_rate_lim(traj.smooth_k.at(i), traj.vx.at(i)); - const double adaptive_delta_steer_lim = adaptive_steer_rate_lim * prediction_dt; - lbA(i) = -adaptive_delta_steer_lim; - ubA(i) = adaptive_delta_steer_lim; - } - const double adaptive_steer_rate_lim = - get_adaptive_steer_rate_lim(traj.smooth_k.at(0), traj.vx.at(0)); - lbA(0, 0) = m_raw_steer_cmd_prev - adaptive_steer_rate_lim * m_ctrl_period; - ubA(0, 0) = m_raw_steer_cmd_prev + adaptive_steer_rate_lim * m_ctrl_period; + // steering angle rate limit + VectorXd steer_rate_limits = calcSteerRateLimitOnTrajectory(traj, current_velocity); + VectorXd ubA = steer_rate_limits * prediction_dt; + VectorXd lbA = -steer_rate_limits * prediction_dt; + ubA(0) = m_raw_steer_cmd_prev + steer_rate_limits(0) * m_ctrl_period; + lbA(0) = m_raw_steer_cmd_prev - steer_rate_limits(0) * m_ctrl_period; auto t_start = std::chrono::system_clock::now(); bool solve_result = m_qpsolver_ptr->solve(H, f.transpose(), A, lb, ub, lbA, ubA, Uex); @@ -761,6 +727,58 @@ double MPC::calcDesiredSteeringRate( return steer_rate; } +VectorXd MPC::calcSteerRateLimitOnTrajectory( + const MPCTrajectory & trajectory, const double current_velocity) const +{ + const auto interp = [&](const auto & steer_rate_limit_map, const auto & current) { + std::vector reference, limits; + for (const auto & p : steer_rate_limit_map) { + reference.push_back(p.first); + limits.push_back(p.second); + } + + // If the speed is out of range of the reference, apply zero-order hold. + if (current <= reference.front()) { + return limits.front(); + } + if (current >= reference.back()) { + return limits.back(); + } + + // Apply linear interpolation + for (size_t i = 0; i < reference.size() - 1; ++i) { + if (reference.at(i) <= current && current <= reference.at(i + 1)) { + auto ratio = + (current - reference.at(i)) / std::max(reference.at(i + 1) - reference.at(i), 1.0e-5); + ratio = std::clamp(ratio, 0.0, 1.0); + const auto interp = limits.at(i) + ratio * (limits.at(i + 1) - limits.at(i)); + return interp; + } + } + + std::cerr << "MPC::calcSteerRateLimitOnTrajectory() interpolation logic is broken. Command " + "filter is not working. Please check the code." + << std::endl; + return reference.back(); + }; + + // when the vehicle is stopped, no steering rate limit. + const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01; + if (is_vehicle_stopped) { + return VectorXd::Zero(m_param.prediction_horizon); + } + + // calculate steering rate limit + VectorXd steer_rate_limits = VectorXd::Zero(m_param.prediction_horizon); + for (int i = 0; i < m_param.prediction_horizon; ++i) { + const auto limit_by_curvature = interp(m_steer_rate_lim_map_by_curvature, trajectory.k.at(i)); + const auto limit_by_velocity = interp(m_steer_rate_lim_map_by_velocity, trajectory.vx.at(i)); + steer_rate_limits(i) = std::min(limit_by_curvature, limit_by_velocity); + } + + return steer_rate_limits; +} + bool MPC::isValid(const MPCMatrix & m) const { if ( From d794bc0be357e9f308300f268817de7523b97150 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 21 Aug 2023 09:22:08 +0900 Subject: [PATCH 211/266] fix(lanelet2_map_loader): fixed parameter declaration timing (#4639) Change parameter declaration timing Signed-off-by: Shintaro Sakoda --- .../src/lanelet2_map_loader/lanelet2_map_loader_node.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index c935cd62b2fb6..c1272c5893689 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -57,13 +57,16 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options adaptor.init_sub( sub_map_projector_type_, [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); }); + + declare_parameter("lanelet2_map_path", ""); + declare_parameter("center_line_resolution", 5.0); } void Lanelet2MapLoaderNode::on_map_projector_info( const MapProjectorInfo::Message::ConstSharedPtr msg) { - const auto lanelet2_filename = declare_parameter("lanelet2_map_path", ""); - const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); + const auto lanelet2_filename = get_parameter("lanelet2_map_path").as_string(); + const auto center_line_resolution = get_parameter("center_line_resolution").as_double(); // load map from file const auto map = From 1f8ac8778ba4b1eb64f82bdb8fdbb71845761705 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 21 Aug 2023 09:24:07 +0900 Subject: [PATCH 212/266] ci: reverting control ignorance (#4662) * ci: ignore svg for spell-check, as well as reverting control Signed-off-by: kminoda * remove svg Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .cspell-partial.json | 1 - 1 file changed, 1 deletion(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index 7d41451bd840a..a3c4ca455d444 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -3,7 +3,6 @@ "**/perception/**", "**/planning/**", "**/sensing/**", - "**/control/**", "perception/bytetrack/lib/**" ], "ignoreRegExpList": [], From 4297f3d25b4ad05e2c15b46760235276a054803b Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Mon, 21 Aug 2023 11:36:29 +0900 Subject: [PATCH 213/266] fix(compare_map_segmentation): fix process died for invalid access (#4676) * fix(compare_map_segmentation): fix process died for invalid access Signed-off-by: 1222-takeshi * style(pre-commit): autofix * fix: missing username in TODO Signed-off-by: 1222-takeshi * fix: change condition Signed-off-by: 1222-takeshi * fix Signed-off-by: 1222-takeshi --------- Signed-off-by: 1222-takeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/compare_map_segmentation/voxel_grid_map_loader.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp index 8e3bb21cc4486..21cb19edcd0ec 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp +++ b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp @@ -260,7 +260,8 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader int index = static_cast( std::floor((kv.second.min_b_x - origin_x_) / map_grid_size_x_) + map_grids_x_ * std::floor((kv.second.min_b_y - origin_y_) / map_grid_size_y_)); - if (index >= map_grids_x_ * map_grids_y_) { + // TODO(1222-takeshi): check if index is valid + if (index >= map_grids_x_ * map_grids_y_ || index < 0) { continue; } current_voxel_grid_array_.at(index) = std::make_shared(kv.second); From 14b68f8e4e5deeeaf72d57c828709281b7223275 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 21 Aug 2023 12:33:38 +0900 Subject: [PATCH 214/266] feat(route_handler): get adjacent lanelet even if the next lane is empty (#4675) feat(utils): get adjacent lanelet even if the next lane is empty Signed-off-by: satoshi-ota --- planning/route_handler/src/route_handler.cpp | 26 ++++++++++++++------ 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 26d226a6746e2..b8cedaa947455 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -969,13 +969,18 @@ boost::optional RouteHandler::getRightLanelet( return adjacent_right_lane; } - lanelet::ConstLanelet next_lanelet; - if (!getNextLaneletWithinRoute(lanelet, &next_lanelet)) { + lanelet::ConstLanelets prev_lanelet; + if (!getPreviousLaneletsWithinRoute(lanelet, &prev_lanelet)) { return adjacent_right_lane; } - lanelet::ConstLanelets prev_lanelet; - if (!getPreviousLaneletsWithinRoute(lanelet, &prev_lanelet)) { + lanelet::ConstLanelet next_lanelet; + if (!getNextLaneletWithinRoute(lanelet, &next_lanelet)) { + for (const auto & lane : getNextLanelets(prev_lanelet.front())) { + if (lanelet.rightBound().back().id() == lane.leftBound().back().id()) { + return lane; + } + } return adjacent_right_lane; } @@ -1036,13 +1041,18 @@ boost::optional RouteHandler::getLeftLanelet( return adjacent_left_lane; } - lanelet::ConstLanelet next_lanelet; - if (!getNextLaneletWithinRoute(lanelet, &next_lanelet)) { + lanelet::ConstLanelets prev_lanelet; + if (!getPreviousLaneletsWithinRoute(lanelet, &prev_lanelet)) { return adjacent_left_lane; } - lanelet::ConstLanelets prev_lanelet; - if (!getPreviousLaneletsWithinRoute(lanelet, &prev_lanelet)) { + lanelet::ConstLanelet next_lanelet; + if (!getNextLaneletWithinRoute(lanelet, &next_lanelet)) { + for (const auto & lane : getNextLanelets(prev_lanelet.front())) { + if (lanelet.leftBound().back().id() == lane.rightBound().back().id()) { + return lane; + } + } return adjacent_left_lane; } From 93b00e4c6cda2cf62767b5e7165c128d834876ac Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 21 Aug 2023 14:17:45 +0900 Subject: [PATCH 215/266] feat!: rename map_projector_type to map_projector_info (#4664) Signed-off-by: kminoda --- .../include/component_interface_specs/map.hpp | 2 +- map/map_loader/README.md | 2 +- map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp | 2 +- .../src/lanelet2_map_loader/lanelet2_map_loader_node.cpp | 2 +- .../test/test_node_load_local_from_yaml.test.py | 2 +- .../test/test_node_load_mgrs_from_yaml.test.py | 2 +- .../test/test_node_load_utm_from_yaml.test.py | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/common/component_interface_specs/include/component_interface_specs/map.hpp b/common/component_interface_specs/include/component_interface_specs/map.hpp index f0cce7a7f97a2..dc162d4a7267a 100644 --- a/common/component_interface_specs/include/component_interface_specs/map.hpp +++ b/common/component_interface_specs/include/component_interface_specs/map.hpp @@ -25,7 +25,7 @@ namespace map_interface struct MapProjectorInfo { using Message = tier4_map_msgs::msg::MapProjectorInfo; - static constexpr char name[] = "/map/map_projector_type"; + static constexpr char name[] = "/map/map_projector_info"; static constexpr size_t depth = 1; static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 44f215b2d8c01..4c64eb1eaecae 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -140,7 +140,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Feature lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_auto_mapping_msgs/HADMapBin message. -The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_type` from `map_projection_loader`. +The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_info` from `map_projection_loader`. The node supports the following three types of coordinate systems: - MGRS diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index f422d3628fe2c..d2e9f66ad047a 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -47,7 +47,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); - component_interface_utils::Subscription::SharedPtr sub_map_projector_type_; + component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; rclcpp::Publisher::SharedPtr pub_map_bin_; }; diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index c1272c5893689..bb52e17c342ea 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -55,7 +55,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options // subscription adaptor.init_sub( - sub_map_projector_type_, + sub_map_projector_info_, [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); }); declare_parameter("lanelet2_map_path", ""); diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py index 721fd5f95e8f3..8ab0db43e32a7 100644 --- a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map/map_projector_type", + "/map/map_projector_info", self.callback, custom_qos_profile, ) diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index 1805d59d54f65..f18f9b7c17e75 100644 --- a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map/map_projector_type", + "/map/map_projector_info", self.callback, custom_qos_profile, ) diff --git a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py index 1f92802231e37..8d863033adcb8 100644 --- a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py @@ -110,7 +110,7 @@ def test_node_link(self): # Create subscription to map_projector_info topic subscription = self.test_node.create_subscription( MapProjectorInfo, - "/map/map_projector_type", + "/map/map_projector_info", self.callback, custom_qos_profile, ) From 73b28776680fcee2dc5527a492e46b46a9bfd409 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 21 Aug 2023 16:36:14 +0900 Subject: [PATCH 216/266] fix(avoidance): fix target search area width calculation (#4671) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/utils/avoidance/utils.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 3f47b97aa0adf..e6b946a130682 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -1622,7 +1622,8 @@ std::pair separateObjectsByPath( double max_offset = 0.0; for (const auto & object_parameter : parameters->object_parameters) { const auto p = object_parameter.second; - const auto offset = p.envelope_buffer_margin + p.safety_buffer_lateral + p.avoid_margin_lateral; + const auto offset = + 2.0 * p.envelope_buffer_margin + p.safety_buffer_lateral + p.avoid_margin_lateral; max_offset = std::max(max_offset, offset); } From 489eb05745990cb2d14469b4b64271ae4f2f09a1 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Aug 2023 19:45:48 +0900 Subject: [PATCH 217/266] chore(freespace_planning_algorithms): fix spell (#4684) Signed-off-by: Takamasa Horibe --- planning/freespace_planning_algorithms/test/debug_plot.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/freespace_planning_algorithms/test/debug_plot.py b/planning/freespace_planning_algorithms/test/debug_plot.py index bc96963f09dcb..a34fd745af047 100755 --- a/planning/freespace_planning_algorithms/test/debug_plot.py +++ b/planning/freespace_planning_algorithms/test/debug_plot.py @@ -223,6 +223,6 @@ def create_concat_png(src_list, dest, is_horizontal): plt.savefig(file_name) print("saved to {}".format(file_name)) - algowise_summary_file = os.path.join("/tmp", "summary-{}.png".format(algo_name)) + algo_summary_file = os.path.join("/tmp", "summary-{}.png".format(algo_name)) if concat: - create_concat_png(algo_png_images, algowise_summary_file, True) + create_concat_png(algo_png_images, algo_summary_file, True) From c3a2f61e8477c7ebecc06c512734e0b1a069a431 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Aug 2023 23:52:26 +0900 Subject: [PATCH 218/266] chore(planning_validator): fix spell (#4685) Signed-off-by: Takamasa Horibe --- .../include/planning_validator/utils.hpp | 3 +-- planning/planning_validator/src/utils.cpp | 20 +++++++++---------- 2 files changed, 11 insertions(+), 12 deletions(-) diff --git a/planning/planning_validator/include/planning_validator/utils.hpp b/planning/planning_validator/include/planning_validator/utils.hpp index 9b5775642424c..6c0d2e86943dd 100644 --- a/planning/planning_validator/include/planning_validator/utils.hpp +++ b/planning/planning_validator/include/planning_validator/utils.hpp @@ -38,9 +38,8 @@ Trajectory resampleTrajectory(const Trajectory & trajectory, const double min_in void calcCurvature(const Trajectory & trajectory, std::vector & curvatures); -// cspell: ignore steerings void calcSteeringAngles( - const Trajectory & trajectory, const double wheelbase, std::vector & steerings); + const Trajectory & trajectory, const double wheelbase, std::vector & steering_array); std::pair calcMaxCurvature(const Trajectory & trajectory); diff --git a/planning/planning_validator/src/utils.cpp b/planning/planning_validator/src/utils.cpp index b896b3f6d8979..e4c882cfaedb9 100644 --- a/planning/planning_validator/src/utils.cpp +++ b/planning/planning_validator/src/utils.cpp @@ -216,7 +216,7 @@ std::pair calcMaxRelativeAngles(const Trajectory & trajectory) } void calcSteeringAngles( - const Trajectory & trajectory, const double wheelbase, std::vector & steerings) + const Trajectory & trajectory, const double wheelbase, std::vector & steering_array) { const auto curvatureToSteering = [](const auto k, const auto wheelbase) { return std::atan(k * wheelbase); @@ -225,19 +225,19 @@ void calcSteeringAngles( std::vector curvatures; calcCurvature(trajectory, curvatures); - steerings.clear(); + steering_array.clear(); for (const auto k : curvatures) { - steerings.push_back(curvatureToSteering(k, wheelbase)); + steering_array.push_back(curvatureToSteering(k, wheelbase)); } } std::pair calcMaxSteeringAngles( const Trajectory & trajectory, const double wheelbase) { - std::vector steerings; - calcSteeringAngles(trajectory, wheelbase, steerings); + std::vector steering_array; + calcSteeringAngles(trajectory, wheelbase, steering_array); - return getAbsMaxValAndIdx(steerings); + return getAbsMaxValAndIdx(steering_array); } std::pair calcMaxSteeringRates( @@ -247,8 +247,8 @@ std::pair calcMaxSteeringRates( return {0.0, 0}; } - std::vector steerings; - calcSteeringAngles(trajectory, wheelbase, steerings); + std::vector steering_array; + calcSteeringAngles(trajectory, wheelbase, steering_array); double max_steering_rate = 0.0; size_t max_index = 0; @@ -259,8 +259,8 @@ std::pair calcMaxSteeringRates( const auto v = 0.5 * (p_next.longitudinal_velocity_mps + p_prev.longitudinal_velocity_mps); const auto dt = delta_s / std::max(v, 1.0e-5); - const auto steer_prev = steerings.at(i); - const auto steer_next = steerings.at(i + 1); + const auto steer_prev = steering_array.at(i); + const auto steer_next = steering_array.at(i + 1); const auto steer_rate = (steer_next - steer_prev) / dt; takeBigger(max_steering_rate, max_index, steer_rate, i); From daa3785033c1b88879e3fd7ebb8303760b53fee1 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 22 Aug 2023 09:25:19 +0900 Subject: [PATCH 219/266] fix(sampling_based_planner): correct spelling for cspell (#4682) Signed-off-by: Maxime CLEMENT --- .../include/bezier_sampler/bezier.hpp | 8 ++++---- .../include/bezier_sampler/bezier_sampling.hpp | 1 + .../include/frenet_planner/structures.hpp | 8 ++++---- .../src/frenet_planner/frenet_planner.cpp | 12 ++++++------ .../path_sampler/README.md | 6 +++--- .../path_sampler/src/node.cpp | 2 +- .../path_sampler/src/path_generation.cpp | 16 ++++++++-------- .../path_sampler/src/prepare_inputs.cpp | 8 ++++---- .../include/sampler_common/structures.hpp | 16 ++++++++-------- 9 files changed, 39 insertions(+), 38 deletions(-) diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp index 89d91bd3110f5..93c6ec6b87f36 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp +++ b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp @@ -50,11 +50,11 @@ class Bezier explicit Bezier(const std::vector & control_points); /// @brief return the control points [[nodiscard]] const Eigen::Matrix & getControlPoints() const; - /// @brief return the curve in cartersian frame with the desired resolution + /// @brief return the curve in cartesian frame with the desired resolution [[nodiscard]] std::vector cartesian(const double resolution) const; - /// @brief return the curve in cartersian frame with the desired number of points + /// @brief return the curve in cartesian frame with the desired number of points [[nodiscard]] std::vector cartesian(const int nb_points) const; - /// @brief return the curve in cartersian frame (including angle) with the desired number of + /// @brief return the curve in cartesian frame (including angle) with the desired number of /// points [[nodiscard]] std::vector cartesianWithHeading(const int nb_points) const; /// @brief calculate the curve value for the given parameter t @@ -65,7 +65,7 @@ class Bezier [[nodiscard]] Eigen::Vector2d velocity(const double t) const; /// @brief calculate the acceleration (2nd derivative) for the given parameter t [[nodiscard]] Eigen::Vector2d acceleration(const double t) const; - /// @breif return the heading (in radians) of the tangent for the given parameter t + /// @brief return the heading (in radians) of the tangent for the given parameter t [[nodiscard]] double heading(const double t) const; /// @brief calculate the curvature for the given parameter t [[nodiscard]] double curvature(const double t) const; diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp index 9dea7d34742dc..624cd585b0a72 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp +++ b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp @@ -33,6 +33,7 @@ struct SamplingParameters double mk_max; // Minimum normalized curvature vector magnitude }; /// @brief sample Bezier curves given an initial and final state and sampling parameters +// cspell: ignore Artuñedoet /// @details from Section IV of A. Artuñedoet al.: Real-Time Motion Planning Approach for Automated /// Driving in Urban Environments std::vector sample( diff --git a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp b/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp index 848d8f11938cf..c44cb5d814d71 100644 --- a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp +++ b/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp @@ -126,15 +126,15 @@ struct Trajectory : sampler_common::Trajectory [[nodiscard]] Trajectory * subset(const size_t from_idx, const size_t to_idx) const override { - auto * subtraj = new Trajectory(*sampler_common::Trajectory::subset(from_idx, to_idx)); + auto * sub_trajectory = new Trajectory(*sampler_common::Trajectory::subset(from_idx, to_idx)); assert(to_idx >= from_idx); - subtraj->reserve(to_idx - from_idx); + sub_trajectory->reserve(to_idx - from_idx); const auto copy_subset = [&](const auto & from, auto & to) { to.insert(to.end(), std::next(from.begin(), from_idx), std::next(from.begin(), to_idx)); }; - copy_subset(frenet_points, subtraj->frenet_points); - return subtraj; + copy_subset(frenet_points, sub_trajectory->frenet_points); + return sub_trajectory; }; }; diff --git a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp index ebd628793fa24..3368c49459a55 100644 --- a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -183,17 +183,17 @@ void calculateCartesian( for (const auto & fp : trajectory.frenet_points) trajectory.points.push_back(reference.cartesian(fp)); calculateLengthsAndYaws(trajectory); - std::vector dyaws; - dyaws.reserve(trajectory.yaws.size()); + std::vector d_yaws; + d_yaws.reserve(trajectory.yaws.size()); for (size_t i = 0; i + 1 < trajectory.yaws.size(); ++i) - dyaws.push_back(autoware::common::helper_functions::wrap_angle( + d_yaws.push_back(autoware::common::helper_functions::wrap_angle( trajectory.yaws[i + 1] - trajectory.yaws[i])); - dyaws.push_back(0.0); + d_yaws.push_back(0.0); // Calculate curvatures for (size_t i = 1; i < trajectory.yaws.size(); ++i) { const auto curvature = trajectory.lengths[i] == trajectory.lengths[i - 1] ? 0.0 - : dyaws[i] / (trajectory.lengths[i] - trajectory.lengths[i - 1]); + : d_yaws[i] / (trajectory.lengths[i] - trajectory.lengths[i - 1]); trajectory.curvatures.push_back(curvature); } const auto last_curvature = trajectory.curvatures.empty() ? 0.0 : trajectory.curvatures.back(); @@ -205,7 +205,7 @@ void calculateCartesian( const auto s_acc = trajectory.longitudinal_polynomial->acceleration(time); const auto d_vel = trajectory.lateral_polynomial->velocity(time); const auto d_acc = trajectory.lateral_polynomial->acceleration(time); - Eigen::Rotation2D rotation(dyaws[i]); + Eigen::Rotation2D rotation(d_yaws[i]); Eigen::Vector2d vel_vector{s_vel, d_vel}; Eigen::Vector2d acc_vector{s_acc, d_acc}; const auto vel = rotation * vel_vector; diff --git a/planning/sampling_based_planner/path_sampler/README.md b/planning/sampling_based_planner/path_sampler/README.md index 533c79252dfe4..2d7fe52e5dcad 100644 --- a/planning/sampling_based_planner/path_sampler/README.md +++ b/planning/sampling_based_planner/path_sampler/README.md @@ -2,7 +2,7 @@ ## Purpose -This package implements a node that uses sampling based planning to generate a drivable trajectry. +This package implements a node that uses sampling based planning to generate a drivable trajectory. ## Feature @@ -33,7 +33,7 @@ Note that the velocity is just taken over from the input path. ## Algorithm -Sampling based planning is decomposed into 3 successives steps: +Sampling based planning is decomposed into 3 successive steps: 1. Sampling: candidate trajectories are generated. 2. Pruning: invalid candidates are discarded. @@ -65,7 +65,7 @@ Each soft constraint is associated with a weight to allow tuning of the preferen ## Limitations The quality of the candidates generated with polynomials in frenet frame greatly depend on the reference path. -If the reference path is not smooth, the resulting candidates will probably be undrivable. +If the reference path is not smooth, the resulting candidates will probably be undriveable. Failure to find a valid trajectory current results in a suddenly stopping trajectory. diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/path_sampler/src/node.cpp index 32c7cebc39b5f..588f29b06c40d 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/path_sampler/src/node.cpp @@ -458,7 +458,7 @@ std::vector PathSampler::generatePath(const PlannerData & plann prev_path_ = selected_path; } else { RCLCPP_WARN( - get_logger(), "No valid path found (out of %lu) outputing %s\n", candidate_paths.size(), + get_logger(), "No valid path found (out of %lu) outputting %s\n", candidate_paths.size(), prev_path_ ? "previous path" : "stopping path"); int coll = 0; int da = 0; diff --git a/planning/sampling_based_planner/path_sampler/src/path_generation.cpp b/planning/sampling_based_planner/path_sampler/src/path_generation.cpp index b574f87e319fb..4ae6382b82383 100644 --- a/planning/sampling_based_planner/path_sampler/src/path_generation.cpp +++ b/planning/sampling_based_planner/path_sampler/src/path_generation.cpp @@ -68,11 +68,11 @@ std::vector generateBezierPaths( target_state.pose = path_spline.cartesian({target_s, 0}); target_state.curvature = path_spline.curvature(target_s); target_state.heading = path_spline.yaw(target_s); - const auto beziers = + const auto bezier_samples = bezier_sampler::sample(initial_state, target_state, params.sampling.bezier); const auto step = std::min(0.1, params.sampling.resolution / target_length); - for (const auto & bezier : beziers) { + for (const auto & bezier : bezier_samples) { sampler_common::Path path; path.lengths.push_back(0.0); for (double t = 0.0; t <= 1.0; t += step) { @@ -107,19 +107,19 @@ std::vector generateFrenetPaths( // Calculate Velocity and acceleration parametrized over arc length // From appendix I of Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame const auto frenet_yaw = initial_state.heading - path_spline.yaw(s); - const auto path_curv = path_spline.curvature(s); + const auto path_curvature = path_spline.curvature(s); const auto delta_s = 0.001; - initial_frenet_state.lateral_velocity = (1 - path_curv * d) * std::tan(frenet_yaw); - const auto path_curv_deriv = (path_spline.curvature(s + delta_s) - path_curv) / delta_s; + initial_frenet_state.lateral_velocity = (1 - path_curvature * d) * std::tan(frenet_yaw); + const auto path_curvature_deriv = (path_spline.curvature(s + delta_s) - path_curvature) / delta_s; const auto cos_yaw = std::cos(frenet_yaw); if (cos_yaw == 0.0) { initial_frenet_state.lateral_acceleration = 0.0; } else { initial_frenet_state.lateral_acceleration = - -(path_curv_deriv * d + path_curv * initial_frenet_state.lateral_velocity) * + -(path_curvature_deriv * d + path_curvature * initial_frenet_state.lateral_velocity) * std::tan(frenet_yaw) + - ((1 - path_curv * d) / (cos_yaw * cos_yaw)) * - (initial_state.curvature * ((1 - path_curv * d) / cos_yaw) - path_curv); + ((1 - path_curvature * d) / (cos_yaw * cos_yaw)) * + (initial_state.curvature * ((1 - path_curvature * d) / cos_yaw) - path_curvature); } return frenet_planner::generatePaths(path_spline, initial_frenet_state, sampling_parameters); } diff --git a/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp b/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp index 25677a5b2d29b..c17f3479932f3 100644 --- a/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp +++ b/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp @@ -125,11 +125,11 @@ sampler_common::transform::Spline2D preparePathSpline( control_points.transposeInPlace(); const auto nb_knots = path.size() + spline_dim + 3; Eigen::RowVectorXd knots(nb_knots); - constexpr auto repeat_endknots = 3lu; - const auto knot_step = 1.0 / static_cast(nb_knots - 2 * repeat_endknots); + constexpr auto repeat_end_knots = 3lu; + const auto knot_step = 1.0 / static_cast(nb_knots - 2 * repeat_end_knots); auto i = 0lu; - for (; i < repeat_endknots; ++i) knots[i] = 0.0; - for (; i < nb_knots - repeat_endknots; ++i) knots[i] = knots[i - 1] + knot_step; + for (; i < repeat_end_knots; ++i) knots[i] = 0.0; + for (; i < nb_knots - repeat_end_knots; ++i) knots[i] = knots[i - 1] + knot_step; for (; i < nb_knots; ++i) knots[i] = 1.0; const auto spline = Eigen::Spline(knots, control_points); x.reserve(path.size()); diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp b/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp index 54e8c457034a9..1cb14fdf56198 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp +++ b/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp @@ -227,19 +227,19 @@ struct Trajectory : Path [[nodiscard]] Trajectory * subset(const size_t from_idx, const size_t to_idx) const override { - auto * subtraj = new Trajectory(*Path::subset(from_idx, to_idx)); + auto * sub_trajectory = new Trajectory(*Path::subset(from_idx, to_idx)); const auto copy_subset = [&](const auto & from, auto & to) { to.insert(to.end(), std::next(from.begin(), from_idx), std::next(from.begin(), to_idx)); }; - copy_subset(longitudinal_velocities, subtraj->longitudinal_velocities); - copy_subset(longitudinal_accelerations, subtraj->longitudinal_accelerations); - copy_subset(lateral_velocities, subtraj->lateral_velocities); - copy_subset(lateral_accelerations, subtraj->lateral_accelerations); - copy_subset(jerks, subtraj->jerks); - copy_subset(times, subtraj->times); - return subtraj; + copy_subset(longitudinal_velocities, sub_trajectory->longitudinal_velocities); + copy_subset(longitudinal_accelerations, sub_trajectory->longitudinal_accelerations); + copy_subset(lateral_velocities, sub_trajectory->lateral_velocities); + copy_subset(lateral_accelerations, sub_trajectory->lateral_accelerations); + copy_subset(jerks, sub_trajectory->jerks); + copy_subset(times, sub_trajectory->times); + return sub_trajectory; } [[nodiscard]] Trajectory resample(const double fixed_interval) const From 7576edbe1794fefd65864c8eeae161e9243d5f65 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 22 Aug 2023 11:20:55 +0900 Subject: [PATCH 220/266] feat(tier4_perception_launch): lower the detection by tracker priority to suppress yaw oscillation (#4690) lower the detection by tracker priority to suppress yaw oscillation Signed-off-by: yoshiri --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 1 + .../detection/lidar_based_detection.launch.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 0a9b719939971..79e04e1d6fc61 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -294,6 +294,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 73d256a802340..86ede0d4be47d 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -141,6 +141,7 @@ + From b048ff471850f5d6331ce3d39aea8ec31f7c1ed4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 22 Aug 2023 11:27:11 +0900 Subject: [PATCH 221/266] chore(behavior_velocity_occlusion_spot): correct spelling for cspell (#4689) Signed-off-by: Maxime CLEMENT --- .../docs/occlusion_spot.drawio.svg | 2 +- .../docs/velocity_planning.drawio.svg | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg b/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg index 8acecba2f558d..a5601e4e0c503 100644 --- a/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg +++ b/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg @@ -304,7 +304,7 @@
    - colliision + collision
    diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg b/planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg index 55693e2a2688c..650194484e933 100644 --- a/planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg +++ b/planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg @@ -220,14 +220,14 @@
    - ---  safe velocity to stop before collisopn + ---  safe velocity to stop before collision
    - ---- safe slow donw velocity + ---- safe slow down velocity
    From cdffba27ac25122f45f5abaf9401cd1ee553739d Mon Sep 17 00:00:00 2001 From: SaltUhey <111027815+SaltUhey@users.noreply.github.com> Date: Tue, 22 Aug 2023 12:23:56 +0900 Subject: [PATCH 222/266] feat(ekf_localizer): short periodic updates of z values based on pitch (#4554) * feat(ekf_localizer): short periodic updates of z values based on pitch Signed-off-by: yuhei * delete an unnecessary space Signed-off-by: yuhei * add brief considering_z_ndt_delay() Signed-off-by: yuhei * style(pre-commit): autofix * add const and reference Signed-off-by: yuhei * modify function about renewing z value, change name of function and variable Signed-off-by: yuhei * style(pre-commit): autofix * delete unnecessary lines Signed-off-by: yuhei * style(pre-commit): autofix * move updateZConsideringDelay() to in updateSimple1DFilters() Signed-off-by: yuhei * change name of function Signed-off-by: yuhei * style(pre-commit): autofix * add explanation in timerCallback() to make it easier to understand Signed-off-by: yuhei * modify a mistake Signed-off-by: yuhei * move calculateDeltaZFromPitch(), delete counter Signed-off-by: yuhei * use variable t_receive_pose Signed-off-by: yuhei * style(pre-commit): autofix * add underscore to member variables Signed-off-by: yuhei * style(pre-commit): autofix * add a description about caluculation delta from pitch Signed-off-by: yuhei * style(pre-commit): autofix * delete pitch_from_ndt_ Signed-off-by: yuhei * style(pre-commit): autofix * modify ekf_localizer Signed-off-by: yuhei * modify README about Calculation of vertical correction amount from pitch Signed-off-by: yuhei * adjust code to a standard Signed-off-by: yuhei * style(pre-commit): autofix * adjust lines to a standard Signed-off-by: yuhei * style(pre-commit): autofix * modify README and name of variable Signed-off-by: yuhei * style(pre-commit): autofix * modify README Signed-off-by: yuhei * modify media Signed-off-by: yuhei * modify media Signed-off-by: yuhei * delete calculateDeltaFromPitch() and write internal calculation in one liner Signed-off-by: yuhei * modify README (Calculation of vertical correction amount from pitch in Features) Signed-off-by: yuhei * style(pre-commit): autofix --------- Signed-off-by: yuhei Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- localization/ekf_localizer/README.md | 5 +++++ .../media/calculation_delta_from_pitch.png | Bin 0 -> 56991 bytes .../ekf_localizer/src/ekf_localizer.cpp | 10 +++++++++- 3 files changed, 14 insertions(+), 1 deletion(-) create mode 100644 localization/ekf_localizer/media/calculation_delta_from_pitch.png diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index bdcc7ac486cd0..748b5ee5becc0 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -18,6 +18,7 @@ This package includes the following features: - **Automatic estimation of yaw bias** prevents modeling errors caused by sensor mounting angle errors, which can improve estimation accuracy. - **Mahalanobis distance gate** enables probabilistic outlier detection to determine which inputs should be used or ignored. - **Smooth update**, the Kalman Filter measurement update is typically performed when a measurement is obtained, but it can cause large changes in the estimated value, especially for low-frequency measurements. Since the algorithm can consider the measurement time, the measurement data can be divided into multiple pieces and integrated smoothly while maintaining consistency (see the following figure). +- **Calculation of vertical correction amount from pitch** mitigates localization instability on slopes. For example, when going uphill, it behaves as if it is buried in the ground (see the left side of the "Calculate delta from pitch" figure) because EKF only considers 3DoF(x,y,yaw). Therefore, EKF corrects the z-coordinate according to the formula (see the right side of the "Calculate delta from pitch" figure).

    @@ -27,6 +28,10 @@ This package includes the following features:

    +

    + +

    + ## Launch The `ekf_localizer` starts with the default parameters with the following command. diff --git a/localization/ekf_localizer/media/calculation_delta_from_pitch.png b/localization/ekf_localizer/media/calculation_delta_from_pitch.png new file mode 100644 index 0000000000000000000000000000000000000000..0fa459f96dd7113388f9aabb59fa36ec5de9946b GIT binary patch literal 56991 zcmdSAWmp_d*R~5GK!6}Yf8Qk5SP2T6epLg#+ z`}gy;j2&I{?2RBytZl4}s2vRKjf|`vOl=&`pgMTo|HNpf zsOl(SZ=~mFW@G(L(ag%|y$}L|fsTQ3r@4-fZ8trHo@F3aCZ@fj zScrXFeh7$f5MqLSimvI$t6r{(JMCw0jff}Wd_UJ0yWyTjGzSJlVvAQ9bAt!Fwgk;Z z6^OpWkRi*#Egv zb@4|>gvfv*eVGwb2f+A)TQXM+oZs!!V-XRfMTJL&)A-EIpqI}XE{%4Z>ldOx6#h^D zv$$YA)5u$e_}>CMtKZq8|JnDq5CRn)?!P-jP~gJ;dnD1vZ+tQTo`xv!Q_TOFhd~%r zK7N7XNe?!!B5;q6)}(d?UFT8YkV-TBrrYwK`kEidq!xNiAFcBH3YQb#VARk`vL6Lw zaTPfXEPPN%kuFKHQ-UY&_+`a~H>mh@endfKoT8&V2C2Wt^uxfIsB}g(5Ecvs|ea$#sk%xH>yOK)%|xj-RMX#etEC@Q778q3sTTw z;ejsoTtIMDR^)=TSqZh_puhgH-zo4uBY455D)A-KdPWrATG7>ZW=5Y|HQ?k*G(9vc zv0F(MS$WcR3jFe8R>I&yoWQe^=tDoYr9|s==-Ru4*FPR15v;TKZaOGw$m&CsU<^yRVOgBZ{m@?2E zxPFPzXE#hqp+7}WJ5DPUT(5%85;JO|JppB zgqm5hH^Zn>P3;4%cyk!tZqB)d5Op6W@$*S6T+#*J#2E7IO@!|ZtRs8SH1Rb5Z?jdd z49IXJG?Bd+VN*luUdlV49%7?9<@8inW%~wkKoHI)QJ7+1z`)bH(*!BtAmYG<{%d9t zHD3tj@Ntaorq}hVbp+y#eiq_4lh%&y~CQ$26>&w99gG zAt|QcHV6>Ru42WK>1LE4&Db>sc8GAP-wyI#XeT9^u;_~lYi$cFHM9(56rks}yqk8dWKTC=%ZO!Z`%jPhV#7EP+1k^kH4UaT7S0b0DX+)(JQn zPy+;svSiEtQVnCSW-bDEE5rDo2l96nv_}3hy*M=jI@{ z>Q-=U{xGm+#NX4g9yp>EFw@LTyw1cS9s|q!ou?!`M9$sScByvsYHx=Qd7oC9K-xh! zP?(u-2=tGxRM9j>8|?uLGqatqP)Wau;kaSbc}APq+1={t_I=(7M>=1Ru1>b)Nrh}n&XvCc(dFZJ-LUO1?`)ITmfsf9W! zH}h)Y8(#$&5C~-YXMWf!$*@+x@j^9hX)i5thJe(9yW$0x@*G;)&n_=07v6FRPp%!m zredfgsZf{)HwiZ00$ ztH(e~?QovvDvtHIIqz(~!mAvlm=+Jr7C?kFz`r zpXRA|U6Hu^8PU^be9NSpqHLv4yxEk>t^gB^>7%Yy$+hdU0g z$Wq_Q^Hts|6qbn|DsuaAZW*iq zzyscPt@qSNU4Sox)soNUhd24M^G*yZ?xT1&E-p*Sj`FD&r;hjO}~YKVW@!Mm5hWor@EB8 z=(#IlH%Q7+b>3bFTVkPLfeI`WqSm_j3>ln&w@h84#=7{+sS2tzuFegly&4iqEL5|I zgY6`BwLN>u(6V-k zI|`dve;%?bb!SU;Me`*y1guLE@7vknIb&Ib?a!3 zVHI~!#RBqiYe|gN+#H`}_&J)WcaL4l*HCvMl}hSJxw(<=a56S?q9+QqoMC^pENp9w z|KpY;OH7mT=Td%XSYj|^m3i*!%Gi!5(wiEtc3O>Xod3^EbH1AY{4&T0dRV7s1Az={ zx7@(Qh+8BL*Ui8MlG4O{qYd{6Ky7exv_b2?S8p=Nx&2dbjiVt!MP5ry{55y|6H`Y; zveK2xd2N6G|r+|2na@>CO2@QOiG2sqk&Y$I|tB}rJ#t|&$@oZ#l^ zs046ScwvRv+;`8H-Y&j%i_i4rH+XPdPW7#XQF5jr&I1T%C5!{zutuL@PDy&^M4SC% zM@89rtQD`))PRwkDQ$vARXDWFFLx8hTQ+{>?$d8LI}-Ix*(3h9%w*o!-l-eiFJ~S@ zhQwlVIXkX)=a{K%sMM=P%}(0HZ%G_q6V=J zrUYiu=vrk&KaQqVj~%WC&tCmLkK7C<) z=L&Z8!CI(eetFm7mHb;n_{u@R!PYAK zmnQmSP@S-WX^WyqRfAl|lY?G`17x;NU8RJmV~XCSIRn+#sa=xn2Y0r}v;G;w8fBx{ zixCb2B$aIqdOi5jZZp6#Pq{!z1BJH>PDq%6k#rNe0Q|51OI2*-^&J;rJDM>`LSnEA zO*rcCtAcGX!5OcBEB{zWKz$c18Of{b>dxo|_G9f|W-mMM~2d$V!m;Hbb>f8diB2vYd%dTyS3dQ445m8X2g)^mIkP;Vpj(_gXWG>&=n& zul=0~Hzn8mPd!vIuN0M5+vQW~NQpPiD*`g(oKtIeS9HjgZ_hV|}NH%75A- zvv0oevFyhd?VDjn4`V>dLZP9Uq?1ESM-uwx+6wy_22gMC#^EY?#qC8Ep=wQhC?8u9Qv-swgX zkA6l7HF#QJoAcip^GpROKJ=Uh3MHNbk2b|VG0uo%mqB{cEuy3=&kKw+O{^k*ehIJ= zg=e*g{}$DQ%@L-l%|*C;p?kdL1$CkS#)cJ!ZJhkH5S&=&FF*CC9o?uCt09`wlr*q1 zycDT28sR^q*d8Zi!+=~eZVu`R96UFa^iK?u8D#;B>2>MOTNkbut}g=PIqL0okb(yj zT8q=Bf)A@wZEAN&NJ(kqTm)QM9v2zW$Mjq#{KVq=TP>KSr+mP9DC_fjXrP>mf%W%7 zAiHMLEqhaIPUgkOZVaJdZ+V@knY?L8t$poV~)@6&^(G4K40)&rcZ9o>UyqOjpQa#9H6aEO@jA-9zA+0 zJ>98yB2@5rLOz}pdBMA$2R-%+zF>H6MKp)*LmrhlefH}3*BJ4!-i=ZHbEDaM6Csb& zx!SjO@J=zU-0BRWBjZITcJd|-p!xydsQkrje6|anDQ-)wZ8+lKD{=xY^XJOn_3-8p zA@Z`q_Y~J8pY7f^|zThpjD(KKX7^dceD#7>S`|$T3O^M^@Uv<{~hG^U*I+ zKDkG08%IUQ^I(MTQ1Gjy$X@)sU!@eG@C_&5KOqU>$q*Ut)+Z3QskTk$S?%PuZ_fdg zO@X&;-&M2Hy{ssOd7)<}j3?srF(HE4wO?-S@0gURolMu$kZCO>)F@1Y)k(Uh!bm0l zjlj1s^P%fItmQA(DVIEKF6DYB+L#pYqXDBDs@aiMxC<C8Qz}{{FaF02|j1ABB){Bc@K?1D}v;y7v)^pk|{Q@p%^jp4H6Q^g) zzr_Ektsvmt-kD8LWr)o__$Iv=)qieFZioiAyOZ66s*R1uKl5z69XiXML7@{b0^?(! zR2f1qTCDS=W*R0G3%e$;{d>)!w9~V0Z?aDcnTSJS_e^AM+3qv<$G*UO&Gc?a(1N!QC_15KF`Ot4!61tEBrUa?XJrQ8FE?p;rvH;)-LWbIzFbWd%wJl zBF|H>mjuq+Q4Tbf&md7y$v>l+?}j}A-US!=35FEaZ+ErfjjqF$ zb=2WT=GAme_&>lk1}@LZ7>s)49B3SNcKI3$nsc$hsg+;3HYB|ZU8Hw+Qy#`X?*qhlluKn@3Y0XZ3N064kM z2bW^5h5jMKHHzE7N}oSoUKk&uP%?tzTOmB#9^3^MP$pGWgdBkCQeFPbUGsOBt#jwC zcgI@en-S1l*DuV+1U>wgT1Dhe?PKpg!k3)irp*AXXEusrE`nEu9e`qQnl=P}sFyNb zM+=t|v)(DWZA;jY0Yx^E*<1u)pn8(XsuS(E${!b?_2x(9`3cvCJ!jv;Y|vOx|4z15 z#4gUKiGQL9n@e<;d|z}`K`B&uAMVZ8>U@K1!m0_*2oQ=ZkZu8u5f9_c8?f;uDd?3Q zZRpL~K;+kBi_PB^d$w4B+YGhma+bPr-!P8#VghP_Di0=gHUXuvRdt?6Y3l0E4BqIYmk;Vx1JiQ7)~dlrGr6q)qoA9@yXn}=$FxB461Z4 zTZ`O&7+}$3N&9k0*}z@^J zqx-0F7rk&MR8?7Q@}HXjePIJCr3aONWR`0c6a&U`w*>&yPMoS5jRExr_4`gZ=pE6C zbHm8%Lo)@IPg2s2KRW6i60goX78lNLYCMeKvq;8CFTNs{0)wKX+5=Y0ax+pQ4z^&9 zy$LfJDX^Xhe`Z&2S6L;*DRF8o=%{ykF&m?vO@7IHyx&(vqc-t_Gqz_n(ciaRzEk=A z13nO9Y<|2`fbIBAaijs(Se)sP>V|AoenB z;E^jFH8^~gGR}3{l=OmyI^C-4wGwLFP1ll(^390RtXn(RS~qnO_hGMJv)p}F>M9X> z#iahXW71bp73{bUnhbwAg2}j?K=r}1Lri!tpd!0huJ1A*N0QORwu~k9cA6#CYE5?? zD`~8uZJST2WD@t9%vEmHXr!a{Gde=hXaNOz9Q{tzoqN*M}Uon3akhSQPAL1W#Zn= zbaGlx{2uysiU(V&!N(IkZ#msOBP$H*;48O%5Im|$>ICJ9E01gR?zDHvRO}@`0fK?Z zec*q?F7`^o=#X?>lD9TTCEj}EVhRG$CwpG5(k-+>g5u>dbtd9&!>Jlc+i|L8X7jV@|w31F~TXF)KAW5>4g|FZfEgL#so!7qu64F^Q;EB zH+PIDi!@XAviGP~%@r>>wnD2VDu&E$C2EZ^^ili045z7OjousH=Mwhg<+y-{j?X+K zbW~uW2gX6HKL0mEv?rZ4zQJJ(Rq#!YjF!m58RgjgxWR3LDu_(Eef39I}vLmOZ#@i=}A9mR7-IVwORFbo~+El4aCKxr) zF@h8e_}o@^Wj`Q=IC}vHVUBP*Q5^Tzcx5*k7d5oRoz1yY5qQ$2v?~2bqw;s46*Umt zeKLh(yv4rk0IKOO$^#w)l#YS58xQIMdbj4z1Y|}=&))z5IpLa1270G8u&;R9vd6)a zg$br?J8g8(bUm5LD$~4j_1g_hs?5`5&yP4QbE7@HRnhd^e=WJuy23C#q zuK*|gJ|a|yk8j50rg_&@L707QriM+p0OxwmS;q3?g{xP#X-Y9Je|v&2Vf1k1-djVr z&!ofAHd|d@Gp}N2^!UkcEx;M&Yr>#-yE1;6bPV?gA{OSB&al&-+ zZeeiXy8RRTS?|H+#4SdTDSreHq{0fbBlzD}2@Zq#d)jByMlAWi`JNu; zy+bK(w10!$fhhA#|9^QR93lRYvOi}|)6N9wR(Owad8;`8W|%faWl8>xe19T>NO33q z-z|O;GSvUQgzrb8|K0d5=>PrSQ}BO+{QsQf|Bl1@BAlWAr>d`s&6<^y*8YEcU8TXr z#l@FZ@Bpk3=9t}PyD?r?#-`*EJ4au{Pi59nau*)nP5iA;f(w{WL_Gs+cY|M|@BqEo zHk5lbf{Z-Qs0!B1v1|r7TR(nb@_(MXJy~Y=xIH#y75M91&X*wKvIsI!;Z%#HM2$yR zy{HH&5(bm+3ZfQC=?wuS4W5G>(l0YN2Y^ZE!)W+Dq(Hsy7LjD``rWSr|6bTfL2?i`RJ|{@h`G6GM4?{~V^^jwbH zP_>x|zFC9|_}l*HLOsmX41AM&MwT@N@-<@%t$h=FPpWoc9~1wzp4gR>_>;xqnDHl9 zMI6SUk&2Y`#mnzV55uh}`gK~ivULxiQ#2S;rkqL_gOm?5vx4Z^!*iDu9QUP?ts{3O z4X|;)l3aG~X8Or8^*Q~>Ut*D+vv-pDcL4Y6`**$=tA0q*m;C+!#UlEx6owPXT|kW3 zA$~w|?U&Z%qO;nIO+IWTl0Yo2J@ZC~ZBUWgibM8xP;L4{H#RBta?r~Nwx)>p_!;hT zy1NV7?!Lo)v2s(ogLl6{a)Ijk+g3!ZkanCmyM6CGMn({-;E0DKE(fjq1 z#<{&M{P+n*rFq~!PjL*tJnqjNe~6r86fx}h??+;Tv!vYjW<2<#of%p^Jg8I`XSa36KQEey5ItBS{H$hObx)Ed z`^99lp8m{DK?_3{%0QHWId^{rAJ!l<0k|#z&=}l`Z|gyEb@u5k@m?d3{U+rz`9Bh= znf41GJ%e+;>;57jO`gSdvS;nnp5bZAdkcCxA@%j&(oBGp5Q@k&Izox@6;z*}r?H+s zCHK9px{eJd{S$54#9==jZvdWEl%#qVE0Bar4e8QmKp z#!EE=tSax)^XZaB_WH=3%a6zs4I{u!hybBTxDd`9BEFcW;}hG$%Q3;R;4K@mICOlO z3*A%M!|^MY{z%F;00%Q=)%h0sGu1*>s-V>V-OsXtWurWNH0-n_{jft9TH6)GDE)s&rC#H2G&2mc^5cR1fYs=r51$j1~W zCzD@g!Y?nt#z#vU6u30KA_V5@8c?^4whrPP?oPx!a6%nqNZn3+a3a3_%Asl5xM>nta1^ zjj-d>1A9Dzn}KpOZDx?ecaO62(;}_p{F?X`80G4}Wv+r;YeZV9yIC&59;^J{SMeH7 z7MDas3wxPtSX?6Tb%PD+l1V?e<8Ri4L@b8BOip9%S?3;$cnluX)`w^ES{}P#gU5AN z$J?7jy?h#f9WE13G7tq~{aR)mjLH}!&j&;J)&poEn%`4Udy?P}68Rv6E$TrU{rO@1;0tETpw^@?3wjUZ z+n|m<$GJm<*GE2NOD8*H3&4{ZIk5wRp~|h!XXST)CF+9fJUmOG@mpMt*{mTBf5&TU z?=g41>v`*e?fLLeWR$mX^O2hMl>aE*sz7du#NurlmpsYG7E-}-c-iagEQQ-1_(Vg? zz1~Y^tYFoUmOLXuHJQ1K&M0$vV#T9(FzJ`oGgRCC5!#54Jv4Y#?$73OaPqb1j_%WC zksbB&@EUe3>iZ**^_tANJbrsk_Ic5n4sF@^HEBIYSK=BqE9+Jax94+jdgi+y%7Gdo zmOqjfP$B{M9b656%elhjgZ2*D3Wf9BkU0{hN+9E`O|}Gs`-+ zt}m#xw#r_ctF$a}wWFf{m5^uY-P1Q=z)m?xirN7zcAj$2NdUo*$b(d_Tw|Z?6NVz_Bzs4a^BEJWQ0>5Qc;_?jEu^T`t99o~rUOP2nHeXL}3%yazb$_RE64KdkxOs^}iy%G05-*W-i zyx3=6df4aD^a(y5*I?r9&UK{ZfXj03M$6*4EonEE!rYRE%j6xqNU6IfxNBR!_~j}i z(sH(0v}21nC%}^ahP`6Ex$QbKctBMb$bRRGdo&z;j?z-(jX5`8TKv{2wXA~jj(1F# zJANID6v1_R!1{|#yao^}eq0JZY2;ito*2^{;x_Oz+Tx%V- zUzjD1XmxGsw2SUucSRr^t_#k>WUjeI{ouT1nQj)KMlCs^V}-Y){uMQ z1cZ8yd8zhIH$P#$#kC)25c?2(;SZs_7)&}j=GZ8_d1gKKIrm|39x+vfi}Llwd`|#x znZUMl!`E<_@+e9i02^!1Ra(g;5lMM63mL+O+LP9H*foVG^<<6B29wc(cl{BLfZ-)7 z^;AsGaADHSvhtciJ{(x;2yWhGh&o9J7S0-IbE%~8l#TXxoJVS)>YU|L;rFs99h=-L zcTR*>sW(|Ow-+^KtMY;!&*Uo$bKSRLPEmI~yrUMc# z<7UO;xid0@6Pa+cYv&GzTLVPZVP{?Unm`|~K1ra-z#Pn_a=A%k*^x6+DzZ}b)4DkU zf#<=p_1*#1_-5#+R6B5ajbe%*9JynD9G8r`@=p;-p3d42vPdNmTk&~Hwa3(!qD6zGAt{pd!mIF^a>skU;=29jh1kFs}bYX>pmEw_^ zxT-wN&c@-_0g5Bz4NN(GG)8Bae5?k7j)|yW-U(D)?S#tg6+iP!WMT{PKVflJXv*IGSzC|UR>OLIum(Sbup(K>xP#eRL|9U z-br99kS?DiOzp;!ntBi8x^}+W%I2MbNOS9$99q+3jGOhc3o<^x%azudT8=5m2zghOo5>Oyx>x~9ZDT_3K@Br zyWRgDEBB9yz;wRqn-q=$$>C_K4K@Ua4nFF3bedqHv98%--N}tIOPUl#_}b z^*-94pd=#P8H|n_H%bVla0IVRtv9!W@m6&7sfyQNE;B2#e~ip!&LfbUUdEl963mJK zHj#hwY*tJ;ksR6wB4?r285ft!{xD!aMY3 zoxg8;rz^s(J%U!|PZUGS^D@PbS8x53lNss9dY;`h&Lz?lt&L;BU7bSU6U`nzI#)FV z7OE6o>;*r$4W8BROP=!3UpfQjb9bhy+*j`)+8ge$nlQ6I(Y{|N#}$?NEp5K#YF%=o z-Wv4d9fwHmYX5;g5(qvc{G~o*#oqxIfDHbSEjHl|t;z=@*x{LUwuUZs9fUOIeTBHf6x2gF^3&mNoPL-w9%a+rc8lpN zrebZ=Y?ohYyQONIpMsD7nYYV_Ndu1k`)O9ss}s1Mamk&So7v}Q!u+LF6n)3%i)YsO zmKCUu3y#a84$bxUw=;y@wg(#E_-oel{8>~VA(j{3Vr*Az60Ccczq2#aa-t*6;Avhp z(f#kl^R0?)+LkuOR^>G5*GkhRP)FutEejI$+P%ea~v)m;%9sl8z`!Py)|fYrg^wO|(X} zg=uQ|RH}F3C3~egRmHm%Nny`ixLW;sJeeMQjtMl&7!lq>ieIJb)kEY{j56qb-VEOtd)~B@{7Ua^-I^G?8EtYn2tO zC#p!Ovy5G!J3Ot(XNRA3pjKR}(!uo~a1b7VmPQ)|*7-tZ;ly3#0$y|htJ;L4ESMt< zzqIdaI;uVw;hesb#3|_uwlV~zcWZm!*)W%<)T6)9ogVBQeH{cLP#fWrJC$V9$LTbu zMM(5d$JUWW3&ut5Ai$fwRwetFHpkN*KCoYHsl+ZSw`bHzBrSyu>I=7$1aYN>y_}G8 z$@Jxj@Y&R5&$p06@&>%atYQk-9FZx{URq1IExW(63ad-!M7%DLQWdU56?qvcGYCy_ z7tS1XE3RTM45N8AxCM7$DFl0~*JE;|hufyk+B07x_H22EIaOGpW_cc+Me<=Z3U~QNqr&`7B3kdZHNZ!tYp10EJ=kH17GbSpD<0_iciU4jmHIjwsPJU;JdF*m?vLPfAFs2dbtc> zfq;j*!;%|nFWz@$V{D&CPxz?dd45B?YEbOg@xCO=Ct9)HbO*i)>K7q8gM5iIJe6u#cDH)ov*qa%j}n@ zt56ddvaqPiJZT^2VK*-ZAPV-zRa;A+9dK4V40wBD-e_nBtmNRR*N@3agku)E__(T! zl#v6q!*Zu{kdq+IV+XxSM?TdIN(^SI2w##T`w(>Om8+2Ch|tR4P2=- zJ?itz$9oi2LRK{dcB=7EO~|v8Q_@Ne-rjGHnYoUu8Al+gg3C#1L8&uYdI=*?S>?8U zKEoV56wAR%fWZ{!WV;j&mK#~3HeOrM#T#LTS?_mif;925Nio;mVH~v07?TGnN0`da z3`cIkD$Tz~R4XYbCu`*MQ1~@}?9pm=x;11F&f)Ly4oQAaElZiAB;jgFjVFidP;fAr z?`Ogf-DSI=sQllt`eTGF9siq_qrqB zCSy^6kV#pIK8;(%1Xi7)CtJE$PK|ED_a&|dCchnl{x=ir{pfDT(p-PxpEcB1?q5&T zSPd;!+gG148_%a$?3v!K%;+|eZjiI&+X>6ym|61*sPw_whFGF)zX!p{CSxtnV@zki*{FZB>`FX8VMlYf zDQ_62Q0A7L$_eg*7TO=U7b0jdYMyC)G&3vB%`XW< z-NNpi-AG1!cnf0T;=z*azi3T!tv$uZqhZZ*<8tM>+dL}jlhY`pb@i!3n~cVFeWQ!; zSh{f+sX24^e}W}^Qdt{)^;^n&^q;R?-X}t&Pv!BiA>-ee;pHTFr>R=RyxI!|Sii8r zSyfo^l6`4$pfPJa$sX7#1oa6yd+y)$mleA}8H|qL%V*?EtGu?)$FbD=dI=q1q0?2eRI2VqD>CW6L#b)PXn@mk^o#>E+5!reR@YVj{gh}1*d(|#|zC!v{zkmt^IKG%NJM-SUfs;Bt`8}J0{Q|nUhWSF90?8p zR&Va)UnKLbU^t%NilKu{v>#Lh9}V=|tECiOXlHt!QMQ{E`zNVZDUo*CjxY?C!8~AFEtZyZl!z}0-GD|<#qk;w6WOC6O}Q* zrcuH0u=M5?nCjy`_9V@SKd@Up+PwFw3o4{XbS6#Zp`p3wb?qZ4B}U5}H_Cfx!X00n z$n5Wp$wnY}r;#n30EAiTc*mE9IkzhW=Hq+P>0U;X)HFP}$1iaA7a5KdmJT`ugL#vB zsTtC92nB7Es)Iu%5EO*W?E7w_Z$(|HG#jo_oB_Q-KYJbeM_=l@`ZB}T4{er2!WUHP zQiEzEwD`Y65L)>hd(GFyIdxTyfcYhK81Frm%EiSua(*t&~DQvW`VR z!69jAG5PH07C4!1Y=*!!*<~GWEv37BIlhJewd_u!v$Xh5!~5-}Ik7ww&e-?B_KX>y zj#$upPyW6iF;7HqDt5>|b1GFb|xjS9t!?23%4EpJYj6g2A;>TNcgiwevSAQq% zT*u^7cmVB~OR?YXm;!<$K*VTd2X>|sNVZE7+xGzyHUT5*95SvWG#3M#N=!oUb$4Cd zYjJZrOB^v+B)55pEnP`j~ky{9U+kuQW1x;)IX@f z<3ev#r!N-TjO#uRzw5(Vx3gPaBFD@ZQ;2(Z`|}L#4I*D)Aq88n0=-`Kbz2^eJONS^ z-evoA=cz!~?9jEtUaTwit{{X#q@m3q2@(4K$=I6c%LIcq{RhLt6cnE=MWvndjcz<1 z&tyiEF*=`D&)xAXz|!dB^5ra~GS>XLhqvhBg;u`y=nhc_M=#u&ONzZmdAaxl>pHE^ z0|M)cEtJpeRn~iMnQE&qax0t`w7%IJE+`~)v3lm6glp3lW8?F*EGY8kbQ>}^ryPaH z{%6^yLrO#h_UZNn_k=Vur0u}vH|tB(q_wah(@S+^ekyU&>kIJBf&&nB=3$f(Q!sVv zydHtQjh6I2kIE3ylzN1jl8N=98k8(EbO$ebpdN8k9uNy&@=r@1U0HotCoISg47>F< zc3Ib95LcMGhPjqo|J+pa)*haq&?iycxl>QTXW?-KnoLevPy5VF*Kcz>vE#|jI@3t)PQR1qa(HtY*6D8znQix4+v6>G z=%qg?T|sQFV8nxAf5^!N%8nvpf&M>)MGB947(62MWtnNBZfof@WvLH#p!CtJVE;QJ zyWXkSfW|JIA`~c;^Nr^Pgo_rxhW%cZ)|h%yd``kv&zI*0{nzR$IKcZXuJjK@ zM}nvdqsGRt*Z>MaXbViOX3FO^+z&frPL>)bTRHr&<`&d|Vdgm5RBvd?x=_*g>B1o$ za#`MwFpGPN(tnL+Yl+ zVLR=2u|))zLGD!It(A_owIIvB(|NZq4E9LxEmP+Ui|-&tZ!Y)Dqkb&KL~z%&Z5Zo_ z$kgIbspF)@B5pGQn?&G}ME`cmAWMbLl2jv`r>owWuo6c}W_l@~mDbm8WQ-cgq5px0 zhuygQKmkr#W^rh!k`d8h`e6^#azsZbyoe?#n5X!go$&{>*@>HHb%{TU7<+>`k_K{g z6=3lO18gBA%mQrknKYB%Y-%~94+NwAUUbX^?aQ-!@m1FEJnkOJbo#0)@Iu$f}4aXC*f*N+1#HbXFJk+ znjpp`-9Z>f1mh{4DgeERv1R`HP%`#SAM4IB(A0S690)Mm2u;GPYir1aMLvUHgDrp> z??0QsJ0xD38AYeTanDA3&4#&-g8*jrt&kLQ6=jdFbWf(gWwm=mhu4g}0bczfPdC;f z4pGQH^|*dO=4JS(fxE!UC?N$$&8$Ie#XZC7fV}fKy7casD3mFASQ@`Hl&_Ll%}Nd9 zbqZ`I@)1A?q3Frl!mxiX!cNxn_JJTKga1IUo>2TR3*aAo^bq}LWM!V2v61*LZTzO0 z18ZTx6As(_+e75wN*0!YV-;%Hw5arGuP&s}g8rJCbHZ<_F#XGqIy?`>C<=%uU&rf+ zwA>gnURGLpN&_2JTWoNK6%etQ%3OEyYc%Cf`2!N`rtb8xvpS<5n(xmBMTO)vl zh1GC1WJx2ZrR}$5$(ui#G_RkTnUPge>V3Cg`n1uR+1bU!RAyKO2qh&Yi1>sAIW;vg zQPEG{-i@bcSJ&?CCycy`AW>=(soFRR$~=;1edFqDy{q6-4kV)f#)? z^NJofTvomo6MC!r9T%BpHUHCh=hreSEw(RaS4^>t)02cNBB|tI=Y?geJMk*2?zTjf zF3hL*LFB)ix%4h~3Jtqd(Y-(wlS8MB8I+_rD#s z@0Lng0y4!eRiuuJxB^mMlb9trZtxg^lw`SfE-f;R>vwAu$~Mw`X)VFD@{lCY1eznI zM&dkp9q3lDNoWsJYTe3a)WdJ7qW0dTgPa=WKjJ(?Gn;)2IwEZ}ogJEgLwj;5j32VH zIGC#Bo_NYdr4OutK|?D~91Yx=hl|J$1J@M8^JhdqIfH0x6mV>QlYdI7O8!Cn6GfvX zQK!(7-{VjNG^k};a!`vtvJ$y`v3&lu?5#RDo!Dc7zzifMc0bbld@<|FuWqdZ4!XPU zlSKjDD>NXjb`I62iH)@%d!2tazH|Vd2fN9UwU#|JP(=t0qp?*xqM5mO>hmXQg!ok< z!H{`NYSd!QbqozWpP?cu-Ni6TrXXZC&xGK~vR8>8{(;Mo0HUgO#3EfHy6Km?mwRc;x@A}#Y z@OqtdJ_-ADb#bz|vhqo%fSR2h%V2h-;knz%vbtt zq{WE0wY{DD3QuP5}=;|Ki-7NScsWBqa(rH}{v6l)b~lmg#9?7Z(>f zIXN(ml4oUQ!8@Ygzay0yRbAb-?by2#t~Wk5K0d#&ASNPmD~3j?ZE$ce?g!)fUOVY{ zjSEYA1ZjI`CrX)47(5N_+8^B0^`RWM)f5-o;4BLc^B%+TpJsO-%+iM?`WLdt;zm2N z=aih4hT#7&YCJ6~b&O4~e5CihlEF*)cx6P=%-{4&kElho{mH)g^S}6#(kz7!-G8}b z(|$gso2)+NNbm1kIy^&_uUy0>_&ZO<_~}yK;TK zvicMOBzboScE^FZq$lm9PyF_u7&YTE-v5|) z%2s;hA`||Qs5Yu8O&q|-Q!!GWTP~0o3{ve-`ywk99*$at|6|VZl5anC*>q`_I&XH_YUIV9pS$O4FuZ&B4uS=CzqqutR2@q; z+OMXj#wItZ(eSq^yRw17?7ZRkf~rvfz?UyYbab9%N=LMfk5?rdr0=}jTacWz&^I%q zLPA24PZJ_8)A5=-*2S{bi_T#oQ?B=W)oy|_Q(sqIR;EC+Vw?H0e1>it6|0NPh?c)Z zUTU6HzS4&~pnzFUjUv`bQ<~A=j&;61B_UJ(gMpUXXr34))sJFk0n)_V4N*p;yb*|1 zm&=(AP>gzcet$6bi_|^__0+}rN^*(G146u)0tEdO&@C$6C8S z*;ZPkbv1#?@#qT0X$k82UFyc^N3aW0l5|C%tr8^z{P zmP2#Qs2O!l&GtkNi#L!P`_n4?`C*Ikb}Fl?$YMI}-@R)c9>(S8=hsbR_3-dOz(7$^ zyK%`&J-x6_(~R2MFV)q2R@Tua?E3C`x?OfYunm8&UAY|i zRpyZ`BH)gb4=*o0KcN#g36}4VQqNF7gN8@q0%3R z&1Kh=6}h%LEO6doCqo~{ahXoYNHibBMiW#}Gg`Wq&KcSnpoKLt^Skv;GIv}esfE!N zX`3JKAi4`j^gBa_8ZKtzH~VBxMIkIh{zR{O;XzZEfwPr6ogF0$LW9obqx!#Io}& z&CUJ(D*EvyeJmjEP=%er)YMe5PJyed>q`RzyF8p9d3oZ|ls|s_D6XhzH)Ms4QSkN_ zs;a62L%u|INdEq{6b>({H#`H8iB0ow=BqnJa5*T=vvANS2qE%lm8h z_Z@EEzKtONR%PeeMV?r9MIZUu<|r*?@g@&;$uF6%8nb>NH%IE147wH)Tm5f$jNIJZ zpni#tj<$DphU^m!XuY`WgT{SPOV>$wp+@u}t#EZfQhn zys5lJ>lZW1SXT}saV*_c%nJ2A#F`_OPu48nY%OW2yWvH{52dowyd5?u&z5#$i!#~Qg`#`;T-Lhn&#MYkfs)k90K5|G zWh{+$(gn=si6?J)IA$(F2|t&<{==+-wk*MPoi75mUdr`9m`;j{inm$BCet=3yu#|U70GmFKKb=Ch}+n1&PC?!~rBRFfhtD$YOs~l*{2G_9Xdz z6LFt;w8qeB7AIw@a1qXAH(CmfFS%&tJt``y^g+vx?r!lc6*iMLbaDy`n@J0_X(bZ= zm|Uby?Ud@U0)I5^vD(Y6C1&T8TW42qV zb*7b;vCjW_%WTnSJmfJ++n($fYiEEObc?7qv3TFce8=;%!fb*0P}E(GP^3Ovv!OoY ze~N~!q%h-iYyUBtHk*rJ&GqNL(VBzP=HfoJtB%Bfe=}Wg9I@98Y^bivinEt3q%gMS zGsYNctTxnkKD%c?$?CAsf)Y+DY^(cZWQyi{qDn3$Ik|7+#|IR$e{dULN{ht<35N_b zumyF@87@Td+LI%hOA>h0_0x2*gH9)5fUN+_7T#3)-SO9&Nhr!U zf#*TuQjyYOR1@1>0e*Ft&l6R{=C+5%HIdx5&=)+pORkr=%CBpEi`m}urs&NsfAD1F z$eFrkQ$A412kPYj8JC`c;X@m0+6sv{lpm0~>FMeJ?e8~1u&!yb{>`tfBuG&VP|R7p zJUduBa^Kk4m_T>b`B_@pJUAF7`tkm_^EvyIFklCe`yuu^Oxc$lc*O%SsGdE0f3Vu` z2uCM4ICug*9bVbd+iSMe5jA?C@~*SQq(!#TGZzcc!Np zs0s)p+5H?Vr$Eb`)H0WU&3s0eQ(2768hx$9(^sUoZMpn8mSEoMA|7`|+4O#u-Lnri zGm?sihR+;S=tl7FeE5uuk2JTqsgPXoQ}8z7jIF^pXHI|7%~A6b8(ltzHowNGf-OF@ z{juDZdro_&+-#-ep^7;a6cis3$98D_O--zuyZgfGYWsVnJAmM;e{)sAQ>3b|-xoz8 zUAda-QMp-IGeHcrDP!1*j*(F!XDEGila7I*`3=`(d8J)MX(@-xtQWUQTWGr7Z2jlB zxajzJMBqMu{v4nO5@ujPz=JyvFid~HM?!zXi41rGzy#zZtGc>+m~C?t@n(x4LPGMM zE?%~PEv2NQDskD>hx38}DJui=ffgxmL!%8t#AP62>UteGIp%xVI zo&EjNdBYi_n^hor0XTDVa=seHgL?`vTs=InpFHV;wdZkMK~GFf#KFadS~_UZvIXk! zyy0L6c$SaSwJv6ks^uxmya1aoD^5XsNocy`wvy@Q9^NYFpTWw9`!9A?CVM?0< zHf&N$t{0rlR0nT#R5a97`kq_GRx@*kCsNFqjtAMi5yT2O*kQC!{{1(o!a`n6TN`nX zc%0TE3;sYE^%xe?*Vh*r4b5cWt7!R!hnpK4Odj>6@CU#e7_vsDq$u26U+LZ>)yTum z90ZucI6FIoC_~_Ym6cVo7UO7LYaP&eRDWNi=1*@&^<3TpyefX-5w*2thD=p{@tkzj zl5=9kf-AWM)(e94?t=%a>gtlOU*~SK+1lEoKjq5TO_lJS@oRGpoj)zsDDMGCN*xVX4#YHBcRB`q%A{JbKs0WVR$?e~W}DCp?lK*BL;4}W`p zxbE!n1U^Uk<;(Z4m@Rq|*kH**0gP3Yl|P838y>C=h7z#dwy;>W)!t8vjrEtxoF7OR zhmv{R*_w#Y$ud5I3Bi|rpE;!<2j5MP_q@3}0R{%=MD~9LH9`ZZy8JZ!0ePD2SvcXz z&8Kg>8l_MEdAn0%Gg}i86Quq2i!@Q

    2ekEU zJtvLFe(u)M(UHia3Wtx6k5o8OP(#BFE}1e1C<;;$B)y2bgg+xi&?62Za)90d+!odu zbTXq7EhsWKokaf1M^k>5qXOw|X?Ypebzr_;>i)+MkbYEERD2^MFe#)$4O;>qPl3|c zvFrc|>iGCLB{g}_l9HD1N0AEFj=O@3ujqdV9l1^lGS9$ANMTSM z!PopgY=y_7KUL7p>-V%bxiW|PU-I-MtqU^cPHu@N^WJ`Hq8^ zYV<=Es}5OfDX_Hm{{DO6qO4%Ha@8$!)rWl5uCJl~&bm~mAVHqm!O^j^r{@<_w*!#% zXU}c{&w1{OMsS(;{pP#q;O5`1ts`H|cRE&XSH!$9cPTg=CapI+{9Gfq~9DcDgx_nQ4Uj~!pU zz`~HgxAk*Rn$c*}g@n=LOo7X*ES0;#>au)_JJ|0;x>N}~-z3OmfWo4ty z2&n4be-vN!mVi`Os*ah$?-Ksu&I9&$8)_i&!i(1bvfYCW4QxM^0>SJ>L4GmJBLT7n zF{tmpPIVuXWD4N28t%nNTQBe&>6@$`uJYqO;_#E_zJw72cSoqG{y7g-Rz45+F#Cqv5&cak?$^7> zYZL7fnuysiy%a@qieERnQl-qOBV-Edi>eEyu3zS$u^B6 zM_rwrqM3umcC$jaCT+u-12FAYqyAsM=#@a6!rtqP*_(_(OP;q2cR${LxDX{xB3hsk zqUX6|xPScteRsC?BaiExV9#Rp`K@Z}CDXPxf00$v-`8VzY3>8kGZJy<*SmeCCsCmj4y%cR*VqCBOu zNs_LZ^`rlX@lSzy>mI#?uLsf-zJaIm)&j*;YFFvl@r2k&n%{g8^{c_23k|a}9Xe*_ z6=0ozM@A;%93PShB-HHIUj!33^q6x1SAs$_IxS5J5Y)`fEJf#dSRK+A{4AuNMj+r& z4E+Wc5!3m1-ijJR97tJY=futH>z+i8@_vE$fq}@>ieF^xiz{E^?ch*j*vxxYu4rNf*}u_wF>$0$iztRDJbQ>Gv*6;YXU>z_(KYI_ za4|x|_~g&ReLcRKhN&QZ_Qw}Ak3qOB_z!RI316R507^i@oCh{7jwwj#y!Y7FM7x#{ zx9?|j7+Iia3)aXL^N;w|zk*MmJYgk3M<73Jnz;C#Xi7H2-?u=>&^g*fh*B9Dw?8(D zh>Cu&c~A;P2*xh^$TSoyz-AEKTtnkid_4Z0`{>WOxhurG`%T#iAZs6h;>FA(SEXf?4D?)83HQ{hoC_uD@KCpTfBY6^p(f(rG4qcHC3r;)Th#EF z^kn{Smu!TB{`yOY3CuoZm78AP?H;<|kGDjM76s~0;` z!%XT_Z=s{jK=tqU8buF8_WqSJCJwClTBURJP={(>>@L^GUfP?RMJP%?^4mc`-r85_ zk)wo3HTMhO^Z<(r3JZhutb&Mr(b~lG)K9r}f?>Ai5cE*<9Ig)mku@&Ud24U~ySqCC zu++Fji^pY$2&z(e=wCVoHkzeFPQ~z5dm{+YQ(k2t&13 z$CGse*n%|;69GssXD)6$x#*ZO4{HP$Nq$d&@SCBDA5QPI$BV!0ivi2TJwWo1#|0E6D4qNNo$ zX!)(Yd}Ku6+qYK+Sf-(WFDAlp4HRN7jpw|y(|PRk?W?5dDRya~?PBGp#URh;5EetK1ZMj!RLIq}N~VWWEI+?+kk19Aven#Is!6B^i%R}F|HmGAN6zE0LY z;Wn^;iFIWvFt3THTwahJDb9~I9+ebS{{435s~`h=oR~$L$4{MN+ti3tEn+SO-%Ldf zxq8d1>~(O*Tx3I_NM@s8H}W?tCCNG>7Igw;?1e<{ zG`k@;(`Vb=y+nM8;Ul-d(j28d{mMeSo7{THdJiYNcrQ<09)rHE|7pO+zM1!^N4<{2 z_;q82@bLUe$Ui- zAljQVGc%w~m&avHGb^SE_44o5Hm|1n%uK2pwS^Kg>Xzs0#vjz}wLPu9KHr>nuARwN zqaWmEA_a!K0_DZZuFs7}Q4iIsU5uNh4fScCvGu+~liAlR%O{uxGVR|8+W9*-6Q@Rm zQ$A;fdUHK)PH3$q^+*^U`Iga8OFQU6lvkcVpX$YOu(j!t#N4F>dZ%OiiwMNs?Wu&{gyv9q z{VtoWZ+!8BJ4RzVWpAHLxGr=*znGuVJ- z{O@rBJ5@=McgIEl{R&jBLc3Ijdap#I0~h09ogRL1=YJPIzg!ihnOADI(O7FAznBt6 zRqoa8Tq2z{e0QFuIlVj1v}J&IKcVAnG_S{?B<4#}`6o>C z5fsS_-0MvW1%P^Zh6G`47*};?{RUSXnjnIGuSgRs`cYJrQ(2j?*d9><;xuR(w6wIp zXJ+c#U0652zkh!Vhye;JYEx(D`VWQg%MQE%s#z+pJ;DJ2qoc8ox5ht8WkN46s)VF>F?Uko| zxukBxuA@#dZ59$5SMFG{n5aayi>vw&AD-|sG_m!MLD(V*>A+QGVyyMaSEiZfuGMU^ zWpgpL+j*&O35{N1ma0O=M-S*Mk36)l^id;jvLuI9<`wnb-RWl6kalTT>Q5PCGSz5% z+}SzPexBE*EPb<`8|S4Kn%zg8XP!QBu)H~N( ze7`+GI^^WZ;(|kZw+1%m2yZ+Yt3X+pTQe?Q*1L?t{8xSeSOWSUrWGJ#9yNXzH4%zOF(WBT7`L0`piUQ zz93Z1)SR3+pn-h(@&!}KTk^z5ntmk4>m>lf}W!*wlfPWJIUs(hOooS#@!{xZC|qD4|a zcwb-NLqaI&H1}#j<6Fkn{zDC=poK76l;sWr7_IJ%wrS5k9wy$=J?;g-j zHg{DVe|>OiUbraiQ;j1*7rUtSYe!!!PH|=22Y0_U_@R8wE^bpYMr7%0rnIFy!L&1{ zm)Pc$4tP}FA>3FCd|~YxSuqDim}e_zNAegUjY^5#e7A5QRR@W)P$@7_)42I;WG>%tjP&R<`y3Y(Pa zBntZob;mI+&Igd(u8L zUCj7IL_MK|90>w$?Bbu$8+&^Tn#l&w4pz^$O8Z@p$1SuQyahoayF4FlSScITH@Q6B z1ABw5EFd7l#4I=#(kZd8$v<$%Pr=wB&-dQF#TDJfTMx>Js!*{Ue`y1R_qd9NUy+L}B_NJC>F;C)8 zb?JkK7dVb-Xf+vWp*VZD=236msa`0LW78v5wK7%}!Ec$;oIrg^sn*YEVaqB48#r3e z5Z|O%)MPh)EpEc{qut=ufD~0+bbFf8GcI$Yh=3ZCpH8C!xS>AIBkJNAZOsyUPEU(! zt|xmbql2I5JR#rCHt5epG__%BCt=;_!|#?M+l*J?+OdRI;gtJN*?Dx0{e(Z%WfX zaH$nQYBoFArnGU_F%enCmfRXf^)(f35qi|J(enzu{ZB`6XerafE%c!hPIkukI8tg7 zleuA>=18PoPV1Xrb`o+J{r)L$bB^u7zyyQ73pR~+k0pBQCqHcRMAow5%nmBQM+Q8f z^Hy^f{U2f9&3gSU<=)FjUc2h$+o~1rON8^d+O{|S(HnIk{t&t zpH1=YY%$!Q4}YnuYO*P)_Ue^9lspaBM@59ZKf?;ceC^Q!gMz9GztYmv2jlCz&fo7_ zTN#~-p@AX@Bwes&O#Pr4>}_jo{4g-^5|{wE)M^Xge+Prx|3n8jC*rfbQYik%-GZ$sN>*nH6y{tLu)9PZ2sc z%Bm6cyI;HMOLPtn4(>RJ&Sq@{H!{(Dcx*kN+7qI{m)9%6+qg zp5#f%kLk0GUpmi_gVCO@k{z_3+%Fv6NId}lzChoY5}M6gR%6bH?7|FEN<~3vC^`f! z1X^2ncXxS+QiJ!EyN8wU02Qi##xRD+D7*8PRw~qgBniX4d2UtO=H}FdgoGf9xbRRy zgI63Zt*>Vr8<9dilgrz~`*i*Rd;r4T0|ockm=-7$trj!H zTh6ad9}Yl~2}PuhL4PuLQGkme!_w@eN^%?uVaLE0<)V%Ych=A4yjSM^b~XE=8`){U z74V*{QpOZ|$;Cu6Vh|DL%Z)joAUwbQX*7(Cp`g^T zxgW00q$WLc8VCH8Ra9JoW*~9(O=g5p7sy<8|MG2ZLEr_yfV(>%h$+x#C>yUlcYuxo z_+WGRx7-DlfS*oQv2`rE;#@D6`yfLF}2^qk?8k;8_t$Bt4!|Y z`uIR;L1yxT{PltU`k(!rV;Lxh?qg(Q(WCz!rjPAH4~r#YM`>LimcuL5KQgK3HKx+N zC+nYzTAAUaS_=0jv>7%I*NOAz>Us2JClP=A5R4(5y}Ifa1VFY7+{uHM7t)x`%@ z4*Xm?Pd39f_ZPW&8*vBfkNil;5DOO>8!M@zf;H=NBPf>@4ccF-&$Zk6$?hzO&VJ0$ z4WOiL{|%Yc}G#>xX70pQQu8c5F{NI>=peeygw zGV&2d0UOGONi<;?ub^aI{xj?9*C{Yl4v7Jv^5J()* zYvpl2q=j$ufW-AZtS=}$5;Bxyhg!R-PxH-6H>h63{X3qtJ2@r#Q@;JI{kE&nZ%39k zY>%*z(X}MO%ZnQow&mTqn9r?#!mh-)bfdDUYU$CUpQr*3(Xoeitvwj8N}PV-{iZ@z zKZqs`c=7ycb{?nGpw(p2t8El-dR#1b`6@zF0+C_!YGd+6OWQ?*tD?HYJc`fP^|VNJ zWC35q0&T3TQiY<m}yrS3e#5gC*8Aw7-M z8(v8DThm|8_e+u(yCR{XsV;WE+2Ypfn98>FmhU@8uYczhh0G~MzRwP6OEwejyP-E@ za6$D}*3!!ro*K1}f%ce*caP5e`1j z+1WHO6WK$oW~k(X(W}0&%FV;$;9oQ5!Qqe+_T$GNpnKHU*EfnDbm%T<;C)5~%{PnQ zr02JwbO#AK8Mc`H?Se$P-K@8s<6}SF)<0P4X3G2L4C07=W2|5 z%f0?gbBOshx7cq7i0VCMw2e|@=K};iwDS6!ap{3Gb4h@Ca{aYm3m3rCc6w;A4h&k zd(kFKfojImTk7vY68JjbxJzMa=yTrZ`^2*?m*b^DPlZ!wci&V;Ea)3IJ;iS(o+xP^ zvCfN~vKvp;kx{J1JLgK1U}|a$&tKc=I-^Gxi@*|%vhU`Fcn4pDP{a9f(O8`aH#8pS zjz$eEW@_C41dfjn@20=-K3}Jq@xHL}KB<{4u^wfHGk_FH83brlYBfxc_}|Bm9}im5 zNtJ?OBpd~s`tb0VogC1)G;avl)0eTi^G>=SAzl&w;;c z9mksZKX-VZ9hjZh%Erfu%QpI)G`{2_3c^_ns#9oqcN?b(Q=bI(GMi}ypzsy4{<&G)~rR-%d2IEHcm6Um9jFr zgj?#DLt*OXb!`23-!8Bdo>C*Z*K1V=hONifHTiqEE-x#D4Zp456W~tg^;h2SC=FZv zv_7Y!uj4W9VIpHOZJpdv{2qrZBHoE$31>j;2DY+G@0-kW(kso4u^M<0)}x<56FXG?O|o?EZ=&o!9?M*5`cm_odJVwNxL<3nf17-YKTd2%t}A4ES|t z-O~D2yx~gy1zt=IogT8=+lMbAgnPR_hM7=DxV^WJy3AR+f~-$#&mZdR)_mlwOAY;t z!+xuiKXlx#t~L5Saf?@3&eK(Tw(I55#MBEu1JftJZ)cZQEooUcXhx6+Q>EFFE!C;# zUo-lDIm9XF7FI}%jzrmG)Tw>HCptZbEr)8p)3$wT;~Fx2GbY{_C1@GJIh#%Cxng{M zY9&C%6i;#7CZM~Y*1@mqg>tj0n?IQtUcUS#>R$~@Dpj|>(SBriyXK>-Nv1dI1!iXx zy+mC~%gL8`5h0-3EyDoSPtBPBKl41+oa;N62Zu!OMga9{b_7$Y!g*nDOI4e7_OT3 zNUEp>D{-3Vevl1{fiAd=!O$gMpaG*}<6waF_xC5B=LOxa{&0_ zED#$^BA5g!QQq|X@A>&X8iGz>?Luhvrlw2JKQ)EraC z!&d*bAB}qJA^YxV(*HNoA|fn&|Kfq(4O^jRH`{bA0TEH?&pP5Ncav16#KR@im9I?C zKZM|WH~YSHbKde~U0QJv%WGbO9?^iIT9>t8pI?1(Bx=ZQ7CWk73=6{)L4$jumg`cN zL}c{Ae#veB8&NtVbAY>*_oZ1r7Aj%*v;`p@XM0&E@*faB}}=-y<^RNq|U1 z*9%;Fkg8UHoWxLe9`j}nTS51acxHd*4OdKZa!6VlDb(}`+(u+OM7tCpKb|2Dt=wsA zj16qwgm_(-X+&pF+o<9=wrN$v{=r*P$QTd!WDSMwx#2a6>{ky)PA5-IOIb;oS8ck6wbm z4*HD(SBFC&;$&CkP$5r~g8>o>RA`0Rx7wV{`UnFekgrvJ0QL+DPnFe6gke)G{rC8I zB8*_b)Rv5%-t@aLgkuk3;@#UbI{i04HaWRCH*oAz1fD5K>7-#&9~E;+0%E5&0Dm0v(U6^aWz(AxS z>%hQ({V??~RE;#y*9M!%;`(~fe}ilL)$s)SBv?ngvp2!0WqH$F7JWou$>tYG{eKQ3 z3*cA-nL7Fc&|Ts{c-zUz-92=C2bh9GLZA;#2JhF^)umApM!@C^za zEn;*4PWu@Ik&c%EbCM%9H8F`L zxrUOOn)+Rh-urT|U1OFzxfd*BP;tC{_inkcW+wyqMzg50V*~{p5jYt#a&ik(RgQjs zeyotdbSq|)s(df=J?VSi->JlW;@{x0imCZ_h2RWV!Qk+~;_p{xBKiMJ$D)<#JC%qH znK)PCyqPvGff+-c=@DY^s6dtj%P+(W;>3Zs2Bs($!1VlzxnU)ory`@NNen)B4A?D{ zC}ldmpXpTp9UZ|$5{g&_G<=HhNyG=BoJ=`l0y|C7*ZHdsmAqxX17ctad@bPC25+m4 zY;0YfS4HUX<=OqP-Y;+yLx^HdGr%cSokn0EaCY8_E2$O-hJ=EQJh#*tqsfStUs$-( zTX4Fp|+H!k@A0z^bamX?-tP&tFu z2Rzb-c07Q_3*?8uNGM>8{R?7Ga_57XV9XK3-5FsWU!7l-U z!F7R~*lP~f28acOa{;EiS9%h~O-)Ue1d0ELZ=#h(ws~LIV3>i2mlxsMb#P$EXMXkd z+c&?zf7Kviz+$h$9)j@$Y`g)$#$n)9RrO8gnVO$EvY^4yffr`2?bq zg6RURWChIm;l%t>V4>kl!T8_c4wS@*8e2`xNz&vmHjU!g_0G~#%cqA=U7?glh?dLF zB78pA0)SqC^0#1IPD0{t47CDmZ&5|gh_#MJE&xNw*DX9vZSB|Azx6@O+$e`paBya( zB8w$GWz$qsEA}|C1!E^f#R6RbWNvxc zALexjJ9iDeyf>GsjQ%O@8@81fFq(U-9AueqCGRM{qXULso(Id)R-o zp2HfQfB#%xU7W3DMrc*qlL59^fa9F|^0`%nN-n~7^hL-kX<}kR<6va-2tpCzoB6Js z$(kq+g0~7hN*)md9bNj@ukT^357G<)sN)erhUl7N|K|lbr-j2*q4&)ggitK42_n7Arqvg0u2QF?TI(=mIYz-TG+#a1Yf=G=4SQxEsm}4&nn+n7U$AZ zi)(2_JIDONs=&g1QHpcmtheD&v@-qcJZ_{e`>dPOuIjKZsS-Dik~Y%x>$8k!^c_N5 z9QhoqtPR5NDZY2?sH~p3o(5R-oqajcUSUleb!#xNlb4r=tOVzr-FAwn@Ku!G0kYLZi@TdsP;6*(1cFDotlrOxFpFq)$`urI&R)$ayQT-P_ zbUdkyhj}s>K#7#g0x&o3*BN<%{fF%=FSjTj{%2x=6dEVQw5fByVITu_1)bT>%i z&qAVe#i}lhg~Ei!o2kku0Cl0uf6XKUs@u&21Cap3FashkCUzSR92mEN|Jpk`n!vz| zn07H(^}w#ZvN4<|Aua8Awr>WR9}Hh};}&VlUIr%BrJ2feg0J}cKVn{Kil zx)dFpcP7-mDWYT$PCXFxARd6;c7R1TZ&(HJNG_|XrN!^(PxhXk9#&4yZ$KIl^FZL4 zH)Yq3Agz%ZMNkevn8(+4u+*lQM{p|IPe}3c+XpkHgMx!$)aETbNTX)X`q_O}&0%l>kv~2F&KaiENFl)V0{Kr0@@1*KMqZrr*C2+p?h5_ z951r$5%z$cPx?hUaJ0eFjL`h3|%}`GucT23xYeJ_$%m zFwF}K|0GOm%s`b<;Y4PrMZZ8JCM6|IBM&I}9W=C%3&#wJiC$GDK}mUebeP4FPhkB3 zvf^ya)y_m&$aIZMOj42@pgK4rn=H!9%c1Txw6f}gtARRB_ZFjMC=piXbnyU4)_$wW z@U|^260Y^H5#~uIQ1Ky?MMg%7yn00h6J)Qd93;o2V;;c_(s)6;I>-#!3dsbJiowUQ zGg87IEJ5BlHbwx7BRENc*NAbMDkwaJAsWAcfS9d)z+^kR}Q50YqtgaenJ zJmcZ1l@H zYb;efW|MIzrHKt|yo0GekoXf>Rt$pKdhTs+alR){HsfPs48JKzXR*4New zAXuSQ8O)WMn43$zdsk-IlsB{vp^}}QEmb)Ke?thF*xH5%1);>n#Q|tTQ6>(@7B1cZ zDF?!hj-Fl&=H&)0-+y|Ob!@7|86*t~;5RVflai**>Lt!Jw*hNFWSTyxcicSwKvOwyn8`0A74XjyCVAltt&bMX-igv4Rg-&Q51<2mLSEn}=H}+KIH>0Rsb0Dj zZ7ZuDJ5yEQFRs7be-X#1?OR%UAQ;x*K|42=?DK4`fsh+t9WT<=6uVSO+em$M!dVBa zqSs=?pqbXvJI`wP+x0$EvNx}k*4F6OjUkq^%Xkg_>g}MtjX1Or4jIP#oM#WIUaQca z?%0?!jf*ZYoo8`zM-{VRqwr(3CD~nfca>lkY5koR-ub_TQQdTh2}cr=%-nCJrsn3( zt}d~H`m>LJpilrWHq_U*)`s)&(eN05kBs1b9U^3bUs#6V&7`FL(Cat_IGe1qiIEN%b^{37EdVaER0V z{QOFXWz;8O*{ugv&oM}aLZKo6mwZZa13&03FgJrz?+lo9_x}Cz8eO<}9OYo8_rELi zgm2C;Vd%SlRd2UC_`E|$gY*qGmNxJF_VQg`{J^>&*<}nru3tYF?Uf+M=EwIGNcrA( z8atL}CGuh+-tOlFe{@lH1vBo^Q9{#a{Qb^A6pE6sZ__imRcp7>(-<^VzMkr86jjq< zX;tsJCk<@zj-&9JI4d{~g-x;8^oRm{g>kNm$~m*DHaLx&R!6Ok|@;=DB`DlZ>8 z*KTBK83_F?IID=<1T@|rs(Qru8l+gnFbYfkDLDi)@q_`4>gFh>EWr7Jq~$o@bPvul zALl1v+Yr-65a6&!MsME87wOkQt@RD6I>_~+epShaIMDEP>=$(D_k;V_$jLmu|NM#N zFV^@&J&)vj#UivkVN@32ABdtapdrB;nI`<yQu&V`!ChT)ja!;|!>H36JEkvZw3FCFnDwgt5)-vU&>uz3VnSYr;4N`n zRYb&kXXj%fM`vgAt+A5Or`+K{eh|?C_5etVo?s=a1*a`B9t8|jAj*t}%YC$XW<7E? zHsGb7F~Z>adZ4@Kwj8Tj{OcFc+WXMx1u~nPpT879>itYW;0tirY4w+&cf-%v!+b9pA*9KPqhh8}Cq<~+B* z!>5(E70_RlZlDYtF$>mh2Pn@h(=S{?GJff^S(sjw%lP*)~`0Sj{L;qEMHmP#kE zE~K$i3rwi3RzXLz8m;%fI?}Aax%MzNHilao7AMNAZOpHxx+2NMwSJnSG&VMh@xm-F z{ijc#0Ke~}6Z{4*DuJ-K08}>l`gKWm4Oivyll${^7g96ISghAy1KgomVJ3BV>(&c*_+zhr2aqEefM9FZU4WSRidaA zrJJpUN~LH?dub>kEfr1LX%W&M8nlO|*7tc{_kDftzv27-!Q*my z&+|OS>-Aj6Od71?m2GWAS@O|ZF8wP2J5-woJH5y4L>XgWWX!W7ePrg4SFCZnBc(se z7$4HKv}@0b?eBY$kUt&&k;Mn}4V5UNYJ(bQ zClT8M>4T5M#1{0ECIBT7y;iKfTI4WEdoh@P7#IuoHxvbJ$&`k!1ZIe(!JwzeUQJyc zt0pGOA<H!D)b#YeJ0+-si9!@SNKRg{rt-C=Yr48hAUuhg z_$izd=)+vA0&mh)cG|T%JF{y_?h1ysXEmfbk4n`3X-rX^H2cyEv5Jn{tZac*&!>(& z6D;MUvxB2lCk^}qN;$SWlkk`y^561$W`CT2%ZM72^^JfxzIT2mtEyRln!6FmbnxCW z6`lC|4W7cGFU=2FdvL4yD^T;~*YE4P#M|CGlc?#DbH+KSN{6=NxW@O4I$jc)B)R`C zIH?Wdr=*mfokgG()5EW>s;MbBa7|o7LjAq%3H;qWrwQAw;<&g##D z+hqPSURd+7IsuDf4wv^?j|dOn<8eteekzD5Oec$4{ukbhd9Q3aB`O{f`1gsvp6~~2 zJbZ$;FIi~Qp?V5B~b)Cza%M zoYW{5d2-klp1@2CBOsSp-# zAR+aho2$C`9!T@BX1rie-~^C)Hew&!{Q={wz06&#eB-bABSi~DH__105Ln#Ce7a=L zt?Io1`r%A7fC`3N^ny?*t{k2d{C7pbi2MW_+u+Zi6#yFH87=huu{S8krPoaH-Rt4n zl#jyv2DX(>j$dw#w1j~_pe^ZAZkm7%5&|F0%N?jcCKe6G98LNCb1w{(V+fXC(vi{Dht$Vj>pz&{wlN$SOS_-)sM|SN$+7FLc z|KEl2bCs#xsN)D3k$RqSkG<5F>wgcUnHGr3x9TanaZ2ARrXRqso~dd3RAXp?6MWm~ zqMrdb!dbf6&VP)P)?SEQVXceg)inl8i^g(>P*Z}VK|NtT{vz$iI7oyO+}weZ=5U>}?J#f0F0c7az)7lnlMaj@P0QB1$a~#~)!7UUVNj{xtQVlH)8eSzgDs|>>McL>YiaWmFWW?yMF{Sz z9qiO3@z;zhHB`!LB;eP79-&kHWqV~snt+Z$@ckl|2yyWeS+;~J3V$vxE+SeCj259wg8Lz#L+G6M?L|;( z*2KS|Zo(RE#&}3wO%2Y>x>s3cL{%huSQA(v7LpNE)xfwOvL!feV_;wyvUN_c8NY<9 zN$6s5B~c(F3Nz%rfwgrDuIDL!{uGQ4p!#?Us49w1^TJ31EdY&O0uTG~JB_dcEU&H>a=6ga(3~=?I}pLGSp%j3 zmQq6_qtlL4S|2N4`A@l&MMp)=_(`ta2l_>{$#5k}qxp;NLO+sgP`e*MHX-9fC-MFY zdkg>wq7s6H%doI&FPXY3vDV@;Ah+etRw5-K5D-0x9Ni91{`>2;O@i_o*L^wM+W!sHj z1G?Y&J^396vr)x^Jz6DB$}_$q=x~Fpy1(5R#~?yS3>DlPs<8Zmhrz)_WYXohGoiT2 zUIZbBdkKmWOdL^D0^)Kw=1MfgM16AjuxFct5j${AAtEq-XKZp3B zjD|mWeyXR~+eC3l|2W1R@mo3$Ch5;v;Y3Q8qbhs63ukSr@gG=v&-zuJfSjz@7_v>W#{J`Va(&c z%zmT}aN%^S=y{NRhWpv@#O5U9;&(wOVY9PGl$BGvN7wy+u&|0)8C|4(#@YYj;&}AH zx>ADaA`R!m&Z_Q-f;6X82S1{$TW+RX{bc3iZR9m#UO_HYzsOz^d15W8)a`dKM%SBHOlmU?haV*tT2MC*#|Gz_^o{+=U{tOfx?^K?|)Kl)@O{}_qL;r>Sv%tPj z6Sc`sBOSA6Vs6(f1+j369?oxmAd_)e(&LnWvAKn++Cs!uG7_0imGS7M&aB6|bB0s9 z9@*I6@wq_FVp(y4systKt?=+z)pUEFFh%}>lr%;$(4qf%q&9R@C%piYkyXAC1724@ z8f}Ml>4Iu369FEe&joTuppD3?`to(4;2daMUEN?%QkeAMyz(mz;v_xk>FDSzEG)8f zbH_dpWh5s{)zPCbmQK1lQ!BY~kUDbl(1mW@7*TI@K%vpmm(alUZ=z1~0_`LuBvcqr zj`joHtQ5>Ww1FgvFf`m5LpU`X|;0J{>q@Wp<2EYKwGOh=J zwF6?D%x5AAP&3H-S2wea!QE=p-qg&v5GbhX`1Mz&ky_G)@An-KfYc^rz!+Pn z0EY2Yw|_m;w8Hjk|K_LSbXxhh-|O`!E?G6I^5<22k_r5~zjjJsQ>8#Rq59{fKN*wC zd8XR3vg%e1GoLUO-A=1$y$VW7HhssLE)sqDo98AzN>phy>8lo1(d&Dq`(|WtK&WK(y%3O@ z7w644Hj|x#_)nq-5e={ZdJIi3koDu3-6$4oK7D$5Wwu`xoD!xWRG4pFDNupR7#gww zp(hkKgM;2uNxyBVTGs*I`Mr3-j#3f53aa|guWs@}MIC^~stq3O1cFFHiKhrg41gRE zS)0WP^~aAN6S@OTc)X74*sr1hj6Ohf$*3_x;VbCvvwu zILA{3?Uq~H3g%Xhp^zm|0jxc{bl9cFq-NeQN4?f=s% zwv%D(UoF5tOF)0ZK3NdZ7M*YXA+XX{4=bYdw4?(rvhPIuT`ZZWW0Iq+rJ zB0yE!y{s;I{@m!*WKXOL@`#+A-W`8~Eq4a0_1^EXzs{#-aJB-OLb-A->jzMYoVRZc zfv5ozC~&5KevJe24e(q(n5dYSaEYM>x{3&EW7pLnrf~VwfX^x_h`t3u9b(tZR8>@< z{S-lv3evBLAhY}T@3#+32rHtKApk4jTwX7JkBrpxZ7d2C3b9)~;J$&w%7BUf+$dCv%`TrXU_0Tx@4}Y`__zTc>&|acl!&>>l#F&Yd@(93w$*C zOIsFGMq+t~L5gP<$^>842FWrybD7z5i6t!m@$}c#IcF9_LB=<+t9ZAE z46AqgOv}28nr6ty@S}o!oNRFS27H2ol9B)_B{$djp}ct)so#4T!7~;XT!1_YdaMzKu}TAwv!uIr`Kd~lyRGm6 z8wT$31(HK7SlC++uQ|~RLFxyXhqAHe1Q2l7C1av=fB!yzhPj9mmke{C$o7$8x~>0O z6S_#|)8h*+NdlK4iB?hh%1CKp`mRrqmJH+M7#|z8^O=l{3`PNgr@&3F9eB&l&F#E0 z90`BL)9hXh5aN^-ILHWL5Vt5puQiGX5GCF3?s%ixCTi4h&YPmwD@L(ZWM*3WEn=Hd zz`8;lG=ZgEe03rZqfXDlqWg>VZyMIHcDE^W`PE{66J><^ldl-QKN|#LmcgpCGuEl^MARb19MR ziG>XnV-V&C;9>j#-6>OAw{ld2>AAUt9vK+Whh*7DICAFVBZDG3u!rJ*8u`KX7pfsD z-v8ml<0zL~JGew!6vz13LSkApF+KQMJH1N525CGiE_W~-^W6Ep!} znv8wRfZLD~{URhVckbMYL&)FTw{KTzEXM_m_#i2HihhEEfgxD_`$q3I9I<46v$h&o zHe=XJggSv80lIrc+{xxoU7b0w<l*5p;)C~!y`JtZ7#E7+ zdx?(be@L~=P*O^*Nj7SBY_u~#GiRHG`?^O?+$Fd}dI@RzI> zE{txaK74pjhcrar7-j*7IkAD(m7a+c*)-xf;isyoiqdWrP ziAafaIDPfs!FDjzRUvqvEbvWY#A9Ra{-T76EInQNw@_nKlX|w^*7N7jW0||m9vgE? ze_L09BZ(0j|LT+ z2Dr8=h+H)_yQtEdF|>$qGic(_sQ~KoI%g+I^fK2^Cf!vB`N+=0V|7zC3{57a3ZPl+ z-%Gr!^Tr)@tHgD)qV#|EF?~#*!r!sHZfF*^4Dw+m{tAx^8sLkV3<${Rfyv90U|=72Ju94Q4usZcN2r34bY$pz{Lbs7`b&j z$+K%2KyVxn?T87HV}a6+7_WAAhf4iDQqVpTvE*l0C-@27EF*d1u0ZJ0C=MN}!qp@g zE-by=8lM%OUjz7B8zX2Qg~p5^QTh2Pu@HdAMUu@gxHqZWcsV!@=K7&}#3fuCRr0)r ziM2F1Gv&4Kk5__TLk#zX+8QZmsfNeR@971(%ryZVo7Q{dXO&blu9w$GZu!4Wx!m1F zh8l;E?e`u%+J_B+*gZi@6Ro#Bc5pzwxP}DZ3HAkS?}3J9kCfEs&u4KF5F-9% zmsI-%DRGbqCe7sparFZqrX9-Vkr%y^_H`5yn&ylTSm9^@CHw5;Rc)D?9Y9K@Med`&qv(CJH1>VGpm5w#8j-0751t1#dGn3d0Q8FbxbUzF z<@%*~*qDAgB(J2DUQ%+jREKvrJFW**tuUx4KthCN2v<_dW^{L-3H7P><=i9^EHx+! zyTL=z1H z5DT+ydFALS3`S7xh+k%*`Q*qlo_R^`iTrakAOK6T4iQpbY`U0TM892Jlpt|HPCII~ zTG?>Aw8{4ey^(ZS%e!#Ouo3HDGrFRYSFUSlbe?*Aj-nPJ@eWM;u{l9s|g}Y z=Q&!n_L)r2+Qp@FS6P23?c4PB;&Wlx6_z=h_$&C&_N&Spn$OakGe$0uCLR2B>E`|X zQn5kSl>wf;UzsdFXG(=$%NW8@BZP>VJYG%!azvo^L>x-jf`015E`mB#HC6P~GB|ESKc5WPFml7Cw8? z(ZsMxervJU^^?`GbRh1X03b1Kt{P({*_o9LwKQ_z711By&e9w?q7OM2z+`BHrXtj2 z=((UMYDZcCtkc8NY!rcTaUr_}$kkD(O078)C)uH~!grk|&P@TBWe_ak3y3#AY+!p} z^ge!}qsBEw+xS|azR0P#olU8#{esr=r0m4#6q-%moMNv3zyQei^bZ}v9bI(PZJlL z&;(+D9ph7%fH@lD3C%T*aiSS%iiK&wB)EF@87x_sl$2lxIs%8)&peb2Nu}-=H5v>3 zJlWFos_YL$T!=4^AGUpe`~a#alttghWHe5O6Ke_dy11V3v*@GniBaA31!>Diu$K@P zOg{Z^TTkyCKsj~}j*tJ5%i<=wmc;gB76ipAJJUN>BRL>L5x-a_!ysg}!$D2q}87X)@}zsbQiLDN{skE?(oJe=NM2 zrtkDyr%$gI5B{dV%x<8@VE?2);qA!R=XuuE8m%UlMooj3mltlFwoogh{$;Nj^))oA zBI2}DvyS|(os{%>^jRa4c}7!@|KzffX?Zhzn|J7??+T65=6Glf8QN z0Pq7UR;6pVR~2O~#%}Zm{|!fMbLxc)^V5 z6aX1N875TOsDE~D#R)4kXd8KS%Nnsx5fR~-g*{gDl1O01n2JJ367Uo3?hYIc+#DR2 z>Z0rrl!fAC*u>m5H!!gN%~p@}mXhKm@l{US^p9)PrDud~RbG_c^{dm|=}O$r$2F27 zF>g-jJ+kBEbKAV*+v?f9q5@q)z!-g*@ky!3v$YkxPrkUNJdoa{N&V>h>DTc;TYOCq z=hBe1ofez1wyqCVl)fFhH$30B%lOtcM=zzJgWWzU?-Em|_f}au@0KrP3%1!`aFU8+ zkM>l{ywczox6sEE%SYNId!>2r7p=sZCI84XyD3V0SGSE}pGi}D&Aap_{l9giPNlR` z%aU!m)5G442OB=iOr47~d4~o7OMwjxi2#y2^8+FN!Z!F?BY!VsHvfq;mDT}Xe!9$p+9%V3SJ%`nOE)6-}!Mlyjy`Fp?_PG4R=k83CW;I;W2lXWN8Sfhu+vwW; zD(wlHZJr=!RNuAuRrR2oLiZwXmeD{hqlMgVqv_Kp?&=)$6n@yP7-?>V?HRu7_vQ^V zBZTf6dYwr7@wS1nu}@G0qqHRlW~2}5@U>cw7x0ZIadDRs7)6|f*Iwex5ArTPz#7#% ztOdSkNDC~xYLHC(fa~+bbM^Oqg=BiEaHkwb$s6&X>UftDd9Z&Jd*I`fI0^W|BxwE?$uFo zr|g~+L@-!M5ER#=M+%SZ zr&sfSZCy7BPkhw*&FiSaSJ&KfP3Pgpok4~iV)l~2E(ER}s%(4SGN8|SktyHE_Fm@MNlu>6y(W zNrRHwnfcYzO{#4n^acJ#Dz&HDF9fCLh-FpQrK`_-?5#$&8M?YRpBJMsfYd%bgVLYRf081P#hy}wDySehccQ+9U3%~f1J0_ z1J>8WkN1DB%DXcX6+3>&C%e&+)Sx8MSb9F*>uT=w_XvXmpM}BkJrZw8`p%wHK4YFP zxL4{*HxtE5=Dy+n;>kZL{_0Bt_;sg@SI%GG(&4J!erS_7kaP5Bhd{o5N9XSmzuaKi zG6NcZ5AFfk`iWJA%KQ+T`p`Pd87Jd|u}rirw;j&JQb`8-Wv-2gBo+n4@5$6y&N zxN_{PQ#?!EF>xoCS=NfYF8fZaThlEOgS+<7b8nA-^7*ib*YR)f(j%C@Jmr2cO>CZ?=}=t+#S#S-YH^P`4s;p?(6Gj9ieftdv)W%8R-xnt|mqhIX9-g}r3Q^z4tx{-_G;3%o=!0VX# zqp>kpR0U=0A9x(9i$2>{7}+n7q+tAO?U&l(6_-c$0x#`u?YCqaaoRo5rIhQ~+e2!0 zW9UTffkfMeR=U}$zAdiPX8NTw<;(o*DKyucHVuCZu!mK2tVG%@PU+S!>C?@c^Lw*I zhj>m6UDlkI=BhckX0;{rqIFYLs8FgWg*+c43$MDg!Y@iPlf`Lfah_wpgoS_h&a)|e zb?V)pni8rpDBel!_>_gMI@`L(uEL<;fQP{H$Y007&a>OnxeRp!NE#>acz&Zc4}3C| zYU5CLtodV#`EH2<`aY^WW7JY&`M737B(Tq<_e$GZ@sz zHo5fZ_JK!3%SxIGmz7D)(^pj7*`F>jKk4{hIFUZiO_-c{GJ z6`%d_`pDO{-Y-v|BpgsGQLKJ>Nz-3xo2#%%$%PkkN|)F~EZAP%Y7Q$D37NNlwOd(Z zaAG7V(w%;kL;h#5$w0SCeWYMZ@dGX7$%K>a_k8V8h zi#M_UrZZxfx=%Yrt!ikLELxUxEn1O%SD)SS5>1(8C!s3~1~;Pi8ZN$*9P``mtc7&$ z`L9L~7$hs3AC8at8~Daz8jPy@Wq%<5}g+*mRw+CliKVIYp~=%Uej4$8rMUydu$C zfZEYh>;ZFuunJ;FE)q!F{j|R6l5J5rQ>+iv3%T+-@3NF1J`{g!x_h%Wmx?LW;vV&2 zx6zRHV>b1U&c3Z=r^mNxK9p&*Dtml4B8=YC*YG)s!03c#*~2?!j;BQ;ItNd4+}pAw z{xi5br1uO*A;Wmf8IvPI%ygtyg8Js_EDvS);@G$io1M%B>XRnK4+P8aig|E_%hg&m zQqqc`#-Gk@b6mXxWBxx=LE~>amGvLYW&G79?b`AxsIhy z?PxTkkQb<0V-7Le)%wwLzu5js!z9f?HV!fMGtLKBgR-yyk6Ok$kN@mAm35vaH}P#k zhRycIQ`Y%jO& z>u|lpTy`v4aIE!G1j*e~&dgh->9R)i52!Yg8k$Rq$La)L6uQOeT3K)^eKbb5t2US8 z{>0@yCSOekc33Y``l=k$t(h->kn+^|;M&4@A;r5^@BB_;KW#|7QM;5g$NP15Q}mgE zcFELns+D88jAxnNn=>5@*{D9*=9{7S`{<(Yq*3#;8uDCeH6f9Z%uB0k?|DM*@ve8> z?0ME|(e0{rK;1y0bncs~XFOv@` zvs1i}x5{`jffRyk8BaTlX=uog@I62vo*w8ah%T3x$~SwYSc)it;KK=+qWWs(=Of|h z{yQ8w@9H==?ov`xLT?Qpo7K|#aVA?%Ol(Wz%Nm-Rd3qnW(K`AVhc`e)VQI}ZcU4cH zrMjhze43QOwj4x|^YT@n>_4%wEqddZ=tS*9R>Aa{2bFR@0e`Se&hkt9fHG3fxLur>Fko3E}iRCP6-X znJBD2PLNr~RAt>FZQkMW^|g)OwU!!P0X<2-E4qD${Ap`qDua4P=S$G)XhXyEf7&-FUzuxY&OS)HfuaLmg(S!ds~DynD2RK`9AZPkZ%3baCFO-V=phs zoWEYuT<-ou+pHz7iP0ji1CEmA90%tunkh?30g{!@JxAA41!xAww_J}~vE5E*F?~wM zHYGdLT%ggjeZ5JhD4wT}0xfCDOvOGo1p8#ZG0@Zd0NW!WKE;8#=%@ogf4((egZi8x z*;LSW0%@gAlleb7*BcKx zpE0HIcL=1j|7Uib!PRzBX$|=n{o#8Pt3RKk*DnMx&W3b-YI&;9C|tKR(DedpB=(NWFTGQD_}yY0){H>dj^Hj(Swlu5br?-{9~v*7EC63RR^`L??I z{iVw>tlf4`K3_IZ4T}vG$a!)*?v20Nsm#M+v^TG?np?@K?RqMh{HCa4DR}3Ott*TH ztXZ{>4QldS7vqc^E1f4-|9GfGefeY7oh#rca^disQo(Nm_cL3J>^!tIwU)P->oAIx z?%bKTk3-}7rr236xFiWh2i>-u}__s~CX;4XaF#Ojz4 z{Yld0g-Z&_X7b|8msHf6g{vP7*-U)g>xzZbMRV9_-^Fz5#`^{~$`*v~@!xX!OV!d` zTy&=D&nx|>`R?#ctnddb?e49gHs7t<7=3ShxJAz|zdDP(o}U}UOkDOiTvK?_qwW2w zO=)0`kwq**#4ufxqpOSlP;6r=*QW~6q2BK#vpKW(b}22Wnz={!M2OQi2!F|T3n>UKo11f%ul7tk&DFCJWF~~p!^M5;Jd~`LKUfHnFLx~gMv&7+KkX2;E*z~zC5h830Avy@b zx@{`Sq(!Fyx7h{dZ$ch@=gd*?*tD^ewmeE+F6PNx%nFR5b;Ez?7qxz`806{~l20rt zw3K&iSEP`jKGw_Ft-Fi~W0S)Xyu=EU!5^-pI{pm2EmpP8Qg-y#1qxy!Yg$ zc--R?D?_YLRod)V)SpE(S-XCyV-cQ~qWO7eSMYb!jHHPq!P1E)>Fwv9ZB>%^eDmrd zo4ne|?W7aY>h4^FIj2k#$a>#Y=CuTpiy3FpIa2D$f9$>3@zA+mBSDw%b6)u&ei7#m zHJz;A1#6Avr6+0l(ng-dc1|n0{OEn>QaRQC@NDJGpmm1P`kaMRN23(_qF(FL?AsFgJN3I5?+tR}u+?j)Solb{ zm-qRN*LDoWxWxJjor)%>3j6c-0$Hp^IMe`L~MuTepO#Pe&9H&a;O0y;@f3UdW=5y^a`D3t0ztvB|xM_ zpSSbHhfEOqK=`X&7cFp%SsfrY5x3=2@coFSGhMjz^Fd-kfe;gOrGJo6l)&w4s}wap z1am*pTN(?uqz13D`n>M0&B*La!Uu21HwKJ`Ig3jKW*@X-;?yOQ*}6SeC*4V8Gcz;Q zGF73$zHMgq6LxvJc>_13X*r40r(KSgQda(AB&fAH6s9El$`6_vzsiCBvel_U&Az{F zA&ZVV)^jHP`6FVU83VdylzaVUeCtOec*+xLjeqWPa_^ZKw=Jgxsi)<` zRjqdI1E0dq;rND@5BWx%z4z|B%Qioc+`afba@3fY_fF1O5QWy2kJ+a4bT(y-U(T42|F^Ltkt&h_Gz;0%@_P3`a7fx@7+JaA3M<@Vg1wmq;+{ll95U4 zD}85m@D_Kl%Hqt89`oJbkTTP8xqZ?BhXA|OZ|T2fX=!;mM!+A3QJ=OS`?ghk1}3%5 zXE=uyyCu{=pO(s&B)~!mzxeZH3T};B5YJ~^7h9WNA$;Z`5K1`1z%)nu`jQaQx`Y`F z=u7cJuG#I|NjW*_9D|^}mH|U36dO1)V*KAD8C*+Lt=h#dtN)$L=zp)LFs*RlfFvRIEva(EY_Oi6bejJSZzWLnRe+;g7 z;Y38tHs5de`UP36JTpfu?T*}|m>K-Def#Ki-vZsb99^@lP^0_0uVqZ-=dzb2AJz>& z`h?VFKUq(?*4BHQ?JR{jFIDzLw1Vzs$6rZ{3$`c!S{fg_vhj8Ms|TO7LW3vYFW}a$ zS>G7gPjlv`mVjX9x^v!;gwk;E>dPH_dwI&TNczuZ2axPu?(+8PT^gF+y^SoTw6o&) zGNmd)qDPZj`3U60tLlRR|=zC=Y2y3ezGST?hXVt z{jgU1HoFm{Qn@r+ag!j^^f+_7 zmBp%fQb@;jGM~N+K-jF4IF|WS7z54qlHOlhTPxn(DYgGu^bE81&#h5#f$$NlXlXS* z*h5LO?$oLRy7bq>X$9^~pvrpiY7jXp2rCIdkfhB_|3@82#8`VEVX&Wa#Sv75)1MHY zCx~|(xs3cVG%4rdFY(p4X)gBmGiJ%-nS4?%@ldNEsHL#iD;Y7{B|5xVCfY58kQyWS zd)*UsGzQx8$#^g(Z}a*z?Cb>g`*{;dzDTk;KdtaaiC7APMHtUq;!v~vX}q~rZ%f~4 zlG@9zU9VhU50$@rzv){ft^JYCMrB1ZKR#S0BD^JUB~m+$HISbtuJT+|uG;Ef-TLXQ zln*bQMo8yh>g(``WQ?nqTl0sz=82S6lZAE+{jx7VUZ5DTt7O?tFW!XV@3#|ShhKfa z=kC$HX)CQ`UFzZX?fcHiEgE5&A1~M4s;1quEbg>_dugC5`SR@Q`>RQJ)Jfx3MAURU z@0lo^cq2yoa?Dj#gG?@wQ8`2;C8{Z&?2Yyhdo@GF-HZLRPD%zWT{+|p9P`I0w(8Z7 zWN^pMIx0#RKhEC$AzM%PNwE8+v$Ew}&mH0^e|fekuPl>jEuCesI42QznWH_8#-_bC zp_E?D_72T(?Rr+wlJuv#h1@6Rou5Th7Ks=FP3zM9AC@3j7+F{zKq7J4d2WbNkS2l8 zNItRe+cd&WOcLEA;NgrSY}Bihg?S$9E>mTzRz5P7>;eLB`^?@1nI)&DvcPV!0wxUu zXr1TA_T{lxSvJKz0zyKB#SJkyNWaiWo$dBZtdEhGHyEyEtVB(ShB@=s)B2_y%S~B4 z3B=a4ef?O5O8Raxvg%)dpl%`-fnBAWP#Y|2X8afcF;}uWRlGKKvm77#0HJ@j0Fz*x zYJ74+;Shzpcgd1x?jZ_)Qf6j}u-8F*lkdd_P`@e?@LTxVsrtiwi-Bg*M8!^Hg~N1h zH-1i1?O1u?YIXQk0$t~|oUhuE1z*ldM+W78$@!wqqvh@--h2M6?~yJqy}qXk8|tSX z*3_|z?c|)G@eqz>;C()~B`R_##8sKXP;;otY@6o->!+oKoGez|LXuMVc<;Nnvzaoc z7Os3-T-@=^+W4ywLloDUNW-0*O?4ITKOePN*8J{zSaq^UC%rRl=i)fsJD=Ua{mzxJ~K=42WBe3mTJv|#I2-W$O~*K*zOO}|OAwXK!q zchRDvbK!a=5Vm5yvz_e2_{XoC``mVOouTeHJ)^RudP0J#vf$l|?h#8*NzzjPBDYd9 z&8vnqB;cCZn3+>*ah{?oa>%4<>F9FQxVqi`G(Jc2!m41!-P?M0ckN5IR365F+>z@&wqaI#}Ts%t#jJrRZCmdH>W zO^fAmE(RX?hp-8PCj0|)b~J`oE-`>{kObDA(=Tcd9Sqe`v*pn8U~HNxd8*K6`AY3i z9jz^OXTAIL;78xSG07KQZ+NF$Uma2Q_(rh!rxfzcThToi+N6h{O6ESUkX+0Ow)$Co z`SF~}s@>N2n`OR&N<}k{*Z10qw<*XTT6_I?j=Js7?|Aj0vTsJ49-9vZ3krr0>j|%Y zE7kEA)2oS&?BX}oxLVaIYdrJgn#**`b?vunP347gUY9x5H&xGjw#3*EYwQiXzuoB2 z`n#8|SASf)*x`NR`pSnor>FS}q6w1xB9dGm%(gA$SB>UmG?pyRmt zBCdAPTPiN6zi;7Cu*1F#_jewu6=^PdE?a%JOR%lf9BGp(M2u#fqDfW*f3Mr0EAR|N z3z}0w5lu|~xB2-C#Vt4*gNjS-1N5edd^P~vOQ_h93fp9CQ2*q_nWOuCcHKNLC$}4! zx-i?`=|9(}y-Tddi2<2*7{=r;8E)Vo5vEYy*8&1pY?aCX@mqW-6}Lte+_aqrU5JdP zE?fS&50MXQ;Nc1C3+Ni%XAhj!P`#a8{IhwrAygs1T63{7@>}m(g+#Tac@Fgl3;fNz#mCEDy>MsGg`wly z@4w}m2sLtwImxc|+aRy$@+a?DcAZlX21_q5+Q&MXWrYc9YCYx3&2b*(%YD-Hc___T z^RT_n_VG_#7Teu3>4XAKE~(UQi8!Q@>s;2!|LoV_ZJe@7Pp{^`-SLC-eX2#?pw?5L z?-S|ziH}}R(yy`Z6B!SvE4db!O1am0!~Z1Jrt66t=JnDIiX!fI{rIQ1vVtsKM_y zb&Zh8P_i--i&6`syq9B)2SYizPbXfnwoWz;&2NxRx^I8`bZj5biC0;VMDMaz-*9dJ z>vT5SpIY1b2-O6qLWjn9vfY<+pLUVPm3LREI8!70e$)C-a=Oiph$ms4M!KxqyN*>` zxW8Jin16ka?9CWw?i-^muZKoNPH$;w-Ilv5I$7l=Wa&7&wyyZvL-Ep|ksile) zI%>_tW;Xt|i#>G1PbF?DRtpKUnB)~Cll&NTzd51h){Hy+B;KMwD=TFz`0%^#(#tN2 zO-XtMTWQYxvGwbXy?x+g^)qRvd+l!WiOsdf`$-ZHd%iZ@lnbXig7ISRHO>1dxQH8X zop(Ps@W#8Gu+1t}vyG5o`%_7vD&5mb4pZba%$3|KuyT#gSFoh%6@4ibp}eRi65d63 zs--z;+0(4uZu+pPVUN#3@0GRu+^D$gHrB6ppWWbL7gWu5+JU zNIs4)5T}PzDv5ver(`3}`$06zAkw0VBMz}hq1?IOHA$Q}H|RsHLm2mZUJ@Zw#Q8z2 ztbABvz|H$M88hRYS-;9JlV0*~%FuDaZuk+AB(4^87)>aKQCry{iEU%0#dH6=++=AK zR>)pEE~38f_ojfT<{;xn2JXebSKnMBvUISj5$*%DW&br!zlR)v5G6rC2!lR0(+afT z&LAccVP#m@QW!KG4TYun%!lpBB63{Z=zM>dP0V3J56LHpfS~rPL^|Y{T>P85AD!?S zH)eURn?thsw>-y8= zXBy05)pWV6^5>Yt;O#jB#ccg!-%jgzubmZ7bedWDn5~v`LaRphb<3kwo9!N7^%6WK zdzHEc1o9<4ejZ?u><8B4P0rsos@h1sskSX&+^pf2w{UEvWN)YE;GfX8pVjWqwt5>+EC4+o#MhqI{S|@ee!_g z?P16+IQtWx7`789d~lRKO!R#zIr9h(UqL{K6QLvO>f7+ev6YzPK*qoaRYPosKK8?a z&CH~=r|Ua%72n^eY6*H5!GTNd#xx`_Tr|cAK7x>)$j2z@-O5A5`fi>JXf;?Vd_?8gj}2?+QnT;M=w+B3IJ;r)(^+C3y>4^W$GbnQQI+fYarw_Hl-pFkr z{+E#SLibC^lVJ7Mv39H^6DHD4vG6ds&mTnPO;5B_l3hSreicwfFHYi_s_kwg!9=kjkj`M+|Jj^L+=nRa+ehv$}&Up zOps=$fIGp?*^JAIq|-s@952TTk=;YGtB(7^4Wje};7|!m6HGD1G3kVG|E5aVqbG@$ z6_3IzT=$^^s1qCyI6P*rHMDe?Vk?|dc0y*BW@b!)z7jXreyuBRhK5p8Qc8mv$U3jA zps-ITD-uU?v0jO(!X?^u^bkyIr*F5WHa|bZ^dmWFIBWZ8k`WDw??J9v2?V)il`hg^ z$RnWbD2BU^PQpt+bi!pd;#se6eXo&l8XKEg{$P9YbhV@DO7KIi;tPhdzaVQyK!!1# zZitbvS3Qt%XLi8=J`3P%@O9M!Bq_2qx3VJa&i}Fg-L|k8!i@!;Qq*$E5r+@qxC3A0 zjKZ4s?CkZq{9K%fL`;52$8x$R3GEvOMbNxHTJgFY{aJn9=B~%08r$dO**$YYIJ;`p zWQOLn@}CidFW&tO?l0oeaGWvYCMyZeWqmy3%Omjfz%xReIv7-C?Y(2^}k zEHYK=XdG4JRLvBo3?2V)m^@%Vy?7lKvv#Z;!aa7BX#8piY_x1I#b`0Wm5g8;0yRoY z!{|P9AFw*G9$d58Ol$W?=utzFtO~yu2C*BI5=2TdUQfAu2aT8m7ev!)TvS#?qpavF zF8+Nh!_&~Wx#37$rUVJs?5;_qT7b5F9eS1v%k2>kR{jXX6EaM;>+hJ(hxScRud$Yv zmC^fEev~GckhylPHQedUk@GmUDE;dt6%|TA5fGN^(;)v?8lTh{ClZF%7igBk-Mjoa zX$qz3K}yOLdTv{7F#>Hhp}z;zlDd4^$4luStIqo=QrD~VSRo<^#2>er82SRYDUk0+ z#CBD#U$qUym8Scanu{K5fvKp*w6(h*!*`~Uzop-ymzB|)Z0i^B@+${&sivIJy zp&#iMpZx|r18~Ioog*jH&3d%T7yll3LuXYOi&`1}g$sYL${6mpdOsWydX~s;4K-Jk z)6_M1fr0zaV~9?6+~eQB?6`WBV jKGflVul)b)i*GWpwT^l1*{K}01&>RziZXAc^t}EbGE6Cp literal 0 HcmV?d00001 diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 651eca1e9de12..0e46a26add852 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -446,7 +446,15 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar poseMeasurementCovariance(pose.pose.covariance, params_.pose_smoothing_steps); ekf_.updateWithDelay(y, C, R, delay_step); - updateSimple1DFilters(pose, params_.pose_smoothing_steps); + + // Considering change of z value due to measurement pose delay + const auto rpy = tier4_autoware_utils::getRPY(pose.pose.pose.orientation); + const double dz_delay = current_ekf_twist_.twist.linear.x * delay_time * std::sin(-rpy.y); + geometry_msgs::msg::PoseWithCovarianceStamped pose_with_z_delay; + pose_with_z_delay = pose; + pose_with_z_delay.pose.pose.position.z += dz_delay; + + updateSimple1DFilters(pose_with_z_delay, params_.pose_smoothing_steps); // debug const Eigen::MatrixXd X_result = ekf_.getLatestX(); From 0cf68fec63e332b161d86532e95b88665d4a9c7b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 22 Aug 2023 13:25:46 +0900 Subject: [PATCH 223/266] chore(obstacle_velocity_limiter): correct spelling for cspell (#4687) Signed-off-by: Maxime CLEMENT --- .../benchmarks/collision_checker_benchmark.cpp | 1 - .../include/obstacle_velocity_limiter/debug.hpp | 5 ++--- .../include/obstacle_velocity_limiter/distance.hpp | 1 - .../forward_projection.hpp | 5 ++--- .../obstacle_velocity_limiter/map_utils.hpp | 3 +-- .../obstacle_velocity_limiter.hpp | 9 ++++----- .../obstacle_velocity_limiter_node.hpp | 3 +-- .../obstacle_velocity_limiter/obstacles.hpp | 13 ++++++------- .../occupancy_grid_utils.hpp | 3 +-- .../obstacle_velocity_limiter/parameters.hpp | 10 ++++------ .../obstacle_velocity_limiter/pointcloud_utils.hpp | 1 - .../trajectory_preprocessing.hpp | 1 - .../include/obstacle_velocity_limiter/types.hpp | 9 ++++----- .../script/velocity_visualizer.py | 1 + planning/obstacle_velocity_limiter/src/debug.cpp | 5 ++--- .../src/forward_projection.cpp | 9 ++++----- .../obstacle_velocity_limiter/src/map_utils.cpp | 5 ++--- .../src/obstacle_velocity_limiter.cpp | 14 +++++++------- .../src/obstacle_velocity_limiter_node.cpp | 3 +-- .../obstacle_velocity_limiter/src/obstacles.cpp | 7 +++---- .../src/occupancy_grid_utils.cpp | 5 ++--- .../src/pointcloud_utils.cpp | 1 - .../test/test_collision_distance.cpp | 1 - .../test/test_forward_projection.cpp | 5 ++--- .../test/test_obstacles.cpp | 3 +-- .../test/test_occupancy_grid_utils.cpp | 5 ++--- 26 files changed, 52 insertions(+), 76 deletions(-) diff --git a/planning/obstacle_velocity_limiter/benchmarks/collision_checker_benchmark.cpp b/planning/obstacle_velocity_limiter/benchmarks/collision_checker_benchmark.cpp index cfd8ea0f3e244..936476c800117 100644 --- a/planning/obstacle_velocity_limiter/benchmarks/collision_checker_benchmark.cpp +++ b/planning/obstacle_velocity_limiter/benchmarks/collision_checker_benchmark.cpp @@ -14,7 +14,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/debug.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/debug.hpp index c33e283ed7c0c..aea169d6ce2e0 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/debug.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/debug.hpp @@ -17,7 +17,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include @@ -42,8 +41,8 @@ visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, co /// @param[in] marker_z z-value to use for markers /// @return marker array visualization_msgs::msg::MarkerArray makeDebugMarkers( - const Obstacles & obstacles, const std::vector & original_projections, - const std::vector & adjusted_projections, + const Obstacles & obstacles, const std::vector & original_projections, + const std::vector & adjusted_projections, const std::vector & original_footprints, const std::vector & adjusted_footprints, const ObstacleMasks & obstacle_masks, const Float marker_z); diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/distance.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/distance.hpp index ca80fc468079d..22d70463fc0d9 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/distance.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/distance.hpp @@ -18,7 +18,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/forward_projection.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/forward_projection.hpp index 51b5111b9d6ac..3f5f8cd814ea3 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/forward_projection.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/forward_projection.hpp @@ -17,7 +17,6 @@ #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -36,7 +35,7 @@ segment_t forwardSimulatedSegment( /// @param [in] origin origin of the projection /// @param [in] params parameters of the forward projection /// @return lines from the origin to its positions after forward projection, ordered left to right -multilinestring_t bicycleProjectionLines( +multi_linestring_t bicycleProjectionLines( const geometry_msgs::msg::Point & origin, const ProjectionParameters & params); /// @brief generate projection line using the bicycle model @@ -64,7 +63,7 @@ polygon_t generateFootprint(const linestring_t & linestring, const double latera /// @param [in] lines linestring from which to create the footprint /// @param [in] lateral_offset offset around the segment used to create the footprint /// @return footprint polygon -polygon_t generateFootprint(const multilinestring_t & lines, const double lateral_offset); +polygon_t generateFootprint(const multi_linestring_t & lines, const double lateral_offset); /// @brief generate a footprint from a left, right, and middle linestrings and a lateral offset /// @param [in] left left linestring diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/map_utils.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/map_utils.hpp index 32b69b149e9f2..94b7f2425a670 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/map_utils.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/map_utils.hpp @@ -16,7 +16,6 @@ #define OBSTACLE_VELOCITY_LIMITER__MAP_UTILS_HPP_ #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -30,7 +29,7 @@ namespace obstacle_velocity_limiter /// @param[in] lanelet_map lanelet map /// @param[in] tags tags to identify obstacle linestrings /// @return the extracted obstacles -multilinestring_t extractStaticObstacles( +multi_linestring_t extractStaticObstacles( const lanelet::LaneletMap & lanelet_map, const std::vector & tags); /// @brief Determine if the given linestring is an obstacle diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter.hpp index 91611938119e5..4d89d4b440c21 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter.hpp @@ -18,7 +18,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include @@ -63,7 +62,7 @@ void calculateSteeringAngles(Trajectory & trajectory, const Float wheel_base); /// @param[in] buffer buffer used to enlarge the mask /// @param[in] min_vel minimum velocity for an object to be masked /// @return polygon masks around dynamic objects -multipolygon_t createPolygonMasks( +multi_polygon_t createPolygonMasks( const autoware_auto_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const Float buffer, const Float min_vel); @@ -74,7 +73,7 @@ multipolygon_t createPolygonMasks( /// @param[in] lateral_offset offset to create polygons around the lines /// @return polygon footprint of each projection lines std::vector createFootprintPolygons( - const std::vector & projected_linestrings, const Float lateral_offset); + const std::vector & projected_linestrings, const Float lateral_offset); /// @brief create the footprint polygon from a trajectory /// @param[in] trajectory the trajectory for which to create a footprint @@ -104,7 +103,7 @@ polygon_t createEnvelopePolygon(const std::vector & footprints); /// @param[in] trajectory input trajectory /// @param[in] params projection parameters /// @return projection lines for each trajectory point -std::vector createProjectedLines( +std::vector createProjectedLines( const Trajectory & trajectory, ProjectionParameters & params); /// @brief limit the velocity of the given trajectory @@ -116,7 +115,7 @@ std::vector createProjectedLines( /// @param[in] velocity_params velocity parameters void limitVelocity( Trajectory & trajectory, const CollisionChecker & collision_checker, - const std::vector & projections, const std::vector & footprints, + const std::vector & projections, const std::vector & footprints, ProjectionParameters & projection_params, const VelocityParameters & velocity_params); /// @brief copy the velocity profile of a downsampled trajectory to the original trajectory diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp index 13fac28291c3d..8916137c84077 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp @@ -18,7 +18,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include @@ -75,7 +74,7 @@ class ObstacleVelocityLimiterNode : public rclcpp::Node OccupancyGrid::ConstSharedPtr occupancy_grid_ptr_; PointCloud::ConstSharedPtr pointcloud_ptr_; lanelet::LaneletMapPtr lanelet_map_ptr_{new lanelet::LaneletMap}; - multilinestring_t static_map_obstacles_; + multi_linestring_t static_map_obstacles_; nav_msgs::msg::Odometry::ConstSharedPtr current_odometry_ptr_; // parameters diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacles.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacles.hpp index 0d7edc649857d..8620c254968fe 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacles.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacles.hpp @@ -17,7 +17,6 @@ #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -41,7 +40,7 @@ namespace obstacle_velocity_limiter struct Obstacles { - multilinestring_t lines; + multi_linestring_t lines; multipoint_t points; }; @@ -69,11 +68,11 @@ struct ObstacleTree }; template <> -struct ObstacleTree +struct ObstacleTree { bgi::rtree> segments_rtree; - explicit ObstacleTree(const multilinestring_t & obstacles) + explicit ObstacleTree(const multi_linestring_t & obstacles) { auto segment_count = 0lu; for (const auto & line : obstacles) @@ -115,7 +114,7 @@ struct CollisionChecker { const Obstacles obstacles; std::unique_ptr> point_obstacle_tree_ptr; - std::unique_ptr> line_obstacle_tree_ptr; + std::unique_ptr> line_obstacle_tree_ptr; explicit CollisionChecker( Obstacles obs, const size_t rtree_min_points, const size_t rtree_min_segments) @@ -125,7 +124,7 @@ struct CollisionChecker for (const auto & line : obstacles.lines) if (!line.empty()) segment_count += line.size() - 1; if (segment_count > rtree_min_segments) - line_obstacle_tree_ptr = std::make_unique>(obstacles.lines); + line_obstacle_tree_ptr = std::make_unique>(obstacles.lines); if (obstacles.points.size() > rtree_min_points) point_obstacle_tree_ptr = std::make_unique>(obstacles.points); } @@ -163,7 +162,7 @@ polygon_t createObjectPolygon( /// @param [in] buffer buffer to add to the objects dimensions /// @param [in] min_velocity objects with velocity lower will be ignored /// @return polygons of the objects -multipolygon_t createObjectPolygons( +multi_polygon_t createObjectPolygons( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const double buffer, const double min_velocity); diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/occupancy_grid_utils.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/occupancy_grid_utils.hpp index 61f4f575f826b..b99407ae97846 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/occupancy_grid_utils.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/occupancy_grid_utils.hpp @@ -17,7 +17,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -42,7 +41,7 @@ grid_map::GridMap convertToGridMap(const OccupancyGrid & occupancy_grid); /// @param[in] occupancy_grid input occupancy grid /// @param[in] occupied_threshold threshold to use for identifying obstacles in the occupancy grid /// @return extracted obstacle linestrings -multilinestring_t extractObstacles( +multi_linestring_t extractObstacles( const grid_map::GridMap & grid_map, const OccupancyGrid & occupancy_grid); } // namespace obstacle_velocity_limiter diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/parameters.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/parameters.hpp index 7521e6b1a0bba..def328c8c9ae7 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/parameters.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/parameters.hpp @@ -16,7 +16,6 @@ #define OBSTACLE_VELOCITY_LIMITER__PARAMETERS_HPP_ #include -// cspell: ignore multipolygon, multilinestring #include #include @@ -40,8 +39,7 @@ struct ObstacleParameters static constexpr auto RTREE_SEGMENTS_PARAM = "obstacles.rtree_min_segments"; static constexpr auto RTREE_POINTS_PARAM = "obstacles.rtree_min_points"; - // cspell: ignore OCCUPANCYGRID - enum { POINTCLOUD, OCCUPANCYGRID, STATIC_ONLY } dynamic_source = OCCUPANCYGRID; + enum { POINTCLOUD, OCCUPANCY_GRID, STATIC_ONLY } dynamic_source = OCCUPANCY_GRID; int8_t occupancy_grid_threshold{}; Float dynamic_obstacles_buffer{}; Float dynamic_obstacles_min_vel{}; @@ -74,7 +72,7 @@ struct ObstacleParameters if (type == "pointcloud") { dynamic_source = POINTCLOUD; } else if (type == "occupancy_grid") { - dynamic_source = OCCUPANCYGRID; + dynamic_source = OCCUPANCY_GRID; } else if (type == "static_only") { dynamic_source = STATIC_ONLY; } else { @@ -113,7 +111,7 @@ struct ObstacleParameters struct ProjectionParameters { static constexpr auto MODEL_PARAM = "simulation.model"; - static constexpr auto NBPOINTS_PARAM = "simulation.nb_points"; + static constexpr auto NB_POINTS_PARAM = "simulation.nb_points"; static constexpr auto STEER_OFFSET_PARAM = "simulation.steering_offset"; static constexpr auto DISTANCE_METHOD_PARAM = "simulation.distance_method"; static constexpr auto DURATION_PARAM = "min_ttc"; @@ -135,7 +133,7 @@ struct ProjectionParameters { updateModel(node, node.declare_parameter(MODEL_PARAM)); updateDistanceMethod(node, node.declare_parameter(DISTANCE_METHOD_PARAM)); - updateNbPoints(node, node.declare_parameter(NBPOINTS_PARAM)); + updateNbPoints(node, node.declare_parameter(NB_POINTS_PARAM)); steering_angle_offset = node.declare_parameter(STEER_OFFSET_PARAM); duration = node.declare_parameter(DURATION_PARAM); } diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/pointcloud_utils.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/pointcloud_utils.hpp index 80d79791d0bbc..9edb197ecba72 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/pointcloud_utils.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/pointcloud_utils.hpp @@ -17,7 +17,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include "tier4_autoware_utils/ros/transform_listener.hpp" #include diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/trajectory_preprocessing.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/trajectory_preprocessing.hpp index 2ee003206339d..258ef8f01b5f5 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/trajectory_preprocessing.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/trajectory_preprocessing.hpp @@ -16,7 +16,6 @@ #define OBSTACLE_VELOCITY_LIMITER__TRAJECTORY_PREPROCESSING_HPP_ #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring namespace obstacle_velocity_limiter { diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/types.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/types.hpp index 81de7463b9e42..e44011e1f0ee3 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/types.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/types.hpp @@ -23,7 +23,6 @@ #include #include -// cspell: ignore multipolygon, multilinestring namespace obstacle_velocity_limiter { using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -36,15 +35,15 @@ using Float = decltype(TrajectoryPoint::longitudinal_velocity_mps); using point_t = tier4_autoware_utils::Point2d; using multipoint_t = tier4_autoware_utils::MultiPoint2d; using polygon_t = tier4_autoware_utils::Polygon2d; -using multipolygon_t = tier4_autoware_utils::MultiPolygon2d; +using multi_polygon_t = tier4_autoware_utils::MultiPolygon2d; using segment_t = tier4_autoware_utils::Segment2d; using linestring_t = tier4_autoware_utils::LineString2d; -using multilinestring_t = tier4_autoware_utils::MultiLineString2d; +using multi_linestring_t = tier4_autoware_utils::MultiLineString2d; struct ObstacleMasks { - polygon_t positive_mask; // discard obstacles outside of this polygon - multipolygon_t negative_masks; // discard obstacles inside of these polygons + polygon_t positive_mask; // discard obstacles outside of this polygon + multi_polygon_t negative_masks; // discard obstacles inside of these polygons }; } // namespace obstacle_velocity_limiter diff --git a/planning/obstacle_velocity_limiter/script/velocity_visualizer.py b/planning/obstacle_velocity_limiter/script/velocity_visualizer.py index d26f6133b0b54..c9255dae679c0 100755 --- a/planning/obstacle_velocity_limiter/script/velocity_visualizer.py +++ b/planning/obstacle_velocity_limiter/script/velocity_visualizer.py @@ -22,6 +22,7 @@ from rclpy.node import Node +# cspell: ignore axhline, relim class TrajectoryVisualizer(Node): def __init__(self): super().__init__("trajectory_visualizer") diff --git a/planning/obstacle_velocity_limiter/src/debug.cpp b/planning/obstacle_velocity_limiter/src/debug.cpp index 853dee2d20f49..051846cfeb8ca 100644 --- a/planning/obstacle_velocity_limiter/src/debug.cpp +++ b/planning/obstacle_velocity_limiter/src/debug.cpp @@ -16,7 +16,6 @@ #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -57,8 +56,8 @@ visualization_msgs::msg::Marker makePolygonMarker(const polygon_t & polygon, con } visualization_msgs::msg::MarkerArray makeDebugMarkers( - const Obstacles & obstacles, const std::vector & original_projections, - const std::vector & adjusted_projections, + const Obstacles & obstacles, const std::vector & original_projections, + const std::vector & adjusted_projections, const std::vector & original_footprints, const std::vector & adjusted_footprints, const ObstacleMasks & obstacle_masks, const Float marker_z) diff --git a/planning/obstacle_velocity_limiter/src/forward_projection.cpp b/planning/obstacle_velocity_limiter/src/forward_projection.cpp index d3193eefe0114..e90f17ae140e6 100644 --- a/planning/obstacle_velocity_limiter/src/forward_projection.cpp +++ b/planning/obstacle_velocity_limiter/src/forward_projection.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -48,10 +47,10 @@ segment_t forwardSimulatedSegment( return segment_t{from, to}; } -multilinestring_t bicycleProjectionLines( +multi_linestring_t bicycleProjectionLines( const geometry_msgs::msg::Point & origin, const ProjectionParameters & params) { - multilinestring_t lines; + multi_linestring_t lines; if (params.steering_angle_offset == 0.0) lines.push_back(bicycleProjectionLine(origin, params, params.steering_angle)); else @@ -78,7 +77,7 @@ linestring_t bicycleProjectionLine( return line; } -polygon_t generateFootprint(const multilinestring_t & lines, const double lateral_offset) +polygon_t generateFootprint(const multi_linestring_t & lines, const double lateral_offset) { polygon_t footprint; if (lines.size() == 1) { @@ -98,7 +97,7 @@ polygon_t generateFootprint(const segment_t & segment, const double lateral_offs polygon_t generateFootprint(const linestring_t & linestring, const double lateral_offset) { namespace bg = boost::geometry; - multipolygon_t footprint; + multi_polygon_t footprint; namespace strategy = bg::strategy::buffer; bg::buffer( linestring, footprint, strategy::distance_symmetric(lateral_offset), diff --git a/planning/obstacle_velocity_limiter/src/map_utils.cpp b/planning/obstacle_velocity_limiter/src/map_utils.cpp index e84734355268e..d10244867833b 100644 --- a/planning/obstacle_velocity_limiter/src/map_utils.cpp +++ b/planning/obstacle_velocity_limiter/src/map_utils.cpp @@ -17,7 +17,6 @@ #include "lanelet2_core/primitives/LineString.h" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -27,10 +26,10 @@ namespace obstacle_velocity_limiter { -multilinestring_t extractStaticObstacles( +multi_linestring_t extractStaticObstacles( const lanelet::LaneletMap & lanelet_map, const std::vector & tags) { - multilinestring_t lines; + multi_linestring_t lines; linestring_t line; linestring_t simplified_line; for (const auto & ls : lanelet_map.lineStringLayer) { diff --git a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter.cpp b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter.cpp index dbe7c87922564..ac1b4bde65211 100644 --- a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter.cpp @@ -34,7 +34,7 @@ Float calculateSafeVelocity( std::max(min_adjusted_velocity, static_cast(dist_to_collision / time_buffer))); } -multipolygon_t createPolygonMasks( +multi_polygon_t createPolygonMasks( const autoware_auto_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const Float buffer, const Float min_vel) { @@ -42,7 +42,7 @@ multipolygon_t createPolygonMasks( } std::vector createFootprintPolygons( - const std::vector & projected_linestrings, const Float lateral_offset) + const std::vector & projected_linestrings, const Float lateral_offset) { std::vector footprints; footprints.reserve(projected_linestrings.size()); @@ -84,8 +84,8 @@ polygon_t createEnvelopePolygon( polygon_t createEnvelopePolygon(const std::vector & footprints) { - multipolygon_t unions; - multipolygon_t result; + multi_polygon_t unions; + multi_polygon_t result; for (const auto & footprint : footprints) { boost::geometry::union_(footprint, unions, result); unions = result; @@ -95,10 +95,10 @@ polygon_t createEnvelopePolygon(const std::vector & footprints) return unions.front(); } -std::vector createProjectedLines( +std::vector createProjectedLines( const Trajectory & trajectory, ProjectionParameters & params) { - std::vector projections; + std::vector projections; projections.reserve(trajectory.points.size()); for (const auto & point : trajectory.points) { params.update(point); @@ -114,7 +114,7 @@ std::vector createProjectedLines( void limitVelocity( Trajectory & trajectory, const CollisionChecker & collision_checker, - const std::vector & projections, const std::vector & footprints, + const std::vector & projections, const std::vector & footprints, ProjectionParameters & projection_params, const VelocityParameters & velocity_params) { Float time = 0.0; diff --git a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp index a738fff7b0e5f..9ab609378621a 100644 --- a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp @@ -21,7 +21,6 @@ #include "obstacle_velocity_limiter/parameters.hpp" #include "obstacle_velocity_limiter/trajectory_preprocessing.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include @@ -151,7 +150,7 @@ rcl_interfaces::msg::SetParametersResult ObstacleVelocityLimiterNode::onParamete result.successful = false; result.reason = "Unknown forward projection model"; } - } else if (parameter.get_name() == ProjectionParameters::NBPOINTS_PARAM) { + } else if (parameter.get_name() == ProjectionParameters::NB_POINTS_PARAM) { if (!projection_params_.updateNbPoints(*this, static_cast(parameter.as_int()))) { result.successful = false; result.reason = "number of points for projections must be at least 2"; diff --git a/planning/obstacle_velocity_limiter/src/obstacles.cpp b/planning/obstacle_velocity_limiter/src/obstacles.cpp index 7f6d1cc965319..603e573e68f17 100644 --- a/planning/obstacle_velocity_limiter/src/obstacles.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacles.cpp @@ -58,11 +58,11 @@ polygon_t createObjectPolygon( return translate_obj_poly; } -multipolygon_t createObjectPolygons( +multi_polygon_t createObjectPolygons( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const double buffer, const double min_velocity) { - multipolygon_t polygons; + multi_polygon_t polygons; for (const auto & object : objects.objects) { const double obj_vel_norm = std::hypot( object.kinematics.initial_twist_with_covariance.twist.linear.x, @@ -80,8 +80,7 @@ void addSensorObstacles( const ObstacleMasks & masks, tier4_autoware_utils::TransformListener & transform_listener, const std::string & target_frame, const ObstacleParameters & obstacle_params) { - // cspell: ignore OCCUPANCYGRID - if (obstacle_params.dynamic_source == ObstacleParameters::OCCUPANCYGRID) { + if (obstacle_params.dynamic_source == ObstacleParameters::OCCUPANCY_GRID) { auto grid_map = convertToGridMap(occupancy_grid); threshold(grid_map, obstacle_params.occupancy_grid_threshold); maskPolygons(grid_map, masks); diff --git a/planning/obstacle_velocity_limiter/src/occupancy_grid_utils.cpp b/planning/obstacle_velocity_limiter/src/occupancy_grid_utils.cpp index 397e20d05ebe0..7fe3d88885c3a 100644 --- a/planning/obstacle_velocity_limiter/src/occupancy_grid_utils.cpp +++ b/planning/obstacle_velocity_limiter/src/occupancy_grid_utils.cpp @@ -15,7 +15,6 @@ #include "obstacle_velocity_limiter/occupancy_grid_utils.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include #include @@ -70,7 +69,7 @@ grid_map::GridMap convertToGridMap(const OccupancyGrid & occupancy_grid) return grid_map; } -multilinestring_t extractObstacles( +multi_linestring_t extractObstacles( const grid_map::GridMap & grid_map, const OccupancyGrid & occupancy_grid) { cv::Mat cv_image; @@ -79,7 +78,7 @@ multilinestring_t extractObstacles( cv::erode(cv_image, cv_image, cv::Mat(), cv::Point(-1, -1), 2); std::vector> contours; cv::findContours(cv_image, contours, CV_RETR_LIST, CV_CHAIN_APPROX_SIMPLE); - multilinestring_t obstacles; + multi_linestring_t obstacles; const auto & info = occupancy_grid.info; for (const auto & contour : contours) { linestring_t line; diff --git a/planning/obstacle_velocity_limiter/src/pointcloud_utils.cpp b/planning/obstacle_velocity_limiter/src/pointcloud_utils.cpp index 25339a49529d6..4f9ca6c5bc3e7 100644 --- a/planning/obstacle_velocity_limiter/src/pointcloud_utils.cpp +++ b/planning/obstacle_velocity_limiter/src/pointcloud_utils.cpp @@ -15,7 +15,6 @@ #include "obstacle_velocity_limiter/pointcloud_utils.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include diff --git a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp index 64693ef8ef249..e9cf8d9ad4dd6 100644 --- a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp +++ b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp @@ -15,7 +15,6 @@ #include "obstacle_velocity_limiter/distance.hpp" #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include "tier4_autoware_utils/geometry/geometry.hpp" #include diff --git a/planning/obstacle_velocity_limiter/test/test_forward_projection.cpp b/planning/obstacle_velocity_limiter/test/test_forward_projection.cpp index 6e35ec95c62e0..536c3e93e4fa7 100644 --- a/planning/obstacle_velocity_limiter/test/test_forward_projection.cpp +++ b/planning/obstacle_velocity_limiter/test/test_forward_projection.cpp @@ -14,7 +14,6 @@ #include "obstacle_velocity_limiter/forward_projection.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include "tier4_autoware_utils/geometry/geometry.hpp" #include @@ -149,10 +148,10 @@ TEST(TestForwardProjection, generateFootprintMultiLinestrings) { using obstacle_velocity_limiter::generateFootprint; using obstacle_velocity_limiter::linestring_t; - using obstacle_velocity_limiter::multilinestring_t; + using obstacle_velocity_limiter::multi_linestring_t; auto footprint = generateFootprint( - multilinestring_t{ + multi_linestring_t{ linestring_t{{0.0, 0.0}, {0.0, 1.0}}, linestring_t{{0.0, 0.0}, {0.8, 0.8}}, linestring_t{{0.0, 0.0}, {1.0, 0.0}}}, 0.5); diff --git a/planning/obstacle_velocity_limiter/test/test_obstacles.cpp b/planning/obstacle_velocity_limiter/test/test_obstacles.cpp index f75e808828ca6..eaf4a29a3a282 100644 --- a/planning/obstacle_velocity_limiter/test/test_obstacles.cpp +++ b/planning/obstacle_velocity_limiter/test/test_obstacles.cpp @@ -14,7 +14,6 @@ #include "obstacle_velocity_limiter/obstacles.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -49,7 +48,7 @@ TEST(TestObstacles, ObstacleTreeLines) /* using obstacle_velocity_limiter::point_t; using obstacle_velocity_limiter::linestring_t; - const obstacle_velocity_limiter::multilinestring_t lines = { + const obstacle_velocity_limiter::multi_linestring_t lines = { {point_t{-0.5, -0.5}, point_t{0.5,0.5}}, {point_t{0, 0}, point_t{1,1}}, {point_t(2, 2), point_t(-2, 2)}, diff --git a/planning/obstacle_velocity_limiter/test/test_occupancy_grid_utils.cpp b/planning/obstacle_velocity_limiter/test/test_occupancy_grid_utils.cpp index a6ff8543f6ad0..4b49c569ab9f6 100644 --- a/planning/obstacle_velocity_limiter/test/test_occupancy_grid_utils.cpp +++ b/planning/obstacle_velocity_limiter/test/test_occupancy_grid_utils.cpp @@ -14,7 +14,6 @@ #include "obstacle_velocity_limiter/occupancy_grid_utils.hpp" #include "obstacle_velocity_limiter/types.hpp" -// cspell: ignore multipolygon, multilinestring #include @@ -22,7 +21,7 @@ TEST(TestOccupancyGridUtils, extractObstacleLines) { - using obstacle_velocity_limiter::multipolygon_t; + using obstacle_velocity_limiter::multi_polygon_t; using obstacle_velocity_limiter::polygon_t; constexpr int8_t occupied_thr = 10; nav_msgs::msg::OccupancyGrid occupancy_grid; @@ -37,7 +36,7 @@ TEST(TestOccupancyGridUtils, extractObstacleLines) constexpr auto extractObstacles = []( const nav_msgs::msg::OccupancyGrid & occupancy_grid, - const multipolygon_t & negative_masks, + const multi_polygon_t & negative_masks, const polygon_t & positive_mask, const double thr) { obstacle_velocity_limiter::ObstacleMasks masks; masks.negative_masks = negative_masks; From c09441be8a605d847da9c528f7cfb851a51b5adc Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 22 Aug 2023 13:43:08 +0900 Subject: [PATCH 224/266] feat(merge_from_private): use separate param (#4692) Signed-off-by: Mamoru Sobue --- .../config/intersection.param.yaml | 1 + planning/behavior_velocity_intersection_module/src/manager.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index ce49163006d99..2b3ca11bbe750 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -54,4 +54,5 @@ intersection_to_occlusion: true merge_from_private: + stop_line_margin: 3.0 stop_duration_sec: 1.0 diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 75c282d117e97..6a2b7200abb2e 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -266,7 +266,7 @@ MergeFromPrivateModuleManager::MergeFromPrivateModuleManager(rclcpp::Node & node mp.stop_duration_sec = node.declare_parameter(ns + ".stop_duration_sec"); mp.attention_area_length = node.get_parameter("intersection.common.attention_area_length").as_double(); - mp.stop_line_margin = node.get_parameter("intersection.common.stop_line_margin").as_double(); + mp.stop_line_margin = node.declare_parameter(ns + ".stop_line_margin"); mp.path_interpolation_ds = node.get_parameter("intersection.common.path_interpolation_ds").as_double(); } From 9b1e4e39ea5d47f90bda65f73e5787090938fd52 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 22 Aug 2023 14:13:35 +0900 Subject: [PATCH 225/266] chore: correct spelling for sensing and perception (#4688) * refactor: image diagnostics spell-check Signed-off-by: badai-nguyen * ci: ignore spell check for DHAVE and YAMLCPP Signed-off-by: badai-nguyen * refactor: pointcloud preprocessor spell-check Signed-off-by: badai-nguyen * chore: preprocessor spell-check Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- perception/ground_segmentation/CMakeLists.txt | 2 +- .../image/block_state_decision.svg | 15 ++++--- .../image/image_diagnostics_overview.svg | 11 +++--- .../image/image_status_decision.svg | 39 +++++++++---------- .../src/image_diagnostics_node.cpp | 8 ++-- .../docs/concatenate-data.md | 2 +- .../time_synchronizer_nodelet.hpp | 1 + .../launch/preprocessor.launch.py | 14 +++---- 8 files changed, 45 insertions(+), 47 deletions(-) diff --git a/perception/ground_segmentation/CMakeLists.txt b/perception/ground_segmentation/CMakeLists.txt index dcff2b33dcdb5..bdd793896062a 100644 --- a/perception/ground_segmentation/CMakeLists.txt +++ b/perception/ground_segmentation/CMakeLists.txt @@ -75,7 +75,7 @@ find_library(YAML_CPP_LIBRARY PATHS ${YAML_CPP_LIBRARY_DIRS}) link_directories(${YAML_CPP_LIBRARY_DIRS}) - +# cspell:ignore DHAVE, YAMLCPP if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") add_definitions(-DHAVE_NEW_YAMLCPP) endif() diff --git a/sensing/image_diagnostics/image/block_state_decision.svg b/sensing/image_diagnostics/image/block_state_decision.svg index 373dc7984b3a6..39c49ab325dda 100644 --- a/sensing/image_diagnostics/image/block_state_decision.svg +++ b/sensing/image_diagnostics/image/block_state_decision.svg @@ -1,5 +1,5 @@ - + @@ -30,8 +29,8 @@ - - + + @@ -165,7 +164,7 @@ blockage area ratio - + @@ -187,7 +186,7 @@ freq_average  <... - + @@ -434,7 +433,7 @@ - + Text is not SVG - cannot display diff --git a/sensing/image_diagnostics/image/image_diagnostics_overview.svg b/sensing/image_diagnostics/image/image_diagnostics_overview.svg index ed72197c7118e..7634974501746 100644 --- a/sensing/image_diagnostics/image/image_diagnostics_overview.svg +++ b/sensing/image_diagnostics/image/image_diagnostics_overview.svg @@ -1,5 +1,5 @@ - + - - + + @@ -111,7 +110,7 @@ - + Text is not SVG - cannot display diff --git a/sensing/image_diagnostics/image/image_status_decision.svg b/sensing/image_diagnostics/image/image_status_decision.svg index ec5ab743e7900..119b2dfe79e24 100644 --- a/sensing/image_diagnostics/image/image_status_decision.svg +++ b/sensing/image_diagnostics/image/image_status_decision.svg @@ -1,15 +1,14 @@ - + @@ -32,8 +31,8 @@ - - + + @@ -49,10 +48,10 @@ Dark blocks > N_dark_... - - - - + + + + @@ -71,10 +70,10 @@ backlight blocks... - - - - + + + + @@ -86,16 +85,16 @@

    bloackage blocks > N_blockage_thresh
    + >blockage blocks > N_blockage_thresh
    - bloackage blocks > N_b... + blockage blocks > N_bl... - + - + @@ -365,7 +364,7 @@ -
    + Text is not SVG - cannot display diff --git a/sensing/image_diagnostics/src/image_diagnostics_node.cpp b/sensing/image_diagnostics/src/image_diagnostics_node.cpp index bd5fbf791261e..3db9ab94f50fa 100644 --- a/sensing/image_diagnostics/src/image_diagnostics_node.cpp +++ b/sensing/image_diagnostics/src/image_diagnostics_node.cpp @@ -42,10 +42,10 @@ ImageDiagNode::ImageDiagNode(const rclcpp::NodeOptions & node_options) void ImageDiagNode::onImageDiagChecker(DiagnosticStatusWrapper & stat) { - stat.add("number dark blocks ", std::to_string(params_.num_of_regions_dark)); - stat.add("number blockaged blocks ", std::to_string(params_.num_of_regions_blockage)); - stat.add("number low visibility blocks ", std::to_string(params_.num_of_regions_low_visibility)); - stat.add("number backlight blocks ", std::to_string(params_.num_of_regions_backlight)); + stat.add("number dark regions ", std::to_string(params_.num_of_regions_dark)); + stat.add("number blockage regions ", std::to_string(params_.num_of_regions_blockage)); + stat.add("number low visibility regions ", std::to_string(params_.num_of_regions_low_visibility)); + stat.add("number backlight regions ", std::to_string(params_.num_of_regions_backlight)); auto level = DiagnosticStatusWrapper::OK; if (params_.diagnostic_status < 0) { diff --git a/sensing/pointcloud_preprocessor/docs/concatenate-data.md b/sensing/pointcloud_preprocessor/docs/concatenate-data.md index 7ff4371f48a9a..a3b5268815f24 100644 --- a/sensing/pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/pointcloud_preprocessor/docs/concatenate-data.md @@ -49,7 +49,7 @@ For the example of actual usage of this node, please refer to the [preprocessor. ### How to tuning timeout_sec and input_offset -The values in `timeout_sec` and `input_offset` are used in the timercallback to control concatenation timings. +The values in `timeout_sec` and `input_offset` are used in the timer_callback to control concatenation timings. - Assumptions - when the timer runs out, we concatenate the pointclouds in the buffer diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp index 09e24bedeb6b9..f30c02a97a6c0 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp @@ -88,6 +88,7 @@ namespace pointcloud_preprocessor { using autoware_point_types::PointXYZI; using point_cloud_msg_wrapper::PointCloud2Modifier; +// cspell:ignore Yoshi /** \brief @b PointCloudDataSynchronizerComponent is a special form of data * synchronizer: it listens for a set of input PointCloud messages on the same topic, * checks their timestamps, and concatenates their fields together into a single diff --git a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py b/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py index b2e245c5cbf4f..6b1fc0f5bd976 100644 --- a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py +++ b/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py @@ -26,14 +26,14 @@ def launch_setup(context, *args, **kwargs): ns = "pointcloud_preprocessor" pkg = "pointcloud_preprocessor" - separate_concatenate_node_and_timesync_node = LaunchConfiguration( - "separate_concatenate_node_and_timesync_node" + separate_concatenate_node_and_time_sync_node = LaunchConfiguration( + "separate_concatenate_node_and_time_sync_node" ).perform(context) - is_separate_concatenate_node_and_timesync_node = ( - separate_concatenate_node_and_timesync_node.lower() == "true" + is_separate_concatenate_node_and_time_sync_node = ( + separate_concatenate_node_and_time_sync_node.lower() == "true" ) - if not is_separate_concatenate_node_and_timesync_node: + if not is_separate_concatenate_node_and_time_sync_node: sync_and_concat_component = ComposableNode( package=pkg, plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", @@ -155,9 +155,9 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("output_points_raw", "/points_raw/cropbox/filtered") add_launch_arg("tf_output_frame", "base_link") add_launch_arg( - "separate_concatenate_node_and_timesync_node", + "separate_concatenate_node_and_time_sync_node", "true", - "Set True to separate concatenate node and timesync node. which will cause to larger memory usage.", + "Set True to separate concatenate node and time_sync node. which will cause to larger memory usage.", ) return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) From f3f8cf5c81d71c50a50f6ad5eefc46d23ef2fc12 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 22 Aug 2023 17:59:39 +0900 Subject: [PATCH 226/266] feat(behavior_path_planner): consider object velocity direction (#4652) * feat(behavior_path_planner): consider object velocity direction Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * Update planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.cpp | 17 ++++++++++++----- .../src/scene_module/lane_change/interface.cpp | 3 ++- .../src/scene_module/lane_change/normal.cpp | 6 ++++-- .../src/utils/avoidance/utils.cpp | 11 ++++++----- .../src/utils/lane_change/utils.cpp | 16 ++++++++++------ 5 files changed, 34 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index b69e95875c5fb..8e6ab24929a00 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -101,15 +101,20 @@ std::pair projectObstacleVelocityToTrajectory( const std::vector & path_points, const PredictedObject & object) { const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; - const double obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear.x; + const double obj_vel_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); const size_t obj_idx = motion_utils::findNearestIndex(path_points, obj_pose.position); - const double obj_yaw = tf2::getYaw(obj_pose.orientation); + const double obj_vel_yaw = std::atan2( + object.kinematics.initial_twist_with_covariance.twist.linear.y, + object.kinematics.initial_twist_with_covariance.twist.linear.x); const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); return std::make_pair( - obj_vel * std::cos(obj_yaw - path_yaw), obj_vel * std::sin(obj_yaw - path_yaw)); + obj_vel_norm * std::cos(obj_vel_yaw - path_yaw), + obj_vel_norm * std::sin(obj_vel_yaw - path_yaw)); } double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & shape) @@ -365,7 +370,9 @@ void DynamicAvoidanceModule::updateTargetObjects() for (const auto & predicted_object : predicted_objects) { const auto obj_uuid = tier4_autoware_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; - const double obj_vel = predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; + const double obj_vel_norm = std::hypot( + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y); const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); // 1.a. check label @@ -393,7 +400,7 @@ void DynamicAvoidanceModule::updateTargetObjects() ? parameters_->min_overtaking_crossing_object_vel : parameters_->min_oncoming_crossing_object_vel; const bool is_crossing_object_to_ignore = - min_crossing_object_vel < std::abs(obj_vel) && is_obstacle_crossing_path; + min_crossing_object_vel < obj_vel_norm && is_obstacle_crossing_path; if (is_crossing_object_to_ignore) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index baa9fd0a7e3f5..270e2064228af 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -336,7 +336,8 @@ std::shared_ptr LaneChangeInterface::get_debug_msg_arra debug_msg.is_front = debug_data.is_front; debug_msg.relative_distance = debug_data.relative_to_ego; debug_msg.failed_reason = debug_data.failed_reason; - debug_msg.velocity = debug_data.object_twist.linear.x; + debug_msg.velocity = + std::hypot(debug_data.object_twist.linear.x, debug_data.object_twist.linear.y); debug_msg_array.lane_change_info.push_back(debug_msg); } lane_change_debug_msg_array_ = debug_msg_array; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 77c5e78d3db50..a8fdfce54b145 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -677,7 +677,9 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( LaneChangeTargetObjectIndices filtered_obj_indices; for (size_t i = 0; i < objects.objects.size(); ++i) { const auto & object = objects.objects.at(i); - const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; + const auto & obj_velocity_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); const auto extended_object = utils::lane_change::transform(object, common_parameters, *lane_change_parameters_); @@ -700,7 +702,7 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( } // ignore static object that are behind the ego vehicle - if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { + if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) { continue; } diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index e6b946a130682..4cbfebef07a39 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -693,9 +693,9 @@ void fillObjectMovingTime( const auto object_type = utils::getHighestProbLabel(object_data.object.classification); const auto object_parameter = parameters->object_parameters.at(object_type); - const auto & object_vel = - object_data.object.kinematics.initial_twist_with_covariance.twist.linear.x; - const auto is_faster_than_threshold = object_vel > object_parameter.moving_speed_threshold; + const auto & object_twist = object_data.object.kinematics.initial_twist_with_covariance.twist; + const auto object_vel_norm = std::hypot(object_twist.linear.x, object_twist.linear.y); + const auto is_faster_than_threshold = object_vel_norm > object_parameter.moving_speed_threshold; const auto id = object_data.object.object_id; const auto same_id_obj = std::find_if( @@ -1475,7 +1475,8 @@ ExtendedPredictedObject transform( extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; extended_object.shape = object.shape; - const auto & obj_velocity = extended_object.initial_twist.twist.linear.x; + const auto & obj_velocity_norm = std::hypot( + extended_object.initial_twist.twist.linear.x, extended_object.initial_twist.twist.linear.y); const auto & time_horizon = parameters->safety_check_time_horizon; const auto & time_resolution = parameters->safety_check_time_resolution; @@ -1490,7 +1491,7 @@ ExtendedPredictedObject transform( if (obj_pose) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths.at(i).path.emplace_back( - t, *obj_pose, obj_velocity, obj_polygon); + t, *obj_pose, obj_velocity_norm, obj_polygon); } } } diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 0e68862f12a5a..f3a1260eecadc 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -855,7 +855,9 @@ bool isParkedObject( using lanelet::geometry::distance2d; using lanelet::geometry::toArcCoordinates; - if (object.initial_twist.twist.linear.x > static_object_velocity_threshold) { + const double object_vel_norm = + std::hypot(object.initial_twist.twist.linear.x, object.initial_twist.twist.linear.y); + if (object_vel_norm > static_object_velocity_threshold) { return false; } @@ -1034,7 +1036,9 @@ boost::optional getLeadingStaticObjectIdx( // ignore non-static object // TODO(shimizu): parametrize threshold - if (obj.initial_twist.twist.linear.x > 1.0) { + const double obj_vel_norm = + std::hypot(obj.initial_twist.twist.linear.x, obj.initial_twist.twist.linear.y); + if (obj_vel_norm > 1.0) { continue; } @@ -1095,9 +1099,9 @@ ExtendedPredictedObject transform( const auto & prepare_duration = common_parameters.lane_change_prepare_duration; const auto & velocity_threshold = lane_change_parameters.prepare_segment_ignore_object_velocity_thresh; - const auto & obj_vel = extended_object.initial_twist.twist.linear.x; const auto start_time = check_at_prepare_phase ? 0.0 : prepare_duration; - const double obj_velocity = extended_object.initial_twist.twist.linear.x; + const double obj_vel_norm = std::hypot( + extended_object.initial_twist.twist.linear.x, extended_object.initial_twist.twist.linear.y); extended_object.predicted_paths.resize(object.kinematics.predicted_paths.size()); for (size_t i = 0; i < object.kinematics.predicted_paths.size(); ++i) { @@ -1109,14 +1113,14 @@ ExtendedPredictedObject transform( // create path for (double t = start_time; t < end_time + std::numeric_limits::epsilon(); t += time_resolution) { - if (t < prepare_duration && obj_vel < velocity_threshold) { + if (t < prepare_duration && obj_vel_norm < velocity_threshold) { continue; } const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths.at(i).path.emplace_back( - t, *obj_pose, obj_velocity, obj_polygon); + t, *obj_pose, obj_vel_norm, obj_polygon); } } } From 098bc0c08c6b056f38ad6ab092ce2e697219ee53 Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Tue, 22 Aug 2023 12:38:32 +0300 Subject: [PATCH 227/266] feat(vehicle_cmd_gate): add an option for using raw external commands (#4325) * clean_commit Signed-off-by: ismetatabay * move enable_cmd_limit_filter argument to param file Signed-off-by: ismetatabay --------- Signed-off-by: ismetatabay --- .../vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml | 1 + control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 9 ++++++--- control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 1 + 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml index 7a49d3e5f82d3..731c73feeba4d 100644 --- a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -5,6 +5,7 @@ use_emergency_handling: false check_external_emergency_heartbeat: false use_start_request: false + enable_cmd_limit_filter: true external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index dc1d9ec1fedb8..3f6a07b6d5555 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -150,6 +150,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) moderate_stop_service_acceleration_ = declare_parameter("moderate_stop_service_acceleration"); stop_check_duration_ = declare_parameter("stop_check_duration"); + enable_cmd_limit_filter_ = declare_parameter("enable_cmd_limit_filter"); // Vehicle Parameter const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); @@ -411,9 +412,11 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands) filtered_commands.control.longitudinal.acceleration = stop_hold_acceleration_; } - // Apply limit filtering - filtered_commands.control = filterControlCommand(filtered_commands.control); - + // Check if command filtering option is enable + if (enable_cmd_limit_filter_) { + // Apply limit filtering + filtered_commands.control = filterControlCommand(filtered_commands.control); + } // tmp: Publish vehicle emergency status VehicleEmergencyStamped vehicle_cmd_emergency; vehicle_cmd_emergency.emergency = (use_emergency_handling_ && is_system_emergency_); diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 17bfe99d45251..b94240ce495af 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -164,6 +164,7 @@ class VehicleCmdGate : public rclcpp::Node double stop_hold_acceleration_; double emergency_acceleration_; double moderate_stop_service_acceleration_; + bool enable_cmd_limit_filter_; // Service rclcpp::Service::SharedPtr srv_engage_; From 00dfb142d87685970f66e204c49c636335a4f1bd Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 22 Aug 2023 19:49:39 +0900 Subject: [PATCH 228/266] feat(goal_planner): add extra front margin for collision check considering stopping distance (#4674) * feat(goal_planner): add extra front margin for collision check considering stopping distance Signed-off-by: kosuke55 * move safety_check Signed-off-by: kosuke55 * rename args and params Signed-off-by: kosuke55 * margin 0.6 and add comments Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner.param.yaml | 3 ++- ...havior_path_planner_goal_planner_design.md | 9 +++---- .../goal_planner/goal_planner_parameters.hpp | 1 + .../path_safety_checker/safety_check.hpp | 9 +++++++ .../behavior_path_planner/utils/utils.hpp | 10 ++++++++ .../goal_planner/goal_planner_module.cpp | 15 ++++++++---- .../src/scene_module/goal_planner/manager.cpp | 3 +++ .../path_safety_checker/safety_check.cpp | 24 +++++++++++++++++++ 8 files changed, 65 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml index 3c5846edf3ee9..39d05a7fb761b 100644 --- a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml +++ b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml @@ -31,7 +31,8 @@ # object recognition object_recognition: use_object_recognition: true - object_recognition_collision_check_margin: 1.0 + object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker + object_recognition_collision_check_max_extra_stopping_margin: 1.0 # pull over pull_over: diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md index 008087ee32b4b..99dadc959f5a5 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md @@ -150,10 +150,11 @@ Generate footprints from ego-vehicle path points and determine obstacle collisio #### Parameters for object recognition based collision check -| Name | Unit | Type | Description | Default value | -| :---------------------------------------- | :--- | :----- | :--------------------------------------------------------- | :------------ | -| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true | -| object_recognition_collision_check_margin | [m] | double | margin to calculate ego-vehicle cells from footprint. | 1.0 | +| Name | Unit | Type | Description | Default value | +| :----------------------------------------------------------- | :--- | :----- | :--------------------------------------------------------- | :------------ | ---------------------------------------------------------------------------------------------------------- | +| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true | +| object_recognition_collision_check_margin | [m] | double | margin to calculate ego-vehicle cells from footprint. | 0.6 | +| object_recognition_collision_check_max_extra_stopping_margin | [m] | double | | 1.0 |  maximum value when adding longitudinal distance margin for collision check considering stopping distance | ## **Goal Search** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp index f4a3a2bc5a88b..f87944641f59b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp @@ -68,6 +68,7 @@ struct GoalPlannerParameters // object recognition bool use_object_recognition; double object_recognition_collision_check_margin; + double object_recognition_collision_check_max_extra_stopping_margin; // pull over general params double pull_over_velocity; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index edfec6a7db579..8606f2cd2397d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -101,6 +101,15 @@ bool checkCollision( const BehaviorPathPlannerParameters & common_parameters, const double front_object_deceleration, const double rear_object_deceleration, CollisionCheckDebug & debug); +/** + * @brief Check collision between ego path footprints with extra longitudinal stopping margin and + * objects. + * @return Has collision or not + */ +bool checkCollisionWithExtraStoppingMargin( + const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, + const double base_to_front, const double base_to_rear, const double width, + const double maximum_deceleration, const double margin, const double max_stopping_margin); } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index d27d9ebbdadec..be227f4f7e93e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -164,6 +164,16 @@ double getDistanceBetweenPredictedPathAndObject( const PredictedObject & object, const PredictedPath & path, const double start_time, const double end_time, const double resolution); +/** + * @brief Check collision between ego path footprints with extra longitudinal stopping margin and + * objects. + * @return Has collision or not + */ +bool checkCollisionWithExtraStoppingMargin( + const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, + const double base_to_front, const double base_to_rear, const double width, + const double maximum_deceleration, const double margin, const double max_stopping_margin); + /** * @brief Check collision between ego path footprints and objects. * @return Has collision or not diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 40998ae3bcd0d..f37149f706436 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -553,7 +553,9 @@ void GoalPlannerModule::selectSafePullOverPath() } // check if path is valid and safe - if (!hasEnoughDistance(pull_over_path) || checkCollision(pull_over_path.getParkingPath())) { + if ( + !hasEnoughDistance(pull_over_path) || + checkCollision(utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5))) { continue; } @@ -1178,9 +1180,14 @@ bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const } if (parameters_->use_object_recognition) { - if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, path, *(planner_data_->dynamic_object), - parameters_->object_recognition_collision_check_margin)) { + const auto common_parameters = planner_data_->parameters; + const double base_link2front = common_parameters.base_link2front; + const double base_link2rear = common_parameters.base_link2rear; + const double vehicle_width = common_parameters.vehicle_width; + if (utils::path_safety_checker::checkCollisionWithExtraStoppingMargin( + path, *(planner_data_->dynamic_object), base_link2front, base_link2rear, vehicle_width, + parameters_->maximum_deceleration, parameters_->object_recognition_collision_check_margin, + parameters_->object_recognition_collision_check_max_extra_stopping_margin)) { return true; } } diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index 07af2c866daa5..7df1749a0fe82 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -88,6 +88,9 @@ GoalPlannerModuleManager::GoalPlannerModuleManager( p.use_object_recognition = node->declare_parameter(ns + "use_object_recognition"); p.object_recognition_collision_check_margin = node->declare_parameter(ns + "object_recognition_collision_check_margin"); + p.object_recognition_collision_check_max_extra_stopping_margin = + node->declare_parameter( + ns + "object_recognition_collision_check_max_extra_stopping_margin"); } // pull over general params diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index ee23ecc005142..34ba607938385 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -303,4 +303,28 @@ bool checkCollision( return true; } + +bool checkCollisionWithExtraStoppingMargin( + const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, + const double base_to_front, const double base_to_rear, const double width, + const double maximum_deceleration, const double collision_check_margin, + const double max_extra_stopping_margin) +{ + for (const auto & p : ego_path.points) { + const double extra_stopping_margin = std::min( + std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / maximum_deceleration, + max_extra_stopping_margin); + + const auto ego_polygon = tier4_autoware_utils::toFootprint( + p.point.pose, base_to_front + extra_stopping_margin, base_to_rear, width); + + for (const auto & object : dynamic_objects.objects) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); + const double distance = boost::geometry::distance(obj_polygon, ego_polygon); + if (distance < collision_check_margin) return true; + } + } + + return false; +} } // namespace behavior_path_planner::utils::path_safety_checker From 8efd31c2e0e318e4e451d84e91a92d7bd5392eab Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 22 Aug 2023 19:50:33 +0900 Subject: [PATCH 229/266] feat(behavior_path_planner): add status_is_safe_dynamic_objects (#4691) * add_status_is_safe_dynamic_objects Signed-off-by: kyoichi-sugahara * revert unnecessary changes Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 3 ++- .../start_planner/start_planner_module.cpp | 20 +++++++++---------- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 40f0dc0289cf0..2e8c9e57f8842 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -53,7 +53,8 @@ struct PullOutStatus PlannerType planner_type{PlannerType::NONE}; PathWithLaneId backward_path{}; lanelet::ConstLanelets pull_out_lanes{}; - bool is_safe{false}; + bool is_safe_static_objects{false}; // current path is safe against static objects + bool is_safe_dynamic_objects{false}; // current path is safe against dynamic objects bool back_finished{false}; Pose pull_out_start_pose{}; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index c7541dc8af544..4dd2e7a13a94d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -209,7 +209,7 @@ BehaviorModuleOutput StartPlannerModule::plan() } BehaviorModuleOutput output; - if (!status_.is_safe) { + if (!status_.is_safe_static_objects) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); const auto output = generateStopOutput(); @@ -314,7 +314,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() } BehaviorModuleOutput output; - if (!status_.is_safe) { + if (!status_.is_safe_static_objects) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); clearWaitingApproval(); @@ -427,7 +427,7 @@ void StartPlannerModule::planWithPriority( // use current path if back is not needed if (status_.back_finished) { const std::lock_guard lock(mutex_); - status_.is_safe = true; + status_.is_safe_static_objects = true; status_.pull_out_path = *pull_out_path; status_.pull_out_start_pose = pull_out_start_pose; status_.planner_type = planner->getPlannerType(); @@ -448,7 +448,7 @@ void StartPlannerModule::planWithPriority( // Update status variables with the next path information { const std::lock_guard lock(mutex_); - status_.is_safe = true; + status_.is_safe_static_objects = true; status_.pull_out_path = *pull_out_path_next; status_.pull_out_start_pose = pull_out_start_pose_next; status_.planner_type = planner->getPlannerType(); @@ -503,7 +503,7 @@ void StartPlannerModule::planWithPriority( // not found safe path if (status_.planner_type != PlannerType::FREESPACE) { const std::lock_guard lock(mutex_); - status_.is_safe = false; + status_.is_safe_static_objects = false; status_.planner_type = PlannerType::NONE; } } @@ -713,7 +713,7 @@ bool StartPlannerModule::isOverlappedWithLane( bool StartPlannerModule::hasFinishedPullOut() const { - if (!status_.back_finished || !status_.is_safe) { + if (!status_.back_finished || !status_.is_safe_static_objects) { return false; } @@ -800,7 +800,7 @@ bool StartPlannerModule::isStuck() } // not found safe path - if (!status_.is_safe) { + if (!status_.is_safe_static_objects) { return true; } @@ -1011,7 +1011,7 @@ bool StartPlannerModule::planFreespacePath() status_.pull_out_path = *freespace_path; status_.pull_out_start_pose = current_pose; status_.planner_type = freespace_planner_->getPlannerType(); - status_.is_safe = true; + status_.is_safe_static_objects = true; status_.back_finished = true; return true; } @@ -1063,8 +1063,8 @@ void StartPlannerModule::setDebugData() const const auto header = planner_data_->route_handler->getRouteHeader(); { visualization_msgs::msg::MarkerArray planner_type_marker_array{}; - const auto color = status_.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = status_.is_safe_static_objects ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); From df6bfb459837f848928dc832c0203b4aee82aef8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 22 Aug 2023 23:19:52 +0900 Subject: [PATCH 230/266] fix(lane_change): output lane change path even if the start point is in target lane (#4707) Signed-off-by: satoshi-ota --- .../src/scene_module/lane_change/normal.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index a8fdfce54b145..dad925c6b2335 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -974,7 +974,16 @@ bool NormalLaneChange::getLaneChangePaths( const lanelet::BasicPoint2d lc_start_point( prepare_segment.points.back().point.pose.position.x, prepare_segment.points.back().point.pose.position.y); - if (!boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d)) { + + const auto target_lane_polygon = lanelet::utils::getPolygonFromArcLength( + target_lanes, 0, std::numeric_limits::max()); + const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_polygon).basicPolygon(); + + const auto is_valid_start_point = + boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) || + boost::geometry::covered_by(lc_start_point, target_lane_poly_2d); + + if (!is_valid_start_point) { // lane changing points are not inside of the target preferred lanes or its neighbors continue; } From b56a7fbad2e717f4ace3d596cb4e5ae6e4566a05 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 23 Aug 2023 10:00:22 +0900 Subject: [PATCH 231/266] fix(intersection): modify ego polygon calculation (#4694) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 185 +++++++++--------- .../src/scene_intersection.hpp | 4 +- .../src/util.cpp | 79 +++++--- .../src/util.hpp | 9 +- .../src/util_type.hpp | 12 ++ 5 files changed, 165 insertions(+), 124 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 7f56afde2f4ea..d9ebafbe682a0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -719,9 +719,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } const auto & current_pose = planner_data_->current_odometry->pose; + const auto lanelets_on_path = + planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); if (!intersection_lanelets_) { - const auto lanelets_on_path = - planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); intersection_lanelets_ = util::getObjectiveLanelets( lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, planner_param_.common.attention_area_length, @@ -756,8 +756,20 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( [closest_idx, stuck_stop_line_idx, default_stop_line_idx, occlusion_peeking_stop_line_idx, pass_judge_line_idx] = intersection_stop_lines; - const auto ego_lane_with_next_lane = util::getEgoLaneWithNextLane( - *path, associative_ids_, planner_data_->vehicle_info_.vehicle_width_m); + const auto path_lanelets_opt = util::generatePathLanelets( + lanelets_on_path, *path, associative_ids_, closest_idx, + planner_data_->vehicle_info_.vehicle_width_m); + if (!path_lanelets_opt.has_value()) { + RCLCPP_DEBUG(logger_, "failed to generate PathLanelets"); + return IntersectionModule::Indecisive{}; + } + const auto path_lanelets = path_lanelets_opt.value(); + + const auto ego_lane_with_next_lane = + path_lanelets.next.has_value() + ? std::vector< + lanelet::ConstLanelet>{path_lanelets.ego_or_entry2exit, path_lanelets.next.value()} + : std::vector{path_lanelets.ego_or_entry2exit}; const bool stuck_detected = checkStuckVehicle(planner_data_, ego_lane_with_next_lane, *path, intersection_stop_lines); @@ -846,8 +858,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( collision_state_machine_.getDuration()); const auto target_objects = filterTargetObjects(attention_lanelets, adjacent_lanelets, intersection_area); + const bool has_collision = checkCollision( - *path, target_objects, ego_lane_with_next_lane, closest_idx, time_delay, tl_arrow_solid_on); + *path, target_objects, path_lanelets, closest_idx, time_delay, tl_arrow_solid_on); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, logger_.get_child("collision state_machine"), *clock_); @@ -1026,8 +1039,8 @@ autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterT bool IntersectionModule::checkCollision( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const autoware_auto_perception_msgs::msg::PredictedObjects & objects, - const lanelet::ConstLanelets & ego_lane_with_next_lane, const int closest_idx, - const double time_delay, const bool tl_arrow_solid_on) + const util::PathLanelets & path_lanelets, const int closest_idx, const double time_delay, + const bool tl_arrow_solid_on) { using lanelet::utils::getArcCoordinates; using lanelet::utils::getPolygonFromArcLength; @@ -1042,12 +1055,10 @@ bool IntersectionModule::checkCollision( auto target_objects = objects; util::cutPredictPathWithDuration(&target_objects, clock_, passing_time); + const auto & concat_lanelets = path_lanelets.all; const auto closest_arc_coords = getArcCoordinates( - ego_lane_with_next_lane, tier4_autoware_utils::getPose(path.points.at(closest_idx).point)); - const auto & ego_lane = ego_lane_with_next_lane.front(); - const double distance_until_intersection = - util::calcDistanceUntilIntersectionLanelet(ego_lane, path, closest_idx); - const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + concat_lanelets, tier4_autoware_utils::getPose(path.points.at(closest_idx).point)); + const auto & ego_lane = path_lanelets.ego_or_entry2exit; const auto ego_poly = ego_lane.polygon2d().basicPolygon(); // check collision between predicted_path and ego_area @@ -1059,7 +1070,6 @@ bool IntersectionModule::checkCollision( : planner_param_.collision_detection.normal.collision_end_margin_time; bool collision_detected = false; for (const auto & object : target_objects.objects) { - bool has_collision = false; for (const auto & predicted_path : object.kinematics.predicted_paths) { if ( predicted_path.confidence < @@ -1068,97 +1078,82 @@ bool IntersectionModule::checkCollision( continue; } - std::vector predicted_poses; - for (const auto & pose : predicted_path.path) { - predicted_poses.push_back(pose); - } - has_collision = bg::intersects(ego_poly, to_bg2d(predicted_poses)); - if (has_collision) { - const auto first_itr = std::adjacent_find( - predicted_path.path.cbegin(), predicted_path.path.cend(), - [&ego_poly](const auto & a, const auto & b) { - return bg::intersects(ego_poly, LineString2d{to_bg2d(a), to_bg2d(b)}); - }); - const auto last_itr = std::adjacent_find( - predicted_path.path.crbegin(), predicted_path.path.crend(), - [&ego_poly](const auto & a, const auto & b) { - return bg::intersects(ego_poly, LineString2d{to_bg2d(a), to_bg2d(b)}); - }); - const double ref_object_enter_time = - static_cast(first_itr - predicted_path.path.begin()) * - rclcpp::Duration(predicted_path.time_step).seconds(); - auto start_time_distance_itr = time_distance_array.begin(); - if (ref_object_enter_time - collision_start_margin_time > 0) { - start_time_distance_itr = std::lower_bound( - time_distance_array.begin(), time_distance_array.end(), - ref_object_enter_time - collision_start_margin_time, - [](const auto & a, const double b) { return a.first < b; }); - if (start_time_distance_itr == time_distance_array.end()) { - continue; - } - } - const double ref_object_exit_time = - static_cast(last_itr.base() - predicted_path.path.begin()) * - rclcpp::Duration(predicted_path.time_step).seconds(); - auto end_time_distance_itr = std::lower_bound( + // collision point + const auto first_itr = std::adjacent_find( + predicted_path.path.cbegin(), predicted_path.path.cend(), + [&ego_poly](const auto & a, const auto & b) { + return bg::intersects(ego_poly, LineString2d{to_bg2d(a), to_bg2d(b)}); + }); + if (first_itr == predicted_path.path.cend()) continue; + const auto last_itr = std::adjacent_find( + predicted_path.path.crbegin(), predicted_path.path.crend(), + [&ego_poly](const auto & a, const auto & b) { + return bg::intersects(ego_poly, LineString2d{to_bg2d(a), to_bg2d(b)}); + }); + if (last_itr == predicted_path.path.crend()) continue; + + // possible collision time interval + const double ref_object_enter_time = + static_cast(first_itr - predicted_path.path.begin()) * + rclcpp::Duration(predicted_path.time_step).seconds(); + auto start_time_distance_itr = time_distance_array.begin(); + if (ref_object_enter_time - collision_start_margin_time > 0) { + // start of possible ego position in the intersection + start_time_distance_itr = std::lower_bound( time_distance_array.begin(), time_distance_array.end(), - ref_object_exit_time + collision_end_margin_time, + ref_object_enter_time - collision_start_margin_time, [](const auto & a, const double b) { return a.first < b; }); - if (end_time_distance_itr == time_distance_array.end()) { - end_time_distance_itr = time_distance_array.end() - 1; - } - const double start_arc_length = std::max( - 0.0, closest_arc_coords.length + (*start_time_distance_itr).second - - distance_until_intersection); - const double end_arc_length = std::max( - 0.0, closest_arc_coords.length + (*end_time_distance_itr).second + base_link2front - - distance_until_intersection); - - long double lanes_length = 0.0; - std::vector ego_lane_with_next_lanes; - - const auto lanelets_on_path = planning_utils::getLaneletsOnPath( - path, planner_data_->route_handler_->getLaneletMapPtr(), - planner_data_->current_odometry->pose); - for (const auto & lane : lanelets_on_path) { - lanes_length += bg::length(lane.centerline()); - ego_lane_with_next_lanes.push_back(lane); - if (lanes_length > start_arc_length && lanes_length < end_arc_length) { - break; - } - } - const auto trimmed_ego_polygon = - getPolygonFromArcLength(ego_lane_with_next_lanes, start_arc_length, end_arc_length); - - if (trimmed_ego_polygon.empty()) { + if (start_time_distance_itr == time_distance_array.end()) { + // ego is already at the exit of intersection when npc is at collision point even if npc + // accelerates so ego's position interval is empty continue; } + } + const double ref_object_exit_time = + static_cast(last_itr.base() - predicted_path.path.begin()) * + rclcpp::Duration(predicted_path.time_step).seconds(); + auto end_time_distance_itr = std::lower_bound( + time_distance_array.begin(), time_distance_array.end(), + ref_object_exit_time + collision_end_margin_time, + [](const auto & a, const double b) { return a.first < b; }); + if (end_time_distance_itr == time_distance_array.end()) { + // ego is already passing the intersection, when npc is is at collision point + // so ego's position interval is up to the end of intersection lane + end_time_distance_itr = time_distance_array.end() - 1; + } + const double start_arc_length = std::max( + 0.0, closest_arc_coords.length + (*start_time_distance_itr).second - + planner_data_->vehicle_info_.rear_overhang_m); + const double end_arc_length = std::min( + closest_arc_coords.length + (*end_time_distance_itr).second + + planner_data_->vehicle_info_.max_longitudinal_offset_m, + lanelet::utils::getLaneletLength2d(concat_lanelets)); + + const auto trimmed_ego_polygon = + getPolygonFromArcLength(concat_lanelets, start_arc_length, end_arc_length); + + if (trimmed_ego_polygon.empty()) { + continue; + } - Polygon2d polygon{}; - for (const auto & p : trimmed_ego_polygon) { - polygon.outer().emplace_back(p.x(), p.y()); - } - - polygon.outer().emplace_back(polygon.outer().front()); - - bg::correct(polygon); - - debug_data_.candidate_collision_ego_lane_polygon = toGeomPoly(polygon); + Polygon2d polygon{}; + for (const auto & p : trimmed_ego_polygon) { + polygon.outer().emplace_back(p.x(), p.y()); + } + bg::correct(polygon); + debug_data_.candidate_collision_ego_lane_polygon = toGeomPoly(polygon); - for (auto itr = first_itr; itr != last_itr.base(); ++itr) { - const auto footprint_polygon = tier4_autoware_utils::toPolygon2d(*itr, object.shape); - debug_data_.candidate_collision_object_polygons.emplace_back( - toGeomPoly(footprint_polygon)); - if (bg::intersects(polygon, footprint_polygon)) { - collision_detected = true; - break; - } - } - if (collision_detected) { - debug_data_.conflicting_targets.objects.push_back(object); + for (auto itr = first_itr; itr != last_itr.base(); ++itr) { + const auto footprint_polygon = tier4_autoware_utils::toPolygon2d(*itr, object.shape); + if (bg::intersects(polygon, footprint_polygon)) { + collision_detected = true; break; } } + if (collision_detected) { + debug_data_.conflicting_targets.objects.push_back(object); + break; + } } } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index a427c4930b6d5..9d1fab1339d0e 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -258,8 +258,8 @@ class IntersectionModule : public SceneModuleInterface bool checkCollision( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const autoware_auto_perception_msgs::msg::PredictedObjects & target_objects, - const lanelet::ConstLanelets & ego_lane_with_next_lane, const int closest_idx, - const double time_delay, const bool tl_arrow_solid_on); + const util::PathLanelets & path_lanelets, const int closest_idx, const double time_delay, + const bool tl_arrow_solid_on); bool isOcclusionCleared( const nav_msgs::msg::OccupancyGrid & occ_grid, diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index f0343891c6051..7fdae3df2d9d2 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -872,29 +872,6 @@ geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( return obj_pose; } -lanelet::ConstLanelets getEgoLaneWithNextLane( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::set & associative_ids, const double width) -{ - // NOTE: findLaneIdsInterval returns (start, end) of associative_ids - const auto ego_lane_interval_opt = findLaneIdsInterval(path, associative_ids); - if (!ego_lane_interval_opt) { - return lanelet::ConstLanelets({}); - } - const auto [ego_start, ego_end] = ego_lane_interval_opt.value(); - if (ego_end < path.points.size() - 1) { - const int next_id = path.points.at(ego_end).lane_ids.at(0); - const auto next_lane_interval_opt = findLaneIdsInterval(path, {next_id}); - if (next_lane_interval_opt) { - const auto [next_start, next_end] = next_lane_interval_opt.value(); - return { - planning_utils::generatePathLanelet(path, ego_start, next_start + 1, width), - planning_utils::generatePathLanelet(path, next_start + 1, next_end, width)}; - } - } - return {planning_utils::generatePathLanelet(path, ego_start, ego_end, width)}; -} - static bool isTargetStuckVehicleType( const autoware_auto_perception_msgs::msg::PredictedObject & object) { @@ -1138,5 +1115,61 @@ void IntersectionLanelets::update( } } +static lanelet::ConstLanelets getPrevLanelets( + const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) +{ + lanelet::ConstLanelets prevs; + for (const auto & ll : lanelets_on_path) { + if (associative_ids.find(ll.id()) != associative_ids.end()) { + return prevs; + } + prevs.push_back(ll); + } + return prevs; +} + +std::optional generatePathLanelets( + const lanelet::ConstLanelets & lanelets_on_path, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const std::set & associative_ids, const size_t closest_idx, const double width) +{ + const auto assigned_lane_interval_opt = findLaneIdsInterval(path, associative_ids); + if (!assigned_lane_interval_opt) { + return std::nullopt; + } + + PathLanelets path_lanelets; + // prev + path_lanelets.prev = getPrevLanelets(lanelets_on_path, associative_ids); + path_lanelets.all = path_lanelets.prev; + + // entry2ego if exist + const auto [assigned_lane_start, assigned_lane_end] = assigned_lane_interval_opt.value(); + if (closest_idx > assigned_lane_start) { + path_lanelets.all.push_back( + planning_utils::generatePathLanelet(path, assigned_lane_start, closest_idx, width)); + } + + // ego_or_entry2exit + const auto ego_or_entry_start = std::max(closest_idx, assigned_lane_start); + path_lanelets.ego_or_entry2exit = + planning_utils::generatePathLanelet(path, ego_or_entry_start, assigned_lane_end, width); + path_lanelets.all.push_back(path_lanelets.ego_or_entry2exit); + + // next + if (assigned_lane_end < path.points.size() - 1) { + const int next_id = path.points.at(assigned_lane_end).lane_ids.at(0); + const auto next_lane_interval_opt = findLaneIdsInterval(path, {next_id}); + if (next_lane_interval_opt) { + const auto [next_start, next_end] = next_lane_interval_opt.value(); + path_lanelets.next = + planning_utils::generatePathLanelet(path, next_start + 1, next_end, width); + path_lanelets.all.push_back(path_lanelets.next.value()); + } + } + + return path_lanelets; +} + } // namespace util } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 081ade30f8f7d..e125f485a65e8 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -126,10 +126,6 @@ std::optional generateInterpolatedPath( geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( const autoware_auto_perception_msgs::msg::PredictedObjectKinematics & obj_state); -lanelet::ConstLanelets getEgoLaneWithNextLane( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::set & associative_ids, const double width); - bool checkStuckVehicleInIntersection( const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, const Polygon2d & stuck_vehicle_detect_area, const double stuck_vehicle_vel_thr, @@ -160,6 +156,11 @@ double calcDistanceUntilIntersectionLanelet( const lanelet::ConstLanelet & assigned_lanelet, const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx); +std::optional generatePathLanelets( + const lanelet::ConstLanelets & lanelets_on_path, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const std::set & associative_ids, const size_t closest_idx, const double width); + } // namespace util } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 55e6308d7e67b..4d2cf9695b2db 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -132,6 +132,18 @@ struct IntersectionStopLines size_t pass_judge_line; }; +struct PathLanelets +{ + lanelet::ConstLanelets prev; + // lanelet::Constlanelet entry2ego; this is included in `all` if exists + lanelet::ConstLanelet + ego_or_entry2exit; // this is `assigned lane` part of the path(not from + // ego) if ego is before the intersection, otherwise from ego to exit + std::optional next = + std::nullopt; // this is nullopt is the goal is inside intersection + lanelet::ConstLanelets all; +}; + } // namespace behavior_velocity_planner::util #endif // UTIL_TYPE_HPP_ From 421edc1a0888bd1dc28b977065ba423e81cc2495 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 23 Aug 2023 10:26:40 +0900 Subject: [PATCH 232/266] feat(multi_object_tracker): tune system noise to suppress yaw oscillation (#4679) * tune system noise to surpress yaw ossilation Signed-off-by: yoshiri * style(pre-commit): autofix --------- Signed-off-by: yoshiri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/tracker/model/bicycle_tracker.cpp | 2 +- .../src/tracker/model/big_vehicle_tracker.cpp | 4 ++-- .../src/tracker/model/normal_vehicle_tracker.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp index edd5e6d7a835f..2b0fff35729d0 100644 --- a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -55,7 +55,7 @@ BicycleTracker::BicycleTracker( float q_stddev_y = 0.6; // [m/s] float q_stddev_yaw = tier4_autoware_utils::deg2rad(10); // [rad/s] float q_stddev_vx = tier4_autoware_utils::kmph2mps(10); // [m/(s*s)] - float q_stddev_slip = tier4_autoware_utils::deg2rad(25); // [rad/(s*s)] + float q_stddev_slip = tier4_autoware_utils::deg2rad(15); // [rad/(s*s)] float r_stddev_x = 0.6; // [m] float r_stddev_y = 0.4; // [m] float r_stddev_yaw = tier4_autoware_utils::deg2rad(30); // [rad] diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 7cb2772f006c3..73916742f17bb 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -54,7 +54,7 @@ BigVehicleTracker::BigVehicleTracker( float q_stddev_y = 1.5; // [m/s] float q_stddev_yaw = tier4_autoware_utils::deg2rad(20); // [rad/s] float q_stddev_vx = tier4_autoware_utils::kmph2mps(10); // [m/(s*s)] - float q_stddev_slip = tier4_autoware_utils::deg2rad(20); // [rad/(s*s)] + float q_stddev_slip = tier4_autoware_utils::deg2rad(5); // [rad/(s*s)] float r_stddev_x = 1.5; // [m] float r_stddev_y = 0.5; // [m] float r_stddev_yaw = tier4_autoware_utils::deg2rad(30); // [rad] @@ -150,7 +150,7 @@ BigVehicleTracker::BigVehicleTracker( setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step // Set lf, lr - double point_ratio = 0.1; // under steered if smaller than 0.5 + double point_ratio = 0.2; // under steered if smaller than 0.5 lf_ = bounding_box_.length * point_ratio; lr_ = bounding_box_.length * (1.0 - point_ratio); } diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp index 12a84a7c7929c..27c2a7b821eb6 100644 --- a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -54,7 +54,7 @@ NormalVehicleTracker::NormalVehicleTracker( float q_stddev_y = 1.0; // object coordinate [m/s] float q_stddev_yaw = tier4_autoware_utils::deg2rad(20); // map coordinate[rad/s] float q_stddev_vx = tier4_autoware_utils::kmph2mps(10); // object coordinate [m/(s*s)] - float q_stddev_slip = tier4_autoware_utils::deg2rad(20); // object coordinate [rad/(s*s)] + float q_stddev_slip = tier4_autoware_utils::deg2rad(5); // object coordinate [rad/(s*s)] float r_stddev_x = 1.0; // object coordinate [m] float r_stddev_y = 0.3; // object coordinate [m] float r_stddev_yaw = tier4_autoware_utils::deg2rad(30); // map coordinate [rad] From 9407021069d20e7867506ff3d03e571d1b569197 Mon Sep 17 00:00:00 2001 From: Alireza Moayyedi <137421365+alireza-moayyedi@users.noreply.github.com> Date: Wed, 23 Aug 2023 03:44:55 +0200 Subject: [PATCH 233/266] fix(launch): add missing launch args and defaults to lidar_based_detection.launch.xml (#4596) * Update lidar_based_detection.launch.xml Some launch arguments were missing. These arguments and their defaults were added. Signed-off-by: Alireza Moayyedi * changed default of objects_filter_method changed default of the "objects_filter_method" to "lanelet_filter" as requested. Signed-off-by: Alireza Moayyedi --------- Signed-off-by: Alireza Moayyedi --- .../detection/lidar_based_detection.launch.xml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 86ede0d4be47d..5b6134dc45584 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -11,6 +11,13 @@ + + + + + + + From 5c21c05466c556a1c13956d6a7a4bf5dda133af6 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Aug 2023 12:16:28 +0900 Subject: [PATCH 234/266] feat(vehicle_cmd_gate): variable filter limits for different ego speed (#4599) * feat(vehicle_cmd_gate): variable filter limits for different vehicle speed Signed-off-by: Takamasa Horibe * add steer diff test Signed-off-by: Takamasa Horibe * add node test for vehicle_cmd_gate Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update readme Signed-off-by: Takamasa Horibe * add is_filter_activated msg Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update is_activate for each field Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * Update control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp * add function test for interpolation Signed-off-by: Takamasa Horibe * fix format Signed-off-by: Takamasa Horibe * remove unused file Signed-off-by: Takamasa Horibe * add missing depend Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- control/vehicle_cmd_gate/CMakeLists.txt | 20 +- control/vehicle_cmd_gate/README.md | 52 ++- .../config/vehicle_cmd_gate.param.yaml | 22 +- control/vehicle_cmd_gate/image/filter.png | Bin 0 -> 89295 bytes .../launch/vehicle_cmd_gate.launch.xml | 2 +- .../msg/IsFilterActivated.msg | 10 + control/vehicle_cmd_gate/package.xml | 6 + .../src/vehicle_cmd_filter.cpp | 170 +++++++- .../src/vehicle_cmd_filter.hpp | 46 +- .../vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 45 +- .../vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 3 + .../test_filter_in_vehicle_cmd_gate_node.cpp | 400 ++++++++++++++++++ .../test/src/test_vehicle_cmd_filter.cpp | 289 ++++++++++++- 13 files changed, 986 insertions(+), 79 deletions(-) create mode 100644 control/vehicle_cmd_gate/image/filter.png create mode 100644 control/vehicle_cmd_gate/msg/IsFilterActivated.msg create mode 100644 control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 81ccac1ea8b66..c5db663ccc77e 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -13,13 +13,31 @@ ament_auto_add_library(vehicle_cmd_gate_node SHARED rclcpp_components_register_node(vehicle_cmd_gate_node PLUGIN "vehicle_cmd_gate::VehicleCmdGate" - EXECUTABLE vehicle_cmd_gate + EXECUTABLE vehicle_cmd_gate_exe ) +rosidl_generate_interfaces( + ${PROJECT_NAME} + "msg/IsFilterActivated.msg" + DEPENDENCIES builtin_interfaces +) + +# to use same package defined message +if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) + rosidl_target_interfaces(vehicle_cmd_gate_node + ${PROJECT_NAME} "rosidl_typesupport_cpp") +else() + rosidl_get_typesupport_target( + cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(vehicle_cmd_gate_node "${cpp_typesupport_target}") +endif() + + if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_vehicle_cmd_gate test/src/test_main.cpp test/src/test_vehicle_cmd_filter.cpp + test/src/test_filter_in_vehicle_cmd_gate_node.cpp ) ament_target_dependencies(test_vehicle_cmd_gate rclcpp diff --git a/control/vehicle_cmd_gate/README.md b/control/vehicle_cmd_gate/README.md index a8ac8c46ae782..231c2c5022138 100644 --- a/control/vehicle_cmd_gate/README.md +++ b/control/vehicle_cmd_gate/README.md @@ -43,26 +43,38 @@ ## Parameters -| Parameter | Type | Description | -| ------------------------------------------- | ------ | --------------------------------------------------------------------------- | -| `update_period` | double | update period | -| `use_emergency_handling` | bool | true when emergency handler is used | -| `check_external_emergency_heartbeat` | bool | true when checking heartbeat for emergency stop | -| `system_emergency_heartbeat_timeout` | double | timeout for system emergency | -| `external_emergency_stop_heartbeat_timeout` | double | timeout for external emergency | -| `stop_hold_acceleration` | double | longitudinal acceleration cmd when vehicle should stop | -| `emergency_acceleration` | double | longitudinal acceleration cmd when vehicle stop with emergency | -| `moderate_stop_service_acceleration` | double | longitudinal acceleration cmd when vehicle stop with moderate stop service | -| `nominal.vel_lim` | double | limit of longitudinal velocity (activated in AUTONOMOUS operation mode) | -| `nominal.lon_acc_lim` | double | limit of longitudinal acceleration (activated in AUTONOMOUS operation mode) | -| `nominal.lon_jerk_lim` | double | limit of longitudinal jerk (activated in AUTONOMOUS operation mode) | -| `nominal.lat_acc_lim` | double | limit of lateral acceleration (activated in AUTONOMOUS operation mode) | -| `nominal.lat_jerk_lim` | double | limit of lateral jerk (activated in AUTONOMOUS operation mode) | -| `on_transition.vel_lim` | double | limit of longitudinal velocity (activated in TRANSITION operation mode) | -| `on_transition.lon_acc_lim` | double | limit of longitudinal acceleration (activated in TRANSITION operation mode) | -| `on_transition.lon_jerk_lim` | double | limit of longitudinal jerk (activated in TRANSITION operation mode) | -| `on_transition.lat_acc_lim` | double | limit of lateral acceleration (activated in TRANSITION operation mode) | -| `on_transition.lat_jerk_lim` | double | limit of lateral jerk (activated in TRANSITION operation mode) | +| Parameter | Type | Description | +| ------------------------------------------- | -------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `update_period` | double | update period | +| `use_emergency_handling` | bool | true when emergency handler is used | +| `check_external_emergency_heartbeat` | bool | true when checking heartbeat for emergency stop | +| `system_emergency_heartbeat_timeout` | double | timeout for system emergency | +| `external_emergency_stop_heartbeat_timeout` | double | timeout for external emergency | +| `stop_hold_acceleration` | double | longitudinal acceleration cmd when vehicle should stop | +| `emergency_acceleration` | double | longitudinal acceleration cmd when vehicle stop with emergency | +| `moderate_stop_service_acceleration` | double | longitudinal acceleration cmd when vehicle stop with moderate stop service | +| `nominal.vel_lim` | double | limit of longitudinal velocity (activated in AUTONOMOUS operation mode) | +| `nominal.reference_speed_point` | | velocity point used as a reference when calculate control command limit (activated in AUTONOMOUS operation mode). The size of this array must be equivalent to the size of the limit array. | +| `nominal.lon_acc_lim` | | array of limits of longitudinal acceleration (activated in AUTONOMOUS operation mode) | +| `nominal.lon_jerk_lim` | | array of limits of longitudinal jerk (activated in AUTONOMOUS operation mode) | +| `nominal.lat_acc_lim` | | array of limits of lateral acceleration (activated in AUTONOMOUS operation mode) | +| `nominal.lat_jerk_lim` | | array of limits of lateral jerk (activated in AUTONOMOUS operation mode) | +| `on_transition.vel_lim` | double | limit of longitudinal velocity (activated in TRANSITION operation mode) | +| `on_transition.reference_speed_point` | | velocity point used as a reference when calculate control command limit (activated in TRANSITION operation mode). The size of this array must be equivalent to the size of the limit array. | +| `on_transition.lon_acc_lim` | | array of limits of longitudinal acceleration (activated in TRANSITION operation mode) | +| `on_transition.lon_jerk_lim` | | array of limits of longitudinal jerk (activated in TRANSITION operation mode) | +| `on_transition.lat_acc_lim` | | array of limits of lateral acceleration (activated in TRANSITION operation mode) | +| `on_transition.lat_jerk_lim` | | array of limits of lateral jerk (activated in TRANSITION operation mode) | + +## Filter function + +This module incorporates a limitation filter to the control command right before its published. Primarily for safety, this filter restricts the output range of all control commands published through Autoware. + +The limitation values are calculated based on the 1D interpolation of the limitation array parameters. Here is an example for the longitudinal jerk limit. + +![filter-example](./image/filter.png) + +Notation: this filter is not designed to enhance ride comfort. Its main purpose is to detect and remove abnormal values in the control outputs during the final stages of Autoware. If this filter is frequently active, it implies the control module may need tuning. If you're aiming to smoothen the signal via a low-pass filter or similar techniques, that should be handled in the control module. When the filter is activated, the topic `~/is_filter_activated` is published. ## Assumptions / Known limits diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml index 731c73feeba4d..92844c61f6f4f 100644 --- a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -14,15 +14,17 @@ stop_check_duration: 1.0 nominal: vel_lim: 25.0 - lon_acc_lim: 5.0 - lon_jerk_lim: 5.0 - lat_acc_lim: 5.0 - lat_jerk_lim: 7.0 - actual_steer_diff_lim: 1.0 + reference_speed_points: [20.0, 30.0] + lon_acc_lim: [5.0, 4.0] + lon_jerk_lim: [5.0, 4.0] + lat_acc_lim: [5.0, 4.0] + lat_jerk_lim: [7.0, 6.0] + actual_steer_diff_lim: [1.0, 0.8] on_transition: vel_lim: 50.0 - lon_acc_lim: 1.0 - lon_jerk_lim: 0.5 - lat_acc_lim: 2.0 - lat_jerk_lim: 7.0 - actual_steer_diff_lim: 1.0 + reference_speed_points: [20.0, 30.0] + lon_acc_lim: [1.0, 0.9] + lon_jerk_lim: [0.5, 0.4] + lat_acc_lim: [2.0, 1.8] + lat_jerk_lim: [7.0, 6.0] + actual_steer_diff_lim: [1.0, 0.8] diff --git a/control/vehicle_cmd_gate/image/filter.png b/control/vehicle_cmd_gate/image/filter.png new file mode 100644 index 0000000000000000000000000000000000000000..ed1c7f772a932ae1d334f024c8a92f78883b3344 GIT binary patch literal 89295 zcmeFYcT`hfv@ROEQhyeDlP(}d>0LpPj+B6Or1#!iumC^lML@cA2we!B03y8;0!r^K z6e%GP+TB4t=iT?-8F#$<{<>qFjDXv)_S$pJ^{qMQ_pOzWuT)+V;!)y(Kp;YSxfkjn z&<%SK=z7QPo4_XqqQUIIKi6HQXm8Hx zYU*Nc?%-z(*W8K{@V}#2QG#n zEizE5#=R#&hab#Yn1rYHRNP)0sEsAXe39CU#Urd^^))0m%3z$bDIGOP7A!*(!}YCK}Yr5L=HuyZJ~ z{!E`enZ69%e5~SqmSp3bCChPD<(O7KGr9M1!Cl+~jq!n85xksK^V)qs*pPOzQGw7l zIrk?oOdmeXv8f~k)!cWAM}os6dr3FwrJ5fk`eDS(&XC?v6!+bs2}>jc$jJmPd){_Oi_5X_+P}5q z!N9DJr(OBm400Ge>)7)KUbT<9#H&7vMeu6i(^_fjnf)8jSOoUBuImwBPCn*-3*WLg zDq$Yi?pk+)PU&S*XmDssw6b|FU*+_FBDATb?W$Ut;BT7OlP2S0s9x$4rKggw$GgHk zys_o~*7lc?W#N=Y>7Jsc_3^-4RE@Y0W0T#_!}ACM+n5^tW!j95>cg$+sYcECba;Jl znO>=}RIC#JtU-(}q?GcIK*K5vlCsR+41b>ayz|BAVUr#|Y6QNjuBMZT7o{h2pPdi2 zeG>*FuJo6mm@T+bXsYMzi@4LtS+IP5|8RCDFSx<7&`&C6Dp9K->#Njqq7c}vTL}!w z*U9|uBpSx{Yf2q_!oJiv#8#6pMH0`eInSAh(8<|@+Hm@FeX*07S*h0p$B5A3r_*kj z#Py{q>mEkvKtI1?THWP0T+=+}N9tltoVqBZwoHQ)>|!6-BEF(}ms4Mrh88YE{k|+8 zgwD+7$bbu7=hAX>%c6#c<*&m|>qk8}5(}0;?2jFG^^NlDmLQ+VR|Hb-r02TiYdAOt zvF9c9if76#!)0uy0yd!^?Hxz6Q0z-?^Ul?KAK z2#i_K6?a45L16F}L$`?8%oKK=G-H$%mol19Yq#VTZe+!5DeG33gP&J|Z5Z+Kf_azVih>*c+g zUJ$v=fkjVJ4KpKXm-DdOL-P(Pye(8p69tuk?^6h)RUVMQ!c~K?94n3bD8z?@}yMH*basNOvIi91ps#)ahY2&!Q z$dz<5S%q!AVS`_Stfs@N!jE+s3Oa&ZVQcM+Hk^EB;c=tZJxZVPn(B0WXYAAwD`1=B zc|SsrsG3R>S&|8|ST^a>fg|H<5B#cS@wW|2j3F_>(xp$OH^SNOg|QuAZ8&|KBc1TNRgynN{95C2WxPAki$3MTqDgv54ugbIo*M}EQ+*FEY}K&Bl{2$|+(%|}a} zFcEs#CsmB1chvaq4Sj9!*R5xB=fq@SJ`@h+-JBL-eQd8&bmJtUN76BA!i4fDWi-5C ztB!eZCsEf(N9@;ULg%xjVYn;*mmIlA=+>ajM@gKxXO3_?5N z6lj&%&z~1*O=}>@NLd(ce9Y=}RR}yp^r{XL&RfQ!F(~u|c{n>o6bCI~5&C7=G6#Oa z{2>6(`^serYAILR%7R()GcbziB3oskggUw*u4S>|yQ>Es(hY03*bN*b>coba5A8*cL1I>BG2 zVU^F58sq}E9mZ)Bi>bvC+0kf^S(*15$}Bp!XFIoxW=+80D(CY4leZ=GiY8VEc-F-5 zD-y}9Tek{Zs*4q1gH`O*5$vbWYj*~#!Mc91?6MC2u&TMY331<4vdbUQ_;g-HLm^KX zI^*$SN4q4t$H2t(iypuK@I2`XXLE&aZ*{VIrs8?N0Mt2}nEvbX4}Ll@Dw`jQ?*lt} zS%T-u6fZ`pEmSVx{+LN7x$3mST-T-7uwbph@q+E%Rk9$4#Z)$|3-X|E1OZirw#IYnrNcasJ9L(q$33 ztuSU}eh|TNz(Q6-s81cxk>Qq8J^$GtW6Iqv+WxvW(^;wMNvv9YF~o5$dVJd@7qdH* zaDPm){OS6RByFWOQ`>v7ahPDP4Ig`)`woG#9Kh4|)+Uy|jqVGSLKTUGd|uWt)72}j zi`eKbymw&0D%g+cd2JpGIZO&UJzJ~Y_iTgSADEpnJA-vpn9l!VM$J;#N$#4VYOsSD zF~vToANKtYU}jr6nNgNL9A%>{;z81M4M(b^ED;A1heYt0H{Z1fC9BWlSc~Z#mATSm zq0ai|F1stOQI=n``Rlyuoj2>QtG=Gmk8{gOe{Y+`v7TJXP-k1NOf#KOoRU6aq@(Pz zxI4Zu+|&&g^j2RT0~`nE6n??qM&&`*X&_m8KY=-}+kW?> zu41g?YnhXc(gb`<4b58cQNrYR+@i74Un1#l|6ySy*9`_s3|d9U94I zzPtoNPJdn%d;?u4qpdk!qx@0m`8oT~0NU9Bn9amAW~de_8&*csXwtcv3#BpnxxP08 zE^ALDtmc%Cue3buPe>><{`FzI;ZDsd@mSIJa7fir40E!i_pdFg@qt81s9tY z&TAQa{a|WE>SsX)g2=+{4f@ERwd|b!E!;0NnJSedimqKtB%`(EzH9AiJG=H*9)(l=pn0p|8?<0|Smz{}PbXXBzX6%uql->pF+d z4RP+|1|QV3F-uLL)7c2079l<_#aMnOq*#n>SKM8+wDAaju;Cad(w(x=Dsp{X39Ou; zdvm?thAa~!wQh>4b2~E3-)19uI_lxUON}qSr$T8__vQfoT>0RPpfU4jci-W^-(t#5 z((?LV=*KdKd-!jumoJZXqJ=eI;jMVVbaU$uT%qF53PnJ=McQIgbI zTemr;vsQcjrptGdonKP8i*Q;tjehWZro$a=rtC-P@*&Rg@ASbWl!qC0M7Vh@7st)x zhsmgZH~087_JF5Lk6jf)<)4z+(lH!1{35va!$nsnwla|JVJ^jv5!*H1DU17 z0Yz7FcFKY-eD8!msFeK7tNH2qo+-6phf=sxf#>OAC;(Q!N%7 zHs7{?dv}4$Rk3iANM^!xq+z#eX8`pxwuTWf63Kg9~kSm&=2;} z6COk~)gm-!B}_T5?T&`V#QxDbu+wEsCDGuNw9}jwpCdS?oh$%j2=2aM!M2^LX{{yr zzN1Ie*@wJL@6N7+gh03Ta`QS*UAFew{rXF6B43Q2K7%FrSI7`6*Bn;CA_nFTbtkTKXY@hA_)jMFkoCT1o|4ZX zuTyzQ=(w_{=tRa;=B}42igiYA`DVWHB%7d6YHuKw`|#j)&Nj%hZ}hZ`nAerBTKTPb zw#L{qF7N!>6WZkGTX>N!PMfd4(rDpaN7MhsY+f0ib3=JhCZPuyh z&+;i;!cnSG*`d_rA`c0g>eX85BaedI>q zU&$`tnom{fH5DSbpUjROAw2tDLE6c#kl}>SwOfGOBqK>2`9rJmLkxMK<55;%k>u41NlV^4}eS z=4%nte%P`e%IefJi~N4R_#QKW_EN7jyMGtvKturFJ_mS<+2l}@Rr6XRH_{V1HC50d zc#Dogr$&=d`Y{zrP^2d63cBBf#^k2!COQ}DE%p!{QvdODR<=;v=x2@W4SD}4M((k~ zb982uj@k6R{w9y$srx;!x%GKV;S7opzbHYQ-FW{_&Z;~uex09#!e5%n+!@#_5jQy% zF9(!B4|qLX5gEm$h7^+j2o%v6+u_Q$@PMypBGNYJi8qojnnvx0y7{3EHBUK^UXF%L z5NL^mnL){EjbMSf>SKeKla-2mwucNbAsbE66M{+JaM#{6Jlg&(TV!n^H>JQNtHO^Nil@S+8U1*q(BX>Eshe z8(*x}adVyS@H%)ePw#2!PlSjo?Qy9xtXmEcJzAc^s5263ZjBzK+4QGYDrMTDzz}Kn zB~?2O+sQ|H)r)?**tJtQ=?#l#y>JO_#j#Ysl4`#)UAQCPA#9vnyYPnVSGR1QYz6m0 zB>KkwM@`7&RvnpcJ&TaK{WB9Aol1pP75O_FF>1{^G&oPS*Z|Sx_R~Dc9I#|@jAv@j z>t}?ssq{4s`n*sJn-wySC67egZN~mkCMM;BqVsl=y+rdu@^LACF)(8pJ=Ohp z5brzXA~K!q?VEiyGRWr0(7itX+geCNC77Mdy>~r5^9FIL zmermK|9QCa6utu^r!KsFN4KOP6;L29 zIkpa_bQ_*<&te;Vbu6aB{Sozd$bE?34F$vt_Psjos+NI-}pU zulH-=aP^WDtpblo?b36Dq&z@?J8#fhgSFZSm1x}|;`D1&gK4KnV@XN7X@~zx zoiKzlQ}50EiXL;Y8U5Cq>hj=F68U3@lk975Us-%vDRM!$u=*bhrOd4>H!v?AP_4%7 zq{rJ#YjQ)9mTC)C(1N}v8(Rcy<#pgzwG{CBD`Z<4+piuxMq>E$|WHGmW`}^H<>65>O`R zAZ0+SB?JGy6ZK@H<~Jv$bgAdi6mECd{~{cEFVAG_Nm39|T~8$OTN9hcnG!w0&$094 zJwvj{S{2X5Jcfq%c(#44uU9Js@MUCUg5q)gf&vkM;+dKs{!}9~F$MXRzaW9t7UqWN_H=)W zDIUvepdwL_V|OdWk~V*xt$Xm33{hQeUl;%n);CWDUv@CST=fz(pqF=5wJ(0Bm9+g{ zEFR6?z+tc8G-HTT`(YLIcv&Dwgt1j4#;vI2Ry4d( z3?I)SP6ZqD7BDegW(V^dxSLz*-Vc#>-AJQ{H31^evsamNN_hknL^X{XMN27*aW#D# zSD!E(@>#EI^oP1B1h-}P2;+mrC#8)qOOh7h;33jW8$ckt4^%Oit_9o_0VK2EAOH8| z{}Fy5*Hl%FLNfohb%{wz5A@z=K8UQC>-UU4WCa4MPJyQpEB5GWfkIFQMDy51eTmK}A|;P4wh_oEoOaF@SbeFXlVGjECT@bGv#`5W!VpPU$< zf5fd5kAPcNy%c^;Yay%$Wa^JL7}R@%>(wUUyGWW z49+ri65`|8xVZ-xLIY!l5s2*fw}=&D_xAVs15UldIC|`9XlR})Ys6~m>Ow0_J9PmM ziJ~?()IB|Gm znmUd|#!Jx2e7d#!_bkB6Na~7uYLEa~R3~DG;*9PH1acwEV z0_oTh$kmot3JMA%JJVINAP^7*fDSAN;lI8C8#Y3#X&W8BEp_aYk{PH;+0d}CJBA>$ z;(`J>85tR^#4DikkBw#*X|F*`spCcvgK>S=e(RFOU9T$7otekr>%S+~2k3HB$!9cJ zioR*DheM|TcftaA-2(=J7&z!KnTjU3{NNz~nzz)*(b1f1w}?`Q>v2%M_woB}z;Bl? zU{ew$98J$4|?0)b_{h8e_bif`9 zHQzmPYa^d^X8)u45XM)8zx#}Q38bAbG4(Ozf=q37P++QW5m67ly>{z6nF=s9>+AAH zlMpN-qnL|z)!of4XRtGd@ntdBt-yYFclX>`-ui}y60Tby<0n#j4?7!Awi~d>vH*UD zNrtNSI(Ev4JV@ZayrZKdc0$7Ms2sVx)L2?tdTvUG!eQ3{gUSVv0{lu-W`k z0j#r@f%^LT(dlVUd3H87HD~9Fb^r;*FMzF2U@y+f?HN!JaQpcBl0?Wd%aiFlUCAtI z2X1gX`t?SBP`JPG7XAWQ|ON-JJZEyKgZ<9qY% z!-47RqN*y*;5TyWSXB_Y0w4!tn^JUuQ!+qMem3Czzw{?iVElPe0Tk^2=OtSe?x>Ee zp0961YKRb9&f3XI1k5#hy(47=eSV(PK&S^u08U*Zi76>0c-oSS=l zKDxOy&BWciMF+LD1?HoSXEJbVz44)%6o`Q%^KBu_@}`}UK$zkw_7Y1EAm)Db2v`Dv z)Gw{Vrebc}pgpy$$A{-{k`$Vpn{cK&q;_~P+UOw)z-0~^kM6~F)GZYr6k-!>z{+9~ zTcEDw{^sLXo&t?|v;Lz`=4LPc;YTkjH(dUtkOAV3u5Tq{rM+x2%*+s$;242EYkH;50P9mLY%fXyOLn@i@asJ! zCxB*UNyRRqePFiZTwxqn2L_@9x5m;4%gn{jTdA5~IEA@tIXadR(TFe=IwojYTNk#I zELU%DJNTdOcE;uat1p6rx8u^QVzjC?nrvKL79J9yB_WFm2G8#%p$a44kD(WDO4vhc zv1uB-1a>6qi-IRt^~N_tMt?2c>u>I(Z+~ZVK64K#Hc`AhTM*;fD~nX3Ov(q%9UKgn zZ>_>>U%0}(3fWm9>hW;~cyycU#;Pv{&!2wz)ygG5Vk+saIPN#EQNMzpQ4O`53twJc z?Ok`%HMpq`#PVYw-oS8R1s4_+bZtBZfdrld({VS9Jt10CKpOrNPA@&Fl$1hQwTb-9 zS13zZgyL&{3~QN>znBNx5cCgCS*E}?3kATEI?R;JpzNKamTH%;inB#$J%P*HVTw!V zBdeOiKXVgjC$cRA>cpE2_a$e)3XvEI*Es?+FXm*#5le*J= zf=)JlYo9EAKDpX^GUak(yhI(f2;NI;E30un3b( zHCy>=vFGi%$5VUp^oIGJ&PMuKw;bz5&M*MNcv6@z*E~;-tJgN2laEOSJgM46$lNV> z^w1?t7xTibC)!j!*U!~&&thUg;I6t;6dQ@p(k{X9(HB5*eIYL@jTg+MOc9fRWsX2o zWneQnurw?RCVe#hGUSsIOMGIY;HHSUxcEkMzUA}hR~9J-y*hZ)cf&2k7AZ22yC9cq znVc@NRh2s`#S`jfN$CPNCREAi3P!(mQX#$cmJ3e?lkduiGLzIVQ?svex^->w<-AZD z_Rz>G;xwkfv@=sgxdOuhU~qQ+EWf%5^U`3~vh5bU`QmKH{a{T^KDKjl_y(DN%YQx< zFu>AYEO6?X@Aakd*N@pXV(Ua7?I*YE4j&`~#9IS}jfXZAsz<(lR4LfZXwhge<@`xZs%iQGOa=BN{UvO_Yxkj7E2NW)vj!Q6T zG~{?a&{zPl2w0x=`SXdaFj?|}`f7~(bQ{WT=i-863wzdjw}k2v7d{gVf=pL!UcWBt z@MN0B=xIW>9%gPHlEO9 zoaz!I1m&+LbNlHM&m85trF=LK^bkt)Wm!WkDvma~&$88A^c6J^?_Z!xw^MnQJ^PZN zs!^-$M7AUk9$0<*aA&=<92dXCM{l)u6iWPaGkX6&t70AmX5Oj4nM^qd?wcDe0U^+qkRfv-pt;9S2D+$_Vf+ElpmK zSUzlsVmeqFtX`jREJNhRTc7$JY z25n8vPXWaFw*)|eR5A3Pn~v&e7*e;X^V2-^)5XnZi`uXUgpL}$^%gf6^1|8pbi zg*jW*wCauMa)SSj!V{+{#IR#QIt6u+u9EYw+Q5{wKOfiI&)C`cm{)_IB+jPT>h$ey z$1P$0%4VLYL6=<5g$Rgwz2~Hy5VJx`LpzOv{aT2p*K$LhmV4AF6i8s~Z9&zs54_!z zZ0HKK5r?m_vjp0?E3-yr%b4ROk38Rs10^`-;n$?nINU-d7g;5onNR`|w1p*J@wajKEOF>a4QG<&fwx;tQt z22lgT2)FhnRkI2py8^<^aUejnK_9B0t<3x!FU7h~RvkuQo>FEcvQ7(ICU5VlYSf{! z9&2A#{zBRSee}D7u9CLC zMyh=F$jDc|vWu+#Uo}1Zlkz6Y4AYl;E|=NrJ)kDN_RjGh1f4Q^G6VUcKGA0HpLUvtmp)dK?H9Z__S&N6i++1b*0 z)(Wu-ii-Rmk9kp72uc86Ha$HZn-d#*kA#d&58%Kp3dg|VN>Gbcm~8fXhFwA3Hoi~( zyv5o6w<1jweW#w?w@tU)Izz|#c81YD){2if_~``?4iEFnw%S67^$b)7fcjA(BZ~25 zQx&{%k$J$oo#PCetvW)a$k(7Y5x98gz0w@Ub zLdtOyE1ke`$sd1^0MwfRm)qW1@g+NabQ+c+i}3RO(Ar2Rk;9r?z0sNCVc9sq2{FiQ zI87{C;3c!Hc$%sT&;<9jA$ocB=g;2)L**=eRO9aHiCT=3Oke^AY1{Yt$tB@f*!A)W zws&@Z!U+aF?EEtyU8OYvRKt6~L_cX0xGiIf=bjHqwplggN{pNFz|BWAK29eA_(*u9 zk;6$E4z-TkM3#Ir{>~q_k5UTjF<6BNww#7by(M+8e9z$E_|fj- zW(9M$mj)5%D3nrG__Irn;faX{y| zws9*Ui_URE9FOFi4UlHnZBKs9w`nED?F0OBWOcDChEXf=TFVN67OZ&o#Wgz6vuy@| z^3752_y06{HCJf!pG#vBLpua8jrF37*+KM3!q6klOQl?h3ZRQTpsl;n_*uhN^~~R7 z$PC;Ds$P=!(V0$TYcg&fj0SH}l}7Vsam)Yvj5BM;R>V@Nn!d@N(WWl zEdIo`bzlfQpiE9D2jBha@^iH175lz&!gtQk-)?z7_-1rIN#?8z>Hv3l*V5s5g+ZvgQLFou^>(tM#E zh{T%Hhw*5-Zj_q_5OyN3ZMjB#_UrP zlvoxC_tt-4{-U|gB-UnC1pz~Fb-TFZ3=RzV+b<+jl6Fi3b)T9cO5z0<$nh06km#6E>!;ohRsTp zo6nzJVD|%o(k*)UC=6Hvr9c{)C5&gM@O_?8)V991zCPUg{uZuyo+6=T;+32XS`Eive!ClK;LAo&qOa2y)DD7aB53NId15^_Iz?@vcFCVAG0!iG6E zeE|-p0&4>&F+X$o0tmuatfB(-|A~-AaNgyrU&~5$jNhOc`>IDBJUTg9BppH|9}DO&fZl3@OGdyz=^#@WEI_cwK0h%9>h!?0_Ql-; zf=OWLx=_%wNXFk74O~2%H%_E9oXCXe(RF#HH8*Xz)_cylogJ?l{F$2pqdzmw^Vy*J zA`V{jCM13G0Ra8xjAf)hL{vIXa=FXI90v}kb3m}cK|gT5>gL54h+eY+Rn3Q|l#++< zuHte!=`4>lnUR&*Z|n<6{)vdsSOgsItT&*p+29BBQeMcvtiUalniZp%-)VYo3Xmmn z2nFSvBFj8b-5K_XhLdcHh>Oz~`P+v^rO7CG^xvky{?_lNK#fueaXg3NR>`%H1;BB+ zlCJAB-Uu`h3;rxWAIf znm@j9s-7Y4tXjyW`GbCl;l5@4jxDd-Ps>gqQR18-B>1QAx-U4%y!rf(Na-xInqT63 zUO+zoN$t{|Em6v%napee+5DtTzq2J$MbMjg$JXH%;+A$MiMm zLokUMgD&Q)aDcbch`7ncY62V^?OOeG7od8FA<}NBccjnc`FmQ|{ zZ(N&Mu#(Dsf?H48=*fo^gxKT?O!O3AaXflu4jY74`A_5)O|u)Eu$RIx4xY9d)45xf z6B7&2>cI`DZn+f4(~4dwXGP#Ygzw1ZZr}fh>6=iT+2{9nc)ibWhex{HeiQ2(dvaF4 zR4=vSd9n9=;k(~n$_}Bi*O#gr(eFk`pRsryBClcBT}5HAU8{_-sK;FhaY0pte~k*= zoEdH!d44?twwrLx+-MFU4bFU_@%00Kn ze~55PQ?iQiObj^f9CvSIoXEE=P1nzJoKer!E2WieS;w`0c=osB!btZQu#N^rNo*TR zghKUTJ$X0d1`E0>x2q(?)Upb6YO9SgQzNuLLS)4wndVl{4DBO%6mzv*mk`u5%-mDdpYvj;Dmg9VOTPNL4 zU~yQt{`z{B{(1~siH~39jC~Y=lhh*9y^l+)9+sB*!_G?F)I_Wo5;Kqs|LjFjmlKd% zj#Hhnw*b9oKMN;kOOGH)%&`~SXW{8O{&A#!3nLN+m3baDQ21^Rt$vNcv_EwP&OxB} z5xciR>O8bpEdC+58OL}Ri0|Z4JW9nSwj+ZA@XX+Ao!F`XeQP+}yO-~57GLs7OZQDx zhL~4?{?F8HQQ5uhLXp}v#Srr^P;4>D13Xw*SokLE)#z@ZP}=)Y(l&3Lg9rLd{oApi z;QE)go+wr-Dz{&+3sg~(YTIK?HCoo|jiFamF1M)srGc5f0kod~!Z?*{G`c-|`08I_rbP^lUcVCl4e-wt ze|*))vUe^ouG^p|>FWUAw-y)Ox!>fs+d7xAuNjb$oALILXd z{(h3)qX+7bN#mI6^tqN-Rwz?%KV!iUX$yVf1Myk|6b~mM0+s6^o>=4>&PUb8JfBZ* zqzcq~eSlXkP}(1lo9iAY75dk&9FOaw*CB>wW#^kR{AlOz-<~Nj-RmCQ8W>Q?Ui@q* zM6Gh}-*|C;BHMW-dLD-n;l%?Sw_K622F^&dq@AN6++(qI_fOpV;~+na z)@S|HFV4oxx@IY8<~{%>fPzIk7(sHaUe`ZA=OI^$eDUbfBV)0v1J($l3|jwy8bhDO zEs2sr&!x5IY4u#kX#wf6=jT&^EgQh@3)4?Kfja%t=VwQ9Bp+XlB9YAUE<)5j-Q7=w z?glE6M##po+R+f*Vg!R)mi`2gKwjSkZeLskA-oldu|CV)zFY6OOW?oU!EsXv$GrmQ zgMme_%EA3L0jD!z`_eeZT){`rvQVGt6pQ2mllZBz$Zl zAN^CHXuAof0NDD8QP9@7?Gofq|GFRybJEOjtGwl4Kj~Ygic-YibGukruV2lx{tfb$ zSI>UK5tK8?eQ}USTQXhJ6mrd9*XT)}ToI}2c-pvu#BY?FJ^j7P-rNjmHp*{4t($hx zc})8L{u?2DnFb$6t!nE;AYcOy;ZKYjfwm*iKPi^U4k{LQYp=eYdH2Hx2F=M?l3HYl zkjjiUsrbwU#3438!ST5lpr<;xU^{Z+{%zf@XWofC^)|?usc0A&3AtUXG0!nRxz(|^ zFfM*$Q5SUvvyJA-U+q>e=v%9sUb>$U3s@gt?B37#N8#^T02^Noy$ne$h8Vd32Tuj z!!@sf;XI<7S8^=$W{GzJ8 z216Lh*jfcmO4V1tmh;=zK&S@2NBz_$wo=~WvJcpo18Rn@-eCX+Fq`i1r4yXZ_ko~L zFa8q9Bah7e(W6gvo9q&x`H}Lr4yn`cQ62>jgLjcz@@Jw=c4lxbeeFVIuLZ>?TqKqT zvP)ml8S^yn>P>MMlaJfQ2OHgFZqIY=HUH|YaicbKcyTk%Ceag}i0(Rn%6YtvaZ5Ql z)%F`rh(IlivVpk_j$^)Q#o~eYk<8G(SU;-tp@cZgi7TK$Vn65Sx#xQqQ>C|>y-GUb z)0?ti1-&^QZSzr*yxos43q^$5p6#Ao3tz8AI ztV9#jXhRtlP0_Joi|7!{zg3)Ntsu!QE{=F)pXruzWCNdSu z%bg^k4GtnMs@QVp-%KRcUn3jhlScp(=!a~@1Ni`ibl0+1pOI4)F>nqih9DHW)^Q%zXjqjhaR#W=3 zx%Dk*x=1i$5HRhCTtV-1)NB!W)=OUkb5DFXE}mUu^BYEJU1Rb5^QYyQPS=FiTRODf z9SS~(eA$egH~JGDi_U53RVI}`2YfYH$12m&#g=Dv<57>@)*w^P5fYM+uL1MZxxjaE z`dznO$0HDK83J`CqgA&NfsVoPz9&Y+L!_%)tefZa+BW3!%7w37OH zqLBT6x2Y!w?M>|Q(xX4|E64;{>coKy)MPx?%^KdFf95mGn=q^exb~%xu(a#-DJ`wv z=hAr9w#$NeS6iZR5aRN6%*%6qT{~H_y0gG!RR@0(v5nmX+gMp^w4Dpck4Q>jzi!v9 zv!f5>KBm(Gzkz*E8()lpyJv=Gln?M_Yeh5Igo^k~Hto7J%C}6|=h1&@l6g*U0R2;u6&+fqw`d(eC&gy?K-Qn6&qn@I7(5hU%tl z>0K`=;3oYWr5Yz0x+j^`;`!$UX=(KBs{Tr=w^u{P@>hh;oK;e9XXwsmi-kyQg@Hf5 zQ0ilBiGb=n zzB+$r44Uu9u7?e$g=cS`lBFs?1`sU_JFGm{{=|Axm@eSq;*|)T8F}mOE|XMR`UruJ z!$(i{->S+zZdx*3<+!8Tfa)kZh{{)(Oq}u3<8InL3^e1fgnl%qOEL0g$zPpH=Ncxa z*)e;8lTCmM^PAX2`sf)(oNe}pD7r5yVU2-ZkBy^DmBg-(N$_FiPdlKph#k#O+$+a{ zOdNGmb6#I)USFN{LK{f2aXTnQc`tg@5QHv`)sG8&U*eJd#rC}9df2#8DMg})+j4Hx zvOS9*yyExWysqLP*Ybl@+SIEAw)Q?QI`LX|U5FlZ8LA>hQVj7h5A8|1UY(yKI{p&< zeL=#GOs|Y2+W`?*A&fO_BNcb*@PZ zNA(<=%$*n>o}C6jTpT`6ZmmEfpDZbzh0HQp7D$|N*I?=%r+V%{2+STMM91ysqxKve zhu^CE=x3Lym1t^GRNx(?q%ezPy`8J9=<3+Tq2320rH)Ekj7;effOHr`6;6*)QE!Qo_^3 z*k|W81UVYqtR7Sc>Rf-{`e}re=Y96u^5MI|O~DBQ^8Ot5p4HUiizhXLO+{PEI~$^^ z4v74`2#x+e7tYl6VW2d#R>FIDUnX1a#{1{;O|0B(_E%b_9@)RaYt_n_P*tc%Q?)^A zXNaNdOPXt6>M@f9SjTA@8o3@4RJvdo;ljtOh&BN6BM1o3<1AvJ?=5UiZjA zf#-$kBC@xlw&IzP4zsiQh_rm8(5SZv(%Wcnd!uuS^Tz#X+>h2p=WLaeMV*aGS_`Ms zilLGc03(7c0C!+u7kSfAvlz3AgMqL`%ZMstlr~p{_dvO z@c^r`N&^o6CDSxi1@F?)uf=Y3)0=^#AKtEhzjj)EHX;xZQdFTIrr2A)b0WJNGPv3x zJXMwsS$wA=(OJJZQ4W)#s;;&&%arEl?STPKQG)9@ZaHZm8iY)^G+GuZ<#?npjJsS04}5I*B405Rk{U4iU1ePH(t`3{IKr`R#9%Mq%v{Ii-j*1G~2io_wC|1 zWNBxRfAUa!usPG{%-T{{V*C4W5LDRxs^`q7Ve6l`uNEi09U&D`wQfMecau*{GdA(* z5NbOL{zs%1TU5=(b-lFOi``OSu0~~kL{CojO>aRj z)ekO^2K+iWG;>A)$#>^4q0&(Lji{5B{r^ z6um&@XuGxIud6qn5L+7jT(TLt@H~O7Zvu=p5sOiZekk3UXOEt3h|&v4_771g+zMVw7bX0 z`lv1$%6ZdJ5#7q>XZ%~8n+;rRS$hLyftJqk|Cmo_hm_Pp3nmwb3OQf zm!tv@{>2e^A0q)rm@Zgd9pL<~_(4*@S?gG)#NOPgsi`X$pCMCYS+huf>qVfpZwhH= zK=vJ2&4;^8i%n+V(>A2Me^n^ONvK$ki9sGXpbZdUK(_&rTmL&VOA7=#{G0FDayfbQ zneN@eMNxGR4}sj0)^GFWBBG+q@^y7}@6{&)wv+E*r}*!?F^rYWUXkRX zW+HYqFbd%QeZbj4mX{0<9y|c#tTx%-B2~_ehAvlP@7#+O(*GONk2x623e#?wH?oL=HMFl ztzsLvG2i8rjfIyR!Y+y>f=kI%3K$Shhr_9#z?HW{h^npN4kEaOlMFT(f#61bOIof+ zC*N^#y~c~%?aKa-rg)w8us610IJ0^ih%ml%`Qj&|gneSVVwUgz2YYWF7UkNui;ud% zKwue&qy-|aC?TmJF?4rH*MJBN9qIxE1Y{`b?vj|HLy;Dcjv=LE7^Go{-#r+w@As~~ zzxaK7AN!B*IS$sEwHRie=f1Bz&+EGGBCGxf>3;xqJN%K5Lm&uzq%RN| z*C3GjoH;$qKJW#|{QQOFt=--d+w3Tfe62a@-sY3m`T&ai2@ycbFq%+k#tG=&apR+EF;>$&ArZ_q&S#@16glg(ef*IETHq1W-)fU;uEMx3u4!v|l`W zgfRMh1<-zVi8#m+eQWr=F|a9|=Hly>2V`VsE2>L<97auH`qh;3qWE-rnBQ z4ew5chM}%28i~q> z;>OLf+k%(G$+Lm%TSw1yjkI=|OP?_!sU1(){}6-5sDcXV4}PF%xRv7=$@7{t@17TS zcU@q?|MX#n(j6Rd_+2{em?yv#AH~5BribG8T8jBN-9JjO#)361h)QggVnl-VU;P9H zm?bc`$GLqE66E%=B@ORGBaX0Q2%>bD-tKsw0yGwdB< znt^Fo!G}>%d{AT2sxWF1Es)p;DckZ;r&DB|gz((|B}w|uwS4(=C>-8|R&C}Tj4_~1 z`aVX{_I+jJI8L2Kv0Xa& zO2?gnwOz8-DMAzQevu#S1W>w*o~Fv3m{oJk?Cn0x!)~nmx!7{NF2tBPZ#q9g>aI0rcX$;7{57XV~n-!iC@_ zvNM0sK~-~9=;=qSS|olaA!00ndobsDrtLXcp$D{iVbzrZsD7_4J^qI1?HCqYpF0B8 z&-xo>@ZmZEk!HAhK0ORo_Y6qX<@1E}cqIr!5dwU8ad|n64&cR#!z4x7-_o)v^|GucdVy2-&4kpNj%HMM_g)7rdxgc^$AImVo(;@ zGWRT|T?_;axAEu?(0g^qyLa~E@E zl;?nh6{y$RZs^SC88nz6`d0UiIOOfiZ)fhl0w6WDpS-+$ozoxZsr;S@gMK04{>=fx zjmNv`E-HYkd%Bj%XLt~6;>phYM|W=9xaa(Cd$sW5)7CeIbn5u@;PzibpnYgsg3P!6 z!-5;+?!%wD;5D=}hUrbG5zHH{lEcHpt_fWYxA5`*mCmTdpFu*M)h}5x+4AWuFx7)~ z0mr{PhMC_M1g130M6BF8fg1|qg=5)!cj5;T0D)BF<67W7@X=V%Dh}8&cmusAPfyBB z9~q@ubOJuG&@cPtaIUK)XNUvbumtZ(`Z#rZb%C>#3GsbJ%3?N_kiLr>}%On}j3xkO0QSM^8s_TfkS^+9!cvz;dDLoJ!yv zUTNNu{d!RHxo{A%EpMIDR2yLNG%Xp&NhjP@3@~vnar5wQ6|Vq(83Hll{SPStJs|@} zsr;Q(b(Y)E=jGb1?d_aA7YMaLMG`Pq$9^ZzQjx#w$fi2K@_DYHWBVVh1^I8=LP8tE znlDd2QxB1Nf|&jX^KtPl_uz1vbPTYKph18b z&$1{+;PGnwo-#k1T?~?w?WakI%@t`9$;Rt}r)4)VpCBl5rkzNU#Q2k&WW z;Rr!a*a(Ck6f}xWqyjoKw#1tPB+=6g!=MaFcGzH0;vXD{ES!?%qF*MczCuht;|U9` zmm2`#U5oZws!c zzv=(_@DdVi_PMy&kv|~%nLlH25PR_zNAjHDN#U4H4r>UwF za;yW_f0^I6Q6#mF!ecaou)*PEkOu5k%e}a-2Gkj8KSt-CzF73&HVCB_gnxREN3*U= z@{eK`-8E~CYvHAPxav-TBWONoOPN_`u?XXjQ z2`J@a*~QW4?N07B6~Z8ZPsfKwW%9pN=e$m5ZGZMK;KwT4Wk8$ zlV?00{{)Hbzl_AyJ>f1kysAxYodQYrO!8KR?VhnFZ-H=I4zp2VD&uv4AT#`{D(sM4 zu7AQ$t9Jd*w{#kLs^MW_R{=x&gC}7W64Hb7Wsp66a|;{ywzNj2vt~Fs(vb$_DYC9` z>^^$&+$c{R)w?vUf2FL$jPax^p%$Rq7-26a0V8tf>Ul{-QE@RNj2K`*eM3WxP@raM zCEiaP!`^&Rv#t`>EB|(mvxWx$O?ck}j3aOclj^0wEP)(1RE#|Mi%hXA(MS$MB(eN+ zJHLN*1d!Vb&gO+o?5zC<0U4I)8m_*6T#1KNfEyOB{Y4P_hwS`#!g!vir$_1SVAk%h zz*p|>w?sdP#v87;B>x*M{92|`#5-oZk=LVoSt-GWuzC{WgL@ChKgV6!NY zlcCBm?yKg$Tdc8rf)N5C#}`K6*+P&!c6U8e9|LkRl5=|FV}}Tk?08s@OmUOt?*2K} zScUi+FW~tNe+kk=$`%btD^4>fezZTCrX36N#t?53caV!|a@inewFQ~*k;>6a!Shw^JHt1VjN+4wy0+moZ(_Nv26krvJl-VvPz@~HOc#xU>@ zH2-)AgDNy_7x)Sw;n`creh+LYtax!Yr^yoh2_U#r*@1YAKz@CNL}dD{$IeSyn|T<5FkVnU$T*Z7DBNGEuT6agV?)htB78(v% z;?J%AvF6e|I{=kkJ8ffKs@2d?pYfIuqFu(4a$Hmd`8?y3)3|{D!Rfur0mkImwXm`R z`&pIfKDJ6TKvgs4GQq92(ZbwlftR0xe0ggW44*0AW+FJ4|=Iw)66U}zj+z>}Mci;D<4P^dC9Jq_s7W~-**TWdAIbnU6ah9{S{1+N6) z16VWXO`}nM*ZHci*Ficjp3MXP;J9!A@U6eBq<#sIw>GVDCah(ii*aX&2Ucm~b05r( z0WTT(aU8tIqN@H&EUt%Ep^ntC3uu>we;8rB$(vI%Tja6sJp*aB`p27lhYU|*lJPL>Kg zKOD)Sg1n{p_3k?Puh=(R9krvAJ$B@_r|v^5W){C`3VId^I&SVfNIL~d^!)9;4vBdp z;A6oGDUFJb)O|MZ?C-W@Fb7+pB1aR7x9uCmzohvp2_*@2q@%Cgm`lRg>gExlNlJh? zxao7OF(3epsKf_=Ud6w114w_;YOe5P2Ny?~>mniaiUtTJinC zy(u1Wb2CVxp`o`GKx8q$vJ%lb;CdY#{)EBJ4Z*t#29)1=eWX2RUkgN8Ggn6Ee6wakwitV3P47uZ%vROYAf40e{xUh*r-i;uK?E#%0`JV)Jk zUTzPU9e8nB3te|b$+XGF)f`Nd8J@n*38`ZNTB2m`I+=i+4j3Qk-`F<*`N;P(0#HiW zW`zCP2HIG2HIHHA^DCm>xkXfajtY0dm-<^fM{g-B$kq&TXkw3|#BWqkOz`S{5%7U8?ndrqV z!xEPv79jOK*kGb#S$RsSb!6^8duW-`8X=hE0DXmC^L|(hnp^U3>e$%q9zW1eD?c|WrH%CF&91T z8E-JCiZA70%(7!91)nI433>>V+BjjVmekl|^2i2s@&VkO;0OTm9l%3K-@NU7#cYN= zdwRF~qPv^^3mu~T0>nWi7z)8f6W*aUY&}$_TNA1{(;a?|(TYAxo>NaJx%J3RJrGa7 zU+d^Pd1#3@#y)g0eaSJV!2|8ZP0UU=`&~~J@2Luu9(aBABjP)abigXWMqM}F1gprf zC}~|!O?mNb?U;`T!Dz|s3e_F!6Ln8AL-a4g!IpJCm|HT{>l*X0V1t=Q`FB(%0J_~J zXEghvim5IKEI<3)HC03OlEol9YuWxsCH&VnvxweW*0dd+!T(qY^hfc##@|(||Jr7b5GJhG z_3PFL2Q;pP-KPdfj501xD=_Fp-6J5)8Smt@^vrs@)GLElMw2&doweDK!<=(t3>!O< z9a=+@g({CLl1gQ3PbBFkH-nD zz5rOhC7_%34$1SwOUE1+)pCLy-JYE)288!gkFMjWQ}|&BfQO}hyRXbn$LECST>J9U zOd8`$g`Dw@+*pn4K^_ilFBOiv$q{up4szki=H&$g$Fd(}v;A0P^gr)}iH1#~1U^?b zix3A%C+F;u3(Ky0-zUMUkJyv_;7Q1(Iu{-bctypT^-k&Oq_PXmC{1Q~rVkt~Svz+i z1yQ=pVx#E{hISj(KCCViZ`LiSHdkX8G?DH3d;{0|E(Q2DLeY(lVlq)2q6lRTjjYl! z7XYk3+Qa9svAm_|(F~hLucYgLUk{6Ia{FrNh<^)6^(s-+mS{9Wx>CI}f zAr;QeuFw}{O{+Q|(!{#3s<0a*S@D$`XRKne7w+91gK=@skgGU6KlfaVYNJB0`!$n{ z&=gb~=pV#H5s+piv}k51pzw~WxNnArJ-@^ut9R1N85sWC-y&#_e94Q$g=;dw_ZOnEj3&7eO~vv%*Pvz!D|L02+qT+t?Mr$%+OR5Hh- zT&0jyN3m?fdQ_FIVUe~wTW?R1HUQ)PWPATvj)4Yk-p<~|xCMQ7$kb&pzu^6Qd2es; z&&3Vz4FLYGtel#hd=mg`pvE)4eo{hkU>d}ZG^ZaC?o=+Z;|rleYmXXlAx&AWg)|3s zxj6JdjTGhT8;IBEy1-_AS`52+-)6wZYR5Ze^(+EzcKN^;Hv2`hY_8gY3`8pBt6Y83%%Q`S)1wnADdYLA z1wtvTLIo6xX{_8g@kW!d1F(^O`vt@;R0ybI`|?>$9?Rrb|MkB2wKA|5m-hM+;OW|G zz!p8kBat7awcd$Oo)p+vyQ1Q;ov^v;>9X1F$+ei)6KqVDz1HKnw1V}JbJXkE_D8PH zHf?kl(~cg+)&|Ik~tNm2Fzv zggCmkX%r;ACxEO^rm{*irK1i6X<)(7E#W|>?abwya~-I^C00Q;RrRV#cyIU?dp6+Q ziu3W636?80H;hwHLh7i0MWzr!IY5zSqt}D*AY#%~9H^)go08N4xM4wU<>B*`sS}X% z98Wq=0^$cicN@TO+gWU!;HEeQajUbyXZ*)k-D&WN-(OyT1^6|HJ}(}E7O$xMQMvhV zAn4!GH_-eSIcm*)TwD9Er6M4W`VRrjCwVeJ!tF*B$SIpO7SKDTu)5{G!Z@p5t%M;fzZO5HqbpnD99C{d;m^gS(-o2iy%A7Dx@oDmz zd=+HAxT=bOW@d(h<`m@Z4ZyJfxG4U@GkC`r$C+cI693xh&*Q`$|FZe|aWH~^`S$T| zO9X%@{Qm>-6Jg6S!}F>gyPcDfA&!`aSAuFPfH9oOiE=(HWbXDh*SzP?O{o7b_tEA|Yi?G!c7TU_D||4A$7I<=(G>Ivi&h zz-Fe`OZ;(O4OD1=u~aRkPgx?{!ufUD7_}gCQ}(>!;e9w(7hT=>59R<#1eplroh+C~ z)OEq@#8af^?taI065m&m+^3Egu2mEA=;GA(0c9Xoe)ZeKCmnl3unu150oHcBBH&Q3 ze}7dq!~lY+|9FNcPD2VupAxCRS5zaAVFKE5b{p5%({l^@ymGWiodqPS-M9Wej*-TXa$*No z4~SJ1(6@hpLcYg*F24Qdo$SAlkrF(U#dqycTNe)jvr#wwyUhv3n<;#m7jsN|dUtpC zH2Q8t+l*v<{!AFF*E$$()!Mpva76%&#+!HmM)Mt8&{AVboqS0{#RD&??vkG74_{g9CddPAO&Db0UZ>?D^~&O+%x4Jb4b- z_*g=S{sW-hUJD?Sp`bZ&^-tBD@J{S`Q0w93eBVp3t*tF3mjFWdyTSY~+Wy~G74aQD zj~U0R0S=0;1p{w0CmAzpO98O+}v{=cfIMQ=b$Y@Pl(?qG3YA%yN{ zo5=su!G^4{@uo*WJQx-Dj1uD2g%1kSm6Vl@?Elbzq@JfLSbP6<{p7?%*-3J=~`b~J1+~6 zYD%DPb@pKR;hP}H`7=3vt#giqpa!L?isDfMh|(1LPeKsC8%*$Z->?7cLE6EQDfUnV zU9pV|t~FpDr#_N^+fR9wl>ZqOCaPN@dYcAm&K@Ai_DO@Sx2C)rX?|k> z-Wh|%brb0n5miI^T&AvA+n&QL*RjGAZ?vMWRDLlapiCYa{nPlt^~Y6`bZ~ok&a~Un z+uXrIBR)TxxF?;b-(?GmC#?4u?)zF36J$!aPp z;boMNM_CtuZD|ccW7r(d))i%DW=`y4uJ`rzxm8irC99~YTmXBxX7(%4CIORjf9&DE z|MDx7!;f5~Y(QNyHh|F_%2BljyK5X)K{p}z5lG_kH4^A0dsr?mLe z3rBSPAf^Te!YG&&0#F?#1`Ylf)&5`!v>eD^h_R^&p#$lx8D`-F|aX1*#|`6POK{b1-oyG3*R}aTubcJI=vg;2JiU298H)GOOj& zm9Q3OWijg1xM?6tEc%$hc!71vjGo>V10}h`SMsFpAiJnY zaj8GAZCuPePowyDZAF9%3UWnJN$FN3Gwxz_c6RosJ_tk-Oc;g8!$+(gv!oyqAZQ}! zv^kxXpFca*4!M$-o$dd=|3t3eUthCIjFek+=0cn+vE?$iFIR$Y8II|^?a@Y_2t{%O z{|uIvyE8hTe1;N5ijvxIm>)8>*te-+Lu><}Z^I?;!0)k@uOyN{O5bdKk0BDR=w)dY zZL|U?N0^n79XURysd`tv)K>ab)(GMALwdxF(M->p?0ie6J`i&5Q1-5M8V(f(VU$em zUS*Hya_)c)(SHR3dP*(Vz9ZwL$0o(Hq~_!IgL7VB=WX7)BDIKv9kQ`0 znOE-l8#Iy34`Df5fzQP0r%;{>wAgS~nX#5{BLyF^`!VGc{^N_)tV`7bNoN+HRrYNh z=+ZniW_9v}IGT71xYGk83v5&0;NTtT8t#DCZdMwv8zAtTdD}fGRGPhsyqCstzXpQ{ zi>l5jEEG9tBJ3^nXyj(6{xWr_>&@CSB9PgYcWU_C)Qtw~3LD)#y;1Rxyk$K~`YCDi zt~wT;ldqF|oHL)cDw#@zGSVyV+O!_^J|;fQmpT+?Ho1R~xVkq#zw{RO$5G8-eiJyE zt;f|!@jRP1W~(z^fa49UsTTPVDHit5gQZ+ES6Mg<3NBn7QY;h2Qzy#L>%O?f|K9AhCHQl%hyPkD(awB*d{uV z{7hZvaBHO`*|%gaLqyVgq5p$i$DR0&z;Au;x3Fubuew??Nvgl3B>9yiQ-d%HIJxI9 zU^>MW<1{M#QOf&EPFuBxrxu-i!;BdBKF}g-FZPch^CKEPhVnb`-@ft%d>peoeg4jX zEqy37(6dY}Z;9UcBBgVhj*d7{Zkd4lBb|cjlUnr|C{KZ;^>R&wS~u@C!OWmd1q==< zk-}0&5JCK7Xzd-okfa-;_YvA24oC1u0(_^|dS|&R&O39JX5-@C6DDj+Aru*KoX_%C z)%)k32D-RBaN19-DBYd8_uSCRLZvh0DQ4Wn#IcGe^#BVtYW(VkxIU^>pjVe zbw|(*D95yOst7JPFw?a7MvLMGMv#WrRq28$Y1SNfh}FBwB&k zPMr+iW;T;-{bWDg_qNd_?>y?k+N?*Qj7czhe=(6zm!y?D<;r-!H8C|`YLN7kkdr4K zc%^{>Wyeb0`XW80N5V5Ws9LLgNLGtc>nlQ7yzo3YF^{qYeuPKzOm&pypjp8|2v?(%zqv#Onx zF|W>DA@ZQ#EhQk@?jv|lhqsd8dNgFdFfU*CHZ|;H0V?yGt7{4N;C-?m+N`%iFfsjW zRG#uuXn~-kD@VF|P2MBnuHyTu`+_`rM$9c6b7}-yrYS=a=MYAs4ki^kFPjP)cP&DU zb`C5)6XX{bcTthE;&{{5S0=23-3aoaIKN+*6 z_J#KkzX8cg03l!e-l{@z0o;)g`gB=(bS=e6rAlu(Y>=_DNq~R-LiF_<}5xi zOG{N`gl-}@Y#Z2T6csI{s}IQ*b(T-Pd&3-$P-ZZ{8LyMa44os%G@g0U5OlL)%3q3u zKJ7MQm#oRUC)TmAz@oZUhz=qZ6b{voMBRD$Z(KKqrY9~?F$3U?CBbe5icAI3x0AELLNeSh#y!IAA| z4S9JXC2~T(asNaHT?&)qty^j9p5{>GLKuCFXK+< zdXvX$j?Y?`rDnTP8s0g2d_F}ZDfHChyNuvvmV74X46Ol5pS251>9oYxFcF?1_07-7 zt?cwQh#Kk`)0{m|sB?j7EM7%mB=krD6Eic?dbDC67Se}j{g^Lcp@ zdsj~O70t=l#*-W~o+UDe;^^K3BIu1sH>MzUe;i5j(wl9Eg= zy9LscEy^|Dygn~X56px+j=rHil`dC9T&hsH(5|a4J(M)Ei6yO1aSP_NrL^!$m< z!DN%bo3Gh5W~<~#>X6W7u_dDP&Rgtk>T{KqBvU@T!djN&u+m6Sb*}Xj@Z6QKz3H}$ zO4?oSS+;FsQHR?uF^rj$N>lcOuJ^LhFM2TA z2(NjNR@p`2CzB~6lv1B-6R?FQyE+IXMu#j3Q?#=BWTErP0d{dtuBd8r{>$<`Z&cp1 z26N77vZY=YsjL;9P>dFX7&VjK8R`+M=+r1hg<kcQDMpAxZd4XdH7}yg>sXu-sCr~of*OY zoc@FjW@>pH7*+AT7J%bEOFP}=LzRpQq2`A2P1vHxUiv+YSBtKBtmx2wf3xv?n#F_b z$-SRdazpQVd-h~a+&>svE#*qw!f*!`r>P~4mSf|V)aJHK`;MFqRIkJ68+(t0<@0KT zjBtH>;P5Z=+3U0pg5&W^zLt#pZEyh``X2onQr(|MD6u2X^#Sl{iHD8bCs^{xP%v~F z+et6GCn*Y?TwIa}0Lyg5KE!7P;L@jv#i-%71Sl)+((q7nELE>X`-Bx3`=KNYjrx0~~tr9R9iMUS>#@vHWe!i7HvR&$ml)O{1~ zlxT9N6?$5$p)Duf9$ED6PUmnN8!7t71&o%>tLcESg(vxos@=+6Rb^jZc;>bl%e9o~ zO^;oEpD=%Bmm48Ae)?96-F1ca7CE)fZ^OiN%@lCxE-D49JjR5kJo}sZpHk^5JRCfo z@OHDa{JFCn_gSCJ;kpWhroO zd9kZ*aA&y=P9pMQp#EHKU)n6MRH2d~C2n6#-_m+T-YivJpBb7S?P)6B zCf^OF*P0=tEnD{B0F<7AwZ*s@v)NMH#n5x-d87t2jFkBhmp?+#z(Ox8Za=$}$`W~_ zpaA-USX8**K=GcaY|~{qO~lh?3@pquMSPYu-w4SjMz(9H-2#;o%hR$>&^z25y6dRG z!Pp=xP8PsmTt2cUIIpIEz$$nJQtIu!gcl4*;%ACAt252TPyHH)ds#Zuy|-CfHyBql zyd@O&|vEBljbL>TBJinyo=gTsy=H9Utt?Mp>W1?$z zXQ`lyqN3jY`8rx({aexD%xXp&L)Kn7Y6THbSzL53d2u`d$tL(uNd(9hmBCayynv?R zPYAff*JAWs)r@F_JzuXj--v?|s#*S=J_+V0BO|l0Hq(YkRmo8W`Q$q_-nfp=$?$NH zxl9E64bM+D`iWlV_N9@Wpvfjmn{ z{&n&K&p%FH_)oojozn}(!aOULk(O>o!JvvdI&rGG>I&f0lQdh*FsJ)^J2xT~48+dU zsYHDu3oiv}Wpfb=wEH+b5d(S5gprbxQiaQAHeFVFx){i@>GRJ(!53ijpVaKs=$3fS~&SfH9n3ovycqKneb9OZh+R zhhM)sf$813gaOa}CeN^n^N_aJ09(Od6SQkWN9#hv6%ILvYwSmgN2{bqiT6!A0MrDL zdh_c|8{o_n< zce6|US~&P5$6xOdO=OP5kY$Zs3PT$Au zK{lv6f*${V#I7?O97?m$u3c?#RqQPDiHHaodaw2fCj{*VSseh`vM;JBkJTJ(X@L`R zWDq6KXCwh)83B$|k&S3E3TrW`Of8EDG9eAl0qUP^kCD<MJ2H2;Wpl)Jt@jYfnsZj$iTC(HsQAkZ_XT(k{LL(i3+-JXk0xBX z_jBL2{Q!LGCXcJex)%TeE0g*4i!vHM_%!-ju6B75{ud&@ev#;V&4UMgO@rRPDE@2y z`hf{RR&ID640z_bzj{KH5ktm5bEI^v%n2prUZ>&tva za>&FL0AAq|^-eW4kx8YdY6iQ#NaS^N%q}0hbKq1r`u0rDQT2NRih`G&j?C)Z;~fzO z05I}=kUQ`FmmuoUUQeSZQ>Igr>WGDJSqp`#4*Y#g zdaw|_drgrYM$(hPL1yztE7}ya&fHv#gZ)`S;{0}SxmfTOO=71_5GN;32C&XkO_V+FIRE5!IdF{VMLK0+h`e#a5+B2$-L=QgwC+w z(bHg>jp_Idu{siW&d!zb_|nsG9L#Xm&TY?mWo_`ofEZ>vkJ=-vsotH*nzVMrD(3!N zFGXn}F>LEYK{vrlBefpWLi6KF*eit{?Q-eL-I=Gj*<#MUB5b2zLk-soQoL5jo@{GJ z3x?`^_f5NH;OSru1Ih3dK|B{kayj@kroUnYyBzV>J-v>tMNWkK5FTRHzArF7_>^@2 zTR%y8FDP1y1p~~>Ok+z)Z8~dqKeh&R@{^&Tzz;;*6H;t#Xc5W@&l&H#nxzi~(T%Go` zbspLzI2G4#Q4Mh$4|{O)p=icn!-%KcwfttJp3grDD$FnStZy0E_1l**xaMlsj(+Pu zi`(B=H(7o^iX3`RU%yrBX3#ZtqKv3Uz~2c{}d`j+H=JXkqI0*gs4{Sp4qW5W;$l2VdyGP_@nD z5K~>!K_8OVnVcvEVp(Y9kO7uN3u$J zLgu04^bJ8IW)JMPf$+u+CC4Y(dXF!^^}J9$oE!Rz5-QOc!R8>qTk4o$sunrCM7Ok& z=p#FR@aoIn2nNMv31uUr{ohu3TEBkL|I|#HaT@g2>e2#0ofW&U$<>EkDoa0Y(3p!cTG6 zNbBPGTpzi5P(&cJv~YSBijz^-vy+lCSt7+Toemus8`y&!T$Bk#)L&wP=h~Pad@2e8 z56S_Kwut{zX*!^cPU*$$qe&gE(mVQ+l5d!wuULZ(V=St+KD#al!UHv zm1aKr<7OW!^P#?ks&a~6>dKx|nVj>>VO)n7p|9|{D=v073>je>i1X#^=%^{FmRejQ zp&)hdr0~-$IvLF(ItrvU#je!O?eL15Q0u4_zJd>X2GS{^h{8fqRs!~1v+T5o*F_@4 zni|gOOU=2U+>RFT6N$|ka+Ddneh zi+3%?eR#VQSAyj}pxouKmHJ?@FU(R|+sU98;_gOOg`is!R{n(KwSbkse|I37EMGV z{(W4QSl82iyml&Dx6?LKQ>BGN0%#p-1QRFanm7gF!mn)L%yX+1jgm_27PIKJhv}afLf%9feJM zx;(1K+8YT~@CH5{d#Xr@Q^^?ic$oYbh4Os;V@&n#*H`&o6=RfNNGR59ES2=d2EyuY zJw{^AXIAfO5XbSR)@)Zed~Gn0AvKZe#N96pi`ZGBxkDip;<=zYFO{{66j>Z9dL0Gd z+vW^qJ2Yu~GmaxT@=!k(_3tZvwVX`BJk39U5ZVef%17Gnh0sk94b<6=aHyHuXoNOI zMya4xVJv56>E^z&r(i$oE$^!&TAT5z)lGLT>6)UYjEICvjye_;QTEsC# zlpOWPy*eFJcM8P;Dnkz1vsp)`FB&+*HDIk6#lx3A1TwRl@y)EoUkF$t?f4;HDc=~b zJ!5}YqyKs6-B(*E71462A2YnGbp=;<(o>9W)5&Y<-CAD^;-bGNjnd>{QN&ljGCGm? z)BZZzR^^Q%4<)GGRX>>Sk%jBgV9#fJme#HYxXn75zI!wONGr!Bm|=PdrFKdjn54=t zoi}$5JShBIE5hWp*Gt1U`sdg!r^7nci*{~VX%E(V;Fw*W8{Zw-eCGI?|>xW^r%?Wz&O?W+5{OM<0*v=e8>@j*?I@gK`y)EeOa=u?%_S_lkUz^th@u5h8X zjAqyZgkz^Y?g`?o)xb2*)7-oLh z)+4v$ztVGEj*oO*K1ldH{4559b}ORHAo`S|p+2P^+uPKcJ>z@eZz8=5&XaN|7MFbT z;JN*iuCpSCbEi4?RF`stWr7Y$9<$a4wG4Wwe+$XiKwF#gC(?Cn=GZyb8tgLP%(#r> z$bQoJ*2eBp{DO)tTSCPcmHdFu$dTT>8qToOVm^6#s5^ZN<`JbTY@-py4b)*`)gTdAhq!+Cbs%tB@9MBI+3 z-Qf`kIBp~zVsRVGO%dmV^_~@HunV z{RC3;c_-6%;Dv^}Bt)Nd_qQf7-w&vcuBIL99?W4qcgS=zr$1vNpNn&VN-~b7YohD* z#kH)d(Myz0F0;}5nOmIPSzzYQ?xtRKo1w$nlNH$+Lqr zHnH!j*Vs)rjP>9N7+=iv#W$zJo>&vKeV#M_z&Q5g%VJidi!4Zha@)Cp$eQEDmwY-nfV}I~955$>e3a|U=iO6w`_&DScp4Hh!(r5q zo6f1M&v~bDwxOdjyjdcC^N{Zvsh0>S$O>eNN1P9qJKR;>jx+*3CG;o!0P%XI{C^{j z|8KjZ9ZdQ@hs=6><_uF1}x-r~%j!Nn~ew7*WyQd9#~ z)8O)I0A%-yT0~l}cV?rYVDc$&NLNa&sH>oVcm-2)_h7AkcClgbo?K+b4|w{?G5)m` zrR7?3WbXL^rplD0Zm&EUT<=fE!gw!TgeI6dOM!TKZDd9=B+}1pb@UeR^A3h>yEHa1 z*$-Si7eI|E>3uF#wx#2{7dL(4d`rm=mx z+*vlGgALKJ>TgL6E4!)&(m)?Zn`$`|42<^q-n&qQ!dz&l;bo!O^0KcKEn3*nCYB<- zd!c6=*lriknbk~v&Rq^r2-K=*7~BI-p^V98Vi?1NtGqa-U%D!9+5x`r@Fjs zhrr=)A5VC*UlIB|$Sh;A%9;7$DAz|3;js9Y_u5)3#!`9em7s&W(WrfJ*iGzq7O275 zwkWOoRsV?AN%NVN-K@T*P-vN{aSf}GQt+6#Mr@O|Gl+X@NfyaJ(LuYOB*y8KGrfhC z$BN&Z2^Iu9B;=t@Y+YJa-Zbw}+4tv2${{;>nSs{rq*ZkF@VEDBD%RLQyXic|@KPwB zF0b+`wW#Mo8KoQX+JVs>oD;{rO~(gDosk6!owU`vBNF`!H!!ZVww(EGy2@;x)~c0# ztLhnhg8o;8xWyCN<6>@a#)pMb_S9gxo2&C52a`cBqV??QGCPgjbxs1uE7h$f`ZJBn(7ya zI2^M~c|-Bo0EdA;!^cHei{PMGRz>;S*@r~&;#&-Bf=ozT31b{?}Lp6 zuaDT0g<07uAC?C8Php6p!6(9#37{CO;MUMLZ3IVo6CD2JG%u}M>(zltU-8Xl6nrzG zgNCy_3~ufkt5M!3?oXhh}xqZo9YTiSW?yg5hO6Q;C5Q}GgP@eN`D2l-dE zO9;;nt9VuLToLCR7%oz}WXZT+V>oxjLYKzYKvt;_&5r?HPWa1_iW&BTw)YOZy?eunjZ@}BYTc50h2cSgi>r1otSnzWQFrh3zTEOzKrGzSWu(NQ zmM`(pE`48aVk4zDV@axGlk9&+lGR{ zqFNbd3JT>;`?~0>-7iXS+69OEEk0_p*SBomej-udmD(No)!#Etd9Ry-xVG!IXI`q` zJq+$?#vc1fnd?N_YpG|B`Z=rz25tQwHo~7z`Wr{yT zD9AWF4;`%@2?R$E*{y#sMQwkWGnw7J@j9#719NoehMknJ%NS2)J(gD0EW>8S@H=nP zp?|6@gU)lngbKmhvc>OdP`F)mI)MWQMHvl#DE(TDY8*cY`gaAmtr&=cY{vx4+M9zW z*M>$X%U$0bjU=E~3I#UPNB091_;k!NZR7?=mx`N0yR5KBhLhPn3HE3~HMo!=`Z1r! zI>{{^6ho;F$MWnz(;O|k`^S}`yVb!~6elX@dQPf{iolCQ`1)_*F!#A(LA7X$n4Y-< zzxu6R8=?WX!%>u*O#G-_=gfRtjdN#G94*q7Yt|xdL_lwkEROd(ytzb%)`O3@}yLQ@hTuo7bWMY-a174Ij-Pi2xcAL5o#pl|$ZT2FY z>yJJ#CMTCjp}~}fIs1j<$DzYQv0|6;c|?JP9mRN$`{Hm|bsW!dK?s57^w?+Kv4R(N zLuh=-D_OP*!Xl<`ThbD~S&XlE<<294GkUUJyrhe9PSH9{CTG7tJ>H*=(t%l^`?BjW zx^~~49m`o4;6@62z3+Jo@nn9X62DwX*CIdB@FmtGFJ7Ft_n`UXRMckA(}J|#@ZBDX z@hw$?0Pnwi^zu4EzWU{aj;^zSk9`*+H&rnrb@-+T*J(1Avi7$FQ{iDS%P%EJi949J z<|WS5;)n-Ps!SO{drYuIKb!gknPFg!qEcvjO6a=%#VffNXt?9E5X1h9SIvM|7|J|mT?8fU|H z2^YrGTXLlJPJhNytO<=4d>HW0^@w8xHADB(cb-T_(5KbPNKv%#3ZxWRy@*E@2a%a+ zPNy`h@Q29rUr@8?MubC|5Ax`k(+8)&=KIfRVVU>J&KtV?f9$Jk@uYMp4(&epF8^Y*FSpy*f46> z-nI6UDbIZ7n&DLXkE2Q4Y3d1}=;Act9w>}8*w}A*^MDvInF8aDp-X-HrXu9X$7Zc> z^|bIK+iYtwjV+!ri$w{kfOd5Z*0QkzFTVG)0Z#g5lF&KwuWtd)7R-UaT zt+DWnZuyTHh|{l+M+l$PB{m?C;->(d$Ox(GVlCS=s%o2!@r8Uvtb>WPM-mYN_3ce^ zayw}bVXUOzy~i%x%sAs^EeY`+fME5O_I=N{I7%PGBjvfD*|K8+ym@+0uddjxKgZek zs>UAf+BnQN5@H_y?LA*(n3DnFxR|uLdYsS~_~}T@b=YFzRUqXTx%=>2*GRHe$?33T zk6(*|h$8FZ$lIZO3@IaM_$Qkb&$;IDu5$rmv@S0Qo>gl7bS5eblZj6>*>I@7lVMz_ zekCZTbp0FC^+5p^3cKHWhvRGdO*P@L|5$>#$SO=761#t1QTP`7Vh-| z$)jQ?VhEeg{YuR&qcK}1i=$W(mr%S`m>@}s@+${8pplV@>5EI>u67;C@KEzShjl+fSqH>q(Fe2Kvd@ijQUpu#LsHI@GK1eDcKshBd&WZW6c3kN3V2xtHW6 z4!UoH`kANc=(u9(KD1%<-tVp9Bz;|T4muZgR><8-3TobOZ>^;RR? zmvd`dW|9S2724OW7ZZHAsU2BcxY^U zJF0fY;-tQ&*+Q2?Vu85ad`gl$m&J;;R_pl-bB{|;l4bfIOm%XM>Ex_;JlXzavMwTL z2{g$FXA1s0>s|D-IGp);*G8!Z8jPp?&~|cS(P&OrX_k?K)~5Oj!0~JU&!33gp3C03 zzrX*Z0}|mX)_>1g?s!87MosodV3?!CQ^n`;C(M*O;3QQ`sDb&R%9+av0un} z|B@X29}#d06J4KANBFK$(Rz>(K+-IV=-`mEW(n@8zTfxGsgVpty z?tK&kE%Et@P=TL5-*}@zimmo%=mGFPz-+d`BT&7hB=#x6&WCb*`jO=B8wcqMeV5S0 zByD;9`$#`}UeTF1kR~Ki=v0gqP@A$4wLGQXwy|&!WrTjfn^_ za;6lXXwv5*7%CMW%QYI zXc50^kNTN|dTHe1Txuql=CMXTdlRgCYv+U{`k{nD1E4kYOt$xz^Z+WbMCMWzO+ zJ2tNWH@h`2o^J4xsll^7s2zp5#yPXN{~z(`IreI~?nH$UzJuzSHY$bR93TI!VaJo> z4Z!>N_N2<8kxt@9LVnrAb#L`+WvOgVI@S+;La>d6Z%qhDxDr0I&^3x?b}fU1#w7X5>bZO#L!=&fGQ z-;M=B|1%HpU$hq(ITHI{bd>*7|N1_SuRS93JFmH~16+&Avm%xSPbbPm==jgE>4&iA zWDzRUC<9Cljcs3W#svwa2{>0#IWG$&2fK|DptID6ehNF<4#nj!3~w$ZNJS2efB!?J z5e+gBM_(H|H6Yi3^MNQ_NVoV$;W$qw*?3Xf9@Zj|@?7a9!I}Fg2kqRXbD3iX4Y9XV z28fP2_C4NGSjfK*6YRh`>i;^3C4ZOx`%1`1B<1hS|8?oV_qKj{*LRXY0CW#v+JyE` zo002LIoea0cJJvX=U}D4fh67&8oW{Hg}B3N zb?Ve@-^kUcZ41Ld@CgczIOJ}a`U(0rY;Vlu?>lX)JP#9LjKYIt`~m~g*dm*bBBCgD zQUVm^p5zea5(C=t%S15{)<<$1$F?^I)y_XoIw_Om0SbS|dSF%p_E!fFTqpF_QjgZn z0yu37HC;oS1=eGq~kQ zw1M8y<9<^znmm7R+H#GC=nmO2aL72;ZhruN*2*xdCdG5z2Zt-K^v9h4fn2nCB4KhBJ zx3l;n)yv)ap^R;{vo}im6Q|E3y3LhyBPlrr(m=pU;Kx2i;BHUe^kR_K6BG34k16hq z5lUpWev`VB3q9d4Yn_+odrjZAgr--mDX;67$KbYlW96FEKg@ zrNC@e<~`87g}t@p(M^_y?2aYpu@&JO^4HIHx|o-=%h4@*!$Vj`$L5wj!aNE!G&~7x zId!Wq@`Gb#!W#~TADvoTv7R>IoUtSi&dIZH%RWi}ggwjT0>oEwye8B|AaEha_$bWp zE-l`_z9{ocR8qB*Ctn)gY)h|`5AF4Y->;CJM(#;wH5Wjp0F z;45fn#s}NWq~kTxzOU60AIIUL#&Vss%V`lrZK*;Ma{_69Jdc%bHJn}P{GvP3_2qAM z1GlF>^mnel#NzurN1WSeO}OJY<>31)wj796SrJ1kn1vSUL$>28S)2j7Rw0Wazlp9X-U4p>pkw( z6O6c!^UZcE1}owQ%Jo6Ny>LNsl_Qi={l1|j>X%uoia@BkY>?h`sQ4r$pSHCnMvloKCOk8%TSYRO+c+!77816Mk&wrko+YXmsxmV$F z8mAU6F%=s~>ji!dBn&4fePHJZ3N!B-c-grhL-9?>{UM z;i*|sygr9d#+xb0=|N3j>Th#pn2v@?EQviEm#48HO{tP)0iFtlI?$sYz7)M(UBG9P z9>-Dvb#Vi|n=6XN_UI6dzKky=%p_~c7iFVrtehREChO4sz?1J2GCq7(s79l2^Df6K zUp(?ex8fVEvu^_JE(ZFj{9whZ^EN%Bfe!B;er0`LPyVZ-2fo1M_P`gGI}5sRJKxmW zDQKXIXbF(jPJdFuit_{<%CK?iGeCQ6f*e65un&>toXu=jnsURCDMZR{`0db8F<8dB zWA~A=JiDYNqN<-ndez4w3uUUtg-*^^zXSFVyZ$P!B7IaGQcV)D)z7B>Ax6)V(1}Gx zKh|$7tU4Y3T^9b`b+w`7Hoxn<1YKElI$n%ZCnl;-RfrE2ScHRkDvMeozC==42`ldB zS`3B7_SbbZr+-mG4vD(*Ta3b8QXVeCcdgj(bKe4)$!_tBUKhSm;QhwZ?hTJ-qtW5N zoTO4$=hqQB*&2FW@TbHJA0wEx#MpNm*&MRFiihhtnWRE?tay$rZt<&oOdeUcUo}U#o%N#eq7Kx@&V?vjp zbRRq~K<*^;&f5Jv6$8uKF>GFUJHc;$Je+)xGwMXKPFpV$)N`iWx2#>@&Ejsei*d4E zu-s-%E&Nuqtt6tU4y_q()e_UbrZizRnqVu_#DMUA^}Yw!0MG5#Ba9^fbh$-<+`v^@ zKy2)`K?Ams_NnLM0u7rOSkO|eJ2$#KwZn`E7WG>ANq>gm zhW5~(%D`6gq8E#_ZJpl%(;tpm`Nd=6R(>)U&v9!ahJS#jm=tl@Yh{vgQn= zH;_8Gv3nIv^DLyk{y}dXRFO257)O5p!gEW&lSLxqx1*o(SpS~*>t&f#x0~Nu{*>^G z^ktezqWuz*(Lc^W7*ig0^Bu=IdPX25loso(=24zCV%iB*lPlE+blR^!D`9nTx7%uc zjIKK(B)jRCDBes_7_4`CtS#sUn%N=6lGC(^zYAehcg6kfisYYnOi|K~ZWR}TThJKI z;38SU!C@vm_^AhlGUByZL$tp7Q+k%IV7qVRDlSz8KOAR3diQ&+CDs8x&dLhK{t$9h z9IyP$5BJhDoyTa?pYJdZmsp8bl%9Y-563<=2?*?o=xAj0;y$Wowe#S}U=kGVcXhZ) z)4w3y9DZXQe)HGL8=e7u*%z$`?x_(%X~D~81$H|BZnSolIZp>HL|<)TcdEKnA(;Wr z(`D9CD?oNM$X@u}X6=T!tCeB*bI7s!j3&bNqy7sZf5~->&EnI$+4EgkB;rI%2D;qC zgjq!QhtUlii@wD_drs%!m={8j+xf>uqDrxj7&)7v`MOZcI@F$ngQ#xFFJUn22BojH zG`+<&9plb(Ul2`TrQt$a9#04%;lRGprzs`w zl(-;aW%UEPUH*!NLrE)X!7^#T&dSHFZkwjL=t@JFg>rgIl?Z3L7n4*4wPh{w*m zq=dhX6Qg~$&KqBt=aq(F0~jPhU2jPqgWZa^Shb$afm?PW?{@etQTr5LWv=v2Vl@li zb$)7!ZkO5;WfLF=7J_b(Y|vbk?Sbe3=(O@7A*t_saQN!OtrB2&T-1}1@`lW&-Zs~& zG;3i`G`_y2f3Pf$OmuA&1Xz~6y+Q(aYr7xHFxdcVbAAXpGOkVyrTwmVE4L=?UHpk& zN?|k`h4Sbq_g%y*_H;`|(Bm9JcJ*~*unvV^yb}!+m6`U961;T;RsjGR%{-b8P7iil z6CGBNG;H}NFN=SVSE5*ZMKrmf(X^+}MRh)=Z)~@Xx@GW9e$D!IK1)?yn#bd#Y7)HI zR_9mo4e0Kml#~d~HFebR1!1*31OBWo>#YPCGs2c6w?`a4;jBe{T3*_R<3d6%~zoLsZE_mLR{9nY~N zv6?u=Ua8!V%DyNxU5T0v{-o#H%Z}CJC@h@)R4Qpeu0Tg zBYgFqM1Oz^t>WIJGGEBjqoDddpVcMq@O4$0p?@IPw8-_N_aK;~s*0meqlT4X81C-i zal2~|Hyq~14eUI7SOzOP-K4fNs`g*uGjAzYsxdm~AB@PM(*|peky)au{+4#TGb~v6 zh_Cd$jTvOV?>Jm0`xOPq)OG*G+RfwdY?@_7b-t^_D9=$c0|%s=UC@Es%3?P>Z^DmKk=95M?{Zm7iHEhU@yVUPR-!Fw5cFnD=jNu z@=nOs#BF8j`HkXM1FoT#9;TroP;*)KqMKsG?_Ku@doFlAOKvVwK6o)#WUn~idu^63t(2w$8>!m}~i&p*#yU zPhJ=)8aVw4(Glh&oLhA%iAxQmawL@)>rPHc+I}qWLw`9gH5j+>6*jy4r^R5iG-St4 z70iyGvm0~W^Ax{gYlaQTk38CaA#$OctkHv6|JfVDWwFdax`Ih`L?kYL=IS3hb|=8% zuU!Pr;A7NS76?Tgof5v@E9-2h$S>`Dq-ASiiFn3Ybk<;449eJY%ib^!x-2@&&8A(| zW|pkXJdsnGLGR{v7YDhmk^{-MJ=u)PzqtURaQD#ZAS?E05s|xH^(~MrV*)Z2!nw}i<7MWF zXnR&29J#jvp2)j{hsogGmS%rmNRkTIy1WlZJJA+@NgBN%<}Y#C{(-LC#ao(&2>Z%m$2V{^+eR_oNIX};XRcA1ro9y)miY`BR z9=A|QX(J&CGs8h^V;Extek_>!C;JW=&d5DMO`)T)!8N5=7?6I$a2=OMiR0C8x~U-B8!?YkC_V zQmnpvV*|WZG(MNhz;S?HQ!=&=heIY!*TOQlTPLX24h4n=*H5#l*L~Yi6fEm;$9{gw zncEPuaP8x;(d&0ih-0kaP&HLW|?!$SUqSpQ#ZLxG@ADN)5 zu#j`dl8Y+NAelafMv-GM4ZXO;c7$^w)LnfSX6N*0D`soK7o3FB+`ityOT&M2(NWSX z?lL)xj2PEQ`EZeArbzzurjc^q%k{7*FfS>U0Cf8loey{jN@?{EOHgn+j+k;-mk>JD z=?tT0U+dL-wVP@{l=GnvH5tve%lakC)5e2_g1gsAA!YreVZ`?r$wwP`a^kn#2gUmR z7hg~^!lq^sb+E3HL9o4y+Ofxp9vukqHu?M|6RVqEHW!3#Yg>v1-=G2$LUQ+$z^g4Gw_#vFFVDh>B#bmLrL0 z>aKh(9>g$~O_CZe{q>P|H*w--%ee(qO5gY_Nus3s;ridArp6;g=i!i?i z6y$HSq9@dp?RAPplf1!g^_I8(UFH7)+us{2hwXhwbDyNB%UoqV}SewMHL4+DD`nFYsE}w|z?0A3{J}My=OwdCKC{;OZPv zM;^T3?c`Jh8P%bRt11k0B0y62H24q8{5b!(ACKz>Jc+u9-y=h|lGS-w{~Gbnz;5gk z5Lr6MwXo5WbKakcAMT+#Gtsyo;3^{kLHZ1>o@n9$mUw)Ca&7t!CpIC>^0nKPe3xI z07qP&e4)1de4iD~#lgs9sGorey$?5?l~}EHhX}v$l@7|qfq7TqhV^6R9oR^e#0&0J-;DQqQzkBoSq2q1LTN&34f`b_t2F8!({)=0%v1dp3GB?VFc8wj@9xycS>x`+b(?nVA z6;eu7lG9%=JD2EiK5VST4YGgV^wUbD9QHe=KJ@^y~gVZ+?=$R)gjLwzr7A6bEOHirprN5i%W?99fovFy^$Z2M5ovHR! zwQD-(2rs86V2O z6z*jj>bsm?Ml&$*G0%p)A!H-8>!EjfixdI%FF5KZ;xpLYQK(HuSLaD(84Zv+Ud68D ztgBX%LCHW$XY+tlg82+~jRVfU_~AH5$m0W$CMZ#5G#pKIizNfV>v=^ue4COmp^i<} z45^>+m5lGO{LN`fvZUe7METL$(9mH{T_ofQNW>fl(bQ1YcxT3nHc{vbIl zSgy(N&Q}q!2}B{U>@;-fUXS8rzV$N3V;fOoJ9K4CrdEr@v50ZyWC>vIT@2H6 zNW<6;+~F!4$NfgXH1FAjMdEf+Wvtw>(|ag2v#W= z+Zn=UvVou=Nl$D_63$%E&bxq67yMN`Fmv`SCGrZZ5*O4Sz<%CI-*Fl5X9hT@lv zvG2_Uu$*0XIFS;kuG9G|svfdVJeahrbppd|OHv;YlZZ>x2X+dXKpw2<5p{KH!2`5L zHC=Dy7}nb6Ue^){q{oXiY_7=H6-GaMR?EXQPy0cV=^fLgDCihOxb`oOEWwdDL`sXC zl-l~C=%8sCcs>!*4q4wLs7gx!H&=Cd;hp;Xa}V!3ric8XXvgEL{Dm_QGIXq+b*9Ge z)h&Zu9OUn8v0A%dnDOh6k5f@Z(y2|hW)Rm5@7bJAzt z@w-LRfUmP9h6+^)rxh#{BL>H9dWHu_@5vZG2z&jIP7g4L+15a9eTAz#dI>XzeOu}v zkTyhl-e#kzK88P&J*9_5DGndPFx)PwUz)Qq@KcOo^JSI|^>@FRCpfHaEbmMOr*^FM zwSf>w(LpVttz~vyUSiXH4(|1WMfpw}=q|(*|MS+e)E6kN(WDhS^QntJd7gQ=tpWW} zV=L~8ip(3#5pQ1^8`7yYqP;0+5CWcQz@rT=sUA7B4QIL0FVEGQqcwg-blXS_|Cfz7 zZ*63u{~Aujc9$2^6FSlzX6%mg7~+GuSW-~Zl&9{`kgf7{p@+L_2`le8B@y^CPgzDa z=aMCi^1zNTbe< zQp(k1Fb%OaU*aVIpDHSCiu8hwL(NfjvLdvu*%Gx?tFMcux1?b-68wn}^pwTdMY%|H z!Tfzi#mk03SNK?Druz6Z2)n}QqXAAa_&v*kFn zXMG75KEub~vX>aI#O}OiBv1^iud6yWN^Eba{Fzqe^-}2`7VE%Ta~H%DTa=d)!+UTP z#ka_l&s=p2Z*eny4+07*B;%Fn$qWJqKS?e?M-zC+5UR<=&Jy%mDg^O^gTu_! zt3kh!sD+0$76i|Ps;FNgP#Jjxn_RimK*USM0&PX#)an+A>U-Re>_%_X_VQ=-A|~2v zflqSqWwu{7$n&ivF9Z7v)+mwXLmuP%PoW3N%djFXQM#5QaLEuG(+eo(TS!nrvnS5) z=5X*x)xj%dRI<>31H-H8;^3qg?q~sASno$1~lr7w@NTK_%`xT*Gri?uw zoYhLK9H8|a!!%8Vnb5?+p^yUvvIcu*ZNQnTfAC`s8HLwCAY^cq$A+a>G(jt7k)p_j zk{X0ex&XBx-Dnjt8UBlv>YW@*RYiBNeEXHW zB#$Qw2a6*24TJcJwe90~7k5S$UTFiKC!oR=@eF&CvE=sDIfi?%=&C;`!B5i>6Jb8~ zRh?*iXe=y6pj+Wq33J2icT}l3Cbmaw;6z6yERZ_mWlMT=YOlNE`^|;vN(uR3iRjIp z4crqbefwdn!?-%k{GpdZC++b25-I(qR(z*Fai0!5zU9&4!~W0ZL2|)u-Mt^i1n!O( z$)Q&VqrGW@*aJB>(=J}NSnlMb4yxxSqRVakTwdJvqt1rdz3F?V+YU;qHn#hl_PFT2 zSN2{8+TjZ^XARYY8JTMrPg{1%&^QDE+m(*Fq~#!8{xa?1LJt>GeE#SLi*&Yg`H)5T z6(AXSfoG}uN%$7hh zk$j@x$5uM^mMj*tq9enw6K6iV;QFY6ugq@TQv#pIwy9+`dX$_eFGAl(4F_7z3CK*C z85$ZzLA27+-*13eOiFLYZA~)EZm63YtxJbxwXNbjz+k(u{HG|KVyCGQw0l?H-G^`RThBh5(a&!a~>1m{I}5<2>Ar+RqT$~!C z>(1%U+jtHar%7e{dHO6!wuEPoOgAe>yVA8kc9!Bs697&qXi#`K_L{)*ZQ4K%yRoZ3 z5RZ&k(}8=t_I=-`_WC-=*sWv>v(_?+IJ@8M*`}M{beaBQi1Q&QPL4yFW3U;gKVDa$ zg+IL?X7@2b19I5wi4PvpFQ?zI1q{{@uJ@mI6O6q5eOV^w)T_92m)6tBv)2F~A+`-C zYJMbNz$DCN4rfyk^mED@wqiI16L82az{-CdLo=CJCz$^FxJb|BCE^Zu0FCXM_;hQ7 z4iTRCBYm%`TOaN2_K@2#3dS(Ogzx)L!=GG4-99mIZXlD!A7@;(SuNu~c#r2oM_cOQys@K`;toYYF zd1an=?k_H!=82Zz{m5838NoIlY9E_BjA zWIXNxIF{vlyAhMQ=jr~oCB|I!nOnBCzr$Z{onN*p2Eo0U^a`wtwU2r-5_T@v+Jmk) z)Ml#ui=5_=qT>ECrdY$P-=Xcim;F2epS8!Vi8~G_`n3;#5HC29uxG9LtsvVPQucw( zg9d`D*Fm@!XMKdP=)-RqU1>v=@P0pU_!n?cx1|xJ;NlHA>ZYu+W*H{ASIWw08U(|r zNg0L`CsbV-oF$STQAYB0k>3^ygkX$(eFv&y#V6`A%8u?IwkYSX*YqaakQm=lk~tmqtu=fjN=L_ z&x@LoKrx5A? zGYdw3!MJy9SeRJ6opJG5h-l}Ff-QUM6cA7)z>Vv%Pb-tkh84fno zOYu8_GoJfKu<$~|zQm`a<*ZHS8bo6hU~h(h6c)t4+hWQ6MGn0}c(GnwAt6ZoyxLF> z+ftn~*HvhC9qq7OVc+1V+lv*fGE$0#7bC1Y+OC3BIQcn`kLdg5&nq_Mqv`V+Fb)p} zTWi8N3e*HE4Zc$K?73Ff2!6&)uT(QJR3I9}-|$%_U-L~qVyGpueTy-JMOC1hO{1Tr~p8Z?&i!fhhH|tCy`(9Kang&p_XKG58Pc(5^R}sNap>kF%p@i$Uu)oQP;oQTl&h(zw}mwY z*q7kKlc<-Qm~Xs*wJ${YwD^x92nfcAxb>FPblMUja62_{cV}e!f1pAS zy;GN6l*P=1L=WliY<%AdUlNKUe<;?V-+XCtx)n-}!-77tsOa#TvkN)r2iECU(yaL2 zp7txE^kOrJB+4;{!FX**I|a3q(5>UvlAe`832M%qu(MZA3oI_Xx$59M1tTJ}_b@0+ z+#^U<0sUU?tz~$MEyx&@2OgD30qfsqKO*gxu-uJn^(e}O)|_l5X}eUOZfU8v;&pP# zk67)ClTx|7mDmT0QH$U5j_%pW)T5qw!9N+I`P|c}do}yUq6tPsZ(YLmSur$XcGQJD zP4*@4^o(Rm2!~Q^+LLk&q-A&z6k3jTyii>g?SX?JIxR0X`!%)NkMu_Jh#luyKH`yn z2FP&O5hg@mkcIDumTkM7eyZ^b?f?2$P|!|)hZz$Q*D+ZPZJIKSHbD291c;)G<9R@i zlWWHIXnwdoozcyFVkPfv#8=@TAZHEmCY55Q;0M=v;-(Lg@gwkJuO?<*D>|B4Q?rZo z6p`cH?IljQ-O#S~M>||@g9H!DyW*^IY<&C)*Ayn_RjGu?dS_Z%fut;^*@$SfAJ(7fD_}TQZ=B+H2{`xsR z17Kaj^(%k7IFvpuJl&xG?D1FNe&b>@(i%YP!@+CzT;BCQPd{YCN2;g@Y+-B+{#?J0(5v{yY4bpWR?fqrdgKLfIL`{i?0B_?|@1KOx&3pt~BBT z+B*JOXH)vyc|EPBjHv;*wIBL~3fIgX(mvhi>vwaO7V%ac)a7j^wlf$ithUbSBswRsI)US3UZ&O zvSGQgu=|FjHJ-7s@Ta%$23~Ag?!>QiIY?)|@8p-Y6Mh3d!W5D@o^KeF1HYt7_J#!r z9%o;QaoLG3jF4jVG96m#c?niuNF$dl+Su3;`*teGg~^DYI&2KR*r)Pw*$yy2oL`3` zCkTI=pSW}pt2oUF>ByXn5%rB8xs`EU*cP;} z+zAgr-}u_fps|+Up|+8ByCiR~e;E>AaceBCVfZ^ExVY7()g^=OKg91-!uKoSt%*o? za6yi|9*eQX@abOH8lKXgRz5v+@R?`gyNWoFk#ay^8$uwY4W`>j016FFXtb`=)%#97 zE}Hu|%sPOhu%9a5_IyQgp;Kyop1vePHAXe8qK}A+&j>q#nKH(x6mO1?%?RsnaQ~6p zy0*;CjEzfsYp6fn0W)LF=68lULZkaTf^3-H71xN|dp%d*@b*sl#|4b{{dT`s@p2mX z5yKB)+0~vC`|X6h2AZ7`%LBNu|NZzcDa?~XARaOxf8QfJ_G8o`R@gGanv7mh5NRTM zbr~zErs>G8ZZ_@VJ|ruMX3J{7V*l|++M*zghWx}Pyqx28*ysZ7`E0&qYs|A{i(=cOf)M;Z(Nj>Cx zMduy(k@-x-PI%T@>=3#x!|0y(ruy!mbcI+$n2|eRCrzM<31lZQ-mOGUQ##omIt}9N zc3eR+P5pPgtCP$ox$jua(HGS@g)NQ)?)#cl5T30^b$g6zRLmB~j zhqj*&)W7Cs^|Wa;TlpS+V=_LBsR2C67sph^!;FOGkL!;#8jWtcTN&b zaR>@@Y+wX5BscMiPj7Ct6k5p(W=PSZpW4Or= zop@B=B0hWKaWov5j>m&S_$gOX)oL*U9&Sj~!ANn3T$IyS7eta-@gUkQZ;GqmmoLpP*)*^3pQ`AP+ ze!jKBM#BZUGM|l|MW`CvBjVQ+83Yz+ufAI#fx>Dm<6;rAnJgw^s~^(So4GKJ^L_#H zS;3T_^i?OCg|(?B&WrLp6em3(r-`SgeLe0mhk~{j0`~{xUR0Yx8f@fUu@0JgjL=!J zS6k~FG)@+7mnTgS_*d1PKJ}p(<$XbjTa_84-#zA$rsW1#KfC~{!XM6kRb5VgyFl8> z!O?fe?M5yP%XHa*{4QvZ+b<8_{B{fD(C9Duf_g&Ac@^&qJq3S6zK2%fR98(e{%hJX z|FAj3k5P`$<_C92;&(ag zRv5>8zS3$#EbR0$mLJVSDG&wvR)UN_mw#8+?%-v0K_+F{fx#k#=4MXJj~_soTRrW7 zm!$T6*gO6tr281fmcqKl7r6RoTfbg;NjVf?OXn*25YGbsd9+V=cP-|hK|o~lHd9lk zvvGtks@#G&!J4m+)qYJ##}QVD;{O&-O?}7)dZq=<r?N9 z7okn{MZh8wuw~2jIpQlK$j>>< zecuVuTD&}cCat?2hSH1J>iAq)J6`A{_iP9eHWDsD7ISOr1i@B?Ip($~Pf-&c2uNcO zuiGBW$CXuic-Z*=4J^`|X&57AGC=GG8WWbxg7sZ@SB#4I=Bf{TAZOYexU^;lBzE?R zJ*ohPRsHS{v!v~Pt2+JHl*lNcD;yXMeDHf)_-NsJoDQ8mAY=Dm(_Dv2?0J)LZ@%da z?8c?5tE-qncB!KrMqPVS8V1679WyP7*abN`%^DxBT0@1Q_5Hj?M(OD)shPSD;9-Wv zi!-7NQ|tc;_zAO{{xRMFe5WYBR?6-wRhB;*6phbw&aFA99@jER-LtKxoTlw3AB*%} zL7G136ZI^qtgqaBG!Y!NFQ+?liZ6?{j$q&0NR9JYzKPml(IBNh>eNlQVru*dpLr*I z1zq|F&ife`?zsYqyu2dp@Fk$nrxD$Eqb0OUdt(~4{^7N|KFQ7aQ>J`3ec5fM9NvtH;TY>5;9O|5f4hsZ>4b0@ zr{&>6rFUKU!hueN74BXM-qYvI%LP&xm^D2rXd|+y5zj`ZNga(s{A~TCV^zSJjBj=FW?+~xTL#%mxLgoxgDJ~MM&l`Z zf_}H(HMPf{+eew+&2YuX)&d8@vR^fTkA<;5amP_{cVp9@3YpOmDs_N zq}?Lkbz>g?r=2jCnC3u5t{xXlJ5UVKIl1J*`-@+s zq>p=_I&!Zf;>3iH{YAkZb3XiaqF|>nRrlv0s)>B;YR=uxu_p85*e5_sy(}0`kz)wV@JY-7;$H+&l8HOZF*NcX}(GYjllNSsBYj% z|K3C00riX>V=5!S?X9W}?6UT&1&>`=sV1*ltBsg=CizDDSE@-i-}YT){(0UXSJ?QL z;mPoGI9@_-)*wMo+~C5cVQ>6@i%l*#1sL`<^~r8t_La}NU|B|#cVX&NE=E)oRS6M@}J|Q3j8an9a%$|0)$$Iln%T--gd{2U} zg!VzOF_QcEXv0eFKVgCxTPm1*|4J?MN>GX5XSVBEAij;s`unGyvcSJ`J|x7epXnSX z@wOte@)D<$`2rTeV1b~!;|AiMbqD`xGdLM^@Rlx7_e~GiqXJI`S0|CAs3JKK7_*T{ zgCY<@Oc`!jKuF35rnKFxLG9xO_cXJO23(U{<9;}PNf`CJ&i0Z5xf>|3?onUcNz73e zO6SsI95RiO{8C%dj+&^a=Y0t?!8|XGRhNH7XnStx^m|-%WX`QEdtKg^>=9K3o?9x@ zuCw8Py-bW8T1=>y4C1=}*a)S9iP3{(9t&H3VV3u!t$5eW%|M$frBC>EWr2)b3L&fU z?%@En8C2JDAcZq#lCx4?9yV~43bgd}K};#bOi#1|?@HxUU95pIf~p~*p;Xs0s>!ij zflT1ah^Ul-kzUwWzW?I#<&Lz{&FCJX?Bx)0p;omyR*M!?s@Mpy$uSq#A#Q}B`)(rx za*^!$+?6M(StsA%>s67N04_M(TQV}^oC!?)inM(6LCK_M7XwWesUz@*#3CPWr`+X3 z$;lh%Nb@;3U3hY~%+3ddu%H|f6gL*Z^vC@dLo_3&Q+$;@J@O{I-K1wV=$kkC>}G4M zl_wB43+-0pd@ft_gN|>K#C$+C*4*fE)6LqPWe}u?vIqMjAZ5EnBT{??Kn%qi)@*a5 z$2FG5y$BfaPWIT6G%6=okl(bTaJRP{zqjk_K93)0&2ZboRm&o7D2pr~u>oO)``~)l z*Th#BoQTG^C$!nrKXp4KvPaBt^7*_{RmtO`v!|})%n5D%MxoSlcu-xQyi8#z`yff* zr}XU>`CUaKuO@D2<8x1?e;ne@9IO4q!|kCfo;sSUgxtpVkNzb7&4Sa&^r^IDTnY^W=YQD9?QR(IP3^J@Qni%+K zrEc0z>uWw`vNf+(7(B$s`TI+X`c+tDk{)#vEn9{ih%)r58%su#urx}&b=6f9{s(Pu z9n@y~wTn`q&=zZwk@hq5=b_OXUJC)JahMUk8`{TtlM?&LZ z6P8l`6&VwMyRuP7QNZJlzt*he+2r%dmQ}Ze-No8{x!WYO%!FVZ^cR=0%NTme;IzJB zobDm?t5FR#`1e6Th0iilPh_Bb(JV}}K@WAV@TSqJUo*^tz!2!RtY>~KuyVDKh1IkK zlenIHv2>Mzq&1}E;Lo|TH1poS%|_k#nGer?zaYD)Or&q+z?vY%&d+b6-PJC)t|qlX z`fx55mTKtT{oAK=R%Ok;QoiuxNFA--m%2w_%D-kGZScKltoee0&zZsc`I-E6g<3VF?S+iVkhYF*`~l<(cZ)0{C+Ykg%KX2gi69!3m?mgE-4;X;J+ zyEA(v2F9lKfO(kEP$XXro=OqaSMPNsbz`=WtL< zS(v6+QpZdRmXj99jI*7rGrR`SM=ZEXdueI4W(Vj?=bV^F?sscFMr#&7q|LqS7u>bcA?G_S59KRj7 zc7J`Z55lhv>{{1Ro0VZFxpGm3HAUZLlwE_m5OR;J_&9|S!DstgCVekT+_VKBQ?s;& z9%A3FxIpL*b#B@>$D^)kdxi~Et;g6aNv5mIy6ZAZ$DHizd9^`swx0hmU9_{n!*~Nm zR%vTH-8mbT+++fl`MUh!1Co*Y6IN@il1=ix=CSHh)?5~2Lb)$<*%d8NbKN<(IVoi! zb`aXNeEb}9SVrhTxsoqzXBGE}?||*F%w5L4W9Z9VyQ72iQQf6-?qRl3NaI|bLh1Xw zIL_t8V-q`h7fGkGSq=%D@Z|RT+_-lgS>28#TD!z6dM8e#)JeWrRV*XbdSyrxV|&~m zuKgsz0VjDDx^od9m|8@lm1`pbC-rwRqu2E=EDOtA2GN4o{oU6;rmjBSs8(l5=vO-D z>mOoW&wVbNYcIkPx=KB{`8oSrZ`0ao?aKDGbd)1zLN)v@|VS1;3k_{VgAc)=+8vk6DYIrWVb7!3o#eI*3>5 zPI}9b?VekjcgbvJ%kb~trPaSbfb>wqRt^7k^X8#{GU49!r+QsdM`IXI3F>o=iHv&1 zM}ZTD+=rp}=$+3eu3C;!vX;yLjE`VzZ5{+U$8K|g8F;@9FFO-4|&=n);Z%lNK8?&7w6 z$ogC~<#MSO%E1!%SqPmSon%-1n)LYQXY;wX>V0`f8!PPyHcW?kM0~gA%Vhnl%{zb1 zRDqBTPt6)Oy{leYmCDNbLmpXgTW@l3*pO_Iu_pP=WZkzNEE?$mEIzfiL*pViO9kV_ zTV!_2NQ@2exES-*7W!t}AZ;m0O?cr2@V*UN9Q0*hgq-{1|KlHG5L860WKb>IKYe zbIG>4QKCT&2fKZ_BX}W%eLL?1 z*b{kjxK*D^tqfP!rQvK2HmP9-DB1pSkAtdaS z(+J%$UI6POhP(;{R=xS}7t=0}g(QIsh6KK7 z714_|k)tS9y<~n68P`3NnFQT;K0+@5H;3r;Ct_xb)fdLDr&~zz&WpRoyDDn;tUd9{ z_vj%Fp6Ind7uN}m?pFwdF_GOL5lRH(f92n7$A-&VFqwQ53W+KHT>5(#<_7cmx-X`$Z8) z$4RqC|K^wcQvIGT=Whp~lGm#lD_ncezaq;fjYR{*$-cMwGfqbNlOIKeRbX0zA!)exQkky(*w`R-rQZx0v#(b|?b=W=ceF%3B;KgQz{kJ6HV2Sog1F#eCSpI5 zB{hZvHHBe>BH_A*v?-Ok{W_N9bi8uc<{FXBE18=+RpGY2>Ep1wp?R--4x(PdUV1vr zN|10w1m^7@EK6$CSh4Fe1bS=R$gs+Kugxu36B~aTrvRBJH)cimih_dTQHSB?RzzHV z+1*DR`fe%dAWui|?TcXqY#ba8>t1wJ8-7>B-D}rSmh9WtkMB(h2zV(-?)Hh6t~V9G z6{g@Ihlr0lGnK6&m?VZg&0QP%NUibhR9Y{gU^afRVhx+#oIN#HFGdCtU}5h6;}j9yQYuh_Cb!|btvSlZ4K)>n(hfF zV2{PNmM|Kymf?Ot;pAYTa>t7Wi@oLOK_Z{hq*{zpXSn-?$F-MhtNrbWHVaY9ja(mG zi2FTLX}m0inU`d{cc|VN5VjC3T?{5MTqS-|za(1fH^6aIy|4REm?8}KWch}hZHuD@ zJGuAhLE@%bn2aGx5$I-}VnYO^kF@Az4lnc<^6M&)P>j=ysKv7|6ld`z{Q2NCfi#eL}09hv^rxnC{6X-W5*KD_wM0hMZ5k(HJ z<{80eYQhoaI?_M~;{_@QV*Ap5w|waRz*bMFrth-J5vTD7N)6z1N{mIa=>>ckT+LE*b6LKr~E^9`rg89S$) z?3~-B*qOXa0%Y_=pNZIM!e*o_$@cx<0TBAxs9>=>UY=>lqQ8FLYw#}4Bcyq)t`HKw zbR4CDtcu^rH;0{NAuYG3)voQLaUkmc>-oyP;A=t-DqO?+bX!jD{OxJk)u6+0NS}pF z3(y>Pi4}=L<^rqBnHI|#`Rb8__rrldj~Y)KOdtQ617{N)vXBc;1^eD*#a;ClpP*?Q z5^z*GD44yd*V&}Ua4^~!bcx-2=$@3>2)UfLcHRtq{;U{-@K%_V#2B?^%OE!G`dv|2 zNuGle`X+rJaBko-1T4SkDtz8zC(bxqVR5qAc7tR8$xOR_ChbQ5OxWB>iX%iGq6LjTqm%#r!^#&IU> z`^ZrSvS{t~G<(D978~u212iOzT#h^QtmAkmXV#QA=+gCmb_i`oI4LYfdllBcG-Zk5 z&LrC9d0?m(BMe&f3hED#PELQKBZ}kQ5XB{#68;sDh?6H?C}*}6Y@)@Ta!W21h`~2G zGePm`blPiMDo_Z0C?XHzk{Ha(BaOF$7){;_8dY5`a3J1q7*6dB4vCq3+M{?}{qktO zszf5pFZKz8e;4x28$;~vM7{0jpt}Iv*&-^)ph5Mo4udxQD$=O9FB#U>Bsg0<_tgx*(1%4p}4CU7i>3n>D;K8^c~_9Z?apJz-!N3*}9= zu$L`t5t8UXBVA;~?x<*Dt50FAVA4-I`Q^7FmOkj#SEP02yR@yS?EztZY|c=0{prou z@Pj;mT;ok$o=GVs6TKEa>%f(mK?QUe*i*R;&$Ih$y zny**7H!c-LR}%K}-;-U~1?b4%(Pu4HR0OTY%Z)$CG7~@CWWlYscvXv3*KaHt{#kC} zFBGmoPOhZ@ap4x>$AJBJ51l>jd;TsD=5$JT0e;ov6{}oSTzjn6q4otjL{QkGn zdqqd^CKYT4gW3IsB{eY_Ft(_Jgmqc!u0(%N#1*5u&R)U&eNoqF(|1E@)

    QnIa&2 zu~7@BV0RTCU0t6*{zRJWD3)c-##~y3`CE|jxo^04(egEC~;T6mtr?HlsPGI zd8l(a^3a?bMcVN-vuP3mDl5PQbT|@<7BW)qTK=whCyuUu-rz~Nk?v|G7%^#Fes)u! zakErTmt99JIL6`kB6Df@9>{myeyqr{gFE?d79JQtJhOXv;*XZUA3L<{FP>k&YZ570 zk=^h4KB^c^NoV2RL3!rf*ZlKhJ1m6zng>|ck-ig`JT=2h?!+&9_`UrkMf^VDW4w*P zXR_ZQ?_U9;uIdICZi6KKgW3ZRB%FEbRJUs@Vm3f=P-FZQTun`)=pn(Q7im7-z0Wo* zb>wquuu1WBRtfOGfWlxw?%#0Xz3^a)wgMyR`Go$A=NqXpmHBVlN0hJlPjrR~>04Op zxd9nd_;}L0nIdY#)GC@ck6w@YQl_3P^jsa8Az701mE;pq0`FT%G2{o>^4EiJ%LkP8 zm4_rJ=VMb6xo+MKiyjE3mh4v)Je;|60tE=ZSMYKqjyj^{(*m?4jJVw$@BPWX-|fuQ z*Cv}zU5YabT;v!ZG9rW!Dx}s_x>112^8Dq4`VI9Le3p?FKR+46wr&^unB<&%lLBUi z@yg0i@M2%uELVkn1Od9VM8%l7@bjl>Z(8btT63iGnznYfS&ZbaCY7}hMF;gKMyVmQ zbZU-D!V`C9Lc=jRBqLp#QG?!fby)jB|J4hS!ip56GOKp)tn6F4*I4td)y7aEBCs~J z+a^B!wn3z;bs57;uQ}{Tmr6r5CsWoAIr58;+oq@`89JbB1SnqyBEoxCYN)(VpXF1q zUvzz(JPI44lAqYFw9)jbeN?o4_6O!rwz$Y(qR}ImhzbE2OdyO@lm`iy8+9FKl(g`Q zQsoOP;ZlQdlKbI?9n$Rj!uEsNGDG3{{oals(} z@7~GErXW?09;ojGPfXW^1MDNTCI=?Z^{{k4PDc+O#=6@*0`CRSIP5O`WG-*Lm|D)I z1`64Db@wL)2`~6`HJQ|yk(klLaRaB(?fT0YwH|n~#+_*Ny!BNs1JdVE?50284xUYt z58O&IS?EP3a}HU+H=FsGeBr+}n@EAi)nSsgtL7Lxl9a9A;}wKj4@ml@W^3-EUU8c2 zxv8ER8rH{$wa|zI38ucuyJiwCKefnYSM{H`PT~UX{<}?MdfgnRN9y z(cZ$>%XprXF;UVlZOtE_x6&z>W7Hb1eb405nr8=FZCSM4bJ-Yx|57Th!#1~W=P=;I zYHreC`1v(b(l zVF>kAi}(29OTIrvmUSN(C#aWVkyYu*s!&Ce1-lG=Z`WT+I2TQmy0bS^L|PMBD$=&H zy5gO})C}B=M0(WduVyak`e5U$0>&=uUV7n)|4)G~{++_#@N@HXSUo()t`EZPNw2EU zeRkt>sOJPDO3zE!Dd-z7(blfmXVoj~!;D61ETj2+GQlqD^_rXe)RhjPr6p}GYYRGo z=Fo=Yjl)nvEl-!^*+0MqE8Uc7UZdTF|Jj4U_GsCRtwtC+$@s< zCz4-}K26!xqt~#^Hh5L3-LbNs`LMvj9+Sx>AYSvTVU=ok{3WlBz7}(>nt=$E170v& z>JC`Ck@!-dV&T7H>=0ltJ>S`M;lW*RC{yCGzVpSfe4YcOUXfeoQ8_5T@6M(ciRuGH zf4?L>zE)Y+JKR1yYnS7xDBo~yv}#6rSh9%wA0AdedjE-PX0&(l8`g{#*KygMW}i6% zx#*X@Cv6ZEAHuPwPWx;WGsNv5G}P!Y985pe6vT%F3U%#s(e-O`^!Cyx@ON?4%FK>Y zD1~GFai8ktHvRf2zPWzz4s*)A@m+__x^o{6e6A4wy$q3!pbHUBNSd8lL{8>cyI0eQ zX;0Fayu2<;$kcS%jC{14f*k_yP~6mru=wDYLZ%M8?R}3O?yiRO94}4O&L2$3%U&K! z8Q@BFHg9kg33BV7=u#o(KdXyy@nAlaW9+^0j2fc|=!kHMK^yp(R&Bzr7)TuxL(lKh zA6jDiHAaQTqMMy=^xrL~ zhHxst&xXme_X+j}CInfWFSlIh{{yZ_ZR@Z5rda5vwqXAkoI*u~oxA_;zwRU@^?wOt z`u}>w|0=Qlz3Kn)?Wzn<-h6%aF!B5_u~Yu}pKxptcLVyQyfq=U4OW3$;j2GOOOb!q zO7!nqsnf?Sd)T8#3^CxKjWSRr;@=n!{vQ3`_-+4>AL+lNZ2!MY;D76O?IYcEyNhpg z|A>jwS>C#8U$>03*kfx0{dwe=T2os-gy8UUzz$Wc!sl}&1`dkBhkdZBxXwj1;ITrN zFmcmU)EMmY&LM)cu+$fFIbT5iTnA@IQ zwXJW{`B=>7A_ddVxu36#G--gn9dxWaO<{dprx0t2jc~tnzw;lFTyaghkC!z`-swW^ z%aw#Q%Xc&-Mm}Ms5&d`b|7K^>t?}0#04i63g-n`d?C`b;QfaqDb@5>I*k=V%gnj~{ zJfCA;Op=g?dHTw{phYb0KlVhu1rXPp(bv&}SBxzUO=s=d14k1NN5y*bpPzVI@}o;k z2`oa~JW=~UI>G=GxW985ZZr?%=$>PE%wyUbul5ue*6H7)pd-Q3RNIbBjLAg?yJI!K zrRoO36e?AQC_pFf2DghHhorWiWz>*waZ@Y$gKZ~>Mt=#C;hHOZzh>|*SkDPfcB%NK?o<(?X~wAqHe0oHNtb?$M*cMzUK7dKt++b1c^rA zhgjtLeY=H=aW(8E!3VbUMXxpcNMXlFV5!Mj1=pW>>wgSx%`qL`>np`dAsUQe?Dh`S zo>z0YZ2wH+%)0yCqS#RK_o1uql{F^{W$OtMA_PQ7hyvrMzgD>XI8h)x|LIO2F^xcx z0F(_R32n8nzzkvu&M7~7zko>adi!~^sCSW~vIHB7D_B(Xk08+DnZ`T9>>9uah4V%x z2O>E>8V(0#%r6e1L#P8oQ#>CpJeyd64S-IU)Y~`m!=I%=C;RDR5nEaJX%y#P>wWE z2;fK#N7SC9ayAit3VO|pUw$!KnT{18Pk}CNOVn`9>EzHo%ALu}jy3DH?YFe2^YSCp z@UOcgPPS|AP{0;!9?{j+jlr+syO;yv%P7lucS-D<*3}7vZiKX%4kKA*M@#_~$NX~W z$wI}S6Vr27w?U@j+`O-rA9BVi=^MTco6(K6@To17iE5L)ssomQ)F}nr3gfv2BJ%fZ znyeP3Z2?ektmd4N<(AmiWfIqH=B;V=w*ZO0DH2!L3x-vf;w|6APZX}okh`$@oa3S= zW_C}(hP4H^ns`^C>0`0Mfv0Ew4)uTb*1DsCzPCR}z>VMc>=< zS=2e!Lx(BK+rygOZ1T%ad~|+!k_uqG-@-r$BZY|azj~4(ZI|?DTzepm0v7+gdJH7o zKyOB)gr4T5w+rZ*YoP8_kC|3onK52ISYS&chMN$oFkSnY_o(j@sqW~YrEvr5X}e+E z{4t&P@~4D4%T}kkbz+7<5}_;@9u4qT20Zcd6g5~?d9xpJL-v;ik#eS4IPdwjmjVLL zSK|2r>f5c&G~+u#u@`&rnI?(f8 z(hJM`?4yj4pz;-HOUbWdZQ>^`53)3EP3<|4TKM9N(TPK6rwa)mA~vz@r%)u4vql$k zw@pzPql)*ztC;F7?(uiGzrXKJ9Go?SwqVCZBpK%ntHfXZJQv2_-B*9#4HLBWJSv)* z_86Z#foxtpHiBlP+Sy+tA^*B*EFPfX@t8&6>G%VULm22lv{yDLmyP2<3LdojG7ZQF znAhLhU?OeNvFA2)jN7wr_P+p<(x1|vZc)Bx{bxhaCV{t##8bZ6Fj9T{+P-4MbZk7& zZ^J3K@A+kTNw#HmMd8h)FHr0J7OBq*31tW?uP(ahKkJZXLDZ@Bx)6*VZqI z1ERSP@#fLaUz@K~s;Id1|-OQRuQIe;hZH|FD-@_g=A_hD>V=Tm~pPe$(^%;%a4#_E|pCa|E zbcFu|!3eXKV+h|M8b`Zaw)YTF6GeVcgIqM;Hgda?k5ZT@zFI4fc|Wc|#mExA$#?k5 zAfc!WVrt-1Adk?oboU8qS|v(MC0--;&kgX zpKdZ4DcAL#P?7^$5KHWX_K2>JFIa~&q*0*6tAe?=^rMBlzbv@7rI-MO5Dm^T8)1ry zuoFt%pgD#(sV#BFv>4r}UXO5|I|1c8CKYbg;jN}YV?!&VfeAC$?@~My$h~8%JfVfg zsc|bjSEbFgO(VJ2O>Cd8ojdbqo((+or!X&4K1iFK|RuaS-% z`KO&R%6oHPBU9yl>G<8#Hln-KUO{BRi2@eSzLK;m%$N zP|}?Jkbr7E+F6f?$Kp1vND{@Tr7C!1%DQa%?K+BY!P#k`WuXxe#bb9}BjQFqW)f1H z>{MwPFyINB@iX$8it+uPDrQIunA#Hx0AS(YKfVLRh$4h$oH?Qy=cFkfNWCJtm?Zf% z@HpbTu=Z&Wu7AP>irf&a>2J!|bo?+0W@`ds$@?d%%d7j&reTmu&x(xB_BN6? zR^MzxI$@5jlr0t@|kWc(k8W|BFuqUF4tj?)Arw_V$^wvq~ zerfsD`Q++j+KrV-=uHhQ1i_eos|)56He1i1P|?t1EUCXa=w;4G7_toe?51pW)zWuldwyB;pw$d|o$fjAKh?sN3$#+U%HQzVY-y84w{9)<@ z_;Ig>X!XwFB`)-&u$m@rSUXbA*BohwmQVyX;XUUt=wCRk1sSakM$%V#7e!XmiSLWEeKA}~v^j;SG3nz%2X*oUuW=Jnopt2vZ=~)}hF?Q=WX|)jd81K<>be9GyVLKmuZrU1njo<>jJN17_@S27m zm_IPfRuG|E`eEeYu36;!a!kbr?82TmKuhMMg@}SS-OV!8^i>mMqd;7`V^f0*6tCTj zx@7(=^7@c#FpwhzhL>_SgY!{?mwW4R{q2)8$~f9R8-)FS^sPJ}@$jJUywaoYSKrE{ z^BfG<@x7?rwiW4{v#01eX8S208(a6MXmeK}GkpW>kXNW!lnt`ev8p%@e$ndWRCM?B zK)E9HPqFCE@$cYsQ1BLPT>Oh_nHBYm1T*{5^`0Cq%FiaoNjTcTxHRw)KS}%@(b#%t z+*7~EEuC*>g<9(g(0N{~x~e`QCWwReyTEf}l2r%1$7Az zg@wgE?$=Hl>redE1nK_rc%uHMby09>*&8ja|Ws6TApQgcGS3=5dU;f`lTJoJze6 z)PkSqds`{&&`1Yh6~x82zn|Np^+~pk4*uXd$K(VBV~wM{mgs=Qx$p8mg=tuWq<;J;(aYVw-P~P%H5fM=g&5bO>XzEyx2l>ufJ1r$UZF+ zojjGMnZ{*Uk%I>>e;3gBSrtjP^+K^y(NZxGEx-KoR)nf2-mSW znyIyp8op0|<+Cj$3Aar22rfrNl(Ep*yI0?M8}CH2aMIY{9E_6<%p;8MS>)6J{Knuu zwecw|@2VTXkz5*4Y%X%kZHLJ7-f~4nSMp_F#}lJ2EmF7#!mcX0On0Xa{W$z|Fd_(| z1hOJ3-wGfNVL&c(BxqvXBsN`f={UrTz{j4%#VqKLi{JALbYAn5sAIbGz_u^Z!FapX z^uSP=IwUVX?N9iw3D?GsMK3o6ktO5Pk~uI*kdkCd-MSD`ZjqbAuBV&J)t(^6JaUk%we06le z_oK?CLp{1&AGY%>wMC?j z1>3tdn&ZYWAMe!t=-7ER#v6f2Uwqg-+M4ImPm% zEW%G(uqbf}DiQNf=5X$C3QBE3giken_aSd;AaI@=SpsTEN&Mmk&Z@Q^Y0q2@5*(Y0 z+^J*R|9PnR^8WaZ`=TvxlIp1%2IWz{NQ%l5!baHH*1jSy5;EY4l(>Nhv|@e#YY{{e z)OhF%m?HCPNZV}7Wv%#fU0%3%Y*{HVq~{8PeO2DN_B(gtpx7?B9rBp*5Q+XXK-?5~ zKQ`*SssJwB4nH3vK-&$jdoPUt`m>NG=30jLsPfa=`y*>RBzll&EkO}RdLXd(fYpQR ztnKdogyW&-=DU%h6||{JobJcrn#PW!=DNFME8RnmF4>*-zARI&8bWA>g~pucF@8St zZaX7N=yIw5>Pi92m?SY{z%(i^Js}$BIF!Q^7B>{=ffX*gB6%l@#Z~z-VR~A>3_$ z$gp~pcLDAc)*4c0YkK`+yh(R?sn`s&Z2~<`#2=&LQJ4^(^Y&E_6hAz)Mz%blho}Z( zg@)Xsrk$*t%B2PJ6{8@p8m=6-p;`7wM+O*%M`YFdLQl9|=X)FSK1VuSxeIj5nw@>- zhsSFMHAGGjyEoptk7~5R?7d?XruQJ%wA#NGGzg0NC%iA&SOgcUE>EzQ_w797vJ=Wu zJQr9kWNRv}#3EX*JP7SB^Ah&h7p`vg;q$TwoivqkYzY|Y>rQlIvsoPrhMG#!@kRu7G^=yg()~5xw%YI}O15e28~3 zDk(BBO}HUhs_)L#0v$BI$HExheVl0ps&pbl9yCk!{xCk(&{n!nqg=BwbRIKWu8x7f zyIB$8^h=zk@wt+`W^Ol;kg?`xO`X!d;et-SIpACA8OuiJbX4iI;1YO(5P8n?n#GP# zJcpA)swNEkMs9qDyj!wkKx<-S$AmP2F^U)!>a1ChA6y)s8StAwYpM=%qlz zF};~G(QC7=we)6=Kj7z>`(6tk ztc`B$N)j%MaJ`_`P>BI6TEz^9241#-fKxh&@>$lz${_(CFzvVDhrOGQXEksJZ~0w5IUclg zbCge5^qgm_eE4V29c-9LzVEQ5a;5wt$<233{wBTX^Kl2UdXD8`y{d4XAIk}nN26#3 z68fg&L{Tk!>@Y0y^qQfIqV81W+Mpr*=T%3ZC5X0tWs+q}O}Et)m+gK22FZ4jTKB}N z*~G%^`?gCVTY#tfnG4t^lZNe9U?N#qNt*4VM=&+1x~nehCs6xSeaTkZ4663oxk8f& zq^cE=%F?p6a2pu4xL4luXz35T;xA&g96P|*@$sF{{XTwIaI_e&=rSa|x~MN{A*o~@ z0(bEbMY(*)Pwv_81BwtK8UT?RDo_ND zkZlHBF_#3^WTZEYd^Hm3Z`5#o?!fonurh?Gdl>M&Xeq<&?|TQ*oZmcZs4y+^MeLg> zD=-CO;D-M!h*6?AjNoZKjfys59`~qP81k~fdQLG=oGgK^i)cvh0mHonsbZg}gC=-6 zVf9o8gFhbje3?(ooQ?Ms$On+xNa98%@x!0ZEX*E3fZp;zfZp6O+h-qzv1 z(1=H<5O(dA3py$eT|dVjqfPjdRr_H#Wjb*z4#^AX_dyY?;Eki_>>P}D-LY*Q6It~W zh+(IMv{Y2*q{cOi?9ogYOjhsWb3a)#aUvSHTr0=)~k_tMTFE_5*1zC5R*3LpH`(-8YLB6n zha6;7@ilU9D}7R2m5IF7j>JG;KyugBZ#2Vf0|E~Iegb2+b!UTix7m(t$;sHa*G+Z{ z=Thf=<+9N37wM1j@wH(qlEZ~&qTk4?RNIXY7Qquu?b#iFl{&m+Ze zm)wy=v>sWDu^h}q@@gDVRmaRe#Gq@}r`0#ZMftVSvfw4XA5kCzJLkfuXR;=BY_b8{uJ~_p!1{`PWgZq^7B6e|I6tXc32uWoFIH6 zpCLVkA*Yy;D7it$HfH6o!8}3<*)X+jKiFyfUlFOO%gn2d)lZ!wa9qZ{hbF->yU(!c zW0JQItCmJbQ&8rz@SL|qDA5Pqn+1{4W;k%OZ8K_Q(AjMG$l`21b;Ov*a8q7BaCCa* zugEX9lF_%lA`)f8r%1KGySRLz14p0kvtu~_Ux-wy%R7GhCMVL}o=BeU36*|(j*k(t8smjOapw--i}YqkX&W6 zdxc)~(}WyXW%pa6zSu{}qIslA9}z9-Ho_l{ZtnyxEIE$D;Bv@N8js{`1=b(y%k&MC zoHVmU$R#GGrFde!>~P;Y1l-ugxqTG1a&^;b5K@EvIq}%uhF=dT{aDZ*9=vti6Xb@7 zGhXsTVg5g6X+GWahlX%N%M!(Nv^cydHiRHO4J(`_kj%}7by}`JwBxjw=IxFN z+SWHMK7+ID)4&3;9A^&WW~Vweo>O&qQHIh7nAjE&m#nH8Gp$3^)bnwCL zoP3n(&X3HET$M@5*<@eyuL-Hz*}xc}{!`{^*Too76Ma z@0=XCeMq>tP&d}lTTd59EL(A7LvNi64taLkP}aD_rgEd5Yz7urD>LJe%R zi*o}_tX z1zZ*pxTMxQ6r-z@kIYb9{4x~g{-YlG)3R`H`19=v?#uYj>t^P;BjI8ECp^6epmXDa z4IRw(*CC79Lv_LcIYU1&yKF#Zrb=wR^JPUi90y7gO)`Ir?^x)ni&=7mX?djc>gL%$ zG7<#`c3iT6!*Xanq6+Y%jpCP>X}jdN6Fu?HpSXC}pP&X14oFDZV#ySKdc6}zV-_ko zQx+Imhbow}mj9%^xb095S?*=#^@^Qx-DVGu3+UPyE})5ft*U*`-*Mk~!7-M!BZH_9 z$<%zA3^+*Sl9{+-H1tjl3Q^d5f|kAP0?~lMCC@#5;KLH!!dN%VfL@K z_Pb?%8R*JxR6hkq8m+_xo)%z=e>HwvxyaFfN!CHEEkN)x%_<~>;GH|2CzaMcLRQFL6ShXYPYJu-T?n-e?RMow=} zOLvO{_jlsGro(T(h4jG-Zm7_3ziQY^&U^GXNR6o<5%n*cnR#3F<>wlsJjAcO9&M6* zVqL2XzNDnE@wfWp+9cQI*3PV%rY*F{Rl8Yd)`=Nnp*hRZ>|$Cl$J?J+(*V>gY(fT2!IGB?}@lcxVf zmyZumh_t~^R<*mLXc~rMWjJ%(cGIGdT~JbfgBSoHqXK4^={Mei6rK|!4`*0`+i^|} zpLj-7F~Xk@BTS(21qx(8AGN84W~Q8?lJ0{*g5JjC8i4yrg{Ft!BTbi63f~0-8OvIv zeK6X9^DQ)T3Hh#81!Xk+2_`FJ4SxdCRYGl|_@?-MDZ~~!BId?Ee(f#xt&X|Zl?nM0 zbekz{WY6OAI98TP!1BeseOAiq-Dh1U@23o&-nbK{ukp=+)GVl$&RY!^wSYPKl~SKg z$(RNxzPS;T1Wo?~44QY|W;@6*#0Ka)FK5Mb8ktTWpY%G8xbmEA!n&B^vy0Qjlg61T z4a^SlwfgfXEAO#|Fh$gG7U-aVWPHU}6B>_vHBqYyI(8Wl1kuI?a*Sc9Y}-6L;*V66 z(ILo#=c*iKUenD@owr%!$EH+Eo94IAb)O$|S$nmGKph?O4`K=4CIs9IZA*L|cii@k z)93&liI*lc7a39cS)pK1zo`ix#MP+KQ7}#G3(<)@qXut&7g}*j!@_u2L6u?MzE;NW zD2}hsAYwc|*=`DSDti3F{oRUaP`D+ww+Nblk}YU!H6Ww)8er?Kr(KtTh4f**cG4AA zbw6Y*k3l?VE*n^$W$!Dr*k@NP{A3_ysu6gByW~h-Zd5O|+m)evX`jum)fa}p^efBH z2-DKoK<>o1IcCW&_KAW5;7dr{Uj5}zd*_v0^}{}%ZLHRw^iLW`!;y1`44qqvh^$3n z=3l~Wk|np{Y&F;McRkumv6azR#%EXvp)J$y(J}Fjg$WeQQ#B1@CNfM4pp*PRXK(DR zVt#HMd$+IB$|cYw^GWK<{n4grpjJ9bVnczSVekrFO0(dE)ibO!nP+C4hy?gjoA&$r zjov@?PV`w>FTY9^w?oFwf{$Hbvi`-f!&bzDmJO8_K#?oSFgaW)rl3dK)qAM$M&=g% zK%^S%aqW{EG69#DA8u+Ns^}ZC2sa3+o6h`-+!_7K(MicqPQ*TPPy(a4vja=re0FPD z(C~y-qP4EdQ(YGP>q1WKgvHh`rsOnu%W|_n{OHCX4!)NLi1etmfUs9pmHsp&mOp<$ zRQ-L@?BJ|J8j+ZZ{UtuEzPI?^R78{7;68+g8JCeva9>y&@dE&l+Gm-EFiT76@!s}8 z8-K{r5z_R0L!uwBJUZnt#;sIRc(xBI&hU&yZD>ej=|DHJ#|5o&@H3)6Ri*!SIj)6H zd|O0I)+W0#-M0O0iABC(Ne*L1>&T)e(U#l7;#C9fcxTTrac0XE-ColIXkTm_yGG6= z({~WP%@HPJP!*n8YhU+^=JZj*@R&#MSeDg%$az*6TUKD`wbf}UOxf;iBR@IJ-?)gf zUdhVy9unN`s81Q@%u-NFppjGa=BQ0ZHY>3i0w~XhD?hrjpXl7D1(t-r{Yqz*K(J3g z=yb6ih$>ZXxyw^j%$@Pz0(jyWJQ+zG31|2IYEGT7J;yG-erj#a+Y}@SW<;eLwciZS^qJ266k90V=t1L**Zmz`g4Dc)UZel zAbLu0+5T+&X!czkcIWoQjv(XX!+>}u>3tp^L?O=UoiaTR4DD}?1B2TF$oPa^)O>?w z6Z+?kEEa#9zI|n?vDzLzd_eSjp3U+MhcL3GW#R7dTeA&>*BkA^>FS1(>;}~nQ1kR2 zCxkTr?TcNGZyZdgRkYLuV9QxBH~(i@xGX=Aht($pJ=yjwyaK#? zS_YE~YDL2a2btENG&Y^d+3EUkr`n zD${e6bNeDwYjM?l+Y<YDO za_Y9A@yTn`p%1oBD%rQP58<0M%5K>5EkfQWYfCn3nI~9t1O0N3>ZEm$T#a+t;+f}P zuw3S2yJ|@mxdox6`{{2-yYPc`QwQyrr2@o7BCwqMtcqKbJ-}~zn0dmsA;fWYPW_7D#p{-$l?b71WW$??48| zKZjI`M!)$SKNI(|7s8t7aKb4Mt2S@uIyxG!EMSs^gne{(82d9P5Gj`u8;WFNB$_Ek zjVSk}T2~$JOm^HKUhINR=zY&kPl0-PR6!4=OpvktOWdAEJi%~q)LL^&ihlSa&?$Hn zZDMkDRT)Cu_auL)L(2n%ab5v`QwkX1f3ER>_xQwVVBNhOzAYK2C_}@Zc~D>xUJ;YI zvBfL9<9}`{JV(lakv>6{Y6F;r6ji_sJT>Fu)(X*QI0zE*fdspBqVqR#fBk1v%JWJp z_lK%m8pJnA*E@^}M9bvYNlZ$nQv`$8*WcEV{5Ic@T<#9x2gzo7`MImAxx3QNCNdSb z+Y#DD*`#Q#i63Trrf0V&9`I0S3^Mo$P3Ze~HWE|?)3`l^2Ct@@ywsi`lItX-1^|NE zWL^yzh}+J6n=Za0#-|71F z2_dBCBpZl-uWzrI&i(liV&DY5bX{xy@+Gd25#7Dzicb+rq(c#>!ODd$MI&1MX& zM55E{W{Nv4E7!NDmq4MWD#UtHc*HF~fzP89OCwjmFK&hu?Szru+BH@vFIMcD{5B;` z$T>WTJ4$5fubuPGXYcq5d`0^D-L5MsJnb8;UB|5s;qPLdKrARRV1(JFj#ln>IHa^o zlyL?MsztJvRE)<{0+JpS4y;F2Djt1;*)RHQnf38%T(L;p=_tY{Scu{g92pO=3^OV5 z6M87cD$OK+wtuqp#T3tWLeuBXodSF{L>Y^pmWAo|CtG-$C>ZpGpE`i;GEA(rOQ!Ml z(`dbO?6&TQG1px$=Hsp(M>o(&VDoJT<$Tb`d~mz?V~3>cNy5^_9l|#>0I=ezsAm>bc*f-Bp-& zn@%2Tkf8@YO;?OREd_{0|5%@EJW1>}d39jD{k9O?-%7Hyi-7s2qIVP>_*b-rR~Qxd zT)@xxpl|K3M#aOUhJm|7V=|bs1E@A4^SC*MrFkrnVp_bPkHNoeeRl`zEDB$;DxpYs z{bDZzzbrdb-PW75gl#S7LVHxIPiyO8#L|@rml?GT5noP99f#P(b_j(S9MU#e1dGd% zjErgxS^qX>eV$@&`S2H%w{cN$Yi{5wvuNxr_ErCPPCCv#rkgeD&dS^P?XEQrYDU~0 zXx)1--jlJWyhzYk121fh4e%-CCzAhWH~#ZxsZzHgi)wMfMlZM@sRe9uS!h3f`buX& znOBl{^yEa)q=F2GMMu+Trs_rx_U!ngjN%E3PT}PGi{elz!zCZMoI)76Yiw1Ytb8^p4_SGlPJws(%J%I+*rRR>5s;io;d&-G3+QEuR<7jM|>3;2dH<_@$ z>Nr(+tTHdLpvJD!K|Lx~<15{@2}D&d<2vWvx&$uZlf*B2dE#-2Gm&(vCnHT(pP~Du z(GAcymc9x4Od4*x_xismB^EaZ&u-el8aq2)=IY%3`Z>O5tlGWVX`H?L*%w_*75{TR zs5yu@OEC%h!v%hIlQT8+zT zDI?!OO(65znCG4n0!kE_(C9$%nid^%h5lfc_d4MazePlYw$kx0pFUl`+r?aBI?{C$ z57;d0iP`H&3VXM%XJ+l^w0t89Z;4Sa&kgJ})LqOF;bWpEfknN&Q^05JHq#3h8#4DJ z8%_55-pDwZ_(k^wTqeqI6ssG8eG}k*duf4==wC1&Of#Kj)(dP?5mv!xxT`bgM6b%R zNjOSO&O`{8lEsA+yVZ(UN;bjkF0Yvp9W8?X?m((d zXIu^(oX`QrhbKuHn@S@$2PniKqF1=&M47q+ska+$DPY&YybhLb+#Zq^ahXnBs^*?@ zAG9e`f^{x^N5Y#AOt)kdX+2w7T8zIoSULnjAh)=<04Bu_jOn@lhf_jv1yS`4X8D_f zqA$0>;u4*4pDo3YdaG(4(6##(d0MX25P-iB+l$MH}Dn9Tjfj~1EiiYAPhZg)dM;~xOjBC|Db zN8L{rg^r{OH+~CbTI@2O^TRN&jyVo&JNJRp3Pm@w_aWg!0}{tF!?&VD#2v&; z0OKDuLWdAC*$4vBlsK&;94kv%v!7%WXrn!fq$7?b!bHg@olXr6>$2Y?GqIn`WI?EB zttYkJ8n8=xFlwh-<5U=TeW?(FxHFXFS)f4`dV#ict?W6rL)s&Im_BL6#~__IuZH^b zR>G(Y5CFahY@R|@_G%yE-i^atI5L0eq8AiB#L_aK!6C`A|N2yw*a&Ffiu5(4{g{}h zf47sy9jPKMy?Xw{5UzyZ{5y_CzaQG#b2yBzHZ&aVoL<%j`j8lX^QlIrg2>S}yE*F8 zXI$H7S2TljoBA6QC5xmeovvGN7){jgkxHX+dk!4Q@1x6$%6@+~xpQ8dd@5t1Vf06` z5<4S0WcaIRf{r}eDgM)3@{xR2`A@SJ1v)^(g{Ho2sRT$^ zkifxQ7@mZoiG6|iwq1t4Akv*1dL#PbJA*G!-*ZMG{ChddN9|;IPQ(pn4Q+|ot!T_D znOgYq>BM>c!)~GbC8==b#hk&1*tlN`n{6fjr=zj%mkFm~G<`F;W1KB3zRrp!-MO?` zFrVd{`KhMriexIDTh>(5D^1($T~?^8DC}=XTW$S0p|lo7M2Dg=6^rleeeRVV{XmcrDliSv<$`GLLM_|h3S*bTE@_Oe_=|uKNf##3pVt6C8 zK}dg;OK$Mb%UkoYP0syaoAJPl2e(b7#1*56F@<7sD(U>-s3^RKiunez(aJhGPq-oE z*74Y%&^q)%EzfHPkHX7i(Uw2!^$~p;w52`%B;}YltAPprEY}Syw;Y*7t+PciE17`O z`l%R;4>+En-Ot0@GHYavFR`7#M~N~)e-;IDrI(0n?`Qp@S7+_~J7k=;i?G?=I&sBa zSiQE?hLd-`CN8@HayD~3Ik#g7kt!y;x9du;P}nTJ*Y^|VgP-?ux-lu-JL&2+)eFES zKDcqih`yS(bFKX_l|~&xLjy>e$i{0{kQK+9Mis}`sR@jwwhwP%bm7Q%M{5*8DS16_ z7M^p5E{~mYW_wslymfMBJgd2f<5Oev8pVmo*Tl1gp@9?;QjF@r^KiISu)yurxWAaU ze5Oe1-zrJWDa#ia%Pg`QU~pC)FyDEloz7=RuL4cZ8O|&U=zacVaY62Cm~E27*1^nc z-WPpUv@`E+&wF4AoSklN&sU}yZT6!_r3!dmoz3gdN$Q)xcEX7o}2uH3;zH&K;^!B{>-#swZQo zA)K9f;!OsP!fGc8MvW`qN>p1M*{6n#dPZIBShM_H!$$=dTH?ZdgcC)RiaaKsJEw^z zmk6XL(7@$FL1Hw<9qqGWoW7iDN2*w}sYN%fVVqx0RFROiKvQb+DLup9uou-sf|ag| zXZ?+i?AjI0@52b|6F{)7YJ*ul&h@Up?k(-~_-|pIv0e#MpoB6RB;`d`iAm2@Icg;J z+hk3pH$C32VXsLgqEfNDFMLb;#U1IttVbiB)w8wo@F=rwY*Ixv|nbGSi z%+K~!6AvCn#8CZ=*NSX!6`!GXS&>pV#D3Sx0RH8?xoGE}gcG42p*f;Q*UY8iJ@*7< zwM}@rQrbrnk}OM+;cV7(HKjs?8xg>XbzrUJ(x0$6-#ZxO7xvI2HkMZQc!<+-v3d~o zgO`}-)05t7I)%cT#P!e-!7k3YnKXcuvAwV}pn*$~fEEY5;u0BxO+ZXc)LaWy=SAlU zQMi^>Jud#z?r5NdQ;xK203U;^yZP->(e#YCE|mWu`_zV zOA@ujNGNXeWT9GiIfgZZ1fqjpzGJJamC*8v;`L`DNSGT@g1K0IgyJ>2FL$?q_>F+Q zTFX5yQ}K(MOcC-FKOZS0@g95IZC`1|q_8A9UG`~-A!K>E`_d}qP+*Kp6Nh@wij8Eh zGbYBOnW-e=OE|X};%W2n&j1QB#Jx54;`<+VoQ-DD=eO5p@f`K8Bg;^WL?KXKIg>Wm z!6Sa_>qDnTMwy`yMl-})*d8h#ZPq+Tsz-H4S(CT?UEPArfmIoG72gM32xyjnv@IQO zs{CqX$Oib8emnvbz;FCX(k-Qr%bx|FpWj_XO=MDUfihF4bRHdW3|Cpxe`!|G;xNcP zF{Aw)prPog%Q%N!e|G-90d$r*(ZLoUaB4c)!uNLIIwqTVezEboPcRnr1IwF{!UYa%jjmaOgc`=>*x( zP?JM>?5Ch9HH&!ilmq>Xklx`SO32>oa!-SpBX%_Q`#3Fxn6s*Bp8`)yR*9bRpaKuL z@1fVgP1{XGl88Tfgq#NONbAst^yA(3#h-SX$<%SiuCzi^UFJb4=dbXZP^BgFjrr-P zivnOZN6&Wn1gG(+%!;g%qft=ToP^8CrV;kVz|dSVnE2&9iUj9>T?*n3O(q8k!NYlY>=`U zW`nv2mpbllFe;`5Op9NeY2f?Ca+(|y?L#R$k7$%nhNB1`SZQ;bnJHXzwom-ejm4mX z9yi8X-{*v@HhYuAVs`bD;2;f7|G7)9m&YRpw;hO6Uf|>i9T%NsQ9PNEigAz!2aCK4 zeY%U#h(W0Nq%!2zcA!d{@&AC8KKPe5{{M=VcEr#7I5n>q9^E-MdHUEAH(?5}{1S5A ziZMeg==y8ur1qvbY-c3tEd(w+8IFa5hcMdl?OdpRs$CdYbnsyry72?<^W^u6k4bON zcri%^uy`THHGx3MYUM-CUt`}&ll{qGHWhwKnTwsk!`613t^~+ldF)%y&GmAds%#v= z7>M((GAo9?k*+K?{~YYp=+rFdJE1j;z}6|Bbxk2z1s5R|&`$2?i_T$P;#1PzeZ@rJ zM)X}PXHkrMny*Tlqrvp9HV^A+u)6iyUMT@yi15|!&nem2-DS`$J!m?4Olp6(gl9tY z(&^sJ-jn*hFGYbpyd}Z*_bZ_tMz>&=ERXATeN9K`EtO-;9V@KZiq-0iWra3IH~4oe zg57UGHdKD*Lcl8>`Ogio<&@7G_StaeN#u&>ZS%dYoo1^=W-jKi0diz*b$cz+uMJsmptF6(hN*Yy0^PDatOUW`n zn+`gVc>9#7DI9jAmD5yY+KyC~Q{HFfiKX5r79&p=s)y*GregeC;xD#`F`Vw=}zhs+` zc3HXzO%Rfw{mbiOQ)pVJhBYf3ZV9W9-6;gmvGVmpCzitB&eKj`_FrkM;(NzE$Hej5 z68%wys$v{JX>XZt5mJd{orv|%wh3tseS3=;k3z70{3tqr6ymMN6Q`e#IJ4D9m~&hz zCfF=B9_SCP2zal+X@7@(8$ZztJ8brboT`nbJ=+f{+a2XbO98q+pRG&{zt@G%0DOxC zGib82V=UvWtXL(t6p=t*GtOCQjMk!no~?^AC%aDt@3n<8d7w%l8!C?EudpaT9X-0E zOpPKT3acCs`npn1FnK^}xzO`N%nJLe0^_o5*I`zyL###N3R!Xf;hN%I>`OQ9_S9DK zr>|#wA5O8Dw^OGC33IR0_4wPI`UG}dvYf$G!GWo3Ctjg4gX?>~4$0gP1Q zGY{%nk;1QWVp8s0It#xHS1BUkPzjffxzjfNfc?Wo*%PQ27gqy84RjGBoeYxK(gGe7 zj=D*ntWtJtJ-69`>c}4ZBZyk6W9k)3!>=)Hu3y;^;bY-Cq6(fsoImIJ2}Mu(XWbfW zgCJKYDbSy{Es>KhHsRY2R0Xz^ygB>jUgC#faSJBpi$s8PdeCU#BD~@|kM}dzHOK>U zV0hjB8Pm{akXhc}A%5*|oTtnw8Tk&QAOIAVkA(=A*icSP6U3@+kyuCE$rkD4Zvh?O zrz2*ep*2Z*3^rCeTURbUFzlMO%qW=f8U9uTE<~3+_zv^{_#Z3{p6Jr@a?3l>^-@b& zd~UGSZ=0x*CwA?Mh$S>Xc+}3P7ndQl?&)~b)fpLkUs+;3=;22}Ye{g=#JI$b_^Y21 zhBRsf5;JoKI6gkZS8EumC55O$?a+mQpk-Iw&%sf#_ziU;Mv7U(o=X#b(k`3<+L~#{o#SxwkJuD`9#L3~>Yo`W!0v#RZ(L3Vb`F`&N-v~i z*59$ROSrOre5LFeXeG2w!hJ?Oqd;Z9fcFvHb=}ncN>l#J$62wPR+Qp`7b zoMDUaF3MuZjyoS=x{x>;H0Oq7OQz+l!729qeF;jo6N|Tiise8xTNiY(SmiZd$gWyQ z>%vzkNX+C`zq9`rMti&ZsMMe)K9V-wS-iEKFX1!Fh-$jYoDU4lND~gg^N<8vj*5tU z=NW_2;5wFPcz*S24>dG|%=dohsY^soa;Yw9qLDS`8Y8`gl*ZVZ?|awhq+Y2{=QKQ> z8Dp0+ELI5J1&5$fr(f9Kllx0G_|}p|^KI30 zS2ZNAPrFU5mvAkf3lZL`oK>An&h_5QHc{-RkAO9tY%+G&)urkGnk5DI8>Q!X^m-XX z>!QY!9<;Ym)bI5m!f(vXK$E0-|5+vm%u(k5eBAa-7jFrtVd5-^VKPa90Uj?Np@R5ggB*V&u{-hqT1h)MNc z&VApbZb%cE`d?|+#hU6LKPboxZI5KkBHJN3vTcV!1W?4ma)!;d>j^o{1UEb3ao41ubZT~@I&1f+QPueNU)BTa9w4<>x4p~0jC}Hu_~5@ z+viNmtA#dS18U<-Nie#|Ck84Gua|f>bL{xneLUl^$y4)vUr-?wGSV6tfYl`0fLxDf zhkcVwYOg0p76ayyB#{YeMha_r92!|n&Z=1)t9O&STsv)8dax0X_T>mU(1L|EhB#>Nin29zw-f|Zuu zMtBW*$1ltej`&EV=_~D*c7ra;*PC#60ON-`C+f!ybqRi}rj(LR;D;XEgE+itb3H$O z)qgV6(R*78Q{b>wH8b7jND7Mi=T3 z|0>LQ@-?1l65tDFOWWR!`3u$f3q7;V0R^oanX^S20>u4~P)@f#FRX)NISVsFv_tju zz*YJFaoEpL%#X1wi<#?twZ75oK>=~RT5b7kM*=%$hTiDoP;PXA*j_c}(HJ(?Q7zr$dO~**BTqD<>@F=HaLgt;bBvgf+WtB6!!CA{osz!=oP21q$mY) z5~@u~nr-wZHHt0AM7-?+WKs&+K(i5k*O9RL7LfZvhmtzQb#}q3fH1$8(uc!7o9|bK zYium5--xin{(?l@VrXALk~J$rb(EEKyYaxb{I*}5(zHj@*M&GQ?ztXG^rSTou3`YH zz8cr*4@%+&$g?NNvvu`r3^7&Jg={ug6rHt+L`IUn+@o)RVq!8myX0&@Ix3C+P@_@v z-`)mSpdVF*dbY-{k8o9iA4_vkdUzFILd}=7AO#7p21s6S!eEX{uG?zjJxkJ5@<-Zw`>F51Uv-u2(4SAWjvpMb^wf#68vt-FfB&>JJD)b9)> zx~>HZ1tAuEmRg2G;{MEq>8$3v#@}N8@A&N>e9wQM>-|gcUuyWLveSR9@xRs>ee?f2 cqJAqy&jt2zs^FWugMKN!P?sxzZXWzU06%U<=Kufz literal 0 HcmV?d00001 diff --git a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml b/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml index 644e937e0718d..a6cf7cdcf8c08 100644 --- a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml +++ b/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/control/vehicle_cmd_gate/msg/IsFilterActivated.msg b/control/vehicle_cmd_gate/msg/IsFilterActivated.msg new file mode 100644 index 0000000000000..fdb47c0a78f08 --- /dev/null +++ b/control/vehicle_cmd_gate/msg/IsFilterActivated.msg @@ -0,0 +1,10 @@ +builtin_interfaces/Time stamp + +bool is_activated + +# for additional information +bool is_activated_on_steering +bool is_activated_on_steering_rate +bool is_activated_on_speed +bool is_activated_on_acceleration +bool is_activated_on_jerk diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index df1de9f370cb6..36bb662fb2f53 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -13,6 +13,8 @@ ament_cmake autoware_cmake + rosidl_default_generators + autoware_adapi_v1_msgs autoware_auto_control_msgs autoware_auto_system_msgs @@ -33,10 +35,14 @@ tier4_vehicle_msgs vehicle_info_util + rosidl_default_runtime + ament_cmake_ros ament_lint_auto autoware_lint_common + rosidl_interface_packages + ament_cmake diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp index 49735da876d9a..8dec06c455868 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -24,6 +24,60 @@ VehicleCmdFilter::VehicleCmdFilter() { } +bool VehicleCmdFilter::setParameterWithValidation(const VehicleCmdFilterParam & p) +{ + const auto s = p.reference_speed_points.size(); + if ( + p.lon_acc_lim.size() != s || p.lon_jerk_lim.size() != s || p.lat_acc_lim.size() != s || + p.lat_jerk_lim.size() != s || p.actual_steer_diff_lim.size() != s) { + std::cerr << "VehicleCmdFilter::setParam() There is a size mismatch in the parameter. " + "Parameter initialization failed." + << std::endl; + return false; + } + + param_ = p; + return true; +} + +void VehicleCmdFilter::setLonAccLim(LimitArray v) +{ + auto tmp = param_; + tmp.lon_acc_lim = v; + setParameterWithValidation(tmp); +} +void VehicleCmdFilter::setLonJerkLim(LimitArray v) +{ + auto tmp = param_; + tmp.lon_jerk_lim = v; + setParameterWithValidation(tmp); +} +void VehicleCmdFilter::setLatAccLim(LimitArray v) +{ + auto tmp = param_; + tmp.lat_acc_lim = v; + setParameterWithValidation(tmp); +} +void VehicleCmdFilter::setLatJerkLim(LimitArray v) +{ + auto tmp = param_; + tmp.lat_jerk_lim = v; + setParameterWithValidation(tmp); +} +void VehicleCmdFilter::setActualSteerDiffLim(LimitArray v) +{ + auto tmp = param_; + tmp.actual_steer_diff_lim = v; + setParameterWithValidation(tmp); +} + +void VehicleCmdFilter::setParam(const VehicleCmdFilterParam & p) +{ + if (!setParameterWithValidation(p)) { + std::exit(EXIT_FAILURE); + } +} + void VehicleCmdFilter::limitLongitudinalWithVel(AckermannControlCommand & input) const { input.longitudinal.speed = std::max( @@ -33,28 +87,33 @@ void VehicleCmdFilter::limitLongitudinalWithVel(AckermannControlCommand & input) void VehicleCmdFilter::limitLongitudinalWithAcc( const double dt, AckermannControlCommand & input) const { + const auto lon_acc_lim = getLonAccLim(); input.longitudinal.acceleration = std::max( - std::min(static_cast(input.longitudinal.acceleration), param_.lon_acc_lim), - -param_.lon_acc_lim); + std::min(static_cast(input.longitudinal.acceleration), lon_acc_lim), -lon_acc_lim); input.longitudinal.speed = - limitDiff(input.longitudinal.speed, prev_cmd_.longitudinal.speed, param_.lon_acc_lim * dt); + limitDiff(input.longitudinal.speed, prev_cmd_.longitudinal.speed, lon_acc_lim * dt); } void VehicleCmdFilter::VehicleCmdFilter::limitLongitudinalWithJerk( const double dt, AckermannControlCommand & input) const { + const auto lon_jerk_lim = getLonJerkLim(); input.longitudinal.acceleration = limitDiff( - input.longitudinal.acceleration, prev_cmd_.longitudinal.acceleration, param_.lon_jerk_lim * dt); + input.longitudinal.acceleration, prev_cmd_.longitudinal.acceleration, lon_jerk_lim * dt); + input.longitudinal.jerk = + std::clamp(static_cast(input.longitudinal.jerk), -lon_jerk_lim, lon_jerk_lim); } void VehicleCmdFilter::limitLateralWithLatAcc( [[maybe_unused]] const double dt, AckermannControlCommand & input) const { + const auto lat_acc_lim = getLatAccLim(); + double latacc = calcLatAcc(input); - if (std::fabs(latacc) > param_.lat_acc_lim) { + if (std::fabs(latacc) > lat_acc_lim) { double v_sq = std::max(static_cast(input.longitudinal.speed * input.longitudinal.speed), 0.001); - double steer_lim = std::atan(param_.lat_acc_lim * param_.wheel_base / v_sq); + double steer_lim = std::atan(lat_acc_lim * param_.wheel_base / v_sq); input.lateral.steering_tire_angle = latacc > 0.0 ? steer_lim : -steer_lim; } } @@ -65,8 +124,10 @@ void VehicleCmdFilter::limitLateralWithLatJerk( double curr_latacc = calcLatAcc(input); double prev_latacc = calcLatAcc(prev_cmd_); - const double latacc_max = prev_latacc + param_.lat_jerk_lim * dt; - const double latacc_min = prev_latacc - param_.lat_jerk_lim * dt; + const auto lat_jerk_lim = getLatJerkLim(); + + const double latacc_max = prev_latacc + lat_jerk_lim * dt; + const double latacc_min = prev_latacc - lat_jerk_lim * dt; if (curr_latacc > latacc_max) { input.lateral.steering_tire_angle = calcSteerFromLatacc(input.longitudinal.speed, latacc_max); @@ -78,23 +139,60 @@ void VehicleCmdFilter::limitLateralWithLatJerk( void VehicleCmdFilter::limitActualSteerDiff( const double current_steer_angle, AckermannControlCommand & input) const { + const auto actual_steer_diff_lim = getSteerDiffLim(); + auto ds = input.lateral.steering_tire_angle - current_steer_angle; - ds = std::clamp(ds, -param_.actual_steer_diff_lim, param_.actual_steer_diff_lim); + ds = std::clamp(ds, -actual_steer_diff_lim, actual_steer_diff_lim); input.lateral.steering_tire_angle = current_steer_angle + ds; } +void VehicleCmdFilter::limitLateralSteer(AckermannControlCommand & input) const +{ + // TODO(Horibe): parametrize the max steering angle. + // TODO(Horibe): support steering greater than PI/2. Now the lateral acceleration + // calculation does not support bigger steering value than PI/2 due to tan/atan calculation. + constexpr float steer_limit = M_PI_2; + input.lateral.steering_tire_angle = + std::clamp(input.lateral.steering_tire_angle, -steer_limit, steer_limit); +} + void VehicleCmdFilter::filterAll( - const double dt, const double current_steer_angle, AckermannControlCommand & cmd) const + const double dt, const double current_steer_angle, AckermannControlCommand & cmd, + IsFilterActivated & is_activated) const { + const auto cmd_orig = cmd; + limitLateralSteer(cmd); limitLongitudinalWithJerk(dt, cmd); limitLongitudinalWithAcc(dt, cmd); limitLongitudinalWithVel(cmd); limitLateralWithLatJerk(dt, cmd); limitLateralWithLatAcc(dt, cmd); limitActualSteerDiff(current_steer_angle, cmd); + + is_activated = checkIsActivated(cmd, cmd_orig); return; } +IsFilterActivated VehicleCmdFilter::checkIsActivated( + const AckermannControlCommand & c1, const AckermannControlCommand & c2, const double tol) +{ + IsFilterActivated msg; + msg.is_activated_on_steering = + std::abs(c1.lateral.steering_tire_angle - c2.lateral.steering_tire_angle) > tol; + msg.is_activated_on_steering_rate = + std::abs(c1.lateral.steering_tire_rotation_rate - c2.lateral.steering_tire_rotation_rate) > tol; + msg.is_activated_on_speed = std::abs(c1.longitudinal.speed - c2.longitudinal.speed) > tol; + msg.is_activated_on_acceleration = + std::abs(c1.longitudinal.acceleration - c2.longitudinal.acceleration) > tol; + msg.is_activated_on_jerk = std::abs(c1.longitudinal.jerk - c2.longitudinal.jerk) > tol; + + msg.is_activated = + (msg.is_activated_on_steering || msg.is_activated_on_steering_rate || + msg.is_activated_on_speed || msg.is_activated_on_acceleration || msg.is_activated_on_jerk); + + return msg; +} + double VehicleCmdFilter::calcSteerFromLatacc(const double v, const double latacc) const { const double v_sq = std::max(v * v, 0.001); @@ -114,4 +212,56 @@ double VehicleCmdFilter::limitDiff( return prev + diff; } +double VehicleCmdFilter::interpolateFromSpeed(const LimitArray & limits) const +{ + // Consider only for the positive velocities. + const auto current = std::abs(current_speed_); + const auto reference = param_.reference_speed_points; + + // If the speed is out of range of the reference, apply zero-order hold. + if (current <= reference.front()) { + return limits.front(); + } + if (current >= reference.back()) { + return limits.back(); + } + + // Apply linear interpolation + for (size_t i = 0; i < reference.size() - 1; ++i) { + if (reference.at(i) <= current && current <= reference.at(i + 1)) { + auto ratio = + (current - reference.at(i)) / std::max(reference.at(i + 1) - reference.at(i), 1.0e-5); + ratio = std::clamp(ratio, 0.0, 1.0); + const auto interp = limits.at(i) + ratio * (limits.at(i + 1) - limits.at(i)); + return interp; + } + } + + std::cerr << "VehicleCmdFilter::interpolateFromSpeed() interpolation logic is broken. Command " + "filter is not working. Please check the code." + << std::endl; + return reference.back(); +} + +double VehicleCmdFilter::getLonAccLim() const +{ + return interpolateFromSpeed(param_.lon_acc_lim); +} +double VehicleCmdFilter::getLonJerkLim() const +{ + return interpolateFromSpeed(param_.lon_jerk_lim); +} +double VehicleCmdFilter::getLatAccLim() const +{ + return interpolateFromSpeed(param_.lat_acc_lim); +} +double VehicleCmdFilter::getLatJerkLim() const +{ + return interpolateFromSpeed(param_.lat_jerk_lim); +} +double VehicleCmdFilter::getSteerDiffLim() const +{ + return interpolateFromSpeed(param_.actual_steer_diff_lim); +} + } // namespace vehicle_cmd_gate diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp index 00acb50080cfe..eb85fcbeb8606 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp @@ -16,22 +16,28 @@ #define VEHICLE_CMD_FILTER_HPP_ #include +#include #include +#include + namespace vehicle_cmd_gate { using autoware_auto_control_msgs::msg::AckermannControlCommand; +using vehicle_cmd_gate::msg::IsFilterActivated; +using LimitArray = std::vector; struct VehicleCmdFilterParam { double wheel_base; double vel_lim; - double lon_acc_lim; - double lon_jerk_lim; - double lat_acc_lim; - double lat_jerk_lim; - double actual_steer_diff_lim; + LimitArray reference_speed_points; + LimitArray lon_acc_lim; + LimitArray lon_jerk_lim; + LimitArray lat_acc_lim; + LimitArray lat_jerk_lim; + LimitArray actual_steer_diff_lim; }; class VehicleCmdFilter { @@ -41,12 +47,13 @@ class VehicleCmdFilter void setWheelBase(double v) { param_.wheel_base = v; } void setVelLim(double v) { param_.vel_lim = v; } - void setLonAccLim(double v) { param_.lon_acc_lim = v; } - void setLonJerkLim(double v) { param_.lon_jerk_lim = v; } - void setLatAccLim(double v) { param_.lat_acc_lim = v; } - void setLatJerkLim(double v) { param_.lat_jerk_lim = v; } - void setActualSteerDiffLim(double v) { param_.actual_steer_diff_lim = v; } - void setParam(const VehicleCmdFilterParam & p) { param_ = p; } + void setLonAccLim(LimitArray v); + void setLonJerkLim(LimitArray v); + void setLatAccLim(LimitArray v); + void setLatJerkLim(LimitArray v); + void setActualSteerDiffLim(LimitArray v); + void setCurrentSpeed(double v) { current_speed_ = v; } + void setParam(const VehicleCmdFilterParam & p); void setPrevCmd(const AckermannControlCommand & v) { prev_cmd_ = v; } void limitLongitudinalWithVel(AckermannControlCommand & input) const; @@ -56,18 +63,33 @@ class VehicleCmdFilter void limitLateralWithLatJerk(const double dt, AckermannControlCommand & input) const; void limitActualSteerDiff( const double current_steer_angle, AckermannControlCommand & input) const; + void limitLateralSteer(AckermannControlCommand & input) const; void filterAll( - const double dt, const double current_steer_angle, AckermannControlCommand & input) const; + const double dt, const double current_steer_angle, AckermannControlCommand & input, + IsFilterActivated & is_activated) const; + static IsFilterActivated checkIsActivated( + const AckermannControlCommand & c1, const AckermannControlCommand & c2, + const double tol = 1.0e-3); AckermannControlCommand getPrevCmd() { return prev_cmd_; } private: VehicleCmdFilterParam param_; AckermannControlCommand prev_cmd_; + double current_speed_ = 0.0; + + bool setParameterWithValidation(const VehicleCmdFilterParam & p); double calcLatAcc(const AckermannControlCommand & cmd) const; double calcSteerFromLatacc(const double v, const double latacc) const; double limitDiff(const double curr, const double prev, const double diff_lim) const; + + double interpolateFromSpeed(const LimitArray & limits) const; + double getLonAccLim() const; + double getLonJerkLim() const; + double getLatAccLim() const; + double getLatJerkLim() const; + double getSteerDiffLim() const; }; } // namespace vehicle_cmd_gate diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 3f6a07b6d5555..9030521b6b334 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -23,6 +23,7 @@ #include #include #include +#include namespace vehicle_cmd_gate { @@ -70,6 +71,9 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) pub_external_emergency_ = create_publisher("output/external_emergency", durable_qos); operation_mode_pub_ = create_publisher("output/operation_mode", durable_qos); + is_filter_activated_pub_ = + create_publisher("~/is_filter_activated", durable_qos); + // Subscriber external_emergency_stop_heartbeat_sub_ = create_subscription( "input/external_emergency_stop_heartbeat", 1, @@ -79,7 +83,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) engage_sub_ = create_subscription( "input/engage", 1, std::bind(&VehicleCmdGate::onEngage, this, _1)); kinematics_sub_ = create_subscription( - "input/kinematics", 1, [this](Odometry::SharedPtr msg) { current_kinematics_ = *msg; }); + "/localization/kinematic_state", 1, + [this](Odometry::SharedPtr msg) { current_kinematics_ = *msg; }); acc_sub_ = create_subscription( "input/acceleration", 1, [this](AccelWithCovarianceStamped::SharedPtr msg) { current_acceleration_ = msg->accel.accel.linear.x; @@ -158,11 +163,14 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) VehicleCmdFilterParam p; p.wheel_base = vehicle_info.wheel_base_m; p.vel_lim = declare_parameter("nominal.vel_lim"); - p.lon_acc_lim = declare_parameter("nominal.lon_acc_lim"); - p.lon_jerk_lim = declare_parameter("nominal.lon_jerk_lim"); - p.lat_acc_lim = declare_parameter("nominal.lat_acc_lim"); - p.lat_jerk_lim = declare_parameter("nominal.lat_jerk_lim"); - p.actual_steer_diff_lim = declare_parameter("nominal.actual_steer_diff_lim"); + p.reference_speed_points = + declare_parameter>("nominal.reference_speed_points"); + p.lon_acc_lim = declare_parameter>("nominal.lon_acc_lim"); + p.lon_jerk_lim = declare_parameter>("nominal.lon_jerk_lim"); + p.lat_acc_lim = declare_parameter>("nominal.lat_acc_lim"); + p.lat_jerk_lim = declare_parameter>("nominal.lat_jerk_lim"); + p.actual_steer_diff_lim = + declare_parameter>("nominal.actual_steer_diff_lim"); filter_.setParam(p); } @@ -170,11 +178,14 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) VehicleCmdFilterParam p; p.wheel_base = vehicle_info.wheel_base_m; p.vel_lim = declare_parameter("on_transition.vel_lim"); - p.lon_acc_lim = declare_parameter("on_transition.lon_acc_lim"); - p.lon_jerk_lim = declare_parameter("on_transition.lon_jerk_lim"); - p.lat_acc_lim = declare_parameter("on_transition.lat_acc_lim"); - p.lat_jerk_lim = declare_parameter("on_transition.lat_jerk_lim"); - p.actual_steer_diff_lim = declare_parameter("on_transition.actual_steer_diff_lim"); + p.reference_speed_points = + declare_parameter>("on_transition.reference_speed_points"); + p.lon_acc_lim = declare_parameter>("on_transition.lon_acc_lim"); + p.lon_jerk_lim = declare_parameter>("on_transition.lon_jerk_lim"); + p.lat_acc_lim = declare_parameter>("on_transition.lat_acc_lim"); + p.lat_jerk_lim = declare_parameter>("on_transition.lat_jerk_lim"); + p.actual_steer_diff_lim = + declare_parameter>("on_transition.actual_steer_diff_lim"); filter_on_transition_.setParam(p); } @@ -503,9 +514,14 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont const auto ego_is_stopped = vehicle_stop_checker_->isVehicleStopped(stop_check_duration_); const auto input_cmd_is_stopping = in.longitudinal.acceleration < 0.0; + filter_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x); + filter_on_transition_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x); + + IsFilterActivated is_filter_activated; + // Apply transition_filter when transiting from MANUAL to AUTO. if (mode.is_in_transition) { - filter_on_transition_.filterAll(dt, current_steer_, out); + filter_on_transition_.filterAll(dt, current_steer_, out, is_filter_activated); } else { // When ego is stopped and the input command is not stopping, // use the higher of actual vehicle longitudinal state @@ -524,7 +540,7 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont : current_status_cmd.longitudinal.speed; filter_.setPrevCmd(prev_cmd); } - filter_.filterAll(dt, current_steer_, out); + filter_.filterAll(dt, current_steer_, out, is_filter_activated); } // set prev value for both to keep consistency over switching: @@ -547,6 +563,9 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont filter_.setPrevCmd(prev_values); filter_on_transition_.setPrevCmd(prev_values); + is_filter_activated.stamp = now(); + is_filter_activated_pub_->publish(is_filter_activated); + return out; } diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index b94240ce495af..d516ecac29ca2 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -64,6 +65,7 @@ using tier4_external_api_msgs::msg::Heartbeat; using tier4_external_api_msgs::srv::SetEmergency; using tier4_system_msgs::msg::MrmBehaviorStatus; using tier4_vehicle_msgs::msg::VehicleEmergencyStamped; +using vehicle_cmd_gate::msg::IsFilterActivated; using diagnostic_msgs::msg::DiagnosticStatus; using nav_msgs::msg::Odometry; @@ -99,6 +101,7 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Publisher::SharedPtr gate_mode_pub_; rclcpp::Publisher::SharedPtr engage_pub_; rclcpp::Publisher::SharedPtr operation_mode_pub_; + rclcpp::Publisher::SharedPtr is_filter_activated_pub_; // Subscription rclcpp::Subscription::SharedPtr external_emergency_stop_heartbeat_sub_; diff --git a/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp new file mode 100644 index 0000000000000..6384fbfb22f60 --- /dev/null +++ b/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp @@ -0,0 +1,400 @@ +// Copyright 2021 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 "../../src/vehicle_cmd_gate.hpp" +#include "ament_index_cpp/get_package_share_directory.hpp" + +#include + +#include +#include +#include +#include +#include + +#define ASSERT_LT_NEAR(x, y, alpha) ASSERT_LT(x, y * alpha) +#define ASSERT_GT_NEAR(x, y, alpha) ASSERT_GT(x, y * alpha) + +#define PRINT_VALUES(...) print_values(0, #__VA_ARGS__, __VA_ARGS__) +template +void print_values([[maybe_unused]] int i, [[maybe_unused]] T name) +{ + std::cerr << std::endl; +} +template +void print_values(int i, const T1 & name, const T2 & a, const T3 &... b) +{ + for (; name[i] != ',' && name[i] != '\0'; i++) std::cerr << name[i]; + + std::ostringstream oss; + oss << std::setprecision(4) << std::setw(9) << a; + std::cerr << ":" << oss.str() << " "; + print_values(i + 1, name, b...); +} + +// global params +const std::vector reference_speed_points = {5., 10., 15., 20.}; +const std::vector lon_acc_lim = {1.5, 1.0, 0.8, 0.6}; +const std::vector lon_jerk_lim = {1.4, 0.9, 0.7, 0.5}; +const std::vector lat_acc_lim = {2.0, 1.6, 1.2, 0.8}; +const std::vector lat_jerk_lim = {1.7, 1.3, 0.9, 0.6}; +const std::vector actual_steer_diff_lim = {0.5, 0.4, 0.2, 0.1}; +const double wheelbase = 2.89; + +using vehicle_cmd_gate::VehicleCmdGate; + +using autoware_adapi_v1_msgs::msg::MrmState; +using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_auto_vehicle_msgs::msg::GearCommand; +using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; +using autoware_auto_vehicle_msgs::msg::SteeringReport; +using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using geometry_msgs::msg::AccelWithCovarianceStamped; +using nav_msgs::msg::Odometry; +using tier4_control_msgs::msg::GateMode; +using tier4_external_api_msgs::msg::Emergency; +using tier4_external_api_msgs::msg::Heartbeat; +using EngageMsg = autoware_auto_vehicle_msgs::msg::Engage; + +class PubSubNode : public rclcpp::Node +{ +public: + PubSubNode() : Node{"test_vehicle_cmd_gate_filter_pubsub"} + { + sub_cmd_ = create_subscription( + "output/control_cmd", rclcpp::QoS{1}, + [this](const AckermannControlCommand::ConstSharedPtr msg) { + cmd_history_.push_back(msg); + cmd_received_times_.push_back(now()); + checkFilter(); + }); + + rclcpp::QoS qos{1}; + qos.transient_local(); + + pub_external_emergency_stop_heartbeat_ = + create_publisher("input/external_emergency_stop_heartbeat", qos); + pub_engage_ = create_publisher("input/engage", qos); + pub_gate_mode_ = create_publisher("input/gate_mode", qos); + pub_odom_ = create_publisher("/localization/kinematic_state", qos); + pub_acc_ = create_publisher("input/acceleration", qos); + pub_steer_ = create_publisher("input/steering", qos); + pub_operation_mode_ = create_publisher("input/operation_mode", qos); + pub_mrm_state_ = create_publisher("input/mrm_state", qos); + + pub_auto_control_cmd_ = + create_publisher("input/auto/control_cmd", qos); + pub_auto_turn_indicator_cmd_ = + create_publisher("input/auto/turn_indicators_cmd", qos); + pub_auto_hazard_light_cmd_ = + create_publisher("input/auto/hazard_lights_cmd", qos); + pub_auto_gear_cmd_ = create_publisher("input/auto/gear_cmd", qos); + } + + rclcpp::Subscription::SharedPtr sub_cmd_; + + rclcpp::Publisher::SharedPtr pub_external_emergency_stop_heartbeat_; + rclcpp::Publisher::SharedPtr pub_engage_; + rclcpp::Publisher::SharedPtr pub_gate_mode_; + rclcpp::Publisher::SharedPtr pub_odom_; + rclcpp::Publisher::SharedPtr pub_acc_; + rclcpp::Publisher::SharedPtr pub_steer_; + rclcpp::Publisher::SharedPtr pub_operation_mode_; + rclcpp::Publisher::SharedPtr pub_mrm_state_; + rclcpp::Publisher::SharedPtr pub_auto_control_cmd_; + rclcpp::Publisher::SharedPtr pub_auto_turn_indicator_cmd_; + rclcpp::Publisher::SharedPtr pub_auto_hazard_light_cmd_; + rclcpp::Publisher::SharedPtr pub_auto_gear_cmd_; + + std::vector cmd_history_; + std::vector raw_cmd_history_; + std::vector cmd_received_times_; + + // publish except for the control_cmd + void publishDefaultTopicsNoSpin() + { + { + Heartbeat msg; + msg.stamp = now(); + pub_external_emergency_stop_heartbeat_->publish(msg); + } + { + EngageMsg msg; + msg.stamp = now(); + msg.engage = true; + pub_engage_->publish(msg); + } + { + GateMode msg; + msg.data = GateMode::AUTO; + pub_gate_mode_->publish(msg); + } + { + Odometry msg; // initialized for zero pose and twist + msg.header.frame_id = "baselink"; + msg.header.stamp = now(); + msg.pose.pose.orientation.w = 1.0; + msg.twist.twist.linear.x = 0.0; + if (!cmd_history_.empty()) { // ego moves as commanded. + msg.twist.twist.linear.x = + cmd_history_.back()->longitudinal.speed; // ego moves as commanded. + } else { + } + pub_odom_->publish(msg); + } + { + AccelWithCovarianceStamped msg; + msg.header.frame_id = "baselink"; + msg.header.stamp = now(); + msg.accel.accel.linear.x = 0.0; + if (!cmd_history_.empty()) { // ego moves as commanded. + msg.accel.accel.linear.x = cmd_history_.back()->longitudinal.acceleration; + } + pub_acc_->publish(msg); + } + { + SteeringReport msg; + msg.stamp = now(); + msg.steering_tire_angle = 0.0; + if (!cmd_history_.empty()) { // ego moves as commanded. + msg.steering_tire_angle = cmd_history_.back()->lateral.steering_tire_angle; + } + pub_steer_->publish(msg); + } + { + OperationModeState msg; + msg.stamp = now(); + msg.mode = OperationModeState::AUTONOMOUS; + msg.is_autoware_control_enabled = true; + pub_operation_mode_->publish(msg); + } + { + MrmState msg; + msg.stamp = now(); + msg.state = MrmState::NORMAL; + msg.behavior = MrmState::NONE; + pub_mrm_state_->publish(msg); + } + { + TurnIndicatorsCommand msg; + msg.stamp = now(); + msg.command = TurnIndicatorsCommand::DISABLE; + pub_auto_turn_indicator_cmd_->publish(msg); + } + { + HazardLightsCommand msg; + msg.stamp = now(); + msg.command = HazardLightsCommand::DISABLE; + pub_auto_hazard_light_cmd_->publish(msg); + } + { + GearCommand msg; + msg.stamp = now(); + msg.command = GearCommand::DRIVE; + pub_auto_gear_cmd_->publish(msg); + } + } + + void publishControlCommand(AckermannControlCommand msg) + { + msg.stamp = now(); + pub_auto_control_cmd_->publish(msg); + raw_cmd_history_.push_back(std::make_shared(msg)); + } + + void checkFilter() + { + if (cmd_history_.size() != cmd_received_times_.size()) { + throw std::logic_error("cmd history and received times must have same size. Check code."); + } + + if (cmd_history_.size() == 1) return; + + const size_t i_curr = cmd_history_.size() - 1; + const size_t i_prev = cmd_history_.size() - 2; + const auto cmd_curr = cmd_history_.at(i_curr); + const auto cmd_prev = cmd_history_.at(i_prev); + + const auto max_lon_acc_lim = *std::max_element(lon_acc_lim.begin(), lon_acc_lim.end()); + const auto max_lon_jerk_lim = *std::max_element(lon_jerk_lim.begin(), lon_jerk_lim.end()); + const auto max_lat_acc_lim = *std::max_element(lat_acc_lim.begin(), lat_acc_lim.end()); + const auto max_lat_jerk_lim = *std::max_element(lat_jerk_lim.begin(), lat_jerk_lim.end()); + + const auto dt = (cmd_received_times_.at(i_curr) - cmd_received_times_.at(i_prev)).seconds(); + const auto lon_vel = cmd_curr->longitudinal.speed; + const auto lon_acc = cmd_curr->longitudinal.acceleration; + const auto lon_jerk = (lon_acc - cmd_prev->longitudinal.acceleration) / dt; + const auto lat_acc = + lon_vel * lon_vel * std::tan(cmd_curr->lateral.steering_tire_angle) / wheelbase; + const auto prev_lon_vel = cmd_prev->longitudinal.speed; + const auto prev_lat_acc = + prev_lon_vel * prev_lon_vel * std::tan(cmd_prev->lateral.steering_tire_angle) / wheelbase; + const auto lat_jerk = (lat_acc - prev_lat_acc) / dt; + + /* debug print */ + // const auto steer = cmd_curr->lateral.steering_tire_angle; + // PRINT_VALUES( + // dt, lon_vel, lon_acc, lon_jerk, lat_acc, lat_jerk, steer, max_lon_acc_lim, + // max_lon_jerk_lim, max_lat_acc_lim, max_lat_jerk_lim); + + // Output command must be smaller than maximum limit. + // TODO(Horibe): check for each velocity range. + constexpr auto threshold_scale = 1.1; + if (std::abs(lon_vel) > 0.01) { + ASSERT_LT_NEAR(std::abs(lon_acc), max_lon_acc_lim, threshold_scale); + ASSERT_LT_NEAR(std::abs(lon_jerk), max_lon_jerk_lim, threshold_scale); + ASSERT_LT_NEAR(std::abs(lat_acc), max_lat_acc_lim, threshold_scale); + ASSERT_LT_NEAR(std::abs(lat_jerk), max_lat_jerk_lim, threshold_scale); + } + } +}; + +struct CmdParam +{ + double max; + double freq; + double bias; + CmdParam() {} + CmdParam(double m, double f, double b) : max(m), freq(f), bias(b) {} +}; + +struct CmdParams +{ + CmdParam steering; + CmdParam velocity; + CmdParam acceleration; + CmdParams() {} + CmdParams(CmdParam s, CmdParam v, CmdParam a) : steering(s), velocity(v), acceleration(a) {} +}; + +class ControlCmdGenerator +{ +public: + CmdParams p_; // used for sin wave command generation + + using Clock = std::chrono::high_resolution_clock; + std::chrono::time_point start_time_{Clock::now()}; + + // generate ControlCommand with sin wave format. + // TODO(Horibe): implement steering_rate and jerk command. + AckermannControlCommand calcSinWaveCommand(bool reset_clock = false) + { + if (reset_clock) { + start_time_ = Clock::now(); + } + + const auto dt_ns = + std::chrono::duration_cast(Clock::now() - start_time_); + const auto dt_s = dt_ns.count() / 1e9; + + const auto sinWave = [&](auto amp, auto freq, auto bias) { + return amp * std::sin(2.0 * M_PI * freq * dt_s + bias); + }; + + AckermannControlCommand cmd; + cmd.lateral.steering_tire_angle = sinWave(p_.steering.max, p_.steering.freq, p_.steering.bias); + cmd.longitudinal.speed = + sinWave(p_.velocity.max, p_.velocity.freq, p_.velocity.bias) + p_.velocity.max; + cmd.longitudinal.acceleration = + sinWave(p_.acceleration.max, p_.acceleration.freq, p_.acceleration.bias); + + return cmd; + } +}; + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + + const auto vehicle_cmd_gate_dir = + ament_index_cpp::get_package_share_directory("vehicle_cmd_gate"); + const auto vehicle_info_util_dir = + ament_index_cpp::get_package_share_directory("vehicle_info_util"); + + node_options.arguments( + {"--ros-args", "--params-file", vehicle_cmd_gate_dir + "/config/vehicle_cmd_gate.param.yaml", + "--ros-args", "--params-file", vehicle_info_util_dir + "/config/vehicle_info.param.yaml"}); + + const auto override = [&](const auto s, const std::vector v) { + node_options.append_parameter_override>(s, v); + }; + + node_options.append_parameter_override("wheel_base", wheelbase); + override("nominal.reference_speed_points", reference_speed_points); + override("nominal.reference_speed_points", reference_speed_points); + override("nominal.lon_acc_lim", lon_acc_lim); + override("nominal.lon_jerk_lim", lon_jerk_lim); + override("nominal.lat_acc_lim", lat_acc_lim); + override("nominal.lat_jerk_lim", lat_jerk_lim); + override("nominal.actual_steer_diff_lim", actual_steer_diff_lim); + + return std::make_shared(node_options); +} + +class TestFixture : public ::testing::TestWithParam +{ +protected: + void SetUp() override + { + vehicle_cmd_gate_node_ = generateNode(); + cmd_generator_.p_ = GetParam(); + } + + void TearDown() override + { + // rclcpp::shutdown(); + } + + PubSubNode pub_sub_node_; + std::shared_ptr vehicle_cmd_gate_node_; + ControlCmdGenerator cmd_generator_; +}; + +TEST_P(TestFixture, CheckFilterForSinCmd) +{ + [[maybe_unused]] auto a = std::system("ros2 node list"); + [[maybe_unused]] auto b = std::system("ros2 node info /test_vehicle_cmd_gate_filter_pubsub"); + [[maybe_unused]] auto c = std::system("ros2 node info /vehicle_cmd_gate"); + + for (size_t i = 0; i < 100; ++i) { + const bool reset_clock = (i == 0); + const auto cmd = cmd_generator_.calcSinWaveCommand(reset_clock); + pub_sub_node_.publishControlCommand(cmd); + pub_sub_node_.publishDefaultTopicsNoSpin(); + for (int i = 0; i < 20; ++i) { + rclcpp::spin_some(pub_sub_node_.get_node_base_interface()); + rclcpp::spin_some(vehicle_cmd_gate_node_->get_node_base_interface()); + } + std::this_thread::sleep_for(std::chrono::milliseconds{10LL}); + } + + std::cerr << "received cmd num = " << pub_sub_node_.cmd_received_times_.size() << std::endl; +}; + +// High frequency, large value +CmdParams p1 = {/*steer*/ {10, 1, 0}, /*velocity*/ {10, 1.2, 0}, /*acc*/ {5, 1.5, 2}}; +INSTANTIATE_TEST_SUITE_P(TestParam1, TestFixture, ::testing::Values(p1)); + +// High frequency, normal value +CmdParams p2 = {/*steer*/ {1.5, 2, 1}, /*velocity*/ {5, 1.0, 0}, /*acc*/ {2.0, 3.0, 2}}; +INSTANTIATE_TEST_SUITE_P(TestParam2, TestFixture, ::testing::Values(p2)); + +// High frequency, small value +CmdParams p3 = {/*steer*/ {1.5, 3, 2}, /*velocity*/ {2, 3, 0}, /*acc*/ {0.5, 3, 2}}; +INSTANTIATE_TEST_SUITE_P(TestParam3, TestFixture, ::testing::Values(p3)); + +// Low frequency +CmdParams p4 = {/*steer*/ {10, 0.1, 0.5}, /*velocity*/ {10, 0.2, 0}, /*acc*/ {5, 0.1, 2}}; +INSTANTIATE_TEST_SUITE_P(TestParam4, TestFixture, ::testing::Values(p4)); diff --git a/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp b/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp index 5fbfec237b047..7ce8580120652 100644 --- a/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp +++ b/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp @@ -25,19 +25,25 @@ #define ASSERT_GT_NEAR(x, y) ASSERT_GT(x, y - THRESHOLD) using autoware_auto_control_msgs::msg::AckermannControlCommand; +using vehicle_cmd_gate::LimitArray; constexpr double NOMINAL_INTERVAL = 1.0; void setFilterParams( - vehicle_cmd_gate::VehicleCmdFilter & f, double v, double a, double j, double lat_a, double lat_j, - double wheelbase) + vehicle_cmd_gate::VehicleCmdFilter & f, double v, LimitArray speed_points, LimitArray a, + LimitArray j, LimitArray lat_a, LimitArray lat_j, LimitArray steer_diff, const double wheelbase) { - f.setVelLim(v); - f.setLonAccLim(a); - f.setLonJerkLim(j); - f.setLatAccLim(lat_a); - f.setLatJerkLim(lat_j); - f.setWheelBase(wheelbase); + vehicle_cmd_gate::VehicleCmdFilterParam p; + p.vel_lim = v; + p.wheel_base = wheelbase; + p.reference_speed_points = speed_points; + p.lat_acc_lim = lat_a; + p.lat_jerk_lim = lat_j; + p.lon_acc_lim = a; + p.lon_jerk_lim = j; + p.actual_steer_diff_lim = steer_diff; + + f.setParam(p); } AckermannControlCommand genCmd(double s, double sr, double v, double a) @@ -56,15 +62,29 @@ double calcLatAcc(const AckermannControlCommand & cmd, const double wheelbase) return v * v * std::tan(cmd.lateral.steering_tire_angle) / wheelbase; } -void test_all( - double V_LIM, double A_LIM, double J_LIM, double LAT_A_LIM, double LAT_J_LIM, +double calcLatJerk( + const AckermannControlCommand & cmd, const AckermannControlCommand & prev_cmd, + const double wheelbase, const double dt) +{ + const auto prev_v = prev_cmd.longitudinal.speed; + const auto prev = prev_v * prev_v * std::tan(prev_cmd.lateral.steering_tire_angle) / wheelbase; + + const auto curr_v = cmd.longitudinal.speed; + const auto curr = curr_v * curr_v * std::tan(cmd.lateral.steering_tire_angle) / wheelbase; + + return (curr - prev) / dt; +} + +void test_1d_limit( + double V_LIM, double A_LIM, double J_LIM, double LAT_A_LIM, double LAT_J_LIM, double STEER_DIFF, const AckermannControlCommand & prev_cmd, const AckermannControlCommand & raw_cmd) { const double WHEELBASE = 3.0; const double DT = 0.1; // [s] vehicle_cmd_gate::VehicleCmdFilter filter; - setFilterParams(filter, V_LIM, A_LIM, J_LIM, LAT_A_LIM, LAT_J_LIM, WHEELBASE); + setFilterParams( + filter, V_LIM, {0.0}, {A_LIM}, {J_LIM}, {LAT_A_LIM}, {LAT_J_LIM}, {STEER_DIFF}, WHEELBASE); filter.setPrevCmd(prev_cmd); // velocity filter @@ -164,6 +184,23 @@ void test_all( filtered_cmd.lateral.steering_tire_angle, raw_cmd.lateral.steering_tire_angle, THRESHOLD); } } + + // steer diff + { + const auto current_steering = 0.1; + auto filtered_cmd = raw_cmd; + filter.limitActualSteerDiff(current_steering, filtered_cmd); + const auto filtered_steer_diff = filtered_cmd.lateral.steering_tire_angle - current_steering; + const auto raw_steer_diff = raw_cmd.lateral.steering_tire_angle - current_steering; + // check if the filtered value does not exceed the limit. + ASSERT_LT_NEAR(std::abs(filtered_steer_diff), STEER_DIFF); + + // check if the undesired filter is not applied. + if (std::abs(raw_steer_diff) < STEER_DIFF) { + ASSERT_NEAR( + filtered_cmd.lateral.steering_tire_angle, raw_cmd.lateral.steering_tire_angle, THRESHOLD); + } + } } TEST(VehicleCmdFilter, VehicleCmdFilter) @@ -173,6 +210,7 @@ TEST(VehicleCmdFilter, VehicleCmdFilter) const std::vector j_arr = {0.0, 0.1, 1.0}; const std::vector lat_a_arr = {0.01, 1.0, 100.0}; const std::vector lat_j_arr = {0.01, 1.0, 100.0}; + const std::vector steer_diff_arr = {0.01, 1.0, 100.0}; const std::vector prev_cmd_arr = { genCmd(0.0, 0.0, 0.0, 0.0), genCmd(1.0, 1.0, 1.0, 1.0)}; @@ -187,7 +225,9 @@ TEST(VehicleCmdFilter, VehicleCmdFilter) for (const auto & lj : lat_j_arr) { for (const auto & prev_cmd : prev_cmd_arr) { for (const auto & raw_cmd : raw_cmd_arr) { - test_all(v, a, j, la, lj, prev_cmd, raw_cmd); + for (const auto & steer_diff : steer_diff_arr) { + test_1d_limit(v, a, j, la, lj, steer_diff, prev_cmd, raw_cmd); + } } } } @@ -196,3 +236,228 @@ TEST(VehicleCmdFilter, VehicleCmdFilter) } } } + +TEST(VehicleCmdFilter, VehicleCmdFilterInterpolate) +{ + constexpr double WHEELBASE = 2.8; + vehicle_cmd_gate::VehicleCmdFilter filter; + + vehicle_cmd_gate::VehicleCmdFilterParam p; + p.wheel_base = WHEELBASE; + p.vel_lim = 20.0; + p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; + p.lon_acc_lim = std::vector{0.3, 0.4, 0.5}; + p.lon_jerk_lim = std::vector{0.4, 0.4, 0.7}; + p.lat_acc_lim = std::vector{0.1, 0.2, 0.3}; + p.lat_jerk_lim = std::vector{0.9, 0.7, 0.1}; + p.actual_steer_diff_lim = std::vector{0.1, 0.3, 0.2}; + filter.setParam(p); + + const auto DT = 0.033; + + const auto orig_cmd = []() { + AckermannControlCommand cmd; + cmd.lateral.steering_tire_angle = 0.5; + cmd.lateral.steering_tire_rotation_rate = 0.5; + cmd.longitudinal.speed = 30.0; + cmd.longitudinal.acceleration = 10.0; + cmd.longitudinal.jerk = 10.0; + return cmd; + }(); + + const auto set_speed_and_reset_prev = [&](const auto & current_vel) { + filter.setCurrentSpeed(current_vel); + }; + + const auto _limitLongitudinalWithVel = [&](const auto & in) { + auto out = in; + filter.limitLongitudinalWithVel(out); + return out; + }; + const auto _limitLongitudinalWithAcc = [&](const auto & in) { + auto out = in; + filter.limitLongitudinalWithAcc(DT, out); + return out; + }; + const auto _limitLongitudinalWithJerk = [&](const auto & in) { + auto out = in; + filter.limitLongitudinalWithJerk(DT, out); + return out; + }; + const auto _limitLateralWithLatAcc = [&](const auto & in) { + auto out = in; + filter.limitLateralWithLatAcc(DT, out); + return out; + }; + const auto _limitLateralWithLatJerk = [&](const auto & in) { + auto out = in; + filter.limitLateralWithLatJerk(DT, out); + return out; + }; + const auto _limitActualSteerDiff = [&](const auto & in) { + auto out = in; + const auto prev_steering = 0.0; + filter.limitActualSteerDiff(prev_steering, out); + return out; + }; + + constexpr double ep = 1.0e-5; + + // vel lim + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR(_limitLongitudinalWithVel(orig_cmd).longitudinal.speed, 20.0, ep); + } + + // longitudinal acc lim + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.3, ep); + + set_speed_and_reset_prev(2.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.3, ep); + + set_speed_and_reset_prev(3.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.35, ep); + + set_speed_and_reset_prev(5.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.4 + 0.1 / 6.0, ep); + + set_speed_and_reset_prev(8.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.4 + 0.4 / 6.0, ep); + + set_speed_and_reset_prev(10.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.5, ep); + + set_speed_and_reset_prev(15.0); + EXPECT_NEAR(_limitLongitudinalWithAcc(orig_cmd).longitudinal.acceleration, 0.5, ep); + } + + // longitudinal jerk lim + // p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; + // p.lon_jerk_lim = std::vector{0.4, 0.4, 0.7}; + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, 0.4, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * 0.4, ep); + + set_speed_and_reset_prev(2.0); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, 0.4, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * 0.4, ep); + + set_speed_and_reset_prev(3.0); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, 0.4, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * 0.4, ep); + + set_speed_and_reset_prev(5.0); + const auto expect_v5 = 0.4 + 0.3 / 6.0; + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, expect_v5, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * expect_v5, ep); + + set_speed_and_reset_prev(8.0); + const auto expect_v8 = 0.4 + 1.2 / 6.0; + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, expect_v8, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * expect_v8, ep); + + set_speed_and_reset_prev(10.0); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, 0.7, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * 0.7, ep); + + set_speed_and_reset_prev(15.0); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.jerk, 0.7, ep); + EXPECT_NEAR(_limitLongitudinalWithJerk(orig_cmd).longitudinal.acceleration, DT * 0.7, ep); + } + + // lateral acc lim + // p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; + // p.lat_acc_lim = std::vector{0.1, 0.2, 0.3}; + const auto _calcLatAcc = [&](const auto & cmd) { return calcLatAcc(cmd, WHEELBASE); }; + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.1, ep); + + set_speed_and_reset_prev(2.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.1, ep); + + set_speed_and_reset_prev(3.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.15, ep); + + set_speed_and_reset_prev(5.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.2 + 0.1 / 6.0, ep); + + set_speed_and_reset_prev(8.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.2 + 0.4 / 6.0, ep); + + set_speed_and_reset_prev(10.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.3, ep); + + set_speed_and_reset_prev(15.0); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatAcc(orig_cmd)), 0.3, ep); + } + + // lateral jerk lim + // p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; + // p.lat_jerk_lim = std::vector{0.9, 0.7, 0.1}; + const auto _calcLatJerk = [&](const auto & cmd) { + return calcLatJerk(cmd, AckermannControlCommand{}, WHEELBASE, DT); + }; + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), 0.9, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * 0.9, ep); + + set_speed_and_reset_prev(2.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), 0.9, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * 0.9, ep); + + set_speed_and_reset_prev(3.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), 0.8, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * 0.8, ep); + + set_speed_and_reset_prev(5.0); + const auto expect_v5 = 0.7 - 0.6 * (1.0 / 6.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), expect_v5, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * expect_v5, ep); + + set_speed_and_reset_prev(8.0); + const auto expect_v8 = 0.7 - 0.6 * (4.0 / 6.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), expect_v8, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * expect_v8, ep); + + set_speed_and_reset_prev(10.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), 0.1, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * 0.1, ep); + + set_speed_and_reset_prev(15.0); + EXPECT_NEAR(_calcLatJerk(_limitLateralWithLatJerk(orig_cmd)), 0.1, ep); + EXPECT_NEAR(_calcLatAcc(_limitLateralWithLatJerk(orig_cmd)), DT * 0.1, ep); + } + + // steering diff lim + // p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; + // p.actual_steer_diff_lim = std::vector{0.1, 0.3, 0.2}; + { + set_speed_and_reset_prev(0.0); + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), 0.1, ep); + + set_speed_and_reset_prev(2.0); + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), 0.1, ep); + + set_speed_and_reset_prev(3.0); + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), 0.2, ep); + + set_speed_and_reset_prev(5.0); + const auto expect_v5 = 0.3 - 0.1 / 6.0; + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), expect_v5, ep); + + set_speed_and_reset_prev(8.0); + const auto expect_v8 = 0.3 - 0.4 / 6.0; + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), expect_v8, ep); + + set_speed_and_reset_prev(10.0); + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), 0.2, ep); + + set_speed_and_reset_prev(15.0); + EXPECT_NEAR((_limitActualSteerDiff(orig_cmd).lateral.steering_tire_angle), 0.2, ep); + } +} From 631f44ad26285914e8885a4101f38e99fc32f272 Mon Sep 17 00:00:00 2001 From: keisuke <31088744+keiota@users.noreply.github.com> Date: Wed, 23 Aug 2023 13:50:03 +0900 Subject: [PATCH 235/266] refactor(freespace_planning_algorithms): fix declare_parameter function's declaration (#4645) * refactor(freespace_planning_algorithms): delete default values of function declare_parameter * refactor(freespace_planning_algorithms): fix way to call declare_parameter function and add config repository. * refactor(freespace_planning_algorithms): fix way to declare declare_parameter function * fix(freespace_planner): add parameters for RRTStar search algorithm * style(pre-commit): autofix * refactor(freespace_planner): undo the change of planning algorithm --------- Signed-off-by: keiota Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kyoichi Sugahara --- .../config/freespace_planner.param.yaml | 8 ++++++++ .../freespace_planning_algorithms/astar_search.hpp | 6 +++--- .../include/freespace_planning_algorithms/rrtstar.hpp | 10 +++++----- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/planning/freespace_planner/config/freespace_planner.param.yaml b/planning/freespace_planner/config/freespace_planner.param.yaml index 75c813266a83d..8692aa293cbf7 100644 --- a/planning/freespace_planner/config/freespace_planner.param.yaml +++ b/planning/freespace_planner/config/freespace_planner.param.yaml @@ -33,3 +33,11 @@ only_behind_solutions: false use_back: true distance_heuristic_weight: 1.0 + + # -- RRT* search Configurations -- + rrtstar: + enable_update: true + use_informed_sampling: true + max_planning_time: 150.0 + neighbor_radius: 8.0 + margin: 0.1 diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp index 6f1810fabec88..3dced3eb1d01d 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp +++ b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp @@ -118,9 +118,9 @@ class AstarSearch : public AbstractPlanningAlgorithm : AstarSearch( planner_common_param, collision_vehicle_shape, AstarParam{ - node.declare_parameter("astar.only_behind_solutions", false), - node.declare_parameter("astar.use_back", true), - node.declare_parameter("astar.distance_heuristic_weight", 1.0)}) + node.declare_parameter("astar.only_behind_solutions"), + node.declare_parameter("astar.use_back"), + node.declare_parameter("astar.distance_heuristic_weight")}) { } diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp index 07f73281e7176..ac21f7333df37 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp +++ b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp @@ -47,11 +47,11 @@ class RRTStar : public AbstractPlanningAlgorithm : RRTStar( planner_common_param, original_vehicle_shape, RRTStarParam{ - node.declare_parameter("rrtstar.enable_update", true), - node.declare_parameter("rrtstar.use_informed_sampling", true), - node.declare_parameter("rrtstar.max_planning_time", 150.0), - node.declare_parameter("rrtstar.neighbor_radius", 8.0), - node.declare_parameter("rrtstar.margin", 0.1)}) + node.declare_parameter("rrtstar.enable_update"), + node.declare_parameter("rrtstar.use_informed_sampling"), + node.declare_parameter("rrtstar.max_planning_time"), + node.declare_parameter("rrtstar.neighbor_radius"), + node.declare_parameter("rrtstar.margin")}) { } From 51817831f2b9e599e5709156d94883b8c88ef71c Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 23 Aug 2023 14:08:51 +0900 Subject: [PATCH 236/266] fix(probabilistic_occupancy_gridmap): prevent node death by adding lookupTransform exception in util function (#4713) * add lookupTransform exception in util function and add launch_test Signed-off-by: yoshiri * style(pre-commit): autofix --------- Signed-off-by: yoshiri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/utils/utils.cpp | 12 ++++++++-- .../test/test_pointcloud_based_method.py | 23 +++++++++++++++++++ 2 files changed, 33 insertions(+), 2 deletions(-) diff --git a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp index 741d333142c9d..f2cd6203b3685 100644 --- a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp @@ -25,8 +25,16 @@ bool transformPointcloud( const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output) { geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2.lookupTransform( - target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); + // lookup transform + try { + tf_stamped = tf2.lookupTransform( + target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN( + rclcpp::get_logger("probabilistic_occupancy_grid_map"), "Failed to lookup transform: %s", + ex.what()); + return false; + } // transform pointcloud Eigen::Matrix4f tf_matrix = tf2::transformToEigen(tf_stamped.transform).matrix().cast(); pcl_ros::transformPointCloud(tf_matrix, input, output); diff --git a/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py b/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py index 6b0150dc3fa7b..093811d4cc213 100644 --- a/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py +++ b/perception/probabilistic_occupancy_grid_map/test/test_pointcloud_based_method.py @@ -238,6 +238,29 @@ def test_null_input(self, proc_info): self.assertIn("occupancy_grid_map_node", nodes) self.assertEqual(len(self.msg_buffer), 1) + def test_null_input2(self, proc_info): + """Test null input. + + input: null pointcloud without even frame_id + output: null ogm + """ + # wait for the node to be ready + time.sleep(3) + input_points = [] + pub_raw, pub_obstacle, sub = self.create_pub_sub() + # publish input pointcloud + pt_msg = get_pointcloud_msg(input_points) + pt_msg.header.frame_id = "" + pub_raw.publish(pt_msg) + pub_obstacle.publish(pt_msg) + # try to subscribe output pointcloud once + rclpy.spin_once(self.node, timeout_sec=3.0) + + # check if process is successfully terminated + nodes = self.node.get_node_names() + self.assertIn("occupancy_grid_map_node", nodes) + self.assertEqual(len(self.msg_buffer), 0) + @launch_testing.post_shutdown_test() class TestProcessOutput(unittest.TestCase): From e45c1ce8df336aef408650532b0477dd174ae27d Mon Sep 17 00:00:00 2001 From: Max Schmeller <6088931+mojomex@users.noreply.github.com> Date: Wed, 23 Aug 2023 14:15:41 +0900 Subject: [PATCH 237/266] perf(ring_outlier_filter): a cache friendly impl (continuation of VRichardJP's work) (#4185) * perf(ring_outlier_filter): a cache friendly impl Signed-off-by: Vincent Richard style(pre-commit): autofix fix(ring_outlier_filter): cleanup code with ranges Signed-off-by: Vincent Richard [breaking] fix autoware point type padding for faster memory access can memcpy between input data buffer and PointXYZI* make assumption on memory layout for faster data fetch misc optimization (reordering, constexpr, etc) Signed-off-by: Vincent Richard style(pre-commit): autofix comment limitations Signed-off-by: Vincent Richard feat(ring_outlier_filter): add accurate isCluster impl Signed-off-by: Vincent Richard style(pre-commit): autofix fix #3218 Signed-off-by: Vincent Richard cleaning Signed-off-by: Vincent Richard style(pre-commit): autofix * style(pre-commit): autofix * resize vector to data size Signed-off-by: Vincent Richard * cleaning Signed-off-by: Vincent Richard * cleaner utilities impl Signed-off-by: Vincent Richard * Correct ring_outlier_filter algorithm The implementation by VRichardJP was erroneously using indices into the input->fields array as byte offsets for copying values from the input. Added the missing step to access the offset of the field pointed at by the respective index. When combining the first and last walk, the num_points fields of the two walks need to be summed up as well. isCluster checks for num_points as well as distance. Signed-off-by: Maximilian Schmeller * Optimize memory usage of walks array The walks array in the previous implementation could in the worst case grow to the number of input points (if every point is an outlier). This increased computation time for gradually growing the walks vector. The current implementation only saves the first and current walk for every ring. The isCluster check is performed right when a walk is completed, and a bool vector akin to the previous walk_is_cluster vector is maintained. Signed-off-by: Maximilian Schmeller * Remove debug timers and outputs Signed-off-by: Maximilian Schmeller * style(pre-commit): autofix * Reduce amount of helper functions and data structures Remove functions for finding field offsets of Pointcloud2 points, replace them with the previous approach of assuming their position. This is okay since the ring_outlier_filter specification clearly states the expected pointcloud format. Remove accessor lambda functions for ring/azimuth/etc. because they are onlu used once anyways. Remove the walks vector and save the first/current walk structs directly in the RingWalkInfo struct. This makes the code more readable and maintainable. Signed-off-by: Maximilian Schmeller * style(pre-commit): autofix * Check for invalid pointcloud format In the previous revision (and before this PR), pointcloud field indices in ring_outlier_filter were hardcoded and fields were assumed to exist. VRichardJP solved this by implementing individual accessor functions, which ended up to be a bit verbose for this small piece of functionality. Now, there is one generic accessor function and the faster_filter function exits if any of the fields expected does not exist. The expected field data type is also checked. Signed-off-by: Maximilian Schmeller * style(pre-commit): autofix --------- Signed-off-by: Vincent Richard Signed-off-by: Maximilian Schmeller Co-authored-by: Vincent Richard Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Maximilian Schmeller --- .../docs/ring-outlier-filter.md | 13 +- .../ring_outlier_filter_nodelet.hpp | 16 - sensing/pointcloud_preprocessor/package.xml | 1 + .../ring_outlier_filter_nodelet.cpp | 342 +++++++++++++----- 4 files changed, 249 insertions(+), 123 deletions(-) diff --git a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md index 42ca694235a00..eedc8e6bcb573 100644 --- a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md @@ -22,13 +22,12 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref ### Core Parameters -| Name | Type | Default Value | Description | -| ------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------- | -| `distance_ratio` | double | 1.03 | | -| `object_length_threshold` | double | 0.1 | | -| `num_points_threshold` | int | 4 | | -| `max_rings_num` | uint_16 | 128 | | -| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` | +| Name | Type | Default Value | Description | +| ------------------------- | ------- | ------------- | ----------- | +| `distance_ratio` | double | 1.03 | | +| `object_length_threshold` | double | 0.1 | | +| `num_points_threshold` | int | 4 | | +| `max_rings_num` | uint_16 | 128 | | ## Assumptions / Known limits diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp index ab7d4e0012304..f655a9245ca6d 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp @@ -46,7 +46,6 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter double object_length_threshold_; int num_points_threshold_; uint16_t max_rings_num_; - size_t max_points_num_per_ring_; /** \brief Parameter service callback result : needed to be hold */ OnSetParametersCallbackHandle::SharedPtr set_param_res_; @@ -54,21 +53,6 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter /** \brief Parameter service callback */ rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector & p); - bool isCluster( - const PointCloud2ConstPtr & input, std::pair data_idx_both_ends, int walk_size) - { - if (walk_size > num_points_threshold_) return true; - - auto first_point = reinterpret_cast(&input->data[data_idx_both_ends.first]); - auto last_point = reinterpret_cast(&input->data[data_idx_both_ends.second]); - - const auto x = first_point->x - last_point->x; - const auto y = first_point->y - last_point->y; - const auto z = first_point->z - last_point->z; - - return x * x + y * y + z * z >= object_length_threshold_ * object_length_threshold_; - } - public: PCL_MAKE_ALIGNED_OPERATOR_NEW explicit RingOutlierFilterComponent(const rclcpp::NodeOptions & options); diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/pointcloud_preprocessor/package.xml index a65d14c0a1194..e3090f34d6854 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/pointcloud_preprocessor/package.xml @@ -31,6 +31,7 @@ pcl_msgs pcl_ros point_cloud_msg_wrapper + range-v3 rclcpp rclcpp_components sensor_msgs diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index d2570b9c4d786..e277b221a090d 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -14,10 +14,18 @@ #include "pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp" +#include "pointcloud_preprocessor/utility/utilities.hpp" + +#include +#include +#include + #include #include +#include #include + namespace pointcloud_preprocessor { RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions & options) @@ -40,8 +48,6 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions static_cast(declare_parameter("object_length_threshold", 0.1)); num_points_threshold_ = static_cast(declare_parameter("num_points_threshold", 4)); max_rings_num_ = static_cast(declare_parameter("max_rings_num", 128)); - max_points_num_per_ring_ = - static_cast(declare_parameter("max_points_num_per_ring", 4000)); } using std::placeholders::_1; @@ -61,122 +67,252 @@ void RingOutlierFilterComponent::faster_filter( } stop_watch_ptr_->toc("processing_time", true); - output.point_step = sizeof(PointXYZI); - output.data.resize(output.point_step * input->width); - size_t output_size = 0; + // The ring_outlier_filter specifies the expected input point cloud format, + // however, we want to verify the input is correct and make failures explicit. + auto getFieldOffsetSafely = [=]( + const std::string & field_name, + const pcl::PCLPointField::PointFieldTypes expected_type) -> size_t { + const auto field_index = pcl::getFieldIndex(*input, field_name); + if (field_index == -1) { + RCLCPP_ERROR(get_logger(), "Field %s not found in input point cloud", field_name.c_str()); + return -1UL; + } - const auto ring_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Ring)).offset; - const auto azimuth_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Azimuth)).offset; - const auto distance_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Distance)).offset; - const auto intensity_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Intensity)).offset; - - std::vector> ring2indices; - ring2indices.reserve(max_rings_num_); - - for (uint16_t i = 0; i < max_rings_num_; i++) { - ring2indices.push_back(std::vector()); - ring2indices.back().reserve(max_points_num_per_ring_); - } + auto field = (*input).fields.at(field_index); + if (field.datatype != expected_type) { + RCLCPP_ERROR( + get_logger(), "Field %s has unexpected type %d (expected %d)", field_name.c_str(), + field.datatype, expected_type); + return -1UL; + } - for (size_t data_idx = 0; data_idx < input->data.size(); data_idx += input->point_step) { - const uint16_t ring = *reinterpret_cast(&input->data[data_idx + ring_offset]); - ring2indices[ring].push_back(data_idx); + return static_cast(field.offset); + }; + + // as per the specification of this node, these fields must be present in the input + const auto ring_offset = getFieldOffsetSafely("ring", pcl::PCLPointField::UINT16); + const auto azimuth_offset = getFieldOffsetSafely("azimuth", pcl::PCLPointField::FLOAT32); + const auto distance_offset = getFieldOffsetSafely("distance", pcl::PCLPointField::FLOAT32); + const auto intensity_offset = getFieldOffsetSafely("intensity", pcl::PCLPointField::FLOAT32); + + if ( + ring_offset == -1UL || azimuth_offset == -1UL || distance_offset == -1UL || + intensity_offset == -1UL) { + RCLCPP_ERROR(get_logger(), "One or more required fields are missing in input point cloud"); + return; } - // walk range: [walk_first_idx, walk_last_idx] - int walk_first_idx = 0; - int walk_last_idx = -1; + // The initial implementation of ring outlier filter looked like this: + // 1. Iterate over the input cloud and group point indices by ring + // 2. For each ring: + // 2.1. iterate over the ring points, and group points belonging to the same "walk" + // 2.2. when a walk is closed, copy indexed points to the output cloud if the walk is long + // enough. + // + // Because LIDAR data is naturally "azimuth-major order" and not "ring-major order", such + // implementation is not cache friendly at all, and has negative impact on all the other nodes. + // + // To tackle this issue, the algorithm has been rewritten so that points would be accessed in + // order. To do so, all rings are being processing simultaneously instead of separately. The + // overall logic is still the same. + + // ad-hoc struct to store finished walks information (for isCluster()) + struct WalkInfo + { + size_t id; + int num_points; + float first_point_distance; + float first_point_azimuth; + float last_point_distance; + float last_point_azimuth; + }; + + // ad-hoc struct to keep track of each ring current walk + struct RingWalkInfo + { + WalkInfo first_walk; + WalkInfo current_walk; + }; + + // helper functions + + // check if walk is a valid cluster + const float object_length_threshold2 = object_length_threshold_ * object_length_threshold_; + auto isCluster = [=](const WalkInfo & walk_info) { + // A cluster is a walk which has many points or is long enough + if (walk_info.num_points > num_points_threshold_) return true; + + // Using the law of cosines, the distance between 2 points can be written as: + // |p2-p1|^2 = d1^2 + d2^2 - 2*d1*d2*cos(a) + // where d1 and d2 are the distance attribute of p1 and p2, and 'a' the azimuth diff between + // the 2 points. + const float dist2 = + walk_info.first_point_distance * walk_info.first_point_distance + + walk_info.last_point_distance * walk_info.last_point_distance - + 2 * walk_info.first_point_distance * walk_info.last_point_distance * + std::cos((walk_info.last_point_azimuth - walk_info.first_point_azimuth) * (M_PI / 18000.0)); + return dist2 > object_length_threshold2; + }; + + // check if 2 points belong to the same walk + auto isSameWalk = + [=](float curr_distance, float curr_azimuth, float prev_distance, float prev_azimuth) { + float azimuth_diff = curr_azimuth - prev_azimuth; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + return std::max(curr_distance, prev_distance) < + std::min(curr_distance, prev_distance) * distance_ratio_ && + azimuth_diff < 100.f; + }; + + // tmp vectors to keep track of walk/ring state while processing points in order (cache efficient) + std::vector rings; // info for each LiDAR ring + std::vector points_walk_id; // for each input point, the walk index associated with it + std::vector + walks_cluster_status; // for each generated walk, stores whether it is a cluster + + size_t latest_walk_id = -1UL; // ID given to the latest walk created + + // initialize each ring with two empty walks (first and current walk) + rings.resize(max_rings_num_, RingWalkInfo{{-1UL, 0, 0, 0, 0, 0}, {-1UL, 0, 0, 0, 0, 0}}); + // points are initially associated to no walk (-1UL) + points_walk_id.resize(input->width * input->height, -1UL); + walks_cluster_status.reserve( + max_rings_num_ * 2); // In the worst case, this could grow to the number of input points + + int invalid_ring_count = 0; + + // Build walks and classify points + for (const auto & [raw_p, point_walk_id] : + ranges::views::zip(input->data | ranges::views::chunk(input->point_step), points_walk_id)) { + uint16_t ring_idx{}; + float curr_azimuth{}; + float curr_distance{}; + std::memcpy(&ring_idx, &raw_p.data()[ring_offset], sizeof(ring_idx)); + std::memcpy(&curr_azimuth, &raw_p.data()[azimuth_offset], sizeof(curr_azimuth)); + std::memcpy(&curr_distance, &raw_p.data()[distance_offset], sizeof(curr_distance)); + + if (ring_idx >= max_rings_num_) { + // Either the data is corrupted or max_rings_num_ is not set correctly + // Note: point_walk_id == -1 so the point will be filtered out + ++invalid_ring_count; + continue; + } - for (const auto & indices : ring2indices) { - if (indices.size() < 2) continue; + auto & ring = rings[ring_idx]; + if (ring.current_walk.id == -1UL) { + // first walk ever for this ring. It is both the first and current walk of the ring. + ring.first_walk = + WalkInfo{++latest_walk_id, 1, curr_distance, curr_azimuth, curr_distance, curr_azimuth}; + ring.current_walk = ring.first_walk; + point_walk_id = latest_walk_id; + continue; + } - walk_first_idx = 0; - walk_last_idx = -1; + auto & walk = ring.current_walk; + if (isSameWalk( + curr_distance, curr_azimuth, walk.last_point_distance, walk.last_point_azimuth)) { + // current point is part of previous walk + walk.num_points += 1; + walk.last_point_distance = curr_distance; + walk.last_point_azimuth = curr_azimuth; + point_walk_id = walk.id; + } else { + // previous walk is finished, start a new one + + // check and store whether the previous walks is a cluster + if (walk.id >= walks_cluster_status.size()) walks_cluster_status.resize(walk.id + 1, false); + walks_cluster_status.at(walk.id) = isCluster(walk); + + ring.current_walk = + WalkInfo{++latest_walk_id, 1, curr_distance, curr_azimuth, curr_distance, curr_azimuth}; + point_walk_id = latest_walk_id; + } + } - for (size_t idx = 0U; idx < indices.size() - 1; ++idx) { - const size_t & current_data_idx = indices[idx]; - const size_t & next_data_idx = indices[idx + 1]; - walk_last_idx = idx; + // So far, we have processed ring points as if rings were not circular. Of course, the last and + // first points of a ring could totally be part of the same walk. When such thing happens, we need + // to merge the two walks + for (auto & ring : rings) { + if (ring.current_walk.id == -1UL) { + continue; + } - // if(std::abs(iter->distance - (iter+1)->distance) <= std::sqrt(iter->distance) * 0.08) + const auto & walk = ring.current_walk; + if (walk.id >= walks_cluster_status.size()) walks_cluster_status.resize(walk.id + 1, false); + walks_cluster_status.at(walk.id) = isCluster(walk); - const float & current_azimuth = - *reinterpret_cast(&input->data[current_data_idx + azimuth_offset]); - const float & next_azimuth = - *reinterpret_cast(&input->data[next_data_idx + azimuth_offset]); - float azimuth_diff = next_azimuth - current_azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + if (ring.first_walk.id == ring.current_walk.id) { + continue; + } - const float & current_distance = - *reinterpret_cast(&input->data[current_data_idx + distance_offset]); - const float & next_distance = - *reinterpret_cast(&input->data[next_data_idx + distance_offset]); + auto & first_walk = ring.first_walk; + auto & last_walk = ring.current_walk; + + // check if the two walks are connected + if (isSameWalk( + first_walk.first_point_distance, first_walk.first_point_azimuth, + last_walk.last_point_distance, last_walk.last_point_azimuth)) { + // merge + auto combined_num_points = first_walk.num_points + last_walk.num_points; + first_walk.first_point_distance = last_walk.first_point_distance; + first_walk.first_point_azimuth = last_walk.first_point_azimuth; + first_walk.num_points = combined_num_points; + last_walk.last_point_distance = first_walk.last_point_distance; + last_walk.last_point_azimuth = first_walk.last_point_azimuth; + last_walk.num_points = combined_num_points; + + walks_cluster_status.at(first_walk.id) = isCluster(first_walk); + walks_cluster_status.at(last_walk.id) = isCluster(last_walk); + } + } - if ( - std::max(current_distance, next_distance) < - std::min(current_distance, next_distance) * distance_ratio_ && - azimuth_diff < 100.f) { - continue; // Determined to be included in the same walk + // finally copy points + output.point_step = sizeof(PointXYZI); + output.data.resize(output.point_step * input->width * input->height); + size_t output_size = 0; + if (transform_info.need_transform) { + for (const auto & [raw_p, point_walk_id] : ranges::views::zip( + input->data | ranges::views::chunk(input->point_step), points_walk_id)) { + // Filter out points on invalid rings and points not in a cluster + if (point_walk_id == -1UL || !walks_cluster_status.at(point_walk_id)) { + continue; } - if (isCluster( - input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]), - walk_last_idx - walk_first_idx + 1)) { - for (int i = walk_first_idx; i <= walk_last_idx; i++) { - auto output_ptr = reinterpret_cast(&output.data[output_size]); - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); - - if (transform_info.need_transform) { - Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); - p = transform_info.eigen_transform * p; - output_ptr->x = p[0]; - output_ptr->y = p[1]; - output_ptr->z = p[2]; - } else { - *output_ptr = *input_ptr; - } - const float & intensity = - *reinterpret_cast(&input->data[indices[i] + intensity_offset]); - output_ptr->intensity = intensity; - - output_size += output.point_step; - } + // assume binary representation of input point is compatible with PointXYZ* + PointXYZI out_point; + std::memcpy(&out_point, raw_p.data(), sizeof(PointXYZI)); + + Eigen::Vector4f p(out_point.x, out_point.y, out_point.z, 1); + p = transform_info.eigen_transform * p; + out_point.x = p[0]; + out_point.y = p[1]; + out_point.z = p[2]; + // FIXME(VRichardJP) tmp fix because input data does not have the same layout than PointXYZI + std::memcpy( + &out_point.intensity, &raw_p.data()[intensity_offset], sizeof(out_point.intensity)); + + std::memcpy(&output.data[output_size], &out_point, sizeof(PointXYZI)); + output_size += sizeof(PointXYZI); + } + } else { + for (const auto & [raw_p, point_walk_id] : ranges::views::zip( + input->data | ranges::views::chunk(input->point_step), points_walk_id)) { + // Filter out points on invalid rings and points not in a cluster + if (point_walk_id == -1UL || !walks_cluster_status.at(point_walk_id)) { + continue; } - walk_first_idx = idx + 1; - } + PointXYZI out_point; + std::memcpy(&out_point, raw_p.data(), sizeof(PointXYZI)); + // FIXME(VRichardJP) tmp fix because input data does not have the same layout than PointXYZI + std::memcpy( + &out_point.intensity, &raw_p.data()[intensity_offset], sizeof(out_point.intensity)); - if (walk_first_idx > walk_last_idx) continue; - - if (isCluster( - input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]), - walk_last_idx - walk_first_idx + 1)) { - for (int i = walk_first_idx; i <= walk_last_idx; i++) { - auto output_ptr = reinterpret_cast(&output.data[output_size]); - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); - - if (transform_info.need_transform) { - Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); - p = transform_info.eigen_transform * p; - output_ptr->x = p[0]; - output_ptr->y = p[1]; - output_ptr->z = p[2]; - } else { - *output_ptr = *input_ptr; - } - const float & intensity = - *reinterpret_cast(&input->data[indices[i] + intensity_offset]); - output_ptr->intensity = intensity; - - output_size += output.point_step; - } + std::memcpy(&output.data[output_size], &out_point, sizeof(PointXYZI)); + + output_size += sizeof(PointXYZI); } } - output.data.resize(output_size); // Note that `input->header.frame_id` is data before converted when `transform_info.need_transform @@ -196,6 +332,12 @@ void RingOutlierFilterComponent::faster_filter( sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, "intensity", 1, sensor_msgs::msg::PointField::FLOAT32); + if (invalid_ring_count > 0) { + RCLCPP_WARN( + get_logger(), "%d points had ring index over max_rings_num (%d) and have been ignored.", + invalid_ring_count, max_rings_num_); + } + // add processing time for debug if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); From 4204c046d436f44f7a1567a7fd688fe405d16f5a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 23 Aug 2023 16:00:28 +0900 Subject: [PATCH 238/266] feat!: rename utm to local_cartesian_utm (#4704) * feat(map_projection_loader, map_loader): rename utm to local_cartesian_utm Signed-off-by: kminoda * fix readme Signed-off-by: kminoda * fix default ad api Signed-off-by: kminoda --------- Signed-off-by: kminoda --- map/map_loader/README.md | 2 +- .../src/lanelet2_map_loader/lanelet2_map_loader_node.cpp | 2 +- map/map_projection_loader/CMakeLists.txt | 2 +- map/map_projection_loader/README.md | 6 +++--- map/map_projection_loader/src/map_projection_loader.cpp | 4 ++-- ...fo_utm.yaml => projection_info_local_cartesian_utm.yaml} | 2 +- ...=> test_node_load_local_cartesian_utm_from_yaml.test.py} | 2 +- system/default_ad_api/src/vehicle.cpp | 2 +- 8 files changed, 11 insertions(+), 11 deletions(-) rename map/map_projection_loader/test/data/{projection_info_utm.yaml => projection_info_local_cartesian_utm.yaml} (69%) rename map/map_projection_loader/test/{test_node_load_utm_from_yaml.test.py => test_node_load_local_cartesian_utm_from_yaml.test.py} (98%) diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 4c64eb1eaecae..816cfc418f016 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -144,7 +144,7 @@ The node projects lan/lon coordinates into arbitrary coordinates defined in `/ma The node supports the following three types of coordinate systems: - MGRS -- UTM +- LocalCartesianUTM - local ### How to run diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index bb52e17c342ea..c443318a146ac 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -98,7 +98,7 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( if (errors.empty()) { return map; } - } else if (lanelet2_map_projector_type == "UTM") { + } else if (lanelet2_map_projector_type == "LocalCartesianUTM") { lanelet::GPSPoint position{map_origin_lat, map_origin_lon}; lanelet::Origin origin{position}; lanelet::projection::UtmProjector projector{origin}; diff --git a/map/map_projection_loader/CMakeLists.txt b/map/map_projection_loader/CMakeLists.txt index a53cdddf93b5b..8658ba172fde2 100644 --- a/map/map_projection_loader/CMakeLists.txt +++ b/map/map_projection_loader/CMakeLists.txt @@ -39,7 +39,7 @@ if(BUILD_TESTING) TIMEOUT "30" ) add_launch_test( - test/test_node_load_utm_from_yaml.test.py + test/test_node_load_local_cartesian_utm_from_yaml.test.py TIMEOUT "30" ) install(DIRECTORY diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md index bbf15f34929da..63095a72e835e 100644 --- a/map/map_projection_loader/README.md +++ b/map/map_projection_loader/README.md @@ -38,13 +38,13 @@ type: "MGRS" mgrs_grid: "54SUE" ``` -### Using UTM +### Using LocalCartesianUTM -If you want to use UTM, please specify the map origin as well. +If you want to use local cartesian UTM, please specify the map origin as well. ```yaml # map_projector_info.yaml -type: "UTM" +type: "LocalCartesianUTM" map_origin: latitude: 35.6092 longitude: 139.7303 diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp index 6d1459c628e35..2bd8a9cfa243a 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -30,14 +30,14 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi msg.type = data["type"].as(); if (msg.type == "MGRS") { msg.mgrs_grid = data["mgrs_grid"].as(); - } else if (msg.type == "UTM") { + } else if (msg.type == "LocalCartesianUTM") { msg.map_origin.latitude = data["map_origin"]["latitude"].as(); msg.map_origin.longitude = data["map_origin"]["longitude"].as(); } else if (msg.type == "local") { ; // do nothing } else { throw std::runtime_error( - "Invalid map projector type. Currently supported types: MGRS, UTM, and local"); + "Invalid map projector type. Currently supported types: MGRS, LocalCartesianUTM, and local"); } return msg; } diff --git a/map/map_projection_loader/test/data/projection_info_utm.yaml b/map/map_projection_loader/test/data/projection_info_local_cartesian_utm.yaml similarity index 69% rename from map/map_projection_loader/test/data/projection_info_utm.yaml rename to map/map_projection_loader/test/data/projection_info_local_cartesian_utm.yaml index 002383c97a474..c7500d37bb35a 100644 --- a/map/map_projection_loader/test/data/projection_info_utm.yaml +++ b/map/map_projection_loader/test/data/projection_info_local_cartesian_utm.yaml @@ -1,4 +1,4 @@ -type: UTM +type: LocalCartesianUTM map_origin: latitude: 35.6762 longitude: 139.6503 diff --git a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py similarity index 98% rename from map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py rename to map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py index 8d863033adcb8..920f5e3be11a1 100644 --- a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py @@ -33,7 +33,7 @@ logger = get_logger(__name__) -YAML_FILE_PATH = "test/data/projection_info_utm.yaml" +YAML_FILE_PATH = "test/data/projection_info_local_cartesian_utm.yaml" @pytest.mark.launch_test diff --git a/system/default_ad_api/src/vehicle.cpp b/system/default_ad_api/src/vehicle.cpp index d22e065d37c5f..61d5b2dde6103 100644 --- a/system/default_ad_api/src/vehicle.cpp +++ b/system/default_ad_api/src/vehicle.cpp @@ -154,7 +154,7 @@ void VehicleNode::publish_kinematics() vehicle_kinematics.geographic_pose.position.latitude = projected_gps_point.lat; vehicle_kinematics.geographic_pose.position.longitude = projected_gps_point.lon; vehicle_kinematics.geographic_pose.position.altitude = projected_gps_point.ele; - } else if (map_projector_info_->type == "UTM") { + } else if (map_projector_info_->type == "LocalCartesianUTM") { lanelet::GPSPoint position{ map_projector_info_->map_origin.latitude, map_projector_info_->map_origin.longitude}; lanelet::Origin origin{position}; From 0e4a772ae9efae87465d346d03eab8610baec5aa Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 23 Aug 2023 16:29:26 +0900 Subject: [PATCH 239/266] feat(behavior_path_planner): add PullOutPath member variables for ego predicted path generation (#4669) * add_pull_out_member_variables Signed-off-by: kyoichi-sugahara * update pull_out path struct Signed-off-by: kyoichi-sugahara * update pull_out path struct Signed-off-by: kyoichi-sugahara * minor update Signed-off-by: kyoichi-sugahara * fix calculation Signed-off-by: kyoichi-sugahara * fix build error Signed-off-by: kyoichi-sugahara * fix code Signed-off-by: kyoichi-sugahara * fix code Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../utils/start_planner/pull_out_path.hpp | 3 ++ .../start_planner/start_planner_module.cpp | 1 + .../start_planner/geometric_pull_out.cpp | 35 ++++++++++++++++++- .../utils/start_planner/shift_pull_out.cpp | 5 +++ 4 files changed, 43 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp index d68985ec27350..608b918e839fd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp @@ -19,6 +19,7 @@ #include +#include #include namespace behavior_path_planner @@ -27,6 +28,8 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; struct PullOutPath { std::vector partial_paths{}; + // accelerate with constant acceleration to the target velocity + std::vector> pairs_terminal_velocity_and_accel{}; Pose start_pose{}; Pose end_pose{}; }; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 4dd2e7a13a94d..2dc2401571d9a 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -106,6 +106,7 @@ void StartPlannerModule::processOnExit() bool StartPlannerModule::isExecutionRequested() const { + // TODO(Sugahara): if required lateral shift distance is small, don't engage this module. // Execute when current pose is near route start pose const Pose & start_pose = planner_data_->route_handler->getOriginalStartPose(); const Pose & current_pose = planner_data_->self_odometry->pose.pose; diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 721ffd3064840..45d36d51d69b4 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -80,15 +80,48 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p parameters_.collision_check_margin)) { return {}; } + const double velocity = parallel_parking_parameters_.forward_parking_velocity; if (parameters_.divide_pull_out_path) { output.partial_paths = planner_.getPaths(); + /* + Calculate the acceleration required to reach the forward parking velocity at the center of + the front path, assuming constant acceleration and deceleration. + v v + | | + | /\ | /\ + | / \ | / \ + | / \ | / \ + | / \ | / \ + |/________\_____ x |/________\______ t + 0 a_l/2 a_l 0 t_c 2*t_c + Notes: + a_l represents "arc_length_on_path_front" + t_c represents "time_to_center" + */ // insert stop velocity to first arc path end output.partial_paths.front().points.back().point.longitudinal_velocity_mps = 0.0; + const double arc_length_on_first_arc_path = + motion_utils::calcArcLength(output.partial_paths.front().points); + const double time_to_center = arc_length_on_first_arc_path / (2 * velocity); + const double average_velocity = arc_length_on_first_arc_path / (time_to_center * 2); + const double average_acceleration = average_velocity / (time_to_center * 2); + output.pairs_terminal_velocity_and_accel.push_back( + std::make_pair(average_velocity, average_acceleration)); + const double arc_length_on_second_arc_path = + motion_utils::calcArcLength(planner_.getArcPaths().at(1).points); + output.pairs_terminal_velocity_and_accel.push_back( + std::make_pair(velocity, velocity * velocity / (2 * arc_length_on_second_arc_path))); } else { - auto partial_paths = planner_.getPaths(); + const auto partial_paths = planner_.getPaths(); const auto combined_path = combineReferencePath(partial_paths.at(0), partial_paths.at(1)); output.partial_paths.push_back(combined_path); + + // Calculate the acceleration required to reach the forward parking velocity at the center of + // the path, assuming constant acceleration and deceleration. + const double arc_length_on_path = motion_utils::calcArcLength(combined_path.points); + output.pairs_terminal_velocity_and_accel.push_back( + std::make_pair(velocity, velocity * velocity / 2 * arc_length_on_path)); } output.start_pose = planner_.getArcPaths().at(0).points.front().point.pose; output.end_pose = planner_.getArcPaths().at(1).points.back().point.pose; diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index 08dcc0254deb1..7352821e140be 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -163,9 +163,12 @@ std::vector ShiftPullOut::calcPullOutPaths( // non_shifted_path for when shift length or pull out distance is too short const PullOutPath non_shifted_path = std::invoke([&]() { PullOutPath non_shifted_path{}; + // In non_shifted_path, to minimize safety checks, 0 is assigned to prevent the predicted_path + // of the ego vehicle from becoming too large. non_shifted_path.partial_paths.push_back(road_lane_reference_path); non_shifted_path.start_pose = start_pose; non_shifted_path.end_pose = start_pose; + non_shifted_path.pairs_terminal_velocity_and_accel.push_back(std::make_pair(0, 0)); return non_shifted_path; }); @@ -283,6 +286,8 @@ std::vector ShiftPullOut::calcPullOutPaths( candidate_path.partial_paths.push_back(shifted_path.path); candidate_path.start_pose = shift_line.start; candidate_path.end_pose = shift_line.end; + candidate_path.pairs_terminal_velocity_and_accel.push_back( + std::make_pair(terminal_velocity, longitudinal_acc)); candidate_paths.push_back(candidate_path); } From d0e99d47b3fc925c0500456e4604fb5b6d3a24fd Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 23 Aug 2023 16:30:09 +0900 Subject: [PATCH 240/266] fix(yabloc_image_processing): handle exception when no lines detected (#4717) Signed-off-by: kminoda --- .../src/line_segment_detector/line_segment_detector_core.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp index 6a127c70bb9a0..57f2302fd5c5a 100644 --- a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp @@ -54,7 +54,9 @@ void LineSegmentDetector::execute(const cv::Mat & image, const rclcpp::Time & st { tier4_autoware_utils::StopWatch stop_watch; line_segment_detector_->detect(gray_image, lines); - line_segment_detector_->drawSegments(gray_image, lines); + if (lines.size().width != 0) { + line_segment_detector_->drawSegments(gray_image, lines); + } RCLCPP_INFO_STREAM(this->get_logger(), "lsd: " << stop_watch.toc() << "[ms]"); } From a69ee45f0ed6758b5538e3923074500f4e36b480 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 23 Aug 2023 16:51:17 +0900 Subject: [PATCH 241/266] feat(gnss_poser): remove plane coordinate (#4711) * feat(gnss_poser): remove plane coordinate Signed-off-by: kminoda * style(pre-commit): autofix * remove geo_pos_conv Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- sensing/geo_pos_conv/CHANGELOG.rst | 203 ------------ sensing/geo_pos_conv/CMakeLists.txt | 11 - sensing/geo_pos_conv/README.md | 21 -- .../include/geo_pos_conv/geo_pos_conv.hpp | 56 ---- sensing/geo_pos_conv/package.xml | 22 -- sensing/geo_pos_conv/src/geo_pos_conv.cpp | 312 ------------------ sensing/gnss_poser/README.md | 17 +- .../gnss_poser/include/gnss_poser/convert.hpp | 15 - .../include/gnss_poser/gnss_poser_core.hpp | 2 - .../include/gnss_poser/gnss_stat.hpp | 1 - .../gnss_poser/launch/gnss_poser.launch.xml | 4 +- sensing/gnss_poser/package.xml | 1 - sensing/gnss_poser/src/gnss_poser_core.cpp | 3 - 13 files changed, 9 insertions(+), 659 deletions(-) delete mode 100644 sensing/geo_pos_conv/CHANGELOG.rst delete mode 100644 sensing/geo_pos_conv/CMakeLists.txt delete mode 100644 sensing/geo_pos_conv/README.md delete mode 100644 sensing/geo_pos_conv/include/geo_pos_conv/geo_pos_conv.hpp delete mode 100644 sensing/geo_pos_conv/package.xml delete mode 100644 sensing/geo_pos_conv/src/geo_pos_conv.cpp diff --git a/sensing/geo_pos_conv/CHANGELOG.rst b/sensing/geo_pos_conv/CHANGELOG.rst deleted file mode 100644 index 12d311b5aaa5d..0000000000000 --- a/sensing/geo_pos_conv/CHANGELOG.rst +++ /dev/null @@ -1,203 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package geo_pos_conv -^^^^^^^^^^^^^^^^^^^^^^^^^^ - -2.0.0 (2020-10-03) ------------------- -* Convert package to ROS 2 - -1.11.0 (2019-03-21) -------------------- -* add constructor (`#1913 `_) -* Fix license notice in corresponding package.xml -* Contributors: YamatoAndo, amc-nu - -1.10.0 (2019-01-17) -------------------- -* Switch to Apache 2 license (develop branch) (`#1741 `_) - * Switch to Apache 2 - * Replace BSD-3 license header with Apache 2 and reassign copyright to the - Autoware Foundation. - * Update license on Python files - * Update copyright years - * Add #ifndef/define _POINTS_IMAGE_H\_ - * Updated license comment -* Contributors: Esteve Fernandez - -1.9.1 (2018-11-06) ------------------- - -1.9.0 (2018-10-31) ------------------- - -1.8.0 (2018-08-31) ------------------- - -1.7.0 (2018-05-18) ------------------- -* update Version from 1.6.3 to 1.7.0 in package.xml and CHANGELOG.rst -* [fix] Fixes for all packages and dependencies (`#1240 `_) - * Initial Cleanup - * fixed also for indigo - * kf cjeck - * Fix road wizard - * Added travis ci - * Trigger CI - * Fixes to cv_tracker and lidar_tracker cmake - * Fix kitti player dependencies - * Removed unnecessary dependencies - * messages fixing for can - * Update build script travis - * Travis Path - * Travis Paths fix - * Travis test - * Eigen checks - * removed unnecessary dependencies - * Eigen Detection - * Job number reduced - * Eigen3 more fixes - * More Eigen3 - * Even more Eigen - * find package cmake modules included - * More fixes to cmake modules - * Removed non ros dependency - * Enable industrial_ci for indidog and kinetic - * Wrong install command - * fix rviz_plugin install - * FastVirtualScan fix - * Fix Qt5 Fastvirtualscan - * Fixed qt5 system dependencies for rosdep - * NDT TKU Fix catkin not pacakged - * More in detail dependencies fixes for more packages - * GLEW library for ORB - * Ignore OrbLocalizer - * Ignore Version checker - * Fix for driveworks interface - * driveworks not catkinpackagedd - * Missing catkin for driveworks - * libdpm opencv not catkin packaged - * catkin lib gnss not included in obj_db - * Points2Polygon fix - * More missing dependencies - * image viewer not packaged - * Fixed SSH2 detection, added viewers for all distros - * Fix gnss localizer incorrect dependency config - * Fixes to multiple packages dependencies - * gnss plib and package - * More fixes to gnss - * gnss dependencies for gnss_loclaizer - * Missing gnss dependency for gnss on localizer - * More fixes for dependencies - Replaced gnss for autoware_gnss_library - * gnss more fixes - * fixes to more dependencies - * header dependency - * Debug message - * more debug messages changed back to gnss - * debud messages - * gnss test - * gnss install command - * Several fixes for OpenPlanner and its lbiraries - * Fixes to ROSInterface - * More fixes to robotsdk and rosinterface - * robotsdk calibration fix - * Fixes to rosinterface robotsdk libraries and its nodes - * Fixes to Qt5 missing dependencies in robotsdk - * glviewer missing dependencies - * Missing qt specific config cmake for robotsdk - * disable cv_tracker - * Fix to open planner un needed dependendecies - * Fixes for libraries indecision maker - * Fixes to libraries decision_maker installation - * Gazebo on Kinetic - * Added Missing library - * * Removed Gazebo and synchonization packages - * Renames vmap in lane_planner - * Added installation commands for missing pakcages - * Fixes to lane_planner - * Added NDT TKU Glut extra dependencies - * ndt localizer/lib fast pcl fixes - re enable cv_tracker - * Fix kf_lib - * Keep industrial_ci - * Fixes for dpm library - * Fusion lib fixed - * dpm and fusion header should match exported project name - * Fixes to dpm_ocv ndt_localizer and pcl_omp - * no fast_pcl anymore - * fixes to libdpm and its package - * CI test - * test with native travis ci - * missing update for apt - * Fixes to pcl_omp installation and headers - * Final fixes for tests, modified README - * * Fixes to README - * Enable industrial_ci - * re enable native travis tests -* Contributors: Abraham Monrroy, Kosuke Murakami - -1.6.3 (2018-03-06) ------------------- - -1.6.2 (2018-02-27) ------------------- -* Update CHANGELOG -* Contributors: Yusuke FUJII - -1.6.1 (2018-01-20) ------------------- -* update CHANGELOG -* Contributors: Yusuke FUJII - -1.6.0 (2017-12-11) ------------------- -* Prepare release for 1.6.0 -* support all plane(1-19) in geo_pos_conv -* Contributors: Yamato ANDO, yukikitsukawa - -1.5.1 (2017-09-25) ------------------- -* Release/1.5.1 (`#816 `_) - * fix a build error by gcc version - * fix build error for older indigo version - * update changelog for v1.5.1 - * 1.5.1 -* Contributors: Yusuke FUJII - -1.5.0 (2017-09-21) ------------------- -* Update changelog -* install target -* Contributors: Dejan Pangercic, Yusuke FUJII - -1.4.0 (2017-08-04) ------------------- -* version number must equal current release number so we can start releasing in the future -* added changelogs -* Contributors: Dejan Pangercic - -1.3.1 (2017-07-16) ------------------- - -1.3.0 (2017-07-14) ------------------- - -1.2.0 (2017-06-07) ------------------- - -1.1.2 (2017-02-27 23:10) ------------------------- - -1.1.1 (2017-02-27 22:25) ------------------------- - -1.1.0 (2017-02-24) ------------------- - -1.0.1 (2017-01-14) ------------------- - -1.0.0 (2016-12-22) ------------------- -* Initial commit for public release -* Contributors: Shinpei Kato diff --git a/sensing/geo_pos_conv/CMakeLists.txt b/sensing/geo_pos_conv/CMakeLists.txt deleted file mode 100644 index 3c3fad0fadf5c..0000000000000 --- a/sensing/geo_pos_conv/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(geo_pos_conv) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(geo_pos_conv SHARED - src/geo_pos_conv.cpp -) - -ament_auto_package() diff --git a/sensing/geo_pos_conv/README.md b/sensing/geo_pos_conv/README.md deleted file mode 100644 index c75a642bdefb5..0000000000000 --- a/sensing/geo_pos_conv/README.md +++ /dev/null @@ -1,21 +0,0 @@ -# geo_pos_conv - -## Purpose - -The `geo_pos_conv` is a library to calculate the conversion between **x, y positions on the plane rectangular coordinate** and **latitude/longitude on the earth**. - -## Inner-workings / Algorithms - -## Inputs / Outputs - -## Parameters - -## Assumptions / Known limits - -## (Optional) Error detection and handling - -## (Optional) Performance characterization - -## (Optional) References/External links - -## (Optional) Future extensions / Unimplemented parts diff --git a/sensing/geo_pos_conv/include/geo_pos_conv/geo_pos_conv.hpp b/sensing/geo_pos_conv/include/geo_pos_conv/geo_pos_conv.hpp deleted file mode 100644 index 68c4b408efd2d..0000000000000 --- a/sensing/geo_pos_conv/include/geo_pos_conv/geo_pos_conv.hpp +++ /dev/null @@ -1,56 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef GEO_POS_CONV__GEO_POS_CONV_HPP_ -#define GEO_POS_CONV__GEO_POS_CONV_HPP_ - -#include - -class geo_pos_conv -{ -private: - double m_x; // m - double m_y; // m - double m_z; // m - - double m_lat; // latitude - double m_lon; // longitude - double m_h; - - double m_PLato; // plane lat - double m_PLo; // plane lon - -public: - geo_pos_conv(); - double x() const; - double y() const; - double z() const; - - void set_plane(double lat, double lon); - void set_plane(int num); - void set_xyz(double cx, double cy, double cz); - - // set llh in radians - void set_llh(double lat, double lon, double h); - - // set llh in nmea degrees - void set_llh_nmea_degrees(double latd, double lond, double h); - - void llh_to_xyz(double lat, double lon, double ele); - - void conv_llh2xyz(void); - void conv_xyz2llh(void); -}; - -#endif // GEO_POS_CONV__GEO_POS_CONV_HPP_ diff --git a/sensing/geo_pos_conv/package.xml b/sensing/geo_pos_conv/package.xml deleted file mode 100644 index b82ea443ef7d5..0000000000000 --- a/sensing/geo_pos_conv/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - geo_pos_conv - 2.0.0 - The ROS 2 geo_pos_conv package - Yamato Ando - - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - rclcpp - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/sensing/geo_pos_conv/src/geo_pos_conv.cpp b/sensing/geo_pos_conv/src/geo_pos_conv.cpp deleted file mode 100644 index 5fc489d46980f..0000000000000 --- a/sensing/geo_pos_conv/src/geo_pos_conv.cpp +++ /dev/null @@ -1,312 +0,0 @@ -// Copyright 2020 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. -/* - * Copyright 2015-2019 Autoware Foundation. 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. - */ - -#include "geo_pos_conv/geo_pos_conv.hpp" - -geo_pos_conv::geo_pos_conv() -: m_x(0), m_y(0), m_z(0), m_lat(0), m_lon(0), m_h(0), m_PLato(0), m_PLo(0) -{ -} - -double geo_pos_conv::x() const -{ - return m_x; -} - -double geo_pos_conv::y() const -{ - return m_y; -} - -double geo_pos_conv::z() const -{ - return m_z; -} - -void geo_pos_conv::set_plane(double lat, double lon) -{ - m_PLato = lat; - m_PLo = lon; -} - -void geo_pos_conv::set_plane(int num) -{ - int lon_deg, lon_min, lat_deg, - lat_min; // longitude and latitude of origin of each plane in Japan - if (num == 1) { - lon_deg = 33; - lon_min = 0; - lat_deg = 129; - lat_min = 30; - } else if (num == 2) { - lon_deg = 33; - lon_min = 0; - lat_deg = 131; - lat_min = 0; - } else if (num == 3) { - lon_deg = 36; - lon_min = 0; - lat_deg = 132; - lat_min = 10; - } else if (num == 4) { - lon_deg = 33; - lon_min = 0; - lat_deg = 133; - lat_min = 30; - } else if (num == 5) { - lon_deg = 36; - lon_min = 0; - lat_deg = 134; - lat_min = 20; - } else if (num == 6) { - lon_deg = 36; - lon_min = 0; - lat_deg = 136; - lat_min = 0; - } else if (num == 7) { - lon_deg = 36; - lon_min = 0; - lat_deg = 137; - lat_min = 10; - } else if (num == 8) { - lon_deg = 36; - lon_min = 0; - lat_deg = 138; - lat_min = 30; - } else if (num == 9) { - lon_deg = 36; - lon_min = 0; - lat_deg = 139; - lat_min = 50; - } else if (num == 10) { - lon_deg = 40; - lon_min = 0; - lat_deg = 140; - lat_min = 50; - } else if (num == 11) { - lon_deg = 44; - lon_min = 0; - lat_deg = 140; - lat_min = 15; - } else if (num == 12) { - lon_deg = 44; - lon_min = 0; - lat_deg = 142; - lat_min = 15; - } else if (num == 13) { - lon_deg = 44; - lon_min = 0; - lat_deg = 144; - lat_min = 15; - } else if (num == 14) { - lon_deg = 26; - lon_min = 0; - lat_deg = 142; - lat_min = 0; - } else if (num == 15) { - lon_deg = 26; - lon_min = 0; - lat_deg = 127; - lat_min = 30; - } else if (num == 16) { - lon_deg = 26; - lon_min = 0; - lat_deg = 124; - lat_min = 0; - } else if (num == 17) { - lon_deg = 26; - lon_min = 0; - lat_deg = 131; - lat_min = 0; - } else if (num == 18) { - lon_deg = 20; - lon_min = 0; - lat_deg = 136; - lat_min = 0; - } else if (num == 19) { - lon_deg = 26; - lon_min = 0; - lat_deg = 154; - lat_min = 0; - } else { - lon_deg = 0; - lon_min = 0; - lat_deg = 0; - lat_min = 0; - } - - // swap longitude and latitude - m_PLo = M_PI * (lat_deg + lat_min / 60.0) / 180.0; - m_PLato = M_PI * (lon_deg + lon_min / 60.0) / 180; -} - -void geo_pos_conv::set_xyz(double cx, double cy, double cz) -{ - m_x = cx; - m_y = cy; - m_z = cz; - conv_xyz2llh(); -} - -void geo_pos_conv::set_llh_nmea_degrees(double latd, double lond, double h) -{ - double lat, lad, lod, lon; - // 1234.56 -> 12'34.56 -> 12+ 34.56/60 - - lad = floor(latd / 100.); - lat = latd - lad * 100.; - lod = floor(lond / 100.); - lon = lond - lod * 100.; - - // Changing Longitude and Latitude to Radians - m_lat = (lad + lat / 60.0) * M_PI / 180; - m_lon = (lod + lon / 60.0) * M_PI / 180; - m_h = h; - - conv_llh2xyz(); -} - -void geo_pos_conv::llh_to_xyz(double lat, double lon, double ele) -{ - m_lat = lat * M_PI / 180; - m_lon = lon * M_PI / 180; - m_h = ele; - - conv_llh2xyz(); -} - -void geo_pos_conv::conv_llh2xyz(void) -{ - double PS; // - double PSo; // - double PDL; // - double Pt; // - double PN; // - double PW; // - - double PB1, PB2, PB3, PB4, PB5, PB6, PB7, PB8, PB9; - double PA, PB, PC, PD, PE, PF, PG, PH, PI; - double Pe; // - double Pet; // - double Pnn; // - double AW, FW, Pmo; - - Pmo = 0.9999; - - /*WGS84 Parameters*/ - AW = 6378137.0; // Semi-major Axis - FW = 1.0 / 298.257222101; // 298.257223563 //Geometrical flattening - - Pe = sqrt(2.0 * FW - pow(FW, 2)); - Pet = sqrt(pow(Pe, 2) / (1.0 - pow(Pe, 2))); - - PA = 1.0 + 3.0 / 4.0 * pow(Pe, 2) + 45.0 / 64.0 * pow(Pe, 4) + 175.0 / 256.0 * pow(Pe, 6) + - 11025.0 / 16384.0 * pow(Pe, 8) + 43659.0 / 65536.0 * pow(Pe, 10) + - 693693.0 / 1048576.0 * pow(Pe, 12) + 19324305.0 / 29360128.0 * pow(Pe, 14) + - 4927697775.0 / 7516192768.0 * pow(Pe, 16); - - PB = 3.0 / 4.0 * pow(Pe, 2) + 15.0 / 16.0 * pow(Pe, 4) + 525.0 / 512.0 * pow(Pe, 6) + - 2205.0 / 2048.0 * pow(Pe, 8) + 72765.0 / 65536.0 * pow(Pe, 10) + - 297297.0 / 262144.0 * pow(Pe, 12) + 135270135.0 / 117440512.0 * pow(Pe, 14) + - 547521975.0 / 469762048.0 * pow(Pe, 16); - - PC = 15.0 / 64.0 * pow(Pe, 4) + 105.0 / 256.0 * pow(Pe, 6) + 2205.0 / 4096.0 * pow(Pe, 8) + - 10395.0 / 16384.0 * pow(Pe, 10) + 1486485.0 / 2097152.0 * pow(Pe, 12) + - 45090045.0 / 58720256.0 * pow(Pe, 14) + 766530765.0 / 939524096.0 * pow(Pe, 16); - - PD = 35.0 / 512.0 * pow(Pe, 6) + 315.0 / 2048.0 * pow(Pe, 8) + 31185.0 / 131072.0 * pow(Pe, 10) + - 165165.0 / 524288.0 * pow(Pe, 12) + 45090045.0 / 117440512.0 * pow(Pe, 14) + - 209053845.0 / 469762048.0 * pow(Pe, 16); - - PE = 315.0 / 16384.0 * pow(Pe, 8) + 3465.0 / 65536.0 * pow(Pe, 10) + - 99099.0 / 1048576.0 * pow(Pe, 12) + 4099095.0 / 29360128.0 * pow(Pe, 14) + - 348423075.0 / 1879048192.0 * pow(Pe, 16); - - PF = 693.0 / 131072.0 * pow(Pe, 10) + 9009.0 / 524288.0 * pow(Pe, 12) + - 4099095.0 / 117440512.0 * pow(Pe, 14) + 26801775.0 / 469762048.0 * pow(Pe, 16); - - PG = 3003.0 / 2097152.0 * pow(Pe, 12) + 315315.0 / 58720256.0 * pow(Pe, 14) + - 11486475.0 / 939524096.0 * pow(Pe, 16); - - PH = 45045.0 / 117440512.0 * pow(Pe, 14) + 765765.0 / 469762048.0 * pow(Pe, 16); - - PI = 765765.0 / 7516192768.0 * pow(Pe, 16); - - PB1 = AW * (1.0 - pow(Pe, 2)) * PA; - PB2 = AW * (1.0 - pow(Pe, 2)) * PB / -2.0; - PB3 = AW * (1.0 - pow(Pe, 2)) * PC / 4.0; - PB4 = AW * (1.0 - pow(Pe, 2)) * PD / -6.0; - PB5 = AW * (1.0 - pow(Pe, 2)) * PE / 8.0; - PB6 = AW * (1.0 - pow(Pe, 2)) * PF / -10.0; - PB7 = AW * (1.0 - pow(Pe, 2)) * PG / 12.0; - PB8 = AW * (1.0 - pow(Pe, 2)) * PH / -14.0; - PB9 = AW * (1.0 - pow(Pe, 2)) * PI / 16.0; - - PS = PB1 * m_lat + PB2 * sin(2.0 * m_lat) + PB3 * sin(4.0 * m_lat) + PB4 * sin(6.0 * m_lat) + - PB5 * sin(8.0 * m_lat) + PB6 * sin(10.0 * m_lat) + PB7 * sin(12.0 * m_lat) + - PB8 * sin(14.0 * m_lat) + PB9 * sin(16.0 * m_lat); - - PSo = PB1 * m_PLato + PB2 * sin(2.0 * m_PLato) + PB3 * sin(4.0 * m_PLato) + - PB4 * sin(6.0 * m_PLato) + PB5 * sin(8.0 * m_PLato) + PB6 * sin(10.0 * m_PLato) + - PB7 * sin(12.0 * m_PLato) + PB8 * sin(14.0 * m_PLato) + PB9 * sin(16.0 * m_PLato); - - PDL = m_lon - m_PLo; - Pt = tan(m_lat); - PW = sqrt(1.0 - pow(Pe, 2) * pow(sin(m_lat), 2)); - PN = AW / PW; - Pnn = sqrt(pow(Pet, 2) * pow(cos(m_lat), 2)); - - m_x = ((PS - PSo) + (1.0 / 2.0) * PN * pow(cos(m_lat), 2.0) * Pt * pow(PDL, 2.0) + - (1.0 / 24.0) * PN * pow(cos(m_lat), 4) * Pt * - (5.0 - pow(Pt, 2) + 9.0 * pow(Pnn, 2) + 4.0 * pow(Pnn, 4)) * pow(PDL, 4) - - (1.0 / 720.0) * PN * pow(cos(m_lat), 6) * Pt * - (-61.0 + 58.0 * pow(Pt, 2) - pow(Pt, 4) - 270.0 * pow(Pnn, 2) + - 330.0 * pow(Pt, 2) * pow(Pnn, 2)) * - pow(PDL, 6) - - (1.0 / 40320.0) * PN * pow(cos(m_lat), 8) * Pt * - (-1385.0 + 3111 * pow(Pt, 2) - 543 * pow(Pt, 4) + pow(Pt, 6)) * pow(PDL, 8)) * - Pmo; - - m_y = (PN * cos(m_lat) * PDL - - 1.0 / 6.0 * PN * pow(cos(m_lat), 3) * (-1 + pow(Pt, 2) - pow(Pnn, 2)) * pow(PDL, 3) - - 1.0 / 120.0 * PN * pow(cos(m_lat), 5) * - (-5.0 + 18.0 * pow(Pt, 2) - pow(Pt, 4) - 14.0 * pow(Pnn, 2) + - 58.0 * pow(Pt, 2) * pow(Pnn, 2)) * - pow(PDL, 5) - - 1.0 / 5040.0 * PN * pow(cos(m_lat), 7) * - (-61.0 + 479.0 * pow(Pt, 2) - 179.0 * pow(Pt, 4) + pow(Pt, 6)) * pow(PDL, 7)) * - Pmo; - - m_z = m_h; -} - -void geo_pos_conv::conv_xyz2llh(void) -{ - // n/a -} diff --git a/sensing/gnss_poser/README.md b/sensing/gnss_poser/README.md index d37152297c61d..f77c6ac1cdeb1 100644 --- a/sensing/gnss_poser/README.md +++ b/sensing/gnss_poser/README.md @@ -27,15 +27,14 @@ The `gnss_poser` is a node that subscribes gnss sensing messages and calculates ### Core Parameters -| Name | Type | Default Value | Description | -| ---------------------- | ------ | ---------------- | -------------------------------------------------------------------------------------------------------------------------- | -| `base_frame` | string | "base_link" | frame id | -| `gnss_frame` | string | "gnss" | frame id | -| `gnss_base_frame` | string | "gnss_base_link" | frame id | -| `map_frame` | string | "map" | frame id | -| `coordinate_system` | int | "4" | coordinate system enumeration; 0: UTM, 1: MGRS, 2: Plane, 3: WGS84 Local Coordinate System, 4: UTM Local Coordinate System | -| `plane_zone` | int | 9 | identification number of the plane rectangular coordinate systems. | -| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. | +| Name | Type | Default Value | Description | +| ---------------------- | ------ | ---------------- | ---------------------------------------------------------------------------------------------------------------- | +| `base_frame` | string | "base_link" | frame id | +| `gnss_frame` | string | "gnss" | frame id | +| `gnss_base_frame` | string | "gnss_base_link" | frame id | +| `map_frame` | string | "map" | frame id | +| `coordinate_system` | int | "4" | coordinate system enumeration; 0: UTM, 1: MGRS, 3: WGS84 Local Coordinate System, 4: UTM Local Coordinate System | +| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. | ## Assumptions / Known limits diff --git a/sensing/gnss_poser/include/gnss_poser/convert.hpp b/sensing/gnss_poser/include/gnss_poser/convert.hpp index 3e4122893ecb6..f2353f070334b 100644 --- a/sensing/gnss_poser/include/gnss_poser/convert.hpp +++ b/sensing/gnss_poser/include/gnss_poser/convert.hpp @@ -20,7 +20,6 @@ #include #include #include -#include #include #include @@ -183,20 +182,6 @@ GNSSStat NavSatFix2MGRS( return mgrs; } -GNSSStat NavSatFix2PLANE( - const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg, const int & plane_zone, - const rclcpp::Logger & logger) -{ - GNSSStat plane; - plane.coordinate_system = CoordinateSystem::PLANE; - geo_pos_conv geo; - geo.set_plane(plane_zone); - geo.llh_to_xyz(nav_sat_fix_msg.latitude, nav_sat_fix_msg.longitude, nav_sat_fix_msg.altitude); - plane.x = geo.y(); - plane.y = geo.x(); - plane.z = EllipsoidHeight2OrthometricHeight(nav_sat_fix_msg, logger); - return plane; -} } // namespace gnss_poser #endif // GNSS_POSER__CONVERT_HPP_ diff --git a/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp b/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp index 2b729a9e374f7..4baaec2dfe80e 100644 --- a/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp +++ b/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp @@ -100,8 +100,6 @@ class GNSSPoser : public rclcpp::Node boost::circular_buffer position_buffer_; - int plane_zone_; - autoware_sensing_msgs::msg::GnssInsOrientationStamped::SharedPtr msg_gnss_ins_orientation_stamped_; int height_system_; diff --git a/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp b/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp index 46fdc6eeff9ee..809648539c846 100644 --- a/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp +++ b/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp @@ -21,7 +21,6 @@ namespace gnss_poser enum class CoordinateSystem { UTM = 0, MGRS = 1, - PLANE = 2, LOCAL_CARTESIAN_WGS84 = 3, LOCAL_CARTESIAN_UTM = 4 }; diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/gnss_poser/launch/gnss_poser.launch.xml index e7dc06864ce84..88a07f8fc709f 100755 --- a/sensing/gnss_poser/launch/gnss_poser.launch.xml +++ b/sensing/gnss_poser/launch/gnss_poser.launch.xml @@ -13,10 +13,9 @@ - + - @@ -34,7 +33,6 @@ - diff --git a/sensing/gnss_poser/package.xml b/sensing/gnss_poser/package.xml index 4887494614a81..1488f329edecb 100644 --- a/sensing/gnss_poser/package.xml +++ b/sensing/gnss_poser/package.xml @@ -14,7 +14,6 @@ libboost-dev autoware_sensing_msgs - geo_pos_conv geographiclib geometry_msgs rclcpp diff --git a/sensing/gnss_poser/src/gnss_poser_core.cpp b/sensing/gnss_poser/src/gnss_poser_core.cpp index 8fc7d9c1599f5..faacedbfef9bf 100644 --- a/sensing/gnss_poser/src/gnss_poser_core.cpp +++ b/sensing/gnss_poser/src/gnss_poser_core.cpp @@ -32,7 +32,6 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options) gnss_base_frame_(declare_parameter("gnss_base_frame", "gnss_base_link")), map_frame_(declare_parameter("map_frame", "map")), use_gnss_ins_orientation_(declare_parameter("use_gnss_ins_orientation", true)), - plane_zone_(declare_parameter("plane_zone", 9)), msg_gnss_ins_orientation_stamped_( std::make_shared()), height_system_(declare_parameter("height_system", 1)), @@ -199,8 +198,6 @@ GNSSStat GNSSPoser::convert( } else if (coordinate_system == CoordinateSystem::MGRS) { gnss_stat = NavSatFix2MGRS( nav_sat_fix_msg, MGRSPrecision::_100MICRO_METER, this->get_logger(), height_system); - } else if (coordinate_system == CoordinateSystem::PLANE) { - gnss_stat = NavSatFix2PLANE(nav_sat_fix_msg, plane_zone_, this->get_logger()); } else if (coordinate_system == CoordinateSystem::LOCAL_CARTESIAN_WGS84) { gnss_stat = NavSatFix2LocalCartesianWGS84(nav_sat_fix_msg, nav_sat_fix_origin_, this->get_logger()); From 9da3b8be4590b52295085694b93068715484f1d2 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 23 Aug 2023 17:49:50 +0900 Subject: [PATCH 242/266] feat(gnss_poser): remove utm projection in gnss_poser (#4702) * feat(gnss_poser): remove UTM projection in gnss_poser Signed-off-by: kminoda * update readme Signed-off-by: kminoda * style(pre-commit): autofix * remove coordinate_system from GNSSStat Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- sensing/gnss_poser/README.md | 16 ++++++++-------- .../gnss_poser/include/gnss_poser/convert.hpp | 5 ----- .../gnss_poser/include/gnss_poser/gnss_stat.hpp | 11 ++--------- sensing/gnss_poser/launch/gnss_poser.launch.xml | 2 +- sensing/gnss_poser/src/gnss_poser_core.cpp | 4 +--- 5 files changed, 12 insertions(+), 26 deletions(-) diff --git a/sensing/gnss_poser/README.md b/sensing/gnss_poser/README.md index f77c6ac1cdeb1..6eef2cc243ef5 100644 --- a/sensing/gnss_poser/README.md +++ b/sensing/gnss_poser/README.md @@ -27,14 +27,14 @@ The `gnss_poser` is a node that subscribes gnss sensing messages and calculates ### Core Parameters -| Name | Type | Default Value | Description | -| ---------------------- | ------ | ---------------- | ---------------------------------------------------------------------------------------------------------------- | -| `base_frame` | string | "base_link" | frame id | -| `gnss_frame` | string | "gnss" | frame id | -| `gnss_base_frame` | string | "gnss_base_link" | frame id | -| `map_frame` | string | "map" | frame id | -| `coordinate_system` | int | "4" | coordinate system enumeration; 0: UTM, 1: MGRS, 3: WGS84 Local Coordinate System, 4: UTM Local Coordinate System | -| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. | +| Name | Type | Default Value | Description | +| ---------------------- | ------ | ---------------- | -------------------------------------------------------------------------------------------------------- | +| `base_frame` | string | "base_link" | frame id | +| `gnss_frame` | string | "gnss" | frame id | +| `gnss_base_frame` | string | "gnss_base_link" | frame id | +| `map_frame` | string | "map" | frame id | +| `coordinate_system` | int | "4" | coordinate system enumeration; 1: MGRS, 3: WGS84 Local Coordinate System, 4: UTM Local Coordinate System | +| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. | ## Assumptions / Known limits diff --git a/sensing/gnss_poser/include/gnss_poser/convert.hpp b/sensing/gnss_poser/include/gnss_poser/convert.hpp index f2353f070334b..5c1f621626aa2 100644 --- a/sensing/gnss_poser/include/gnss_poser/convert.hpp +++ b/sensing/gnss_poser/include/gnss_poser/convert.hpp @@ -61,7 +61,6 @@ GNSSStat NavSatFix2LocalCartesianWGS84( sensor_msgs::msg::NavSatFix nav_sat_fix_origin_, const rclcpp::Logger & logger) { GNSSStat local_cartesian; - local_cartesian.coordinate_system = CoordinateSystem::LOCAL_CARTESIAN_WGS84; try { GeographicLib::LocalCartesian localCartesian_origin( @@ -83,7 +82,6 @@ GNSSStat NavSatFix2UTM( int height_system) { GNSSStat utm; - utm.coordinate_system = CoordinateSystem::UTM; try { GeographicLib::UTMUPS::Forward( @@ -107,11 +105,9 @@ GNSSStat NavSatFix2LocalCartesianUTM( sensor_msgs::msg::NavSatFix nav_sat_fix_origin, const rclcpp::Logger & logger, int height_system) { GNSSStat utm_local; - utm_local.coordinate_system = CoordinateSystem::UTM; try { // origin of the local coordinate system in global frame GNSSStat utm_origin; - utm_origin.coordinate_system = CoordinateSystem::UTM; GeographicLib::UTMUPS::Forward( nav_sat_fix_origin.latitude, nav_sat_fix_origin.longitude, utm_origin.zone, utm_origin.east_north_up, utm_origin.x, utm_origin.y); @@ -150,7 +146,6 @@ GNSSStat UTM2MGRS( constexpr int GZD_ID_size = 5; // size of header like "53SPU" GNSSStat mgrs = utm; - mgrs.coordinate_system = CoordinateSystem::MGRS; try { std::string mgrs_code; GeographicLib::MGRS::Forward( diff --git a/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp b/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp index 809648539c846..fa17bf0e6e232 100644 --- a/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp +++ b/sensing/gnss_poser/include/gnss_poser/gnss_stat.hpp @@ -18,18 +18,12 @@ namespace gnss_poser { -enum class CoordinateSystem { - UTM = 0, - MGRS = 1, - LOCAL_CARTESIAN_WGS84 = 3, - LOCAL_CARTESIAN_UTM = 4 -}; +enum class CoordinateSystem { MGRS = 1, LOCAL_CARTESIAN_WGS84 = 3, LOCAL_CARTESIAN_UTM = 4 }; struct GNSSStat { GNSSStat() - : coordinate_system(CoordinateSystem::MGRS), - east_north_up(true), + : east_north_up(true), zone(0), mgrs_zone(""), x(0), @@ -41,7 +35,6 @@ struct GNSSStat { } - CoordinateSystem coordinate_system; bool east_north_up; int zone; std::string mgrs_zone; diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/gnss_poser/launch/gnss_poser.launch.xml index 88a07f8fc709f..3883a492358d6 100755 --- a/sensing/gnss_poser/launch/gnss_poser.launch.xml +++ b/sensing/gnss_poser/launch/gnss_poser.launch.xml @@ -13,7 +13,7 @@ - + diff --git a/sensing/gnss_poser/src/gnss_poser_core.cpp b/sensing/gnss_poser/src/gnss_poser_core.cpp index faacedbfef9bf..7d244ce188eee 100644 --- a/sensing/gnss_poser/src/gnss_poser_core.cpp +++ b/sensing/gnss_poser/src/gnss_poser_core.cpp @@ -190,9 +190,7 @@ GNSSStat GNSSPoser::convert( int height_system) { GNSSStat gnss_stat; - if (coordinate_system == CoordinateSystem::UTM) { - gnss_stat = NavSatFix2UTM(nav_sat_fix_msg, this->get_logger(), height_system); - } else if (coordinate_system == CoordinateSystem::LOCAL_CARTESIAN_UTM) { + if (coordinate_system == CoordinateSystem::LOCAL_CARTESIAN_UTM) { gnss_stat = NavSatFix2LocalCartesianUTM( nav_sat_fix_msg, nav_sat_fix_origin_, this->get_logger(), height_system); } else if (coordinate_system == CoordinateSystem::MGRS) { From ab1a2e9fd71fc0f3c328853b01bb18395ee2f1a9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 23 Aug 2023 18:09:34 +0900 Subject: [PATCH 243/266] fix(utils): drivable area generation supports anti-clockwise polygon (#4678) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/utils/utils.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index dbbab9f040cfa..075190095d23b 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1606,6 +1606,10 @@ std::vector calcBound( const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + const auto is_clockwise_polygon = + boost::geometry::is_valid(lanelet::utils::to2D(polygon.basicPolygon())); + const auto is_clockwise_iteration = is_clockwise_polygon ? is_left : !is_left; + const auto start_itr = std::find_if(polygon.begin(), polygon.end(), [&bound](const auto & p) { return p.id() == bound.front().id(); }); @@ -1621,7 +1625,8 @@ std::vector calcBound( // extract line strings between start_idx and end_idx. const size_t start_idx = std::distance(polygon.begin(), start_itr); const size_t end_idx = std::distance(polygon.begin(), end_itr); - for (const auto & point : extract_bound_from_polygon(polygon, start_idx, end_idx, is_left)) { + for (const auto & point : + extract_bound_from_polygon(polygon, start_idx, end_idx, is_clockwise_iteration)) { output_points.push_back(point); } From 10cf1dc10d1dddad05ff6ce87f9e0fb280d8eeb1 Mon Sep 17 00:00:00 2001 From: beginningfan <103237402+beginningfan@users.noreply.github.com> Date: Wed, 23 Aug 2023 18:36:52 +0800 Subject: [PATCH 244/266] test(traffic_light_utils): add test_traffic_light_utils (#4643) * test(traffic_light_utils): add test_traffic_light_utils Signed-off-by: beginningfan * style(pre-commit): autofix * fix(traffic_light_utils): fix magic number Signed-off-by: beginningfan * style(pre-commit): autofix * fix(traffic_light_utils): fix namespace cpplint Signed-off-by: beginningfan * style(pre-commit): autofix --------- Signed-off-by: beginningfan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/traffic_light_utils/CMakeLists.txt | 9 ++ common/traffic_light_utils/package.xml | 4 + .../test/test_traffic_light_utils.cpp | 96 +++++++++++++++++++ 3 files changed, 109 insertions(+) create mode 100644 common/traffic_light_utils/test/test_traffic_light_utils.cpp diff --git a/common/traffic_light_utils/CMakeLists.txt b/common/traffic_light_utils/CMakeLists.txt index 567e7653b524f..741bdd585ed7f 100644 --- a/common/traffic_light_utils/CMakeLists.txt +++ b/common/traffic_light_utils/CMakeLists.txt @@ -5,9 +5,18 @@ find_package(autoware_cmake REQUIRED) autoware_package() find_package(Boost REQUIRED) +find_package(autoware_cmake REQUIRED) ament_auto_add_library(traffic_light_utils SHARED src/traffic_light_utils.cpp ) +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(test_traffic_light_utils ${TEST_SOURCES}) + target_include_directories(test_traffic_light_utils PRIVATE src/include) + target_link_libraries(test_traffic_light_utils traffic_light_utils) +endif() + ament_auto_package() diff --git a/common/traffic_light_utils/package.xml b/common/traffic_light_utils/package.xml index 48c6212a5909e..de05355eafd66 100644 --- a/common/traffic_light_utils/package.xml +++ b/common/traffic_light_utils/package.xml @@ -11,6 +11,10 @@ ament_cmake_auto autoware_cmake + ament_cmake_ros + ament_lint_auto + autoware_lint_common + lanelet2_extension tier4_perception_msgs diff --git a/common/traffic_light_utils/test/test_traffic_light_utils.cpp b/common/traffic_light_utils/test/test_traffic_light_utils.cpp new file mode 100644 index 0000000000000..bd777265b4195 --- /dev/null +++ b/common/traffic_light_utils/test/test_traffic_light_utils.cpp @@ -0,0 +1,96 @@ +// Copyright 2023 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 "gtest/gtest.h" +#include "traffic_light_utils/traffic_light_utils.hpp" + +namespace traffic_light_utils +{ + +TEST(isRoiValid, roi_validity) +{ + tier4_perception_msgs::msg::TrafficLightRoi test_roi; + test_roi.roi.x_offset = 300; + test_roi.roi.y_offset = 200; + test_roi.roi.width = 340; + test_roi.roi.height = 200; + uint32_t img_width = 640; + uint32_t img_heigh = 480; + EXPECT_FALSE(isRoiValid(test_roi, img_width, img_heigh)); + test_roi.roi.width = 339; + EXPECT_TRUE(isRoiValid(test_roi, img_width, img_heigh)); +} + +TEST(setRoiInvalid, set_roi_size) +{ + tier4_perception_msgs::msg::TrafficLightRoi test_roi; + test_roi.roi.x_offset = 300; + test_roi.roi.y_offset = 200; + test_roi.roi.width = 300; + test_roi.roi.height = 200; + EXPECT_EQ(test_roi.roi.width, (uint32_t)300); + EXPECT_EQ(test_roi.roi.height, (uint32_t)200); + setRoiInvalid(test_roi); + EXPECT_EQ(test_roi.roi.width, (uint32_t)0); + EXPECT_EQ(test_roi.roi.height, (uint32_t)0); +} + +TEST(isSignalUnknown, signal_element) +{ + tier4_perception_msgs::msg::TrafficSignal test_signal; + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + test_signal.elements.push_back(element); + EXPECT_TRUE(isSignalUnknown(test_signal)); + test_signal.elements[0].color = tier4_perception_msgs::msg::TrafficLightElement::RED; + EXPECT_FALSE(isSignalUnknown(test_signal)); +} + +TEST(setSignalUnknown, set_signal_element) +{ + tier4_perception_msgs::msg::TrafficSignal test_signal; + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::RED; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::CROSS; + test_signal.elements.push_back(element); + EXPECT_EQ(test_signal.elements[0].color, tier4_perception_msgs::msg::TrafficLightElement::RED); + EXPECT_EQ(test_signal.elements[0].shape, tier4_perception_msgs::msg::TrafficLightElement::CROSS); + setSignalUnknown(test_signal, 1.23f); + EXPECT_EQ( + test_signal.elements[0].color, tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN); + EXPECT_EQ( + test_signal.elements[0].shape, tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN); + EXPECT_FLOAT_EQ(test_signal.elements[0].confidence, (float)1.23); +} + +TEST(getTrafficLightCenter, get_signal) +{ + lanelet::LineString3d lineString; + lanelet::Point3d p0(0, 0, 0, 0); + lanelet::Point3d p1(1, 1, 1, 1); + lanelet::Point3d p2(2, 2, 2, 2); + lanelet::Point3d p3(3, 3, 3, 3); + lineString.push_back(p0); + lineString.push_back(p1); + lineString.push_back(p2); + lineString.push_back(p3); + + lanelet::ConstLineString3d test_light(lineString); + EXPECT_FLOAT_EQ(getTrafficLightCenter(test_light).x(), (float)1.5); + EXPECT_FLOAT_EQ(getTrafficLightCenter(test_light).y(), (float)1.5); + EXPECT_FLOAT_EQ(getTrafficLightCenter(test_light).z(), (float)1.5); +} + +} // namespace traffic_light_utils From ae0ad538f09c7b60116dd49949864f296db88720 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 23 Aug 2023 21:28:44 +0900 Subject: [PATCH 245/266] fix(utils): make cut overlap lane logic better (#4697) * fix(utils): fix longitudinal length inconsistency Signed-off-by: satoshi-ota * fix(utils): improve logic Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner/src/utils/utils.cpp | 77 ++++++++++++++----- 1 file changed, 56 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 075190095d23b..6da5ff97b9bf8 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1223,6 +1223,7 @@ boost::optional getOverlappedLaneletId(const std::vector boost::geometry::intersection( lanelet.polygon2d().basicPolygon(), target_lanelet.polygon2d().basicPolygon(), intersections); + // if only one point intersects, it is assumed not to be overlapped if (intersections.size() > 1) { return true; @@ -1265,35 +1266,69 @@ std::vector cutOverlappedLanes( std::vector shorten_lanes{lanes.begin(), lanes.begin() + *overlapped_lanelet_idx}; const auto shorten_lanelets = utils::transformToLanelets(shorten_lanes); - // create removed lanelets - std::vector removed_lane_ids; - for (size_t i = *overlapped_lanelet_idx; i < lanes.size(); ++i) { - const auto target_lanelets = utils::transformToLanelets(lanes.at(i)); - for (const auto & target_lanelet : target_lanelets) { - // if target lane is inside of the shorten lanelets, we do not remove it - if (checkHasSameLane(shorten_lanelets, target_lanelet)) { - continue; + const auto original_points = path.points; + + path.points.clear(); + + const auto has_same_id_lane = [](const auto & lanelet, const auto & p) { + return std::any_of(p.lane_ids.begin(), p.lane_ids.end(), [&lanelet](const auto id) { + return lanelet.id() == id; + }); + }; + + const auto has_same_id_lanes = [&has_same_id_lane](const auto & lanelets, const auto & p) { + return std::any_of( + lanelets.begin(), lanelets.end(), + [&has_same_id_lane, &p](const auto & lanelet) { return has_same_id_lane(lanelet, p); }); + }; + + // Step1. find first path point within drivable lanes + size_t start_point_idx = std::numeric_limits::max(); + for (const auto & lanes : shorten_lanes) { + for (size_t i = 0; i < original_points.size(); ++i) { + // check right lane + if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); + } + + // check left lane + if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); + } + + // check middle lanes + if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); } - removed_lane_ids.push_back(target_lanelet.id()); } } - const auto is_same_lane_id = [&removed_lane_ids](const auto & point) { - const auto & lane_ids = point.lane_ids; - for (const auto & lane_id : lane_ids) { - const auto is_same_id = [&lane_id](const auto id) { return lane_id == id; }; + // Step2. pick up only path points within drivable lanes + for (const auto & lanes : shorten_lanes) { + for (size_t i = start_point_idx; i < original_points.size(); ++i) { + // check right lane + if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; + } - if (std::any_of(removed_lane_ids.begin(), removed_lane_ids.end(), is_same_id)) { - return true; + // check left lane + if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; } - } - return false; - }; - const auto points_with_overlapped_id = - std::remove_if(path.points.begin(), path.points.end(), is_same_lane_id); + // check middle lanes + if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; + } + + start_point_idx = i; + break; + } + } - path.points.erase(points_with_overlapped_id, path.points.end()); return shorten_lanes; } From b3d62fad3a79f973fc758cae756ea092489d5f09 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Aug 2023 21:47:01 +0900 Subject: [PATCH 246/266] feat(glog): add glog in planning and control modules (#4714) * feat(glog): add glog component Signed-off-by: Takamasa Horibe * formatting Signed-off-by: Takamasa Horibe * remove namespace Signed-off-by: Takamasa Horibe * remove license Signed-off-by: Takamasa Horibe * Update launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Update launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Update common/glog_component/CMakeLists.txt Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Update launch/tier4_control_launch/launch/control.launch.py Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * add copyright Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- common/glog_component/CMakeLists.txt | 18 ++++++++++++ common/glog_component/README.md | 29 +++++++++++++++++++ .../include/glog_component/glog_component.hpp | 28 ++++++++++++++++++ common/glog_component/package.xml | 23 +++++++++++++++ common/glog_component/src/glog_component.cpp | 25 ++++++++++++++++ .../launch/control.launch.py | 7 +++++ .../behavior_planning.launch.py | 7 +++++ .../motion_planning/motion_planning.launch.py | 11 +++++++ launch/tier4_planning_launch/package.xml | 1 + 9 files changed, 149 insertions(+) create mode 100644 common/glog_component/CMakeLists.txt create mode 100644 common/glog_component/README.md create mode 100644 common/glog_component/include/glog_component/glog_component.hpp create mode 100644 common/glog_component/package.xml create mode 100644 common/glog_component/src/glog_component.cpp diff --git a/common/glog_component/CMakeLists.txt b/common/glog_component/CMakeLists.txt new file mode 100644 index 0000000000000..c2a68d0130b37 --- /dev/null +++ b/common/glog_component/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.14) +project(glog_component) + +find_package(autoware_cmake REQUIRED) +autoware_package() + + +ament_auto_add_library(glog_component SHARED + src/glog_component.cpp +) +target_link_libraries(glog_component glog) + +rclcpp_components_register_node(glog_component + PLUGIN "GlogComponent" + EXECUTABLE glog_component_node +) + +ament_auto_package() diff --git a/common/glog_component/README.md b/common/glog_component/README.md new file mode 100644 index 0000000000000..94a40fe32e40d --- /dev/null +++ b/common/glog_component/README.md @@ -0,0 +1,29 @@ +# glog_component + +This package provides the glog (google logging library) feature as a ros2 component library. This is used to dynamically load the glog feature with container. + +See the [glog github](https://github.com/google/glog) for the details of its features. + +## Example + +When you load the `glog_component` in container, the launch file can be like below: + +```py +glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", +) + +container = ComposableNodeContainer( + name="my_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[ + component1, + component2, + glog_component, + ], +) +``` diff --git a/common/glog_component/include/glog_component/glog_component.hpp b/common/glog_component/include/glog_component/glog_component.hpp new file mode 100644 index 0000000000000..d940363d75ac4 --- /dev/null +++ b/common/glog_component/include/glog_component/glog_component.hpp @@ -0,0 +1,28 @@ +// Copyright 2023 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 GLOG_COMPONENT__GLOG_COMPONENT_HPP_ +#define GLOG_COMPONENT__GLOG_COMPONENT_HPP_ + +#include + +#include + +class GlogComponent : public rclcpp::Node +{ +public: + explicit GlogComponent(const rclcpp::NodeOptions & node_options); +}; + +#endif // GLOG_COMPONENT__GLOG_COMPONENT_HPP_ diff --git a/common/glog_component/package.xml b/common/glog_component/package.xml new file mode 100644 index 0000000000000..0d6e7daac1de3 --- /dev/null +++ b/common/glog_component/package.xml @@ -0,0 +1,23 @@ + + + + glog_component + 0.1.0 + The glog_component package + Takamasa Horibe + Apache License 2.0 + + Takamasa Horibe + + ament_cmake + ament_cmake_auto + autoware_cmake + + libgoogle-glog-dev + rclcpp + rclcpp_components + + + ament_cmake + + diff --git a/common/glog_component/src/glog_component.cpp b/common/glog_component/src/glog_component.cpp new file mode 100644 index 0000000000000..9e7e70da6c884 --- /dev/null +++ b/common/glog_component/src/glog_component.cpp @@ -0,0 +1,25 @@ +// Copyright 2023 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 "glog_component/glog_component.hpp" + +GlogComponent::GlogComponent(const rclcpp::NodeOptions & node_options) +: Node("glog_component", node_options) +{ + google::InitGoogleLogging("glog_component"); + google::InstallFailureSignalHandler(); +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(GlogComponent) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a673eb08c222f..116055dd9e87e 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -306,6 +306,12 @@ def launch_setup(context, *args, **kwargs): target_container="/control/control_container", ) + glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", + ) + # set container to run all required components in the same process container = ComposableNodeContainer( name="control_container", @@ -319,6 +325,7 @@ def launch_setup(context, *args, **kwargs): shift_decider_component, vehicle_cmd_gate_component, operation_mode_transition_manager_component, + glog_component, ], ) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index fc1b55ee52eac..59e8038e49188 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -64,6 +64,12 @@ def launch_setup(context, *args, **kwargs): with open(LaunchConfiguration("behavior_path_planner_param_path").perform(context), "r") as f: behavior_path_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", + ) + behavior_path_planner_component = ComposableNode( package="behavior_path_planner", plugin="behavior_path_planner::BehaviorPathPlannerNode", @@ -211,6 +217,7 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ behavior_path_planner_component, behavior_velocity_planner_component, + glog_component, ], output="screen", ) 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 34ad4659b5ece..d8c5d7825f19d 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 @@ -309,6 +309,16 @@ def launch_setup(context, *args, **kwargs): condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) + glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", + ) + glog_component_loader = LoadComposableNodes( + composable_node_descriptions=[glog_component], + target_container=container, + ) + group = GroupAction( [ container, @@ -319,6 +329,7 @@ def launch_setup(context, *args, **kwargs): obstacle_cruise_planner_loader, obstacle_cruise_planner_relay_loader, surround_obstacle_checker_loader, + glog_component_loader, ] ) return [group] diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 4de0f91c53c6a..39b95286bb6cc 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -60,6 +60,7 @@ external_cmd_selector external_velocity_limit_selector freespace_planner + glog_component mission_planner motion_velocity_smoother obstacle_avoidance_planner From 67bda6bf3f48ccee51379e6db2aa9623535a1b37 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 23 Aug 2023 23:00:00 +0900 Subject: [PATCH 247/266] refactor(safety_check): use safety check common param struct (#4719) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 8 +++++ .../config/behavior_path_planner.param.yaml | 13 -------- .../config/lane_change/lane_change.param.yaml | 12 ++++++++ .../behavior_path_planner/parameters.hpp | 14 --------- .../scene_module/lane_change/normal.hpp | 2 +- .../utils/avoidance/avoidance_module_data.hpp | 4 +++ .../lane_change/lane_change_module_data.hpp | 4 +++ .../path_safety_checker_parameters.hpp | 2 ++ .../path_safety_checker/safety_check.hpp | 7 ++--- .../src/behavior_path_planner_node.cpp | 17 ----------- .../avoidance/avoidance_module.cpp | 4 +-- .../src/scene_module/avoidance/manager.cpp | 21 ++++++++++++- .../src/scene_module/lane_change/manager.cpp | 30 +++++++++++++++++++ .../src/scene_module/lane_change/normal.cpp | 11 +++---- .../path_safety_checker/safety_check.cpp | 28 ++++++++--------- .../test/test_safety_check.cpp | 8 +++-- 16 files changed, 108 insertions(+), 77 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index e06393495fa1b..9ecc1a63b55b0 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -143,6 +143,14 @@ time_horizon: 10.0 # [s] safety_check_backward_distance: 100.0 # [m] safety_check_hysteresis_factor: 2.0 # [-] + # rss parameters + expected_front_deceleration: -1.0 # [m/ss] + expected_rear_deceleration: -1.0 # [m/ss] + rear_vehicle_reaction_time: 2.0 # [s] + rear_vehicle_safety_time_margin: 1.0 # [s] + lateral_distance_max_threshold: 2.0 # [m] + longitudinal_distance_min_threshold: 3.0 # [m] + longitudinal_velocity_delta_time: 0.8 # [s] # For avoidance maneuver avoidance: diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index 02dc13ffd84da..95c60612bfdb7 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -25,19 +25,6 @@ visualize_maximum_drivable_area: true - lateral_distance_max_threshold: 2.0 - longitudinal_distance_min_threshold: 3.0 - longitudinal_velocity_delta_time: 0.8 # [s] - - expected_front_deceleration: -1.0 - expected_rear_deceleration: -1.0 - - expected_front_deceleration_for_abort: -1.0 - expected_rear_deceleration_for_abort: -2.0 - - rear_vehicle_reaction_time: 2.0 - rear_vehicle_safety_time_margin: 1.0 - lane_following: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml index 745fd3877fec6..925e70d9084d6 100644 --- a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml +++ b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml @@ -26,6 +26,18 @@ min_longitudinal_acc: -1.0 max_longitudinal_acc: 1.0 + # safety check + safety_check: + expected_front_deceleration: -1.0 + expected_rear_deceleration: -1.0 + expected_front_deceleration_for_abort: -1.0 + expected_rear_deceleration_for_abort: -2.0 + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 1.0 + lateral_distance_max_threshold: 2.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.8 + # lateral acceleration map lateral_acceleration: velocity: [0.0, 4.0, 10.0] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index e7d017477b177..d6b99dca70618 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -141,20 +141,6 @@ struct BehaviorPathPlannerParameters // maximum drivable area visualization bool visualize_maximum_drivable_area; - - // collision check - double lateral_distance_max_threshold; - double longitudinal_distance_min_threshold; - double longitudinal_velocity_delta_time; - - double expected_front_deceleration; // brake parameter under normal lane change - double expected_rear_deceleration; // brake parameter under normal lane change - - double expected_front_deceleration_for_abort; // hard brake parameter for abort - double expected_rear_deceleration_for_abort; // hard brake parameter for abort - - double rear_vehicle_reaction_time; - double rear_vehicle_safety_time_margin; }; #endif // BEHAVIOR_PATH_PLANNER__PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 9a6a12427d783..5d13507f5206c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -140,7 +140,7 @@ class NormalLaneChange : public LaneChangeBase PathSafetyStatus isLaneChangePathSafe( const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const double front_decel, const double rear_decel, + const utils::path_safety_checker::RSSparams & rss_params, std::unordered_map & debug_data) const; LaneChangeTargetObjectIndices filterObject( diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index ef956fb7950dd..1f47b804e185b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include @@ -296,6 +297,9 @@ struct AvoidanceParameters // parameters depend on object class std::unordered_map object_parameters; + // rss parameters + utils::path_safety_checker::RSSparams rss_params; + // clip left and right bounds for objects bool enable_bound_clipping{false}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 721c5b00f6e33..0556a780467c0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -76,6 +76,10 @@ struct LaneChangeParameters bool check_motorcycle{true}; // check object motorbike bool check_pedestrian{true}; // check object pedestrian + // safety check + utils::path_safety_checker::RSSparams rss_params; + utils::path_safety_checker::RSSparams rss_params_for_abort; + // abort LaneChangeCancelParameters cancel; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index 519f589f561ee..c4a6a86861e6c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -123,6 +123,8 @@ struct RSSparams double longitudinal_distance_min_threshold{ 0.0}; ///< Minimum threshold for longitudinal distance. double longitudinal_velocity_delta_time{0.0}; ///< Delta time for longitudinal velocity. + double front_vehicle_deceleration; ///< brake parameter + double rear_vehicle_deceleration; ///< brake parameter }; /** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index 8606f2cd2397d..6d9df7677ead5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -65,8 +65,7 @@ Polygon2d createExtendedPolygon( double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, - const double front_object_deceleration, const double rear_object_deceleration, - const BehaviorPathPlannerParameters & params); + const RSSparams & rss_params); double calcMinimumLongitudinalLength( const double front_object_velocity, const double rear_object_velocity, @@ -98,8 +97,8 @@ bool checkCollision( const std::vector & predicted_ego_path, const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, - const BehaviorPathPlannerParameters & common_parameters, const double front_object_deceleration, - const double rear_object_deceleration, CollisionCheckDebug & debug); + const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, + CollisionCheckDebug & debug); /** * @brief Check collision between ego path footprints with extra longitudinal stopping margin and diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 3e2ccd23d58e7..3023357bd0a96 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -391,23 +391,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - p.lateral_distance_max_threshold = declare_parameter("lateral_distance_max_threshold"); - p.longitudinal_distance_min_threshold = - declare_parameter("longitudinal_distance_min_threshold"); - p.longitudinal_velocity_delta_time = - declare_parameter("longitudinal_velocity_delta_time"); - - p.expected_front_deceleration = declare_parameter("expected_front_deceleration"); - p.expected_rear_deceleration = declare_parameter("expected_rear_deceleration"); - - p.expected_front_deceleration_for_abort = - declare_parameter("expected_front_deceleration_for_abort"); - p.expected_rear_deceleration_for_abort = - declare_parameter("expected_rear_deceleration_for_abort"); - - p.rear_vehicle_reaction_time = declare_parameter("rear_vehicle_reaction_time"); - p.rear_vehicle_safety_time_margin = declare_parameter("rear_vehicle_safety_time_margin"); - if (p.backward_length_buffer_for_end_of_lane < 1.0) { RCLCPP_WARN_STREAM( get_logger(), "Lane change buffer must be more than 1 meter. Modifying the buffer."); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 3550b2035248a..b0fda03418069 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1879,8 +1879,8 @@ bool AvoidanceModule::isSafePath( for (const auto & obj_path : obj_predicted_paths) { CollisionCheckDebug collision{}; if (!utils::path_safety_checker::checkCollision( - shifted_path.path, ego_predicted_path, object, obj_path, p, - p.expected_front_deceleration, p.expected_rear_deceleration, collision)) { + shifted_path.path, ego_predicted_path, object, obj_path, p, parameters_->rss_params, + collision)) { return false; } } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 606869eb4007f..c13c237673625 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -131,7 +131,7 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.object_last_seen_threshold = get_parameter(node, ns + "object_last_seen_threshold"); } - // safety check + // safety check general params { std::string ns = "avoidance.safety_check."; p.enable_safety_check = get_parameter(node, ns + "enable"); @@ -149,6 +149,25 @@ AvoidanceModuleManager::AvoidanceModuleManager( get_parameter(node, ns + "safety_check_hysteresis_factor"); } + // safety check rss params + { + std::string ns = "avoidance.safety_check."; + p.rss_params.longitudinal_distance_min_threshold = + get_parameter(node, ns + "longitudinal_distance_min_threshold"); + p.rss_params.longitudinal_velocity_delta_time = + get_parameter(node, ns + "longitudinal_velocity_delta_time"); + p.rss_params.front_vehicle_deceleration = + get_parameter(node, ns + "expected_front_deceleration"); + p.rss_params.rear_vehicle_deceleration = + get_parameter(node, ns + "expected_rear_deceleration"); + p.rss_params.rear_vehicle_reaction_time = + get_parameter(node, ns + "rear_vehicle_reaction_time"); + p.rss_params.rear_vehicle_safety_time_margin = + get_parameter(node, ns + "rear_vehicle_safety_time_margin"); + p.rss_params.lateral_distance_max_threshold = + get_parameter(node, ns + "lateral_distance_max_threshold"); + } + // avoidance maneuver (lateral) { std::string ns = "avoidance.avoidance.lateral."; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 5dc2a1ee9837c..f392ef6a26e22 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -85,6 +85,36 @@ LaneChangeModuleManager::LaneChangeModuleManager( get_parameter(node, parameter("check_objects_on_other_lanes")); p.use_all_predicted_path = get_parameter(node, parameter("use_all_predicted_path")); + p.rss_params.longitudinal_distance_min_threshold = + get_parameter(node, parameter("safety_check.longitudinal_distance_min_threshold")); + p.rss_params.longitudinal_velocity_delta_time = + get_parameter(node, parameter("safety_check.longitudinal_velocity_delta_time")); + p.rss_params.front_vehicle_deceleration = + get_parameter(node, parameter("safety_check.expected_front_deceleration")); + p.rss_params.rear_vehicle_deceleration = + get_parameter(node, parameter("safety_check.expected_rear_deceleration")); + p.rss_params.rear_vehicle_reaction_time = + get_parameter(node, parameter("safety_check.rear_vehicle_reaction_time")); + p.rss_params.rear_vehicle_safety_time_margin = + get_parameter(node, parameter("safety_check.rear_vehicle_safety_time_margin")); + p.rss_params.lateral_distance_max_threshold = + get_parameter(node, parameter("safety_check.lateral_distance_max_threshold")); + + p.rss_params_for_abort.longitudinal_distance_min_threshold = + get_parameter(node, parameter("safety_check.longitudinal_distance_min_threshold")); + p.rss_params_for_abort.longitudinal_velocity_delta_time = + get_parameter(node, parameter("safety_check.longitudinal_velocity_delta_time")); + p.rss_params_for_abort.front_vehicle_deceleration = + get_parameter(node, parameter("safety_check.expected_front_deceleration_for_abort")); + p.rss_params_for_abort.rear_vehicle_deceleration = + get_parameter(node, parameter("safety_check.expected_rear_deceleration_for_abort")); + p.rss_params_for_abort.rear_vehicle_reaction_time = + get_parameter(node, parameter("safety_check.rear_vehicle_reaction_time")); + p.rss_params_for_abort.rear_vehicle_safety_time_margin = + get_parameter(node, parameter("safety_check.rear_vehicle_safety_time_margin")); + p.rss_params_for_abort.lateral_distance_max_threshold = + get_parameter(node, parameter("safety_check.lateral_distance_max_threshold")); + // target object { std::string ns = "lane_change.target_object."; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index dad925c6b2335..8fdb79a6271d1 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -1045,8 +1045,7 @@ bool NormalLaneChange::getLaneChangePaths( } const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe( - *candidate_path, target_objects, common_parameters.expected_front_deceleration, - common_parameters.expected_rear_deceleration, object_debug_); + *candidate_path, target_objects, lane_change_parameters_->rss_params, object_debug_); if (is_safe) { return true; @@ -1059,7 +1058,6 @@ bool NormalLaneChange::getLaneChangePaths( PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const { - const auto & common_parameters = getCommonParam(); const auto & path = status_.lane_change_path; const auto & current_lanes = status_.current_lanes; const auto & target_lanes = status_.target_lanes; @@ -1068,8 +1066,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const CollisionCheckDebugMap debug_data; const auto safety_status = isLaneChangePathSafe( - path, target_objects, common_parameters.expected_front_deceleration_for_abort, - common_parameters.expected_rear_deceleration_for_abort, debug_data); + path, target_objects, lane_change_parameters_->rss_params_for_abort, debug_data); { // only for debug purpose object_debug_.clear(); @@ -1326,7 +1323,7 @@ bool NormalLaneChange::getAbortPath() PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const double front_decel, const double rear_decel, + const utils::path_safety_checker::RSSparams & rss_params, std::unordered_map & debug_data) const { PathSafetyStatus path_safety_status; @@ -1388,7 +1385,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( obj, lane_change_parameters_->use_all_predicted_path); for (const auto & obj_path : obj_predicted_paths) { if (!utils::path_safety_checker::checkCollision( - path, ego_predicted_path, obj, obj_path, common_parameters, front_decel, rear_decel, + path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, current_debug_data.second)) { path_safety_status.is_safe = false; updateDebugInfo(current_debug_data, path_safety_status.is_safe); diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 34ba607938385..c6a68e108e7e1 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -135,8 +135,7 @@ Polygon2d createExtendedPolygon( double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, - const double front_object_deceleration, const double rear_object_deceleration, - const BehaviorPathPlannerParameters & params) + const RSSparams & rss_params) { const auto stoppingDistance = [](const auto vehicle_velocity, const auto vehicle_accel) { // compensate if user accidentally set the deceleration to some positive value @@ -145,23 +144,23 @@ double calcRssDistance( }; const double & reaction_time = - params.rear_vehicle_reaction_time + params.rear_vehicle_safety_time_margin; + rss_params.rear_vehicle_reaction_time + rss_params.rear_vehicle_safety_time_margin; const double front_object_stop_length = - stoppingDistance(front_object_velocity, front_object_deceleration); + stoppingDistance(front_object_velocity, rss_params.front_vehicle_deceleration); const double rear_object_stop_length = rear_object_velocity * reaction_time + - stoppingDistance(rear_object_velocity, rear_object_deceleration); + stoppingDistance(rear_object_velocity, rss_params.rear_vehicle_deceleration); return rear_object_stop_length - front_object_stop_length; } double calcMinimumLongitudinalLength( const double front_object_velocity, const double rear_object_velocity, - const BehaviorPathPlannerParameters & params) + const RSSparams & rss_params) { - const double & lon_threshold = params.longitudinal_distance_min_threshold; + const double & lon_threshold = rss_params.longitudinal_distance_min_threshold; const auto max_vel = std::max(front_object_velocity, rear_object_velocity); - return params.longitudinal_velocity_delta_time * std::abs(max_vel) + lon_threshold; + return rss_params.longitudinal_velocity_delta_time * std::abs(max_vel) + lon_threshold; } boost::optional calcInterpolatedPoseWithVelocity( @@ -219,8 +218,8 @@ bool checkCollision( const std::vector & predicted_ego_path, const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, - const BehaviorPathPlannerParameters & common_parameters, const double front_object_deceleration, - const double rear_object_deceleration, CollisionCheckDebug & debug) + const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, + CollisionCheckDebug & debug) { debug.lerped_path.reserve(target_object_path.path.size()); @@ -267,16 +266,15 @@ bool checkCollision( : std::make_pair(ego_velocity, object_velocity); // compute rss dist - const auto rss_dist = calcRssDistance( - front_object_velocity, rear_object_velocity, front_object_deceleration, - rear_object_deceleration, common_parameters); + const auto rss_dist = + calcRssDistance(front_object_velocity, rear_object_velocity, rss_parameters); // minimum longitudinal length const auto min_lon_length = - calcMinimumLongitudinalLength(front_object_velocity, rear_object_velocity, common_parameters); + calcMinimumLongitudinalLength(front_object_velocity, rear_object_velocity, rss_parameters); const auto & lon_offset = std::max(rss_dist, min_lon_length); - const auto & lat_margin = common_parameters.lateral_distance_max_threshold; + const auto & lat_margin = rss_parameters.lateral_distance_max_threshold; const auto & extended_ego_polygon = is_object_front ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug) diff --git a/planning/behavior_path_planner/test/test_safety_check.cpp b/planning/behavior_path_planner/test/test_safety_check.cpp index e24f3274179fe..e1b74636f5ed1 100644 --- a/planning/behavior_path_planner/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/test/test_safety_check.cpp @@ -178,18 +178,20 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) TEST(BehaviorPathPlanningSafetyUtilsTest, calcRssDistance) { using behavior_path_planner::utils::path_safety_checker::calcRssDistance; + using behavior_path_planner::utils::path_safety_checker::RSSparams; { const double front_vel = 5.0; const double front_decel = -2.0; const double rear_vel = 10.0; const double rear_decel = -1.0; - BehaviorPathPlannerParameters params; + RSSparams params; params.rear_vehicle_reaction_time = 1.0; params.rear_vehicle_safety_time_margin = 1.0; params.longitudinal_distance_min_threshold = 3.0; + params.rear_vehicle_deceleration = rear_decel; + params.front_vehicle_deceleration = front_decel; - EXPECT_NEAR( - calcRssDistance(front_vel, rear_vel, front_decel, rear_decel, params), 63.75, epsilon); + EXPECT_NEAR(calcRssDistance(front_vel, rear_vel, params), 63.75, epsilon); } } From cf425883613269b45261a077d947e37f81497e47 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 24 Aug 2023 08:21:25 +0900 Subject: [PATCH 248/266] feat(obstacle_cruise_planner): add a hold stop distance feature (#4720) * feat(obstacle_cruise_planner): add a hold stop distance feature Signed-off-by: Takayuki Murooka * add param Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/obstacle_cruise_planner.param.yaml | 2 ++ .../common_structs.hpp | 14 ++++++++ .../planner_interface.hpp | 5 +++ .../src/planner_interface.cpp | 35 +++++++++++++++++-- 4 files changed, 54 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 37d3ab4984501..e2012fab43ba4 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -14,6 +14,8 @@ 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] terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] + hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s] + hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index b6a242609dfff..12ebadf770996 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -165,6 +165,11 @@ struct LongitudinalInfo safe_distance_margin = node.declare_parameter("common.safe_distance_margin"); terminal_safe_distance_margin = node.declare_parameter("common.terminal_safe_distance_margin"); + + hold_stop_velocity_threshold = + node.declare_parameter("common.hold_stop_velocity_threshold"); + hold_stop_distance_threshold = + node.declare_parameter("common.hold_stop_distance_threshold"); } void onParam(const std::vector & parameters) @@ -188,6 +193,11 @@ struct LongitudinalInfo parameters, "common.safe_distance_margin", safe_distance_margin); tier4_autoware_utils::updateParam( parameters, "common.terminal_safe_distance_margin", terminal_safe_distance_margin); + + tier4_autoware_utils::updateParam( + parameters, "common.hold_stop_velocity_threshold", hold_stop_velocity_threshold); + tier4_autoware_utils::updateParam( + parameters, "common.hold_stop_distance_threshold", hold_stop_distance_threshold); } // common parameter @@ -208,6 +218,10 @@ struct LongitudinalInfo // distance margin double safe_distance_margin; double terminal_safe_distance_margin; + + // hold stop + double hold_stop_velocity_threshold; + double hold_stop_distance_threshold; }; struct DebugData 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 index 8aeef15c8b97c..9be6ec10e952e 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -254,6 +254,11 @@ class PlannerInterface SlowDownParam slow_down_param_; std::vector prev_slow_down_output_; + // previous trajectory and distance to stop + // NOTE: Previous trajectory is memorized to deal with nearest index search for overlapping or + // crossing lanes. + std::optional, double>> prev_stop_distance_info_{ + std::nullopt}; }; #endif // OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 1aaa897986bcd..4cf6bf9e23806 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -228,6 +228,7 @@ std::vector PlannerInterface::generateStopTrajectory( motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + prev_stop_distance_info_ = std::nullopt; return planner_data.traj_points; } @@ -244,6 +245,7 @@ std::vector PlannerInterface::generateStopTrajectory( motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + prev_stop_distance_info_ = std::nullopt; return planner_data.traj_points; } @@ -315,9 +317,36 @@ std::vector PlannerInterface::generateStopTrajectory( } // Generate Output Trajectory + const double zero_vel_dist = [&]() { + const double current_zero_vel_dist = + std::max(0.0, closest_obstacle_dist - abs_ego_offset - feasible_margin_from_obstacle); + + // Hold previous stop distance if necessary + if ( + std::abs(planner_data.ego_vel) < longitudinal_info_.hold_stop_velocity_threshold && + prev_stop_distance_info_) { + // NOTE: We assume that the current trajectory's front point is ahead of the previous + // trajectory's front point. + const size_t traj_front_point_prev_seg_idx = + motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prev_stop_distance_info_->first, planner_data.traj_points.front().pose); + const double diff_dist_front_points = motion_utils::calcSignedArcLength( + prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, + traj_front_point_prev_seg_idx); + + const double prev_zero_vel_dist = prev_stop_distance_info_->second - diff_dist_front_points; + if ( + std::abs(prev_zero_vel_dist - current_zero_vel_dist) < + longitudinal_info_.hold_stop_distance_threshold) { + return prev_zero_vel_dist; + } + } + + return current_zero_vel_dist; + }(); + + // Insert stop point auto output_traj_points = planner_data.traj_points; - const double zero_vel_dist = - std::max(0.0, closest_obstacle_dist - abs_ego_offset - feasible_margin_from_obstacle); const auto zero_vel_idx = motion_utils::insertStopPoint(0, zero_vel_dist, output_traj_points); if (zero_vel_idx) { // virtual wall marker for stop obstacle @@ -338,6 +367,8 @@ std::vector PlannerInterface::generateStopTrajectory( const auto stop_speed_exceeded_msg = createStopSpeedExceededMsg(planner_data.current_time, will_collide_with_obstacle); stop_speed_exceeded_pub_->publish(stop_speed_exceeded_msg); + + prev_stop_distance_info_ = std::make_pair(output_traj_points, zero_vel_dist); } stop_planning_debug_info_.set( From c8ee0d4a37a541ee0f3e8e754f40689eff2ab628 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 24 Aug 2023 14:27:54 +0900 Subject: [PATCH 249/266] docs(lane_change): add missing explanation for lane change parameters (#4703) * docs(lane_change): add missing explanation for lane change parameters Signed-off-by: Fumiya Watanabe * docs(lane_change): fix spell Signed-off-by: Fumiya Watanabe * docs(lane_change): add turn signal parameters Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- ...ehavior_path_planner_lane_change_design.md | 45 +++++++++++++------ 1 file changed, 31 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md index b793173285629..dff4fa9bdc5eb 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md @@ -270,23 +270,40 @@ The last behavior will also occur if the ego vehicle has departed from the curre The following parameters are configurable in `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :--------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------- | ------------- | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | -| `lane_changing_safety_check_duration` | [m] | double | The total time that is taken to complete the lane-changing task. | 8.0 | -| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 2.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | -| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | -| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | -| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| Name | Unit | Type | Description | Default value | +| :------------------------------------------ | ------ | ------- | --------------------------------------------------------------------------------------------------------------- | ------------------ | +| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | +| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 2.0 | +| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | +| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | +| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | +| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `object_check_min_road_shoulder_width` | [m] | double | Vehicles around the center line within this distance will be excluded from parking objects | 0.5 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be acitvated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deacitvated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | +| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | +| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | +| `target_object.car` | [-] | boolean | Include car objects for safety check | true | +| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | +| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | +| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | +| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | +| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | +| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | +| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | ### Collision checks during lane change -The following parameters are configurable in `behavior_path_planner.param.yaml`. +The following parameters are configurable in `behavior_path_planner.param.yaml` and `lane_change.param.yaml`. | Name | Unit | Type | Description | Default value | | :----------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | From ae24eaff3d4add9785532e0beba8ed1a95c1f74a Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 24 Aug 2023 16:44:13 +0900 Subject: [PATCH 250/266] docs(lane_change): fix document for lane change (#4732) * docs(lane_change): fix document for lane change Signed-off-by: Fumiya Watanabe * docs(lane_change): fix typo Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- ...ehavior_path_planner_lane_change_design.md | 20 +++++++------------ 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md index dff4fa9bdc5eb..fddd535931d94 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md @@ -163,6 +163,8 @@ First, we divide the target objects into obstacles in the target lane, obstacles ![object lanes](../image/lane_change/lane_objects.drawio.svg) +Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. + ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. @@ -177,21 +179,13 @@ When driving on the public road with other vehicles, there exist scenarios where ```C++ lane_changing_time = f(shift_length, lat_acceleration, lat_jerk) -minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_velocity * lane_changing_time + backward_length_buffer_for_end_of_lane +minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_velocity * lane_changing_time + lane_change_finish_judge_buffer ``` The following figure illustrates when the lane is blocked in multiple lane changes cases. ![multiple-lane-changes](../image/lane_change/lane_change-when_cannot_change_lanes.png) -#### Intersection - -Lane change in the intersection is prohibited following traffic regulation. Therefore, if the goal is place close passed the intersection, the lane change needs to be completed before ego vehicle enters the intersection region. Similar to the lane blocked case, in case of the path is unsafe, ego vehicle will stop and waits for the dynamic object to pass by. - -The following figure illustrate the intersection case. - -![intersection](../image/lane_change/lane_change-intersection_case.png) - ### Aborting lane change The abort process may result in three different outcome; Cancel, Abort and Stop/Cruise. @@ -215,11 +209,11 @@ while(Lane Following) if (Is Abort Condition Satisfied) then (**NO**) else (**YES**) if (Is Enough margin to retry lane change) then (**YES**) - if (Ego not depart from current lane yet) then (**YES**) + if (Ego is on lane change prepare phase) then (**YES**) :Cancel lane change; break else (**NO**) - if (Can perform abort maneuver) then (**YES**) + if (Will the overhang to target lane be less than threshold?) then (**YES**) :Perform abort maneuver; break else (NO) @@ -284,8 +278,8 @@ The following parameters are configurable in `lane_change.param.yaml`. | `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | | `object_check_min_road_shoulder_width` | [m] | double | Vehicles around the center line within this distance will be excluded from parking objects | 0.5 | | `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | -| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be acitvated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deacitvated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | | `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | | `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | | `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | From febb989350a5a2f37cc41b37279c5211648f4993 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 24 Aug 2023 17:47:46 +0900 Subject: [PATCH 251/266] chore: fix cspell errors and enable spell-check in planning directories (#4716) * chore(cspell): change variable name to avoid cspell errors. prevs => previous_lanelets Signed-off-by: Kotaro Yoshimoto * chore(cspell): fix comment to avoid a cspell error Signed-off-by: Kotaro Yoshimoto * chore(cspell): fix comment to avoid a cspell error, dists => distances Signed-off-by: Kotaro Yoshimoto * chore(cspell): fix comment to avoid a cspell error, dsts => distances Signed-off-by: Kotaro Yoshimoto * chore(cspell): entrying => entering Signed-off-by: Kotaro Yoshimoto * refactor: fix typo Descritized => Discretized Signed-off-by: Kotaro Yoshimoto * feat(cspell): enable spell-check for planning directories Signed-off-by: Kotaro Yoshimoto * style(pre-commit): autofix --------- Signed-off-by: Kotaro Yoshimoto Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .cspell-partial.json | 7 +---- .../src/scene_intersection.cpp | 2 +- .../src/scene_intersection.hpp | 4 +-- .../src/util.cpp | 22 +++++++------- .../src/util.hpp | 2 +- .../src/util_type.hpp | 4 +-- .../velocity_planning_utils.cpp | 30 +++++++++---------- .../include/obstacle_cruise_planner/node.hpp | 2 +- 8 files changed, 34 insertions(+), 39 deletions(-) diff --git a/.cspell-partial.json b/.cspell-partial.json index a3c4ca455d444..45b85e779c39d 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -1,10 +1,5 @@ { - "ignorePaths": [ - "**/perception/**", - "**/planning/**", - "**/sensing/**", - "perception/bytetrack/lib/**" - ], + "ignorePaths": ["**/perception/**", "**/sensing/**", "perception/bytetrack/lib/**"], "ignoreRegExpList": [], "words": [] } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index d9ebafbe682a0..7ae549ce8b274 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1166,7 +1166,7 @@ bool IntersectionModule::isOcclusionCleared( const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, - const std::vector & lane_divisions, + const std::vector & lane_divisions, const std::vector & parked_attention_objects, const double occlusion_dist_thr) { diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 9d1fab1339d0e..774b68710be7f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -219,7 +219,7 @@ class IntersectionModule : public SceneModuleInterface // for occlusion detection const bool enable_occlusion_detection_; - std::optional> occlusion_attention_divisions_; + std::optional> occlusion_attention_divisions_; // OcclusionState prev_occlusion_state_ = OcclusionState::NONE; StateMachine collision_state_machine_; //! for stable collision checking StateMachine before_creep_state_machine_; //! for two phase stop @@ -267,7 +267,7 @@ class IntersectionModule : public SceneModuleInterface const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, - const std::vector & lane_divisions, + const std::vector & lane_divisions, const std::vector & parked_attention_objects, const double occlusion_dist_thr); diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 7fdae3df2d9d2..a987ce9af9dfe 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -709,7 +709,7 @@ bool isTrafficLightArrowActivated( return false; } -std::vector generateDetectionLaneDivisions( +std::vector generateDetectionLaneDivisions( lanelet::ConstLanelets detection_lanelets_all, [[maybe_unused]] const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) @@ -778,15 +778,15 @@ std::vector generateDetectionLaneDivisions( auto & branch = branches[(ind2id[src])]; int node_iter = ind2id[src]; while (true) { - const auto & dsts = adjacency[(id2ind[node_iter])]; + const auto & destinations = adjacency[(id2ind[node_iter])]; // NOTE: assuming detection lanelets have only one previous lanelet - const auto next = std::find(dsts.begin(), dsts.end(), true); - if (next == dsts.end()) { + const auto next = std::find(destinations.begin(), destinations.end(), true); + if (next == destinations.end()) { branch.push_back(node_iter); break; } branch.push_back(node_iter); - node_iter = ind2id[std::distance(dsts.begin(), next)]; + node_iter = ind2id[std::distance(destinations.begin(), next)]; } } for (decltype(branches)::iterator it = branches.begin(); it != branches.end(); it++) { @@ -818,9 +818,9 @@ std::vector generateDetectionLaneDivisions( } // (3) discretize each merged lanelet - std::vector detection_divisions; + std::vector detection_divisions; for (const auto & [last_lane_id, branch] : merged_branches) { - DescritizedLane detection_division; + DiscretizedLane detection_division; detection_division.lane_id = last_lane_id; const auto detection_lanelet = branch.first; const double area = branch.second; @@ -1118,14 +1118,14 @@ void IntersectionLanelets::update( static lanelet::ConstLanelets getPrevLanelets( const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) { - lanelet::ConstLanelets prevs; + lanelet::ConstLanelets previous_lanelets; for (const auto & ll : lanelets_on_path) { if (associative_ids.find(ll.id()) != associative_ids.end()) { - return prevs; + return previous_lanelets; } - prevs.push_back(ll); + previous_lanelets.push_back(ll); } - return prevs; + return previous_lanelets; } std::optional generatePathLanelets( diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index e125f485a65e8..287a75979927b 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -114,7 +114,7 @@ bool isTrafficLightArrowActivated( lanelet::ConstLanelet lane, const std::map & tl_infos); -std::vector generateDetectionLaneDivisions( +std::vector generateDetectionLaneDivisions( lanelet::ConstLanelets detection_lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution); diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 4d2cf9695b2db..26187d75ff53c 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -115,7 +115,7 @@ struct IntersectionLanelets std::optional first_attention_area_ = std::nullopt; }; -struct DescritizedLane +struct DiscretizedLane { int lane_id; // discrete fine lines from left to right @@ -135,7 +135,7 @@ struct IntersectionStopLines struct PathLanelets { lanelet::ConstLanelets prev; - // lanelet::Constlanelet entry2ego; this is included in `all` if exists + // lanelet::ConstLanelet entry2ego; this is included in `all` if exists lanelet::ConstLanelet ego_or_entry2exit; // this is `assigned lane` part of the path(not from // ego) if ego is before the intersection, otherwise from ego to exit diff --git a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp index 3d72d6e4b5c83..2bcb31ff10969 100644 --- a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp +++ b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp @@ -222,38 +222,38 @@ bool calcStopVelocityWithConstantJerkAccLimit( return true; } - double dist = 0.0; - std::vector dists; - dists.push_back(dist); + double distance = 0.0; + std::vector distances; + distances.push_back(distance); for (size_t i = start_index; i < output_trajectory.size() - 1; ++i) { - dist += + distance += tier4_autoware_utils::calcDistance2d(output_trajectory.at(i), output_trajectory.at(i + 1)); - if (dist > xs.back()) { + if (distance > xs.back()) { break; } - dists.push_back(dist); + distances.push_back(distance); } if ( - !interpolation_utils::isIncreasing(xs) || !interpolation_utils::isIncreasing(dists) || - !interpolation_utils::isNotDecreasing(xs) || !interpolation_utils::isNotDecreasing(dists)) { + !interpolation_utils::isIncreasing(xs) || !interpolation_utils::isIncreasing(distances) || + !interpolation_utils::isNotDecreasing(xs) || !interpolation_utils::isNotDecreasing(distances)) { return false; } if ( - xs.size() < 2 || vs.size() < 2 || as.size() < 2 || js.size() < 2 || dists.empty() || - dists.front() < xs.front() || xs.back() < dists.back()) { + xs.size() < 2 || vs.size() < 2 || as.size() < 2 || js.size() < 2 || distances.empty() || + distances.front() < xs.front() || xs.back() < distances.back()) { return false; } - const auto vel_at_wp = interpolation::lerp(xs, vs, dists); - const auto acc_at_wp = interpolation::lerp(xs, as, dists); - const auto jerk_at_wp = interpolation::lerp(xs, js, dists); + const auto vel_at_wp = interpolation::lerp(xs, vs, distances); + const auto acc_at_wp = interpolation::lerp(xs, as, distances); + const auto jerk_at_wp = interpolation::lerp(xs, js, distances); // for debug std::stringstream ssi; - for (unsigned int i = 0; i < dists.size(); ++i) { - ssi << "d: " << dists.at(i) << ", v: " << vel_at_wp.at(i) << ", a: " << acc_at_wp.at(i) + for (unsigned int i = 0; i < distances.size(); ++i) { + ssi << "d: " << distances.at(i) << ", v: " << vel_at_wp.at(i) << ", a: " << acc_at_wp.at(i) << ", j: " << jerk_at_wp.at(i) << std::endl; } RCLCPP_DEBUG( diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index 1927b266b0186..260a4c6400588 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -235,7 +235,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node } void reset(const std::string & uuid) { counter_.emplace(uuid, 0); } - // NOTE: positive is for meeting entrying condition, and negative is for exiting. + // NOTE: positive is for meeting entering condition, and negative is for exiting. std::unordered_map counter_; std::vector current_uuids_; }; From 80583a68f45c946fd08ad622aec49612c00fb353 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 24 Aug 2023 17:51:34 +0900 Subject: [PATCH 252/266] chore(imu_corrector): add maintainer (#4736) Signed-off-by: kminoda --- sensing/imu_corrector/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sensing/imu_corrector/package.xml b/sensing/imu_corrector/package.xml index bd067e00e4c4e..07c6cfd9a570d 100644 --- a/sensing/imu_corrector/package.xml +++ b/sensing/imu_corrector/package.xml @@ -5,6 +5,8 @@ 1.0.0 The ROS 2 imu_corrector package Yamato Ando + Taiki Yamada + Koji Minoda Apache License 2.0 Yamato Ando From 25cc92248d42be25031c35920036ce9bbba900fe Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 24 Aug 2023 18:31:21 +0900 Subject: [PATCH 253/266] chore: update CODEOWNERS (#4594) Signed-off-by: GitHub Co-authored-by: kminoda --- .github/CODEOWNERS | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 4b1727e8a67b1..fb6df15ab7679 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -15,6 +15,7 @@ common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp m common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp +common/glog_component/** takamasa.horibe@tier4.jp common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/grid_map_utils/** maxime.clement@tier4.jp common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @@ -53,9 +54,10 @@ common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp yusuke.muramatsu@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -control/lane_departure_checker/** kyoichi.sugahara@tier4.jp +control/lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/operation_mode_transition_manager/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp @@ -82,7 +84,6 @@ launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp localization/ar_tag_based_localizer/** masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/initial_pose_button_panel/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/localization_error_monitor/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/pose2twist/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp @@ -183,11 +184,10 @@ planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp -sensing/geo_pos_conv/** yamato.ando@tier4.jp sensing/gnss_poser/** yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp -sensing/imu_corrector/** yamato.ando@tier4.jp +sensing/imu_corrector/** koji.minoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/livox_tag_filter/** ryohsuke.mitsudome@tier4.jp sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp From 1e68b9167270e4f644a0e9a3e6b0577b0ec98c02 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 24 Aug 2023 20:25:45 +0900 Subject: [PATCH 254/266] fix(costmap_generator): prevent invalid access for current_pose (#4696) Signed-off-by: tomoya.kimura --- .../nodes/costmap_generator/costmap_generator_node.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp b/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp index 381b8b472adfa..afe345490201b 100644 --- a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp +++ b/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp @@ -350,6 +350,7 @@ bool CostmapGenerator::isActive() return false; } else { const auto & current_pose_wrt_map = getCurrentPose(tf_buffer_, this->get_logger()); + if (!current_pose_wrt_map) return false; return isInParkingLot(lanelet_map_, current_pose_wrt_map->pose); } } From 2624ad018a2153b710e39354969457c99589f1dd Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 24 Aug 2023 21:25:34 +0900 Subject: [PATCH 255/266] fix(lane_change): skip safety check for stopping vehicles (#4733) Signed-off-by: Fumiya Watanabe --- .../src/scene_module/lane_change/normal.cpp | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 8fdb79a6271d1..3db3e049c3c81 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -645,10 +645,6 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( const auto & route_handler = *getRouteHandler(); const auto & common_parameters = planner_data_->parameters; const auto & objects = *planner_data_->dynamic_object; - const auto & object_check_min_road_shoulder_width = - lane_change_parameters_->object_check_min_road_shoulder_width; - const auto & object_shiftable_ratio_threshold = - lane_change_parameters_->object_shiftable_ratio_threshold; // Guard if (objects.objects.empty()) { @@ -709,9 +705,8 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( // check if the object intersects with target lanes if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { // ignore static parked object that are in front of the ego vehicle in target lanes - bool is_parked_object = utils::lane_change::isParkedObject( - target_path, route_handler, extended_object, object_check_min_road_shoulder_width, - object_shiftable_ratio_threshold); + bool is_parked_object = + utils::lane_change::isParkedObject(target_path, route_handler, extended_object, 0.0, 0.0); if (is_parked_object && min_dist_ego_to_obj > min_dist_to_lane_changing_start) { continue; } From be626b77544184cccc446e751795e069269fe0fb Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 24 Aug 2023 22:15:58 +0900 Subject: [PATCH 256/266] fix(motion_velocity_smoother): fix the arg name of the parameter (#4740) Signed-off-by: Tomohito Ando --- .../launch/motion_velocity_smoother.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml b/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml index 78bddc2b81f4f..86f767560fd7c 100644 --- a/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml +++ b/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml @@ -13,13 +13,13 @@ - + - + From 59c7eda9c8162b88167c689eb4f30f299200f4e4 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 25 Aug 2023 00:31:54 +0900 Subject: [PATCH 257/266] fix(utils): improve monotonic bound generation logic (#4706) Signed-off-by: satoshi-ota --- .../behavior_path_planner/src/utils/utils.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 6da5ff97b9bf8..eb2859ff700af 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1795,8 +1795,22 @@ void makeBoundLongitudinallyMonotonic( continue; } - for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) { - set_orientation(ret, j, getPose(path_points.at(i)).orientation); + if (i + 1 == path_points.size()) { + for (size_t j = intersect_idx.get(); j < bound_with_pose.size(); j++) { + if (j + 1 == bound_with_pose.size()) { + const auto yaw = + calcAzimuthAngle(bound_with_pose.at(j - 1).position, bound_with_pose.at(j).position); + set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); + } else { + const auto yaw = + calcAzimuthAngle(bound_with_pose.at(j).position, bound_with_pose.at(j + 1).position); + set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); + } + } + } else { + for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) { + set_orientation(ret, j, getPose(path_points.at(i)).orientation); + } } constexpr size_t OVERLAP_CHECK_NUM = 3; From b5e2c13f00ebc5b802c41c847f5c8f5404c9b01b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 25 Aug 2023 09:05:03 +0900 Subject: [PATCH 258/266] fix(avoidance): avoidance shift line processing bug (#4731) fix(avoidance): safety check chattering Signed-off-by: satoshi-ota --- .../scene_module/avoidance/avoidance_module.hpp | 6 ++++++ .../scene_module/avoidance/avoidance_module.cpp | 15 ++++++++++----- 2 files changed, 16 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index fcde58756d4be..7889e91767155 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -513,6 +513,12 @@ class AvoidanceModule : public SceneModuleInterface unlockNewModuleLaunch(); + if (!path_shifter_.getShiftLines().empty()) { + left_shift_array_.clear(); + right_shift_array_.clear(); + removeRTCStatus(); + } + current_raw_shift_lines_.clear(); registered_raw_shift_lines_.clear(); path_shifter_.setShiftLines(ShiftLineArray{}); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index b0fda03418069..70999f1504fee 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -602,7 +602,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif case AvoidanceState::YIELD: { insertYieldVelocity(path); insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - removeRegisteredShiftLines(); break; } case AvoidanceState::AVOID_PATH_NOT_READY: { @@ -2115,6 +2114,10 @@ BehaviorModuleOutput AvoidanceModule::plan() updatePathShifter(data.safe_new_sl); + if (data.yield_required) { + removeRegisteredShiftLines(); + } + // generate path with shift points that have been inserted. ShiftedPath linear_shift_path = utils::avoidance::toShiftedPath(data.reference_path); ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path); @@ -2546,12 +2549,14 @@ void AvoidanceModule::updateRTCData() updateRegisteredRTCStatus(helper_.getPreviousSplineShiftPath().path); - if (data.safe_new_sl.empty()) { + const auto candidates = data.safe ? data.safe_new_sl : data.unapproved_new_sl; + + if (candidates.empty()) { removeCandidateRTCStatus(); return; } - const auto shift_line = helper_.getMainShiftLine(data.safe_new_sl); + const auto shift_line = helper_.getMainShiftLine(candidates); if (helper_.getRelativeShiftToPath(shift_line) > 0.0) { removePreviousRTCStatusRight(); } else if (helper_.getRelativeShiftToPath(shift_line) < 0.0) { @@ -2562,8 +2567,8 @@ void AvoidanceModule::updateRTCData() CandidateOutput output; - const auto sl_front = data.safe_new_sl.front(); - const auto sl_back = data.safe_new_sl.back(); + const auto sl_front = candidates.front(); + const auto sl_back = candidates.back(); output.path_candidate = data.candidate_path.path; output.lateral_shift = helper_.getRelativeShiftToPath(shift_line); From 4cf251eaac9c440fcbe3286ae20d56d254d815f6 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 25 Aug 2023 11:17:45 +0900 Subject: [PATCH 259/266] fix(traffic_light_multi_camera_fusion): assign multiple regulatory element id for one traffic light (#4727) Signed-off-by: Tomohito Ando --- .../traffic_light_multi_camera_fusion/node.hpp | 2 +- .../src/node.cpp | 16 ++++++++++------ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp index 4cd5569129a00..bdfd07ae54b28 100644 --- a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp +++ b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp @@ -113,7 +113,7 @@ class MultiCameraFusion : public rclcpp::Node /* the mapping from traffic light id (instance id) to regulatory element id (group id) */ - std::map traffic_light_id_to_regulatory_ele_id_; + std::map> traffic_light_id_to_regulatory_ele_id_; /* save record arrays by increasing timestamp order. use multiset in case there are multiple cameras publishing images at exactly the same time diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp index 387b3ef1f6758..6c29be9858a9a 100644 --- a/perception/traffic_light_multi_camera_fusion/src/node.cpp +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -216,7 +216,7 @@ void MultiCameraFusion::mapCallback( auto lights = tl->trafficLights(); for (const auto & light : lights) { - traffic_light_id_to_regulatory_ele_id_[light.id()] = tl->id(); + traffic_light_id_to_regulatory_ele_id_[light.id()].emplace_back(tl->id()); } } } @@ -302,11 +302,15 @@ void MultiCameraFusion::groupFusion( if (traffic_light_id_to_regulatory_ele_id_.count(roi_id) == 0) { RCLCPP_WARN_STREAM( get_logger(), "Found Traffic Light Id = " << roi_id << " which is not defined in Map"); - } else { - /* - keep the best record for every regulatory element id - */ - IdType reg_ele_id = traffic_light_id_to_regulatory_ele_id_[p.second.roi.traffic_light_id]; + continue; + } + + /* + keep the best record for every regulatory element id + */ + const auto reg_ele_id_vec = + traffic_light_id_to_regulatory_ele_id_[p.second.roi.traffic_light_id]; + for (const auto & reg_ele_id : reg_ele_id_vec) { if ( grouped_record_map.count(reg_ele_id) == 0 || ::compareRecord(p.second, grouped_record_map[reg_ele_id]) >= 0) { From 5b5b416226a0a2ac982c5c33fd691372c7df8bc5 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 25 Aug 2023 11:51:05 +0900 Subject: [PATCH 260/266] chore: do not display steer and velocity value when message is not subscribed yet (#4739) * chore: do not display steer and velocity value when message is not subscribed yet Signed-off-by: tomoya.kimura * chore: change msgs Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp | 6 +++++- .../tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp | 6 +++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp index f13e971b4d6d6..5d3684d0351c6 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp @@ -150,7 +150,11 @@ void ConsoleMeterDisplay::update(float wall_dt, float ros_dt) font.setBold(true); painter.setFont(font); std::ostringstream velocity_ss; - velocity_ss << std::fixed << std::setprecision(2) << linear_x * 3.6 << "km/h"; + if (last_msg_ptr_) { + velocity_ss << std::fixed << std::setprecision(2) << linear_x * 3.6 << "km/h"; + } else { + velocity_ss << "Not received"; + } painter.drawText( 0, std::min(property_value_height_offset_->getInt(), h - 1), w, std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignCenter | Qt::AlignVCenter, diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp index 18977367afbce..60a81e45c9c29 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp @@ -153,7 +153,11 @@ void SteeringAngleDisplay::update(float wall_dt, float ros_dt) font.setBold(true); painter.setFont(font); std::ostringstream steering_angle_ss; - steering_angle_ss << std::fixed << std::setprecision(1) << steering * 180.0 / M_PI << "deg"; + if (last_msg_ptr_) { + steering_angle_ss << std::fixed << std::setprecision(1) << steering * 180.0 / M_PI << "deg"; + } else { + steering_angle_ss << "Not received"; + } painter.drawText( 0, std::min(property_value_height_offset_->getInt(), h - 1), w, std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignCenter | Qt::AlignVCenter, From 59a5e29846cc1e7674eab21786b5d919aa7d4174 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 13:14:40 +0900 Subject: [PATCH 261/266] chore(autoware_auto_perception_rviz_plugin): higher visibility of predicted path color (#4737) * chore(autoware_auto_perception_rviz_plugin): higher visibility of predicted path color Signed-off-by: Takayuki Murooka * change alpha Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../object_polygon_display_base.hpp | 30 +++++++++---------- .../object_polygon_detail.cpp | 8 ++--- 2 files changed, 18 insertions(+), 20 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp index 48f7d18ce67a5..b20a835f80e39 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp @@ -346,9 +346,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase { std_msgs::msg::ColorRGBA sample_color; sample_color.r = 1.0; - sample_color.g = 0.0; - sample_color.b = 1.0; - colors.push_back(sample_color); // magenta + sample_color.g = 0.65; + sample_color.b = 0.0; + colors.push_back(sample_color); // orange + sample_color.r = 1.0; + sample_color.g = 1.0; + sample_color.b = 0.0; + colors.push_back(sample_color); // yellow sample_color.r = 0.69; sample_color.g = 1.0; sample_color.b = 0.18; @@ -361,22 +365,18 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase sample_color.g = 1.0; sample_color.b = 0.0; colors.push_back(sample_color); // chartreuse green - sample_color.r = 0.12; - sample_color.g = 0.56; - sample_color.b = 1.0; - colors.push_back(sample_color); // dodger blue sample_color.r = 0.0; sample_color.g = 1.0; sample_color.b = 1.0; colors.push_back(sample_color); // cyan - sample_color.r = 0.54; - sample_color.g = 0.168; - sample_color.b = 0.886; - colors.push_back(sample_color); // blueviolet - sample_color.r = 0.0; - sample_color.g = 1.0; - sample_color.b = 0.5; - colors.push_back(sample_color); // spring green + sample_color.r = 0.53; + sample_color.g = 0.81; + sample_color.b = 0.98; + colors.push_back(sample_color); // light skyblue + sample_color.r = 1.0; + sample_color.g = 0.41; + sample_color.b = 0.71; + colors.push_back(sample_color); // hot pink } double get_line_width() { return m_line_width_property.getFloat(); } diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 73a524e130776..894e377a6f851 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -64,8 +64,7 @@ visualization_msgs::msg::Marker::SharedPtr get_path_confidence_marker_ptr( marker_ptr->color = path_confidence_color; marker_ptr->pose.position = predicted_path.path.back().position; marker_ptr->text = std::to_string(predicted_path.confidence); - marker_ptr->color.a = std::max( - static_cast(std::min(static_cast(predicted_path.confidence), 0.999)), 0.5); + marker_ptr->color.a = 0.5; return marker_ptr; } @@ -81,9 +80,8 @@ visualization_msgs::msg::Marker::SharedPtr get_predicted_path_marker_ptr( marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.2); marker_ptr->pose = initPose(); marker_ptr->color = predicted_path_color; - marker_ptr->color.a = std::max( - static_cast(std::min(static_cast(predicted_path.confidence), 0.999)), 0.5); - marker_ptr->scale.x = 0.03 * marker_ptr->color.a; + marker_ptr->color.a = 0.6; + marker_ptr->scale.x = 0.015; calc_path_line_list(predicted_path, marker_ptr->points, is_simple); for (size_t k = 0; k < marker_ptr->points.size(); ++k) { marker_ptr->points.at(k).z -= shape.dimensions.z / 2.0; From 6af6876fa550f372f79b9b91ac026132a6637ffb Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 25 Aug 2023 13:24:16 +0900 Subject: [PATCH 262/266] feat(motion_velocity_smoother.launch): add glog component (#4746) * use node instead of include Signed-off-by: Takamasa Horibe * use container & add glog component Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../scenario_planning.launch.xml | 28 +++++++++++++------ 1 file changed, 19 insertions(+), 9 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 665bd82423ea6..b293c5836817d 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -24,15 +24,25 @@ - - - - - - - - - + + + + + + + + + + + + + + + + + + + From 72a4e29bb74cadae89e10246a8e2a9b927088db8 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 25 Aug 2023 13:25:39 +0900 Subject: [PATCH 263/266] feat(mission_planning.launch): add glog in mission planner (#4745) Signed-off-by: Takamasa Horibe --- .../mission_planning.launch.xml | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml index c1ace97b9788f..ec7545956e774 100644 --- a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -1,7 +1,18 @@ - - - + + + + + + + + + + + + + + From c5a6f8094b5a7a5e19f4a7d8b9bd252a5a5371cd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 25 Aug 2023 14:21:31 +0900 Subject: [PATCH 264/266] fix(crosswalk): guard invalid sharp angle stop point (#4750) fix(crosswalk): guard invalid stop point Signed-off-by: satoshi-ota --- .../behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 64410c08a6f80..0edfa6167e999 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1034,6 +1034,9 @@ void CrosswalkModule::setDistanceToStop( void CrosswalkModule::planGo( PathWithLaneId & ego_path, const std::optional & stop_factor) const { + if (!stop_factor.has_value()) { + return; + } // Plan slow down const auto target_velocity = calcTargetVelocity(stop_factor->stop_pose.position, ego_path); insertDecelPointWithDebugInfo( From 2a9fdb798873bb62f0c6b0889c0410e5e2d071ee Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 25 Aug 2023 16:30:45 +0900 Subject: [PATCH 265/266] fix(map_projection_loader): fix readme (#4753) Signed-off-by: kminoda --- map/map_projection_loader/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md index 63095a72e835e..e31db7890cf47 100644 --- a/map/map_projection_loader/README.md +++ b/map/map_projection_loader/README.md @@ -25,7 +25,7 @@ sample-map-rosbag ```yaml # map_projector_info.yaml -type: "Local" +type: "local" ``` ### Using MGRS From 343d718977d55a15e0bfe163532f625d28e996d2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 18:52:47 +0900 Subject: [PATCH 266/266] chore(behavior_path_planner): use RCLCPP_DEBUG for some frequent RCLCPP_WARN (#4757) Signed-off-by: Takayuki Murooka --- .../src/scene_module/avoidance/avoidance_module.cpp | 4 ++-- .../src/utils/path_shifter/path_shifter.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 70999f1504fee..ff5706c34bdc7 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -461,7 +461,7 @@ void AvoidanceModule::fillEgoStatus( if (isOutputPathLocked()) { data.safe_new_sl.clear(); data.candidate_path = helper_.getPreviousSplineShiftPath(); - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 500, "this module is locked now. keep current path."); return; } @@ -2455,7 +2455,7 @@ bool AvoidanceModule::isValidShiftLine( constexpr double THRESHOLD = 0.1; const auto offset = std::abs(new_shift_length - helper_.getEgoShift()); if (offset > THRESHOLD) { - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 1000, "new shift line is invalid. [HUGE OFFSET (%.2f)]", offset); return false; } diff --git a/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp index 653efff7058d2..9ca083af35c92 100644 --- a/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp @@ -321,7 +321,7 @@ std::pair, std::vector> PathShifter::calcBaseLengths if (lateral_a_max < lateral_acc_limit_) { // no need to consider acceleration limit - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( logger_, clock_, 3000, "No need to consider lateral acc limit. max: %f, limit: %f", lateral_a_max, lateral_acc_limit_); return getBaseLengthsWithoutAccelLimit(S, shift_length, v0, a, T, offset_back);

    aDQn3j14p~Qn& zM~Txm2-_O~uww4bWnQMpb`y)?mTddIh-hXxmB*;&j~@^1=fzC}F{x0Dnv z0V>34jiN+2+40#BU?{E_Y6&sJ;o||q894vqOsd)Q0b;3jyo(3qjPRAXaNqeLl;O}i z1nlvq)y(s(B&}2v&75PwEn~y7hYY=fHZfs6N3U@*2iL)k!9T-wOC{y2D!t{`lCS#- z9wbcbLkqupP6$9&p>2M@@0L{rmt_66AOCF!gB^t^?GF#hF6COkss^47mXc$$to{@V z7LU9rh2X7U_y>E;aD>$o<_NrqKzK~NegcT!)i^dstVuvf5%5$%uf zbn%!Xg9}8`c<&^efPh4b&sd`#e*Q57T`vMFAyESDOhA?h3ZgmM=CAAJ16&YyDy{=) zVT`S~Q?32~=zwSwPBcn`Ujj}?P?aEb&n6~c+wj9J+kec49nN#jMm`}^D#Zv8agb+UVD z(TG8bO%vTK(eGl)>w!apDKII-@B3dOSrr;qPBt@_KYrz&wF zm~Q_N-9V#wMciu9w-ladty|=%8GZ!{ykY%G8AjL9TzX;jFJo$FoskncUOb+m;}gZL z&u%Lz`+w7G(iqrU8;<7qJ6*Mq^fPG5Z)Ypz`Koq7EuUpNrn*bfXO`=zdq8+KOPT=H zn8;tx!CCgY_Qob_p*O=jS<9q%mR0p6)2X*~mIMLUuk34%``zyw1yK)M% zc7M2w+qKcVDzmS?&qeK&kG#ml`#eD|x9E#%p>N|Rk;$8b9*l3!NQ_F<^{z*FkF6-W z)VgFfU9&rwpj`fjJYaM%_Cg@7^U3wLi)+ukxm=mu)%+atC~sTs&EQ~HeB1HG?;rVzkMag(RVD1>gcRin%|Ps#`cHV^c~bsOiX(kw)#Eo z+1q16CEiEMyHyucBaTDAo<4=PGziPwUVPcFRgjF75VdT9X#itM;3K0< zg{*rmpU>PpS{uPNojMWM6%Z_sXOqSH%K1h^SWN3{X9sVybRPZ;b~n=?wLQII@rqv- z`H6YEMAaW}!5m-pSX55?Wv-h+i>>WeSI_TBchZX-x@t$cva9P))|FQ~C@2zix|}NL zc<;rCMd%1BKNnaza=rOIy%njIG9r)^C{H(;!9`C;fBqjm#i|bPn3Y+Dof!KuTmII6P?^#EJDJN-uEK6-LR{R^vyK@KVd5EcbG%AVVWKWokI37)VFI4n%hUK4 zg_KC${Ewjcz<^9|W}K=gFi*r#aB%pr%F-3|lM7ovaxT`41sP9&R!{U^+Y!wNB&xu`?ejm5V<*ar;sA9E+FH3R4P z{1v?P6Z*#~XOR_$DFieD2s6?S%JV=vLHeMmz4yUEig$wP2$Y)^9g3WM9N<9stz-wL z!M~9BI2D>wm)2RdFt-3Cgvb!T%dE1F9L6E8yMdd@A{QTeh7&op zE}j$Z5*QeOu07UHx=(Bh#0n(TW|UM&K}&^-5QBsW{oeNh33bL&oG2FB*v?$rh>_xc zy(ok-RF~2|ivu5IyH#`V6^T#CQi^k!{2FOG0FUuHT&!Pp6-(`(nY+BZ-Pk;_B~hhr zP={Xp@J1#e-c!=@Hj_Xr2@R&T^^c8}W|iNtwn0!rte4{03|3U8Isv05fxzOMrI0Tv z=a9?K68i#nEaU(VB;Ytg7UEiHnsbZ*&%kyA-IbsZ z%qRL1m>!8$L2$bYv|+3cvz=K3nhrh`)`zcAF)jT_>w}Xae9&Cm1KSL6vjO8JrbZ}f z(28LV#=$b{u^BSQ)A`Pvli;gB0Ur1-FkcreAG)UC(-{v4LKsSpPsiWixcuEOe4W@x zX&tzH7T*nGFmxviX$Tv$Z7YGTc5pW#65mad8jRo zY~N}z^=}776NeD@lm2&)KJAbFqW71{*mVD3Xze$#umV;s`Q$diGERn$CNJj1pK@E3 z28?8;NDuz)7EJ5W?el#q<2aq9(>x3P0;o!A96&b3Oi#9EA#Wy1p z1@?jT`l*YoJTJdU*SRqKisQPFJ2?F@(*4;r%k?v)MnlK0hw**pADmBz?q`=`rdNLT z^};jT(v|33&fZ1F#+#XqWG#a&B#vyestHb-o$ae{&YyVsL(K5SiOfq{ZTgx#Ox0Ph z=gz)PveP=R(W8{2Oi@8AY`C$TqkQ;vu)5PY>GWg~OXoYz&^LQS#}7FzZrXZ^W~Xt- z{Zq^Z`A$mp~QWeXXoFZLrn^~$urTlyWA~^Ip@#kD|tMF zT7s{JqnB(y>YY7&QC&=?(ENu}WqHo>{9^7muv(l)J}$l!pbOdbK-&v_+Er z{NPkz(B7%KD^wKa6lYpB_cQ!`s@`73Hgh;G>>&fCOenNzL63B)3?X_uq5ocmGoxPy=l1$Z6U0^>HBG3^&ih{UN_nkPcnHl>i3_f6F&xS^e>PO!&X>pyB;=&fb&8 zf#+m4UNE)>=Rb{EL{Xe3q8J8xh^7+wWd1emjKoS%S#GKDuJaYj9W+|2uvJ(8Ip(>I^rpZ7@dOP z8_E=XK&64I0QCxK^AY(SQ09Rh2$uo`8t@lHxef)XyrrWG4@RA70VMC-<0PMh1fjJp5je%yp1JXxIOG^=6V-@bi zkKg?e9f)|TfoNYur1SjkWb``yRsTc{TPSv|oCr#FNhCnyk9vHH$+zqoYn05gmfXES zF*C8Y55Y5VMhkNq00GB97Ze&WuK4ku^ONI)kceaN`i%=1?dk5fFCA zu#$Ku1?@xm`1Oak`~wUB!`Pr{fY+nOW#=Y%x&S`}G^QO(84zO!wHIz%{+vnRbo76N zu^BXj2qE%6haJ4|P3Jn8*P$2zASwkCL6#W9#X6wnFo0FOxS4SZ4Dz7610pG`9R6oQ zgS=+2{D6Csfc9Z?ExZR|K@EPk)KD!EG??R&1*FC7h=^P zEd5O9;FV^hclK}F&N$(JuW7wd?+_3eDc&ybYqH9y_F~39_3NaalI&ib?8~#yIdbMd zhu5}3OS66|5@wZpe&A5=2#aCe7x-9wZ{eOrTJcCneX~i2_1Ox~ZX}_I5wn{x#mD!9 zrmmHhj-vM%7EZ-E_LGCIzPBKajzgXkVcbUiN(!(DUWoLeo5AV zm`g_7p^*Ml-q^|aZ6|%#g1{SZ`a0xV3>uWb^v2n^r0P^Wr5Ba14~Uh2bJ+JF>EUcy z;p@FC(c1C6PaDOGH$0td`v2Ev3-(}X2zL#NTh)@fUlM@uHF zN6w$-suFZqd!KY1i9F3?@|tp{s&t>HI(njco@gnz6fkhYU58D3y{+21E0=Wj(eIwu zRtr{Vyy{(d#?XYGQ)u~QeSa^zTWhH8!*9kRkb3sP;#ln6L{0NXVT#=AXHRr2%AFO> z)}!+(50fut!ljkL_d4Q(k&9y9)e!p_03 z?+mr^Oo$Eg`1XY>=7+96>SCN!zI~Q!{XoWoRWa1G%HpSxmQ41i{T;K8SecbrIcYXA zGZrR*(meT1MmE07eSYtx-`8AKDtNzbN$eJwmfc`p()PMt znqgRTy6D zZ>aG%!8Fw+8Lo0*gm(kU|1HorEs_yF0=5l0RRJEijnDNN&R`;xFG_iDTXlsEFEJUr zR9FxEP~afuX*%PF^BQQzNb>va<$2R(2lXn4Ob^mQ!rlbhN8nEZgBWDnGD@9>RDc(h zr(9o_QUXV-KzQF`4MfqcPK8Q8%Z$?Ge|`gP1I0UTc*OOZH%nbhRAJjM!w7OtUW@#RVJ7ce(DN@+T#MzAu0jAJ~g$c-2K z#ST+&j3a*2u&)KV^h>f&UQPW{0w^Ro6o_eHUj_vQ(HYNFj_J#YrU4}rZ&LGFDP&)@ zds&0KJ8YGZ_&4Bd!e%X&7|gE`sX5GCv$r7gM6N;qWnF>ct%9&0qis~9TZgrtof6;* zDsvT>F~IzW?Vl%tlIv-vnBN$gep_7m}r?U-Zsj+DUM8U z@yppL6C57n( z+{?c~%{@-8{^Rzrd!G5G-;H)spY}!}C8+)&&Nw(Q^L$hFe_Vir8X6gZ``N{V3zj)1sx`t(}Gtdzx1QCY43^Vhu zuTIxsLkzbGV&MiWcX;2y7susRJ?_M-#VFK}JFlpC8MT%i)U1aUX{7AQ2Y1MberVsz zz6AzEQDYc6+ZTS#@r)|&mcfUom(0Uq@$2ue z`8CddF1p4StENXY-|IHJNBHL3SwVS3LG!&OQ*3JG_K&$nI>lcnJG7?Q%%fur)?xc3 zvi!SAZeIl#EpDRY#G9E^L1Wl#^Yx=^6B06?!evSmqQ4U{^jq*0jPySiM8gOl>Sy0` z84Sd;aM<&VyfZFuvuICMfX=Yq$~taMS(&*)B`q_z@#(Qpb&eIkm35i#SYG4pEUdTx zuJ*5e&&*r7{ZmV+(MtYll=>N=uckSt;!}B&NpdyDnA=0z zuD!pVbub+Ac%7|uNo$p-Z{gF6*h$@<`M6Ov(rNAwjvkVFtTc<9E3X(NHvi${Mb2?@ zUK5#Kc_P)@UzP31&3vBgIQ>*%Bib16uYG7Ehd>%@9i^v8HiPEG#ZBu)1;%_uSEHfP ze7Qx1pKoYO!fBryKKW(nH-bH?SVxxYwE3}lzWs#D5S?t-#}LJ9*nD*#2O~1i4^5{3 zp}p1UwJ$!5p79a1Y@U%PdE)6;P{W^MJr!Ckhbn$oqW2LWh!@)>NA(RK#JOd39NuW% z{BBKdcJmQoxWboH$wO`Xy(dmIWLb_JthS6=a(c4fY}O0OFPFWHDwYprM(<87N((zB zXi2&gDG2+Bv(NtGxqr(2A?6PK(_qqo*7T2MNu}I^X9Z!gpHl6f8N94S%~irIh8A4(-Mkm)!uF!rEs z%3%&l5qG+fDWK}IXdQbw2CxkR?*|I*Q#Z~p@*XnvDbl&BYThVr)eOI13Y7eZ5*j@w zC>H?_OUpGG)8iBC1=#i@j=cWTym<46c~fwHgPkt!u;5NEk0-9r_r^!XW6uzxHZX9Z zc7SRJ`dHYkA$UJ@e6W@QDN!U|NelK>Mj(NKB_&bF_Zt1S_&Xqtg1tO=6*<&2!&wdq z=KmeQV734m$5%kS1!^*F&OF~_aDsw&FG7X}EfG12!j38Tf9Xaq&5~h|1KPc96QYR$ z%J60i}=FAf$@{JWZPpd-fAFdYD3 z=v>#UEQf+q2duF{mj?bEi942H(G4f_tQ`gL|Bx)~C!c?*u{knz!T=NK|3TdnwtA>$ zS5=U#O>a4*!wGJIffu+V&{9qk(zTb23>(7ynVjqO)q(|6G7Ql)7S|5b&yy2LSz;qA3(gzi}V|U z!CYhx_Gt*FhXh5!R}th6fz)^@+Cq35-~Yc%EzkvjA6AnLgLN6g*-qfrYXJo^6cZ@F zaEbN3&z%s)$N13UkLVh zFk33HBYxA6uYzUq$vPHzqAQMwpdAL?O;$vy+_+z8i#V>vDJ?t*L4%jrW#>Ej&dFLa zeK#=`K_KWR;Fbkv_125K|Cxm$h#?S!5vmLf=}5t}5=y!g-ki`jo)?gLrCHgw%~|0B zI57z9329vL0n;l&d|4|4`&N)~5QHg9h|xtLH#yvE&>S2MB{cfMWD2`W8alc;$W?{v z+y;m=Xeh4@3&KtX^d)ew*g*ms;A@Eb5hU_3^dqI*Us}d0l(Z^QTi{UvX}aqoCBbQ~X$9fC*pU2ws>HmcJFw+9}7!h|v;YPON$if@ZYyk9*LS*=`^Z+G3yq@4J4w}r_ z;)~T{iTKR3(leU{`OD)B?mPw4;iUUVU2m|%=B>)`t%YeZz6dJ?I9vSu7eHLPOkFQ3 zwOk_`FdOD=@94@TL~~pya@v#?COO;H%4BOBvm#%)Z9K_QxMw5CzU55r$6G_zkoJ`(t-E^~iZMO=9cp%cBRE@^6Qm+LRYR^^Tz7D=OXk;OybwQ8&>M%PrRE zenUdHNn`$3!~HX6QQWLi*)iWcj-S7bOqE6mH2I$A4PytX1f3Q3{af%1^(7J^udyBbA$8j4t9-)VI=Iq`A|@1``cEHOU_DvQU&)^AFQ_wPmGx%-$(KE@ z)Ihd*rn^5F=FC61$d#)@$G}>=rNcU`x_YieOF(>(7bcz{tfy~Rt26zyU1TEYqz;wX z`!M5_1{KZAIW_2E&G!-)i@VnQ(LDXag0MS0jyL|y1o88;^TiUKaXN?j34dBF;v z$&>ar!9|+tRg*5mcK))At}ondJh*kb9}5fm@Ypc;Mph1-6W3BNGT)G#Cqs^JLZh%5 z3r2g734P`GcsFbP;@^8q^fz3(b#ffWanHS`<@35b9{-^0^O!rQ+1?>uqnjAm9QJ?s zW~a^54N(PjJPZgZaSxLhVWChLLiypgqFM%d=Z=N*`c#eG%&=B$uJ*>UtWuk1UOhVT z@_T>^;6=00W4*%Q@4&O}CG^N!v9;0tF+F*DNr0wjqrG@PAMb%;dKxk>`g+VYn}ARW zj2xDT0Iy_E=%yLvA`Zf{c5%n`P4}Xv#KVFT0ZS=_A&+_@NF@sqybzQLv=;m}0En`f z(bmiW>?o!CpD0@<_Ikbo{x|So1oQ&&`UmI0co_+JlfoVj(clWec?yU+7CW+{l0zdC zh7@=t1q%sd0EeXiT(6{n$zd1Jh6C+@D^ufy6@Rl743-BlG=K_fO_kFU(y+h11fQ4I zI1Q-UogoYrNB1+a7{3g}1I-3F_N|8++R|4^6i&we3m^iGu~Ke}kC@RIQ(h8~Uci1C zI7DXjH)nJKIk8JLDMmiiYKYYh3=4RiTzmOlJ+g)yZ2cgng+c?LB6u@lQ+=m|8qF7n z0?cgT$$=QE_62pox2#HZ#5Ve7{bxwe|l~9V+-Jz6rA_H+da6y9wBs|d~@`;Q| zm5qKIB9fK+p3I<#%jbd~fCBzNL&5Qikidb|UZ8~-Ducia=}iEdt8rK&K|tu>cO^c*eCnrxl{JxfGq9@E=^+!o zd$;3@8;YV{#?)g(ioY5dJfQW0)U8*uG(n|cSZ)jt0WeQ+C;h0J)`FOHAE1GC^$~rT>B!V5Sw!0K_dq8K(8 z47RE6HoP%5Itp6+#Ep;>=F$>a3K+or4RsqJT0k!WEQfmq6eZU8hs*^j*noyKF{TR| z54e=@tD*eDP2Y1M%V`3S7z#d=`dPcgZ=a#CKzvpu`8L<+ATai^vSAK{f_5`aRR+fw zQEdvNA&t<4RlKja3HH@Os)!CWZR3vR>GO1-zfE>$d_)&D#I=e=!(&z>VmZE zjW6CGK(<2VH*Dd3At>{KODj8arbfsAP{TE5zFxt)}O{L=9R99X0 z)LmI}j?VF+BIpjF`l`vXs_+r5LeQgf*Ym*?5${_;=Wj`0E`Nq;E=Xs2eGPv&#urxA zsu$qr+=te&lAy3a+@}&PGwA;2rJACMUk20+|0blGcm+oI{R_0ta5ML zM|M75yn7v9^mGX~?YPC5KyxzG*JM&G2cvytS|+9{x=#_~TzK!F7RIYX^j9LEY>j^Z zs0z-QvsrFPTE|Kjabw?Y!S2Nh<-XuogU7bey7-}u@fx34JL?flyG)4?rGY1*b= z(;q5pO~x}hsOUoPKO`(V|K)@^33r4e0oJxxZ{?OI-4+7%mhDH%(<88 z-a`yE7Qq0I0Ky9&dU)ps%)YCTS@zm%X8yUQePO}*RoK9Uy4i|CeN#{}e$MAFzJj8c zuK1zGLG6D+=y*KIy9AP+qOE$;!Dt4FKD>+!21j^!(kxgPXl{kvqA6UlbTv_ANp@&iL;-PDj>G}}hdU_J}20$IT3FU^y zd1IadCKJd>1jwL1$&*-wTX0d4nJna+pb8>iLV{QTlmJ%9JM3Sa7NioVAQJFHaUoVbtw!I&dXS~ShQ#AzH)a zpO7mLH>Qz^jEHeXjZ+TJF;K<=lN30F5Nxx=8-S^4DM$qm3QB=7DvAhZ%iwSR$e}zr znT)0M6&6v5v-GcCEt5KX8er=&1k&7DVU4bgj+V{>4);9rs7U>b^ah(J`^~3`mK= z(-Bl#!e9^$qz!7l%5#|Fh9N@(TJ^gnZ^y^^nL1zo* zOvuI%4BY4>Jbp0xN1%%~ffLOUsOyUMbK!&z_5BoCjEnUStYUil77tI8j=6#P0jIHW zI}}%#W#Kr_hRnf~-q#Ax_EqeOjnYA4(j%y745B#R&*R_#h7@AhQNZR926M>hZskR2 z!7y2v*)SOhmO2xY(4bkY?Tdo$3mA)F7!KnV+^>LWK?4IkS{O*-@c}F65Um+qj6})- zY8(v#*hj;757p9a0_;~nY5}g$=Sxcxha&JYA+FBEK}gOIlHLeuNAOcAXH=A3{-2XJ z2-}jJwx^~q4k(ll*kkE06--$k(I;DcQ=hPUe0NhUd@zvOrW<}2H z9qsLb`}}`gw=1PDi#EB}LiSc!;u^=Z;`lzD(7EAVYOZG62)mD}qj4)nILNF#UT7Pj zTsp;mp~!e|h_KKz-MrT$_G0y}X?gP9Keg&(ZzC~Ss8`3*bMKA5780V3jQezrOBsJ< z-6?cqEz`9A{+&LjRr@zDa(c}hKHsBW{$t##_f|f|y<<zVPr%mIDD+M2V|vIMeAn z_jltLx3Z2oo88MdaqjG|^ZmkRwp`7+e#qt7nmnA}Otl)(Wp8797uBKk;YI%#LBj6e zn*m+~`=b9mb@Y~NUZHG#erb5B3`=ip(OG|dD_&pZFxI(3(B-;0)GE>9RD1pyFC!3L zH`79+roL(BbKt7iNWR@E%hrQno1DJe-gMm;T^Xl68eDgbinKh#=YIuWUeEt7BbnYw zaU?x0?&zSpt6}=eIeJ@rn53p-C||Nm8>e+XHD+tOa-geJOQWMn^Ddq3A2XK77|~JM z&%y^LryLuF6Ylxvx*Id9@{47rF5y3$%H`ZhEFP8V*rK5{ah+Ib?=-Jy(JNdk9>hrt zw@zfzD>dMnnNe`_CZ!d(@|)Q*e=}ss$wu+IC?^XEBwbUMGyPPR>uzR5{LV4G6~B&N z>5B3qHPG@#os=#xYv#5jFuXDdB{Jv(dLJy7d!OQA5CseyA6@9N9gqmwb)&m$DA)|g z_MJpqlugGC8Bs*{-3V8KKvvoXU;Sgm9uCdp62w>HiGLvHk_{yeE_2b z*>$&6doai$xIL?A+bhYHjs6;KTfCz~FW-}EQREGU@VS>IGVEM3YNQwM&G+rnHEG?_ z?Z*kg)xRZBNY1D8Tc|6JKlol?{+HOn@lW5r;2Ai2;=ruVykIVRT+r`Qge|{6hK&_t zA2(7va`n5igzMkacw~>skUhBELH_Ro?N&lJ;_eDy&1flOl>~k?q?UA=l)y@g{Z^pa zX$i$!a1%tV5fSTo;3G_*{y7X+ZUXxu2!3Vdn1|Fh761Xj<+YIT!#r5=fqQTRq2op% z7wPLh+E-iioR~%Gt#juu5|H&30My>+W8Pt4g9v*Mz{t+Pq>d@weN*IYs_C4%aW9u= z_UF?V-+>aL?=pJ@SavfYx=QUpvSq*$38Msc8+;LErW?Sv0Yp9Rz(0e)Q;AQnE=Hwi zzQH;Syg*PhcKIP8As*|OWuS;M1R4b#2R)5(ohFd7vO{>eO^Cn`jhE*LnJx!bgxXtd z&)^*H>gtMGxL!96_4G#td<(R@0IRt`w%s;tg?4L!mGJ6(hnW}-eS$!d^@0Rg$(Rv| zfxRDGA>>?Le=py8w{Zs_!2UDPUAf(CP#9X-i?or(fhDW}i6N*B5YVY-L2(iTRgMp- zhWzuBFrF0Y*1iSE26mQ&{=wq#^I&HOa~*Ie>=30cbjDO+ui1v6E$;v4N0gZH-&z#e z>$xu6I2-dmCx`7VtWiOM>pHs(^a>;r*dqB-(%tresnb3!!Yk_8ss3-hhQoE5=(*6g ztOtd8%w6$lSNTD6M{F=oWI!G1{gvE{*UsLa$L`$Vh-dp9n&k1f68t9Z&(=~Wif_rf z^O!Yn%4*6Gyj(&4EBtC%+!J~l>8hIkzGroFmWA7i>gVGm%I=`|B&-QX|L)NkB{o|C z4Z%+DuD!U78wTThcd)gbzPvc3#94NwLmcye)x9A^)^JM>dXP;^0uzR?`vE7i<^=dj znFTS&I9ryNG}_+Q`g89e`DMq`fsOr8YBOWTG_uULY~#73>u+{R&{*YBUq<|xE7&OM zQ&HZfWH~V*M@nbaw@b-94JA-&w{M*rzRUf_{15YCNJUl0sb<&p(??Ciq}XWLLyxc4 zJ;5qT9QfkL<`BvzB2H0e&Eghd5~}vb%6&DzZSCe@ie{K1NW9yu5cB83&O?o%{NBzkk^@uf zVkzA1iaWtkxWm3CG4y|vT=53J^Qm3p&@fCHV8kikVe-j*TxYm6+7e_^&o{;7!=frS zD(_2bjyDuu>UHMOf=O)3Ozzdw`{7)JZ{?yR|A%Vy&>KzGi3sP6c3I{QHf0_)GSR3* z^Xe~ty~{4o$4hY|vyY1n7nQCat3CH_Emk!M4v!N|!rPEjrjc${h!7R%u&CTKF6CED z`_9+;v}97r*|vpsTUUUF?y1ov?}l*``##_BN81q3PK@l=Ife=ee{0WvSfGY4L#*15 zJ~m*I&_yp@w_XggEZNHxV{dZ$K^&KNWPfwat0actA4&$9IL5lX+ML`U20bQM^?*m_d7{1@(Z`KI7b zxV>eoVBU`kZ_gmxXx)y}sM95{)g_zI{rjVn-I*x+g3 zcc0`#=|}|RzTohAg66}ZT%gCcV3c~u%k3h?Eh>n~i_V{e_wPQM%?ygeM-%Psa?azw z4+Uq;uUvJ*WfP{db9CXfLpS5E<4K_WJt-U>+?UIU)8|p@dp6-2doQk_UjDCMr*fWF zkF=8{r-5w+kuf1(E40jJ8vi`$A+n~8k>^DOWPku60I^C(+T8YezCd)?USPc&fdK`2 zZCF1DTj_w6g;^P#*WeNHx)u-RGUJQQ3+OZA{Ecvzx@XIPHz3l(R{DBER1tXcx-6v& zh?A0WE$rVBA{z`U0RD43K)zY48M;A(FHx+Nl`fd7E<~Ec5(69;lA5fLV;x#yQ2QdZ zIW$E%I&_zTZ1K1_$mKdk5=#IsL-};P0RRX>X8{Wb%mL2Vmr@v|^xgStT%x*q3rpVzJ7?ffE>Wb_tFJc#;1BVO*L*|0g z_RiF&b$lgHu(Y<4~h`zwszLoF1Z zf-}8!Hu5yGOIKI-0f?pm4+25b`nnbRm$|Rpfo(BTE#MGnQ|->ou#$EY8jE8O2{+XI z3GFf(F@ctyJjJ7SGem7CBMQ0m^B@Xyfnau5 z3Ah<%W#~_c0uPzJfkHXn0h|^Ia`mG>uwlhYM9YfM0XHcKiN%)KMnkmj$W*t(k*HUxhZ`Ech=lbbmX-*o5osF$jpL(>*a3}N z9U_t688CQ+UY<~>f3{X-NT_(`$lxVRZ_kQ1Zsnwxo7k+bsf&MC?l+A|w$MakYhWH%n z1at`nW~PCb>$$n?4x}awrfevOL6Im){4+kqj5f4eT4i2SQsPG4kzpdM-+C44$P@)J zco^i}IZqd_v}+FsEfe7~KQz7-LVs~>TN(XtB&O7O+@}f&1vD9o8WN_aL8_cyEAI|p zWfR3!X2RjvFlt2&E)k~T-hOlrwyA4uQH=UpLQ9pn+gfwB(sx!u^mHmX@bgXHb+$D+ zUK*XKRo$=iT6t5zUu$uLd*ilB_Wof>;z()58kwZ(3Bw(9jnp&Oq5w>X_W6%<|9l?M zvsMV5a4pnu#p|`XMxzQbecYrc{+3U?QQNLX#}&NaLlDu?UEvw0kV$;v-_g69Dc(y# z6FabDqMKbc`RheTD#5Vh&x4&dSCtCA)aNGjog%r}7_aYzDTYd#;f}sY4OsO5tvsw2 z?4b8cBw*`Sv-;PRl6#yh@4gH@I*qlKrwUz=3u~-m^*Jj0?)+QVcg>Fd{=esY-EMghh7o?kvMJQw!MHn^pJ^}4$52(53MG;f04>lSbS zk5_xiTJiL#u!NO-Tg<(kFaC1cF!^GE%9 z%5#%z#CxwY`fpvM)SK$EWL8qS5P9)qHYURZ{ZSHsOhb}%|IGUF{Xs(JNb~IS8>WiN zCB%(yJ+x@DpPY2(bbAWiYLv)O`ug7CYw!yXw|gNYQT-uv5^{ecR7^P@xxNgl-!HQv z4}CzaK=!s=ll+ zDw9pi_*H(#>z}cd8!~evNa@m2c76J`(}&1o?rYKYyzQ_^okC}$?J*ZIp&_^Qjx26= zkDn>{%uFI;Vh@0Gj3Dp~IH02hcmlnD7f2C*K>h$S27JIog}>cuPTJ%u1Ju|% z0^{mQKpzK}LNtMxaVuDr1m;tR$+c%o_&etaX|gCgD@eK*rDFoJOn#~>ZygZ5BL11V=^h-v>`|{`!1ur+%!64WPkc?EtZC#vh&J} z@`@2K)Ir&Tnm7Yy5QrDzw7KL?8woH)?DWVH?}W&5>!_2YW*I=R;VL19y@<&KbOFjN z#^Y3ILW=$R#V`GAa~mVAAg!XTqp^$qA;Fc<4G)9nRiyMHL7+_47L+Xg;tmFl z{#^j3g!i(yPQ`3H1HbRB1f!`7$r#n@V)1EnAhDl7+zxwjc{29jQkDMlsH0$B62!;Y z^d3YIhV#oa;|=yZw0;5fmz@qcD~Vus1RF@0h--=veKNS`0`;S;Kdbt5sBKq_Kx567 zE~8qkzZH0P0%;b7J3|k73;|Fz+8iD z)GO-NA4$dVI&!sGL&+ARYh~<4oIU9%&KNh{3V~rY8;r)l}@IBN4oeqev2jEl}o;>BLdqd#-!jbcoEzn`}yXACA_pcg~nM& ziSs-aSn`PU@7_19L|lPlBGu$|Brq5ef}xEsES-Rk{po`hDd z=R62sq*j}Z%j?;GN?=$Tt5SS&GiL0de5XjC1UFWwO4a#t%#Voi0(E^=;;jTPY;`kw zYMTz4+c_5O7&4jE)beKUR3kQoMmLW5gqnR)Z~c0CBz@5l$mOKDnrz~6pc9$<>aCN~ zv&!$wSr5F`hpnf%zL^HE4(vEHd^6_2vgb_PF9;6T}M^zr5>rJq4rq`$JS zj4ZK|Ul;QX&Rm&729a{Spq4%Uk!NExAoeyDbU8>He<#dqn#~_EJqpe-vG#l zt;e)&F4K;m_gQAE#A4%XWA!vtjN;78o}rg1?}86QcJ99UK9)>6B$&|;1tA#@U-rcH zUQ*oc;3YZX2n@cl&FUT(G_gPAqo%s{XbO@|Fy=7M4zw*LSC^0X`&Ps=;Ki867TE`d z*>XHe>bfU0;x`>bd`0R0ZK>N*7H+R*(CxCW`-c<0c;SO_C6|`1#x7gXW3d13!yT3T z9%CPfnm#ewXz1TgM zali-cB!r9u^G3hqr5KMgB!9uDV5C49E>}Wqh{F^JKCu}v4~T}rtaWKm3mXMQKaBUS zU*L@oDabHkAXeT8$*Yx6vga#|4_?~$kKY@bgT@Hnm{2E_*v(o+fr88P3xjbxa=Z-1 z>mI-M6%JE?8|LgBLE{QE+VTcptS|wj4I*ZRB_*gaCwpK8!4@p@$!9}A z$BWip3ztH2M6*2&u#bUL_qqvO)-z$&`T2^k=G{M}#6cBvKT}XC%|F~p-Z`lwS)M_{`|xV z>oG)dfZL$~*aA6aBqc#mmBIE8SS3P1h2R=GkL~*axPLqJ1YMzwIqr9whM_&h8f1xV#inyXh0h}oX2K!SByE%*pj4-w@h%b^{*O|{S78#bq=C%FbI#vgON?)sP*`GM0}yHv-udu<=Ga#WQ!Kkks^uhq-in#k?j22&q-_5jdw1kbWbeTt5TYS9eL$%X5nk|rxOM1Dn5AN zmNMU-B=7hu-sO2ke=4np#%ME@kJyI`300$#kclVGpF6p6Bc?pr)*~Osha6M2Yo{1n z+LY5aZ)@&koA0H?PmjJkH~u7!OV82HE+TJ4Z)$#PGM>ZYUGyCFLZ0eGv8c$G~U9@>_;zv$p({3)^_4NoC2y3XH_e=IWCdc4G#@7XQ&&{BQf zfRVtLeo^`}*2Eh`x7va>S$pd8Fd|1=bZmOWrWykWh-$+r~a51tv8*!LE z0$`Sa^}2QPv&plB44>v3XS8UE+3xqRGE$bA9m5*y>OJ_&mBEg~_U&xjX~I^Bug~zt z_RDdcwA2?H%oW+qc(j>HCnF26{g`Pj{D@zhY8JNjtS;nmm{bC7R&n+f~oo#`jp zn2Dm8+nVMzN0V*!(O1tm1ltz0^8VS}z?b@rqmG5`bM1x+Y6E@JH-Kd0sa*vLT4zf{ zfOIA*V>i&BosEKm?+U@^<8~#QZ2d-3BZRULQer>r+d3m? zJZ#u%usJA3x{F$aqBF-u6;mNc!yiR{yow_7C-EtZ*$TUgGTyj zmeBi$=y78|o|2AbqtC75AMz4!Ax&=r7EThY58K4c_q0Ya(*AeK>=GDa6VJ22y@J?x|^b6 zMtAKk3QCNQrCD(l;eEwGMIpoLS!VtqLpJMQALxK<;C&S64PnnAh-~UE0%9Nx1_bp1 z6T)h}@JhYBiZrlV03!Cb8WtsN}Jz7(D{td;`MK(DWcPmpm z_f&-pv-0C2^mz5t3@~={fR$F8xnN6qzeEV~yQBaRN6r**CM8c_LO8z*uSMbvAF}&{ zH38Vz0Jc2`5ZHgIXLs)+rU(FGjfmK#!s9Y{^XAQ*4Cd6I;V!X0EaXK&5+A+1=%9Iq zA&;c{krD#j!^RP*<}@AOUR>_Km`5nIi5uZ2@bBp1RoaFtJ|NuGko5ZapDE&|gbYXE z2L)@Hj9X{(_R?AThX)5lm}o%!`X3|?^B*`>>_B`XK<;x*7i&$4=PH)se127$2>%M#l zgpeP=s67!au4PJMf8^1B9)aBnJo7LPA;XVxgm^&4<=K)h9TEBp0P{$_1?f&VN=0>{ zf$?(b=><8)=LMsuZ@(*gbvqi}bGkpFQJ9eOgyO#!K0rZ_&s@(^tzW zc4SNkQ?)zpQ&~eG8CtLB3bBPvKBrF1C~4^rGS=ZIWY&3VgZD#JEBD3CwEaG@d$woN z>->$lkC7)~k()=ewEtpF*D@ka(=L@lJCj&6H!QW5$7xn`jZG^Kg*$k&xH3QIyCkhG z1(ynX>R;W5+$S7UVr_&vM?ym%tv*)%PL@4WW2!xRHIAn(?{jW#;b|z4qeP>Sj3@`!Zxv{Z&FM?FyLD} zr?ysnY}B%u!@yjY(IUaWF)_kJcNr97tb>7DM|zT5XH`(tgK0r-anbRE)vC3MS|ClA zImA=yR~LnkbZ?YI?4{*y^{)iGza^(bzig{d-#>bl+Lvz`?ftVrKCEd)nEh}P! zZ%B=TJ=^%wC}V7ndGuI)vwXj@-6UFvJ%QV(xN0@|L)}lApwhejFEG6ng$B?SmFh?w zlpbz4;SJoW7~$KEqv@+LmBu!%DWIE((3td#QfeZJm-#Kf|HD=mb^As}hD>IBE1tx^ z>R|nYSbEAyK9kk1X8YfEhJT#0c_VEqaOf6iUFU`EXvmdht+a6_%6)|QXpYUM4`otE^VJ9v7&nUA{2ZWB`bPp{aKNm5i$JS}34&yrz!`k*gjA9B6Ud>PIU|38}|B- zP8z(@>@pG9#dwiwJHM9r_gHqP{=OFWvHfbutHR*Rt>TLp%2$s5fHb<_ll!=3MoYh` zZ7d0uIg!^{o$j~u0KL;g5_8#ahUs*2{L65kWL$NIpAgZ>8+=-R*|`mhC%yGc40haU zG7C<4rLq1}VQr=tT6z3&)ur2xX)ZA&EJGU6&A4cWN*GB}-v$SrDm1rm5Ct^up%&zG z@8Jv@a%cWFj|dm;LPyP3mW12fJnFlNo-9ITck?&;4ZHU$g$sH=IwuvB>x$O+jk((< zyA{70!G4RUt4^rr77@QH7Z(?0NX_AGXz=0i>B!3&h_ZvxQ#@3T2@Z11 z`^{e%Z1c>)JtD%36!zHwDzroJIxO)cJ;LXC8P>7_>7>D$4xy!B0I`J*$be)K@IX{Am{Hg2Ghm5D z(ZSY3#}cdWddM))ASB?M0REXdoxYTStqXt%BC%^9CHC2ENJ_EOK!^iy0<380^Pl)#}3?POQYLJ!(`yRl-;7^zlNMUc^j{dk*8yw$+q=cccNcEUM zu(}V*qJ1#MWxBspm?#K z#<1t}jQzV$6EOC8JXanf8I*|e0U`~VQ;*I#Uw=8ljr{)4Pm2*l0$3Cc=#<-L^L~H? z`&O71M8qt?s<*M|=PR+7*0X_GI*6tBuQ93dX%M#n7aPVRU`SvYtT6k4EF3NvV(+BB zUvrlcBC(+1KPv15P01|S=C#0$0YfGTMv=xN!uxC?jIgiJxYd z@PCA3;10MPFC^e+ZURkju=?){E5>Pl0fAP-Aolt%a0h~W{MZ_B=@4A*pb6{*LD~gY z2`B@yuW%*70e1QjxewuvMMS3nL=~eUrW@ecOTemtxLY8kaJzyFwDn@!%*StiNO;&3`}0NcZK2hdRYYB_Zr`WmD`nA9=4fd? zCXUwlZKt@H->g_g^&eb~p&iT!Zp5tXy#DnT*>2^;L)|au%--mcoGRq+`L2F086@3F z*OKyk%!YvLgEwE@IwxqyibJQd#vhhGVPAMj zi`uhp)Vg7djsD|1PxM&o6A( z61{IW#mo=sa!e!ovLHMgotj;y>A_jqN%%IhmP<$K+S_f{#4Yz8I&%GfzaD$T#D^JE z#QZ`;k=!G3GRN%KFNkmUn2t1IN(7=p{m+RgP}UOit1hX3`6k}9a8UShsDu=SU=&96 zFKqvPDG^6ecbKi*s@v#lG+r{!+O+lY%k~sn0~=HLKP|~k)98YFPv%B!oa)MLTU(x} zLqhu_>tQU#H(&iC$LL^Fru9c#O!sJu=kY6pe(9Fb#h*9?mHn{yG@KY{T?Lm@|lk zzG0vUuEIYAw>eqUEN%uuyx=KoF8Zeja$ZoRD49N zU{j~f$zRfEPlLs%@tz<36H!hS<_?@R@Hn~4bqb{|!+<5=ez?hZisxGa3QA~ypo@lb z1w2=pj{BwBe-?KwO#DI?@lMX@( z}a<6^tjveu5_?-g8(l0$q1XihmoI;%3+nx zB>un`;8Es%gje>yTQLFirq$aY{BzXC1)s8F)1EU&GcebV6>-;EY${{e=FT?Myn6nU zDP_WTN8efuCo+x(pRQbqd^vN(Yq&jO+~Umx4`WpZesuot*U|>{BAn zkEki)d}hkeYnny_qzdZK&<*0Tq+=zR&k_vU6$Ofx&CitkX`YI*Sl_Hltsz|I z%fz27tBmn93btU4W$yK-@M2nE)a{WlL;p_9X+I)Sbm5ZmvYbqX>^nuA*14+ov_|wQ zQ%u~gj`s)G38Mo^xJt3cutNcoy3f1u=;YpC^6Mpa9j6gMpzvOC>clkbEkEk}p@KAl<|8T|d z+VzZTPU`IQxi)6f>(oIcp6jgPsl_DW->pe6WR7GDQZ^D;_I+nrqc*XL-C084t<2w9 zyFrInZt>(Kr+j=9MS5D`;yYd1S1j}n zZJ*KilQh<_&mp^CPa>w7Lw2daGm%_9Hnw-ZY#wCf=pCu~jgb>9CKe98yIHe@#^>)< zdOwzABug(Jdt^`vlm?u#M`-%Y2Uyt;@ZAQT9?{z>bXtB%1+uCVG1^14cbyM#lq~7~ zd40~9pAFkkmN!oAx*+9Z^EW6{`>509u99a^RxL*?bV}8YL)jT#ycCvi%V8U)P&N3b zFEQ!hPGvPP(+cCOJ3K;WwGHC59Gwb%aD?+R1wH57MOl@w2V#17pW+cb^6~U6ZgGF# zX%TVyAX#>-X4bvebew@b8YUT~Tz)=!Uq94` z040o;Ywa-Ge&beop8D^em?_X-4 z|F9KFzxo7@XF$V%Ue-}JfBN)`$6Cx}VMJi4tOOi6%2{wT6oI@A23n7!U*Rw!BM=iT z2A{`gIO7U{8dAJkXBby z*keJ1H5rR0PVc@T!^VL9Ve-Ie0t(UO2UX5nM9FfqsvTFRn%SVRZ2v*|#H z_riA-Zonf=SXdw<`13{3$@H!ivVoeEgNVKT8LiaWR>wLG#IskxVgo@yASyf<9wFl6 z;enkH7Ge-63N0*wgaGS%0q|hIEE!HI;bupCJHMPFU^N2!6I@cDFho**Vi)GXI0kwM z1QrGU20%v81#WG}`P0V9T!_>A9ht+YMoTQ^uqypZGbVF8BinS1Kh3Nx{#&(TCW1-w z7hVJ>-E7kvuX3lqwA~-snf99O<+|!$td_-LAMVA=E82!n+MuxU;`CmT*k;HLwI%!L z_?l7ngU14tym`UPUlL^r%lMa??@A@gVydzq&fI-Q_oilgo$VPT=92E_<4)NsPKI#R zxtPsC)-V3VNq=0m|icy8XqKc5qkV7Md}i3;ChzrGnp?+xNq;&Y%+Mc`J7Zorm>IM z*iM{l9G$ul_OFvqQ~lHb&Q=_kGcpkJ`}ysgy!J#D>o1KyEp?C;VG3R3|H&=M7rA%x zIraK7r!7PL)0MD%(aS;(IsSSxh3tLLmZd9vlE3G$c77LL<*^OO=eb5#lu_|a;}P`_ zmt@x1_hY=)XJn7A;A#)owM$o~GYVq0GJm-tXfP*v?i(HY3-S^_nHACN_E458q zwVR$>=UZfo=4`8E*d&JB=vP<_XiUMl-?jEBpW0Qi79~c0vbJi!e54r8_T%lxp)Fr! z$F6txS3I97-&o09VzJiTkyJJKyz;km+tvSZbe(!OrHYAnLD~)Tr|CZu#3@braePWC zVn4>VQ{tQnwE}^nl|osaH2)ld%4FZX5ltyRvtirDpA%!ejBYazqyB}H85H1UcS^`3 zg}dM)RQHcoPePrx=f-%z5gU=8`4WNC!Mw7FkKCd(!~G`0JnzpMu_@a(c%^ zrZ0no0v~R_|K@dDp&v@0VMOdW^fiJihX+p(Z$iu25M6%e*s}A;jZ~LB%Br^ z)KnVH*bsPHW@5Hj?=Q z(X0#G=?Y(l=Or=t;7|dvD1bmPFvI+6s7>{EWLL^2F;57#1z}Q>HCp1>Q!{}%$(x|_ zVq+nW$2V7TO>8oW+trzrvLJdbX}69Jd7X^(g90FyQ5n_#p|1+9vFu6z;hnBW2jED* zoO)YjNgww(iCdw_J|^|=NyY86#D}hUdi*<`jf2Tr2p!vBBqbs}HnDRPjhQ1xJ{?2Z zj{qJBy8(m_EIW`=0*YUSCKDK!Tao%+xD(+`$_IWOt~7`?fhROjByq3Q;Fl*oRtMTg zzUDcENw+eLC`^9_#hh!AQ~sD^RjG(+f$@~D+<}^%orw* zO9B`e*q&-6sIO!>{LN;5@B|L!gT7|OY&egUe}KE@Vp0178?ZOTe6)om$pIjPWbgq^ zk|FmL3V3>qzI;Q%bBHeHh_*Hy{b>M2LjqCZ6c>(zYWag3b~U$|hnOI+^H)o1YAT{- zf*b=4_70bj<>U>$Ko6rpVnb0%{B-L$`zVyw;*)h3s?avJt!yjZe4!yYs^LH#f4C+v z$Ug<=D51}+%7>{%oopoD1y0;an^}A&3f0-em}9vMTY%Ea)-0YsPn*$RNd|>BmX0WO z3?;q~pqRF$o@IJJVR?W6mM-ys1s~&t&C1RPC$V48tcghT&biDIZDgp>O}$=B97 zWTFQ_&QnpYA2qB-AU&gnBOiWYNY3@aeMH+0QFtKUy8T}>Q!s7O&QB7mWuat`yb;t| zgc9@Be{-(e(rrOzMYoOp3bSs1agFBe958d%7P`(`)#o~I+9*>gK(lG}QPFfV($2I* z;m_j-JGF*;nz{qMH;xYs?nebptMa6gX!F@zk9Iq;+@Z46jwDM@s%f-DJLTtFSKQjo^FGG*Voz3PXj7WWdu zI^3_@r=0}!3#J>hQ{97u=2I-`OiP?EimWp1tJj|39PR<$dK~#$;bN_*P{Cp3_eZN- z4n}MTnKQ*bDP!L*9F7&eXA5v-6MpXTON!!L!7zLJr(oPBFjAD7M_FWp=iI_6=F;!v zD_LVq&Mjg0Q-#*~jdK@Rf8}pDn(W?&bq`zDTZ z@Oh7n%^MVcBGIy(GO)<0x@G5Gr9s|7b6mhZ_m!ZkjxMNEAHRf| zUGM-aA+EZd3RZDl?n3bbOSEKEhs>Y1XNu{!hcAzC*{ELey_1;1V|3JKCFGQR{p_)i z@fUYxYxofij9XYwTQ>2~LBt-{j!1~FV1(DPnlY@tO2#6fD~vJ0cKe}YN*7u;CMWLw zQh>Y&6aFYWmb()=E5Kt@^1iL$&1dPii3gT^%&vuSkIiBj&eVf*}en5_t5>p+Rl3N^bqmZv9wji;62j0dyR6F2-pJ4E1GE06Jjl$U2IROx~fC zf0xuQ^5ygAN=tX+YkyYZm)-zPOuAtBG-EmZAjx-dZKGU4eAMG1 zWm6-CIROBjY*iTa4A8s$(Yu+9F%@qAsM65N{ln7IQV8A1C5@-I{pF;UfKd zfNxl@?aD?%2|iz+vO(deUk*ZnM+G!W8CNj2LQUC|)G9(t%geD)SPE>m?qF1f!5!fs z$h-y+#a!;`_Z9d|Kwm-t0usG!ncZaY*77T5ZgY@rd^HQj9pD%N7pED7EKK3`)sh;< z0V|4|31VLtDec8NeDwW+2c-rUf3*@Jf^24=M(D1it*9 z6IdB}c$@f=cvK1(#>>i9t?9wE`qUh+es!TN+v`zb*~Tu?7RC`7*Q&qa33~LJnOwFI zh_Nb&JY=gMoXky5?lNr1jU9A+BRZXED|21)mxI8ik>#QMhct6${(e}W~O?{H#Ty$H* z!1_S$;b6AASV67IRMxO)pzEM0HRE+G9=qCaC6l->*-z1Zo{w&F++oR#d!}i_jMb{- zU}ema-J+?6**vO86{Cw1PM#u&_Ipw}AT^-W^AWdFb31&hYhEdk7`@cR;7EHeN;TMS zDJ>$Hax9%z=;l*at0m-q-O`(FF0V>PpjP76l&?{IHN(OSHSrfm)EZem`NrFxQwPt~ zW|PQwUzUaDX8g{*5i3r8oqgpCtKgS!WG6E<@B2bECMELLi#5P@kIHde-;S~CADV4Wg{IBz=^@r9;`Cs2b zq7KAz8syC~PFcYroO}mZ10>O?7RfaN9sy=c1U82FB|MoUIhePQ7ULd8p(X(6Z6uRq zu`Q&pL*1&r0*dr9o@$R)uJq?TDp2qPa~>{BOBilnvVJ-j4f_7hoPVE1M4)XuX?o5kT$;2g`&T!2Ib{??Cu_ln5V*O#m=BssRG`k#-D8VSC6z z{Axjb@QjtJ@-2hiPm=sQ5H$nuDHPw#Ox`r6_xjBQBr#GGhRCJ2LC!|WaMX&o1%v=5 zfLL(7Ar^5!^|uxn{-yT>r{mG}nAg++HV3Z&!6hJyss$3K5wS1fb9IfoR<}|3|FYS^ z7n5-mn*=%p>V6@BrB0^?2ct>G-4yqq3d0>2DT zj%@9o1;LdJxL%-z)bV`W@t5hvk|}BP1?$S9*d18Y0Ckh#c|?p2dIo*rxPy*YUkO?$qs#G_zl5CVb8{%zJEX$k(*(ar@Y_Iyx0&5bczk#tV3C58 z8Fn_HXas2q;R*%uEc^^eMTI#9)Vl)M%=bj**3-G)6EC9Ar ztZzZl0RI|EID-u=PHG1Yk4A!x0gJ-c-l+Bha$Ob;T5ZZ5FHf}4o7~%akSj#dv)=W6 zvAs-ax6n8I68r53C#NK#i|WrCsU7Ln%M@v*Mkz|;9Q@_2^E>rJH&>K++!Q@Y(Fxcq z>8qUv)XQu?{TB;6hNE6MGu@*1u8YqZH|6S*JyX@sz?Q6_Tqy7u799_#lSD_^vNGfG4(KfdFR;4{6JL?-eyWOnP~6qN zr>N#>plDo@_+sV{6Ry-;uVaIh#L&WzH@smog~o5jcm+t@UoSpzuQKY;Hr$UITi#9< zirtM2Sxvk->8}z>d2TuR&?r1{cPWGvE3gE!kXF!`BZXU7eN8((xynoEn}5&gX!nDn ze?A$mx|Kq9h!wbqb}F*+ z&d+!=Kkd={Tb0Q2rqrV(3TG2NlhR-TR&D)qEA}h1?mhss=-Qfeq?`K{v zgtny#{EOQV%)$Cb$eJDOac_3UBdP*MHpL_P*Nb-OQ;sCDBA>+9D*t{U;YlC@Vp|HP zk@WxkTv(+rrbHi2AIH3B!F9sfzP0|)tb0eA`FQZ&_gc**#huvoVk5rirdP6I)m`qI zNa}YIUsT!=F(b#2g3}sAKXJSWxQxaeKZRss&>IcL3WI?POilP|Dt%9I!e9-jp1~%+ z4lR#aS(X9c;mZZXHz2o=2@)W%PEjcWN?8pxZ#4XPYH4TJS8)ZdnsqfG zF-pWxh<)n6FDw8Z@tvY-0I{2(M?^&FA38F=Y{34BC2z*{*^&#!UC8P? z1=&lyLm~8uRbZhr{=rq}Txaz9B>)c2qsDq|zO~w_7Pn5kkdzf)`v+J5^ z$atn)3s@XLo+bA5yDT6u-QBprX%DRDBN)qvy8uefgZsnk9Ybb+gK7Gs>u;n~)hyq{ zwTbkdxt@L8`bF9Lp;NfWBfRpHoqz5tiign$b|=@c&{kQb>vs+OU!r2%W`&CR3A(e$ zCb%gK9HNOwuElC+PH1&JSWUl${%3Y+@c*;`2D8I{Nrks*&ZYCh3@zFG-|(EdG=JjQ zs1z~maUE1l#ZK(1?^?Pa_3ct{#1qXYN+YiGeiovI$*DA+A3b{Q81YMMwri#+Xi`+K z3|7S!EZc>>7Ec()QpRHAjEj~NXhY{(2+0=er?Hdvnq#orPb8u|Rb@j_LcLYm7vG~u z=$_?9J`42hB=+6=Wp(SY@)Y}9mcc-WP#=*dw_=o__C5aM*XrlD>V`@^S?yn}gjR@+ zPB?K7jD*IF2s+SVMLW;4Kd~E0?eVl!yh3B~W29TQ<7<*{WS(=CanBgNU!(-PO5~e| z7TtmsY?ow25?^TUtgN~fUNw8Dp&nSAa(OF-^px@7k}<1l6v%eD?{~8MJ^(7iHe@%5|LXgq@NZwYjVI1LNz12;?SpHX`8x%+GIk$r+x=YlkLwqxC67DV18tC@ z8L;r#==g!!%{tQsp_MGYZWoNwe1UH*cBOB2vPes@V*l=qCyDl6Q=0cBjc^<)QmYNu z%XmRfcP#29p}2*;It&}b;0sCflF)kWK5uFN?CN$Io$59Bpi3dDy0kX#`Q)Ej9pF8s*B z8?zt|aXcj$uM&jl<2;!%r=6g`0Y)4_vT@Ki{9|v*;FErhUEqK@+FJugE}^Y{z|N5d zXbJspSYtsw2NMZIY#>hMsN|?EeLjZ)=^U_R!6=AmQXuAsBgX?1NH_Qn3Y{dQbUJs~ zPJQ5u59y;FO^^qVg%We0O2>{G5L?8pQCD5a%>Y;q5SKP`Nzkrw0s;w2#Hp}cYDGN2M5VytX#jzvTx za5Q#!KQ4U+Zwn%Nq|q;*=va~Y=ZR$UySOB^1;H_$vm&SiA*ari;{eI~NW*y-bF9tC z_D2tM+#@F(t{^yJ%s|CymiNcKA+k=B$6G{e%&#u4zoIAJ2iA#pDCz}B2At-QUII%_ z`1?XZ#)sZw74f?MkRky_!1i4!Bvl^as7-wL?>0go$bWfN0Fj$X(F?O&{S12)Vg%mx zfVBeQ?ch~__8+Y16?JtPDC?bQPXZ7XmvlX$Jm9sSAp&(l~Lnu$hahHSj zDeT+yg+oiugRGn#^?u93xoz*un=j8E0v`?BVTZjN zEdB#W!zuetrO=tklwe>Rym}y8GORy>OBv|bj%UrAzMCCz+rsor#hDI)WgvP&^vmBK zUj@$_CV<@ktrzg5;Msrz7+SlKC}ohys7UXS_<(XVC#>Fws9&sQ+pW#x-F&EkiFhGS z&*FR@wm+2ynL$o<f(rz@N4gFP~TBpsXPd%9{ zuGp|;(c-UF!_tx|nYYDLj!afF0+BFGS`y)u&YnTh;!mGb%i~`WOXyj!TwRw~#~O8w za`^F75ucv1MUL+_#`OAMeI2x04dsWVCQm8Pj9bU!DhXT9lcl6RBh}ja??Z3bOy73=K^<9_lTVRr;hn*=nrb`fqKms< zJLSA%?LIYqRQ2)ej@h2xL#mMzVYkeJn(k?}rR>E;Co7?WRF3J2jVpter0FSJbX5sz z;Up8c>PX1;Z^Y7?|2v>nZBk5sn-C;XV`1g?a!hKL3Xkzo?cL1cC;g&_rNeH+?qhuP zV!XajPQH?jQsz$Lpd&X-q((1`xmELzn642^vCoh#>1qxBxq6`&DS@ZRW7IF_(R^iB zl6yLw@|D)g70vz2zee<>zU<9Bqy3bDZ#1zKN;2X0%f_OnN??=KrfQ48SH|n7V!%#% z29F6Ro2)OoWb~`9EhUEqmbXhkBbwo}NmybwS*MxK6C4lneew z2gymMuPg0!l}~f!WaoIOz;VvS-J^}!FBwb3`%g@DDnOFmH(8(T8!$uF5i2?{&t2Ld0NovQgA?O~CbQ}U*yHVEt*Xwz?mnY1 zcdPV9xUsA81X@kmp|C0f2Z}cGA>Eo%saOny((V-KT%=iQT>Qkg^uN+_tzkpYoSqU} zefoXmsuCABBTgF6TuVDpx7MW+BKRmbO)y0fBV4KQ87y1?79)aoB$^Kl%yL|zaejOG zN1$Y|4^Y{V=9rR?Lu9u#B)HuGQp)QV6a+;sf3$URtG3l_vla7t`^e`6GHo`Rs!ssUwo zL_mrup$;)r-B?DKF&Zi>F&MF@!2t)SKJLFellLz3HUK>iND*QPK(%{bZ!1!{gfYeW z^7<+O6UeiaI+_bUnx1G5g9t*Y( z#*|^h;7SPLMFOZi*u{&I}l`t@M+k)^vgHd%k|IuIS(JOt_WYUs&MAouGG)r zEcRT)Y?yo! z&y+LVx7*!GckMCl1KMbYWlk|7NiXT0=Imxzb5N$o{*F?sDULpGw;8cl`&}NQg?k#c zM^0*(WMg^eSoN9eR4+5ll@4<+WhDJ5kBVTvpx!zwLG{V3FsJ3wlEOlg>_e{5uwe_f z6Rkfl=UYo&_Pp3@KWLQFm5Z!oWbE0-nY2{C#fqU5ss6U_wc|!d-wXSJJM*`x8s=jx zT{*lzu2dN^31}*_`D$1kY2c+u-qWk^B>$`&FZG;bhFrnR_IA)wHD#35c~!FOC(Q@^ z?-uGsbu;#^?HJa_6z9KJy-BRSd?_PVJdMFSb7I*r@>$ACeF&AI`>nd^e96&}i$c>& z1qY0$)Xy@AjX4w_lAR`eVO9HlOqEPXBWosjiTR3xwleP+)2E1Gt5=JAjlzEwRLTaK zG&a9pO3O`C@|%42>XrPQ;j4}swOILBxI&|xI$)VX_`j#o-e;C|yQc2eKUusMDBX{MZ6$$P9q#>znDnG zN6Pe)JH;SY{|mGO6dE%2qKO}Y z#~u>Ls2o5*0hl)oRGFXO47+3Yqvqm+?!e##Jdil+vY9}@f;jDtqZB<1l+^pz3xVbG ztjv{_a}|OV0yxHVbcrfoK;nZyI((U)eJX>18juXay+N}<4>?2=YjDSa^gIZoKd-_J zNHZOE!JFD3H53>Ht5fy(Am*68XkIeXNCa>y;>v+A|2e=s0DK4JCKzOjko7|t4oAll zapss92&8F+V$(kWG#bpRCNpvq(#ZgWaG?x+&VoxbRSWRziUw#GmoVLmVoLk^e8&pu|g2BGy87-_p(4%Dr&@QMqkt=Q{ zxzR39#})i*3Z@9S2B76^*q|*!Id@oeD)PrHHZD`%0w62uUFPP2Ul~-F z--8|!)dkxK8208`C+3rW#@^v1hf=BvcmSjV7leJ#+2wz+;=hFiNgzE^0yl47f$Sj& z>VQ22@`8|zJ}{a=5)U9`y*3|^OeOfuLdsj^r%w@x>I0dE;SK_f121$VgB-n#omRtZE)ox0L&u%g_j%nVSAMwK;0@OTthPF~h2|?;~}? z;7`O*uVQ_{qWU_F`H}c-?dRH?#!n^^GY*;7UPebmm;Al2N*L~jd+RP0)mkJON7cNK zXDkrJ6jAuf0Po>fBwHsnVvIDigrDNHqCUVW53-j7pWotyIpFq&^(!CZ7NHLL`_-tf zh?NF$byiZaC_+52!O2~|wC#(-76yoyMM||uBeA7VhU4a&HhuY#0N`DEU)t7b8YR#> z90XXnyHkL6^N+N&8`Ppt#w_6zclZq;EPd|6k{>Vxn1@9I`7R(R*k;lj zVP)n8(T32~0uA@Zx2xe@2Yqh+=C5#uZU{w}V0DI851|Z2AQ%?nWMV;5`zXf~>4t&_ z#fX5YB?wnihOT5F-64wW>o|ydk({b4165nd^KRZ;nDE<}fU>f`Hr(BNq6PV_R`y4C zNA!iLla;D9#)vd*m8@7^@8$E2BxAf)7Rs)5xkz;T( zSb*F$A%pyFpr3%qJDq~N`w#7tB)|SLY$@$9p?+k5Tl;$suj$gUJT5nj?(-`wV$CUxr)yIN{bZb zLRe^}b1wcs8derx`~ulbvHb^lF*tZ{Fbj%$Ysyh*>uh0c?A6aIvRA`g&{RA{)J1pq zl*GFi=#)w3I7Cu!hu>!wXwM>?oF{DPtiUJG=^|0H_OZc>b}3o);nMwlt?mU?(YT+u zOvf{MN@u!oc>)(&0je8ZhryDRbdHmr8TWern-9re1%t38OuJG_11z7iZ{dgM_({i^|4e? zm3kJNT1{f1-%{)iQ7`ZRwid^iv)BuI`NiADvR7rG%Iu*iZBLl>6#kzoI+~hWm>SFB zzE@1|6guU}Z5j^+Ut7!IL1lY3U#otElhY?P`^bqlJ8x8?UYmYE_MBbd{@8UC#whs@ zE-GcW*6hCC!r-#~#$T3)lfoGqmI71h-6C(qf{uJ9CmQv-gNhuXd4NV!SEmYRfVBJk zk;W!|KZw)GFB7-VN3iUj?HcrkocVAT#n@@|u-y-9Z}Gl9G`zC!ZLnX-IqBV=g!fTq zVc)sIb*R+}I~4zkFIj& z3|R>%K_?&)-x$%(3nj}UiCg00vheWiNrFK;=siVCrcF6)GeB2V*^~Mwe-nt#%Y4*k zB+U2+=zAbF3T`@};UJS1@DQhi_4{zAA>fUi!5GDMXxVdjcgXgG7Fdvhe)|uHt{0JM!oQdfbp-@@h4z(x>Or z;cS}hNwCUvz;*%v3h0kOP7eqO>?Ph}Nowf4fX0X(><0yIYC?*~#uG8UzEG#$@MHO- zrer_)A02kG-k3(=5kt;(V|cMmCM_%htLGXu4h#7V=bXqhK?IjSHvPn4z5uRyaE&eH zzbp&{Rew_6gga0*Il~-El=JeXm9{QGF!0akKdPE(VCt>@WQt=Ri4!7GO>!LrQ9CN6 zRhW6l7B8TQq2CS76tBS!>LsQSGh!B0SJKr$d`R3XSHPSEZ4m^iBUd_Px&!jQ;rG{~t*N0?id8z*vhK-LCTSy8AL^VOh9m0qp%Avp4OB?cAy|A~MCKU6iG>0%j zI&iG~OL@sRyk8e>n!R(}h`Bei^t&^Xtnm?XMXXhN_q*V(fPibP?@w+q?)?#`#5a_= zK}|r|p=PqeNp1&%BqaY4$>|Fp04eF(M7brDGlEggg2)z_0bpuCL<=$^=t-JA{_=ba zNnM48_nt>*>GbHtHmg7k1I{q_gGGy)x6XCHu6-nAVm`E*ON)QYf^KDC8LE%DaUsel{?X{F{p$_7fjAbnXgl7M(AW+4%xQLAm?*zW@A z3yD7;X_hgE-^BIQmlaKHGF6U7D|q@AhjibgGb$8foEKKb>(kY1uclR6e2{SMz8Ep3 z9B$dxCq=_7;%TSQeyqCk{zu|`=MOM??Sf;1s%@i(J=2=PsoJcZa~GD4-fwcQj>hSD z(2LxUDpNkM`0T3b|CmJt_eO&qZF8l2Q^(HBa3SVs>y#Y3UFJ>8f?#ILs}W<4%ogT8 z@xzS4o2zRJ;`I+HrwYC2l2jP@*;MQ?J7|<|QQhaq{q#ECrmOlHajV+YTF8T_ME1Sa zIiKM_3iQ1%?a6RelEb*U{yBi8m)9cjG)a>@7g$-en&E$Ny`2E zu2xZ9;(pax+-8;}ufA{h{`HCNAJ-Czi}#84h3hJqx6(I5Ctgxue(wFC_=)7mJj1*x zsWZ#9sh zv~Sd$NXM%eZRZi4$Jrh~XN+mHvZNkO|0%vB=!6GdGGM$pb1v^QaFz))Yu{kUcD|W- zICNTEZt1nl>EZbUia6<%8!k7MH&Y3j>mE6-)`gh_#j_kn+iBF^=1yOaaa{ZSX6sD% zbia3P`C>Zw@1y!h&x+x=I=bm8EXkK}FGJTAyoklcTno2^s_E}uETx$uFe)71%-v6S zygoo;9EwHG$~hare2BSA@CJ>93TYid-47U^Xh%VbF^rX^u^4G*VG$&E9Y%HdLV!#N z#hiB&tfe#q*367k2xZ%93%D~zK##In2n@d#0+fmYC^)8LhOkSRI;4pMFd$O^&aV$s zkS5&R`2>4r~bd~{KKM;7$opNWIsY7zx5%k~+98c}-=KzNCn2+SJI5yxU|D-kF zL@Rm~g=pvix;kUrks<=cA^uU71JcQjfx>kF4i%L*!G#$BcH@I|7kJgqb%Qx?RKIX4 zuENWOqxzFCrd?l735>|FooKxjZ`)OvQ)Y}ey?mErULsy zgGUA=?hquz>8WP0dn~1uBL#)JNS-tZcc3;7rq=}*sAxnwT1(2yErH|xx2OHDGfyOx z7;z#^$OU9Vh5}RCKqXI(lxJd7Ca|CY=({|c5k<~mKviG|03^!Z-d?f$1_*VaXte9} z+VI7N^iZxAwzOaZ{+u@=F3)bVNr0GG`q!oj~n-#0g+jDsS(ZkcOT~ z@ntlIc9UQ?n~mpKtYoDU>1}iLT@sf$?yw12S=R--0!f=G8)njpZ#&k{A>fQ zvH(y)(;*caNm)gdOn?}|?gfYY`mfl7b!5N?x&bi)Bl>;FJ4Cets^vKp51#O*;6Ag5 z6Qw~fer<{NrfCjK2kM7C_mK$4o{#5?o9aziRXOm|_hw(H50e=Fw}?f*R1tp50>5RK ziP#ux?n&Lof>0-lP-m0bBAKr5<;@J@;g=m3~5mEbgF}3o1inB`JGuEyz%Yrx(ukpsRzE)e=|EPWM zdDY}CmW+*r?~ic1%b#>E`klq=FX?TZ{2|o)R?fbjcn9N9d95brRi2t!>=?74Gkc$Z zJddYxqLK`coz&K0N^>7$*YB^c2I%vg_QnO(fgcR7!WQmYcN1;yIGB9!Gt}B4x|&g? zDieBPT+d)0mdUZMP;eNpuOa?i*;A00;bZH@@2d-1;;(J7TLmP<##>&N;oI|Qcrd#538~!erM>g4oK@EhO9$Drk#VA-o2FEfZamBxG~ZUe^ET*3 zysk^U4myX~yB1F=S0}Ji@Bw>L59>_LEW6a@112WS(=vS4q^6S4J$K5{^uMX~KR_&o zdo!rQ;r5Q#o^p~|NgN z(5nHgZ+USF{P~9uoB1cqANS~o$*LmEBWUWk;{F}Q_0zbmKlSYlJkWJfZcJDkJAF1L z&Z$l7s7mqn=}CcW#t``fXA28?jN#wTtRbx+3IQ&U%9U&)e4#%NKfCa3^rvITGsw`KhCnm8e7aWJO=Do)SLYzH9>+!>H{1b+bP6WKX7rawlU z^_``RYFZ}kuDS5-4kh#R#mEQJEA7z2`vWPbpd68QniG6&C3LCh*;bnWaT;=qY;pMS za3F9pH16C35F3zdcx&fBPMBa34^AL)K#;YGB!l92YZl%)+AETYL83pq0iAY1wM{># z4VN?NVH!31b6Cvq%o@z8@E6FOVt#H0pu|6clOGB=hdEYVGXu>*-$OISpZJ^+-IA%w zdUWF6qs~OLzm*}6MiS|OAQ+A6Vg^{ij{tlLo$%6vS3m{`YYJnCnRd=%<#y?7pjdNw zH5E~RAwmxV@_sgu!953;FUTy_d)GgCF@P2mfz)}f0pb9tk&Trp)i;&nsb7%9iNO15 zg}y8q8lX;se$u4fB(VX&KOl)<0dPAcZ5nDNc86sASp}Rmi0IFU{+;_@8IN@p&-1v< z^pJ<S@rLW)vlLG;3Y-P?cwfqk?@U=-dBv5_B5_7( zgHm>CnXZ|cZ$3A@&JC6He^&4=AnziQ%ld2AyBB+fCmun}cU})rZ`>G`nl|dCGK(iG zEs^fkd3yJ!id?7Q0s}X_>Gem6k&K#{k+y5vBdqey#r_>DG{z7OlI5?JGM z`@HJ2pCX;HcWc$7PLs;&jpLRSZq6e&m%B;%CprC(uaA7?FTPvI=N9ry;O?vUC0NG| zxRS}I6gGD~DeB6%6>*BxpY)D3i&}i)h|}I|$@5R}OmK@=D^mV5jM9ChtvMT+S8{(u znlS|3bVK!&Whu`)5My$Avt~mUKc>CC3X`SQ8gG{O`c{?oOq(RRLOE;4lZe)v_qK$J z0#tm`rUOy9SZV%Q!;W=~p9yjxa#vRT_&I%e1i3jm!H#UIDr?Y(l#mVwHquM1WL)Ak zSYEh9L!ChqB$Q!ZB$zpCc@vwKUx`etcEd?Xeix3-;fP%;TWP1m|H`lzKG%rBb8{}V zg2zLl!o?+5QJEov-Y1zH zx3s@rQ2t%Y`yTdl1hqqHL2&okTtcZK&m4dAQOoO{W5R+>pVOJ6&$DNgD9#g3Y+3qa zMJLv-b7>6yIKH;yrV9=6H-bO>$$j0gL`YpTe;f6azO`5^_4ib2qav1 zMtnp}m@5DznjM{)T_65nTYlpr(=6NFac?#KFVTpDk|X=-Bg~UJrra3H^#{l#FETRp zv0EhZFXtdzC^?I@qWO|*W^S&`NCyQmWsSp(a?9*Wh4bNy-s^b7@Ks0nIHM-7ebrWQ zAVw2R+_-g%4kJUC^7al2F;=PwI6^U~zH z)X|2Z<*V6})Ns;8goUvNs$eb_kdWxhxd+}LEN-ZGOgBXm=fG(0jlb&)8t9Z+L!byi z-3?r?r{{dF6jTuohZPVGw34y%0VC%~N6N#mXS#I2a#-71SYX1G3C2sXuY!|5Jtrq@^A!HB z48m)~HvmG&^Frc;J@@c+UYIDE5>z3(t>R_;VG)#({<;NA!w)`K34wQDIfa_)K!+K4Q%dmcj1Nu`o&y+H z=TGh65O~G&INy+G=V!Wl;U_3+%`0Ka?!7{VVXx*-rt1xCEJ9MO?3Sc~gSG1zwy6KW zc%*&Mb(J(=&Zz+SCG<4R-;h!lg%I>5A>Vwj!!Nw+?^FQ?;BkgU97$>gqju1~#KXfw zd)z4RZDOSAkXZ`?c|w*t*h9di3=xRZ9KfkeLpBlukavZTvH z0e@#1qJz&1V&FwyS+V|{Cq3BaApP}NVgvlM@F`S*w7$hfR_UFDIHzo&rNljVSp62n z{IG!N{@$YPx06It{>sv8Yc*^3=-wV)hd>&sVQ^WbhM7>8IM2MyzH@zw40c&>x6&no z*Z*`K?wBlzy^1IZu_XTU@uEod38i+y9S7C38;`A0m3=0u>`+T;2FSDsC&Mbu23Z<;p-K4ZGssuD)#U?8mttAqj3g zD=BhTB7{*^ntfOf8~ssI{mro$<1(hfNDcE&pa|tLWbvY- z%8W4LHZw(SZE8sL`FxYBTRz*NrR3;)W$JqsZDp^ZwfAvbsjYPROW^VKS5>;I=a=@w z$4z}}w>kvht;v5W{B!@lW5~&u?=1_7B-m_8Whq9#{GLcL~Z{D(iDJKz>h>$S5LZ+sjYlklGu zmtL~Q-PgKOrhuX=AAJ@4{n|1U%JHbN&5XY|uA_+G?gAUDkB2F=+BM9aFSIMnVTQ0w z;UIiYGPf*zj_2fuI{$1tkyK*+gY?@+a_P5c55vz7s3=wVrRwNI>#EIWI=*IK5K}H5 ze}6PU9Xq=#vB$qJ!^wh$AJp`dx<9_Wl)$$|KjN7FOL&Ql?<_zV?cvgAaxTZuDRIpC zS_UWDKRw+{jV&I)XIvAES@kQ>$yK$BD9f(oS!;aZf4t~7pK?Y^643378;9e4IS_YA zf+&}F?9qYX+bucP^TEB+ji~PoON8C1Zuqa!UTbMv#z~u4schus83}3RnQmv6g@K{Z5lD`X)+?VdpQ)MWDu!6m zNwImEz&@DE-+!BbMr;-yJugd{Q!=~h^0w`NC_5f0#AY`A>}6^M@O&2%{RNI*$RGE; zy#V9{$uScPRb+kr>|tsbBN7pRTn@PfJ@nrAfHMH1vz}K7Zr)p~t`9KC@6ce!!!>6m zkhys}m<3^v16BXaT%e4XU2T(7bNUBXOY4{Pl5{-)d>hCj+&cvN|A&w-zt*uP*Sbs3 zKpaBGmb3PX^0KkINtu;|-Ny$~Ma~SiTF_+-CplpIlG$3=W2(E!>V;sd6a?G^z!1PP zP;=X#AvfQ}g$zLhLa$u=&($>Rn!J+GEpqEtj1eE+K$XXjk%uoKS6`Kt6!Hqp?~ir- zfeYmC6XpbH=Y|IBM<%F1=0bsdkdv;uQs=BF9m%?_tyNE~F=c2t=iV;7(@B#`$jTzX z6nG1+7$*;p-t+ni)bwefsumK=Z+iaCw2LK9DhTvma4QjZJme&YCE@EY*sBJ_Lyt?o zJqC8?w|fJ;OHwr)W%&_%+nn0^^%q}Oc6sheuG+z&jbv;(=|OWhyhBzAt_y&3Vb!VP zdFOzzG#tEN5I@$`)HHLMAVaI@S3Mt)&E*(m-`3n9kQV-eaBXGTe1?myaPt{a&|NWX zOR}76p60H2BF8DuzUKv zpz#piR3F%G6~K}F$_YNmP;-ZfkQvT@s~nxr{yVn}m7^OCRvPl(rGZ(+UN)YH6(#gk zO<9ViGbp<4akF7SxX%$gCqHUcxRK+ZS}XgMhoc(TxpMoIb~$ECKd~r6 zg}cePX~-D}mLQZAIp#pv#7oTsW^5eWH$*}Q*S68p;jQuU{z4vc|3q>)&4fH-GN?xf zeztMRTRn}#Va*qkYzfVi_T($9u6VYgle`yMZE_=7=AQOSk@BQj%`t(qH<7N33eHgvD47C_J;dpC3)%`)9eGG7(_ZfY~bfc=buisJrfs zxV)08!>sAu{ToHDB6s2*=;J2#wK6MWi;(lX$oOpNeY-sp@H?v@x6Y>HV|+$Y?X}g0 zzvoxtF|3~LxQt?N_{>qN;YAzUoaA zYb1eiQ2j#<^p(F4D~UitXC zLZMHzF~ff1bsr1H*oh3+Z&{9ZJJa4d(zwArEeajj*gnd{4%hDJYOFf>_x zn7Uauu`6XM&X1|l=kUie_vK5G@eEbg$s|AuqA^LQXJ&#OX25Fyoly6GLIjX0)UGH( z@kh267P{TNzHH#v`?s-MUzu3{9D)b|>QC(dA5B*Ql-0s*5s;D&=}rYHY3T+@6%^?b zDQW4FH0YL=5|otg5a9zQRY0Vqq>*mkKKGwDbH~ddew^H~_S$Rpe)ymK85YYG^LmtS zqE->;wZN=&Vp1Q>z<5(I(6HiTJrf_77A8V@jD|j_UloxBrF@2@H|hWM^%0sPGy-Ut zSxfLgs;}}vK`=ChN)Z7~5>Wg>>}eVZ`3BfRFu_1H%EqA3;^{|7LQopVOu**+<(1&& z)c=VykJm;)Q3#7ifSG5Axu65j6zX&|(7Cz-01Xt$&a@CEDtN9T7&F$RcpF+K%o5~i z&=5G7ov#KuqWZ5e1?{ze2wV#wVhk{IIZl4r+Y>?%c5FJCWu)=0gV`R7XE$I z53L9}KV&rx4h+y9u$}K1eOgbtL40?twe^e!XTg3a4K^O$9G(ZD~?D@moB8yQqc<2(gU{ttwkG_IZk^ zE2uwQeO=gF`b(kGaE%C~-g_=M+W1>^C9tHxVz7p@HS z5@QUK@TUCb(zO4+{7mtLh2md9YxtrS6Iw8Fr^TzXdV(x&Ssv51Ph}x2*8aus`6%_g zrPUeyycOqu=~$`Ki}YvVAL%ZlsT)9>-JNWH^%ZY3<)8kY1#YAI(vp~e^41QcEJ8QK z8avQr1#3SXbc}7O`FxF87^_;zYt3Y)u24Mj5A$1j-Ky$smkyK#jg=Jp2g(Km zACdd+2|}D%j9%aIE+lVQS#8HhbBD#cOHr1IQWX*f-`_N&igr0#KA0ms>8h6gJ=Y&o zwx;flwH?lf<(<_(gX=)y|7@>o8J$F$8RyvC{3t_lu$-R??ZNbF1|g-*!bI00MZ<#; zR&LqJE-yx$WqUDVf?4eO#C}7adYPlg9}@2ew7#Bh@t=zx-mWV>nxQ85|AMoy{tYd@ zq0HuKpoV2*wp#K-^bg^>Je!m;N|uecN%g5DCh5c74kS%6ezE-KF8*DCADrjUNaDMe z`o*2EcZ{LElaeAV-ln-U8l^FRzS5C9yO=+;R?R0Bg0pgbGL4p@B$DpmQ=9}PDnh#h zob|AVGf6ZZWDF}B8%y$s6^Mz^8bRNKbrH}M2(zCRMrqZcyaMpGurgav3SM+XfmY^n zS7s)GvCw7XH&Hdvrh!**o661A)iwVi3lmy`ql3enkB2DE?9h2J2nWa%4+^decnPm> z`HVFoim+hife6L|N-!(PAsu%HoigIlGIMcI2c0iyAi(kXsI-?rNOhMe^*Zdc609^E z6b%9M5=a0L%YX|hEl4*v8Mnvy8J3^g&L`WV+KyhgwIfhAOdAp0_-Gdnl(oecml8_IY9IZw(}Zyoftw2FYQ?#l?{} zchHGz9^XRXl3i~?PPJK3l3j5xI$1?@)d6*B{TJm#$L;qQLN(y!0KG_#Owytu!kkDX zbowB}sg)7wRnWia3SkXzT#Lg$#!E*HCm8Bd$Q}Q0j^o*OYW%Ylu87&}FPK!gZ2S@i z1RrrJNVc9M%Ra&cKq3s0$WKj8ZAU6~V3r?0%Gnl>dbAgKHaKI`{t=(eQk$%*yLWH0 zi)b{=VhFF}>8r~A7;?O*4SvSfw}D5*+niV@3mAoWTp3wsUz=Y<3TP?zaLnZGs6YPv zsElJ&A71m4$zlnUY z=uuheIC6}w!9K{(a63P$p>bG4=4L zo+i9gUS=~fuctWb!cai3d0kA?uHPy$nN6-#eMf{057R2Shcu!i{^Ip0_k(m@)4OXd z@9stn4!N4zX5;=e!=Xd(JQj}Q!T1`J+U&}(+k6stt~HkVAg=st8DrA5(Sq8x6*H5@ z*!7}UWzp`cGuq0UW$%dg&PaR7BZu!K%1y>pOAS4IhC`*q8vkz1iOTASO)Gc1;D$-) z`71eB#karTH|w)e@1gq1JAFxbyQTS##EPpuMiNO!Z=_H$7$RlnTGYrdq|Tm0a3hjA3whHtr!Go|`y6CDdcF zsvMy0%F`e2XrRglRPOjL%EhN!#6gTSB%wJeH*a}i5VZslQ*^mWd9}s_l*5v9|FEFs zVAyg474hrc1UFIe^cUgcG*R=r2430=$H`>;GX|`X_B%(H=a*-E2~4f? zfA7p(h)5q)#t3kA9({FBA#YkfuCi(3_gke3y z;t={USYmj_vZO}~@6MC1-A$gGKOt25y}A=cJDU0+{*dSRGX^LC=9xECMrXc{*zg_|Cs#ew=e%nPZ81fZgT z$rHTI0QN#bGL_`Xgtx^7-KYhh2Ffb_7?8$Tts;uncuv+;%3<9xSu`;8ck|tlE_@rN&N1FcW5(Ndrun%gfOj#QdO*()mvuQ z-;}x^qyZT9W0yJcHq@G5`eJ}gi?bLCA*Mi633zi?gl=jjppHnD37B(WV77uiSZ}lZ zXH5>qh`CVzfl(s_KWJK^GV4D)^?#I%jL_VUz&P7k>$;fQFWq z1<>h$t_Gkvj5nd?LgFrHy^do%0`3El9E%^^TN*y}2Rs|9Qy2;6{;<1YmI8?m2Bb{e z&5F!-ZuMJiNdiOxJ81AHVENE<|8~OjSD!xn+pcb+z{bcn$i_+D_{`Q87ol%JEp3SP z)Hm<_Bc4BX0c&;6Fcd&Es@lQI1%P$LA8ig%iASub5a0FB4_kLAp!h$i{SHh`*mr^n z!mcC`Bn4({H7|NVKP%3kDdw@~TCoFchgy39O9VO`sB>r8c6gN->bcezp|gm1;bBY( z85gkYb@uqBO!?n$5xO5#y^!TVd}mN{7XkNSMWF8l7?p1CH3GeQdA91ouE~-%_5oPsekdQ-gqoeLF@TLHRSr5KHodCMeAh#9~RY;sV z^-L7ds>RZ=wMx-ycxDicOO}87Uh!uJ;#>XlFc;$g44@D^-k^vE_Yj^mwC`oo|IY=8 zkvgDSYlK$^mJ!YtIAuB*&xaYKz%T-1#c(h%q04B8S(-kz(wg=O58n4ZoLP0M5&WO_ z)M6IWcN04Vu0&OFs$3y|>?kpN@cyjNa|(?<@W>Y3I?Z8IQp`~&fGs=ObR}0v&EZkf z?yGSb-W%T%&SI7X{MK}zjeS><@zKWc3cYnh&m~Y(R&ZYKQ&4WXPXXy@vG=)X_*XQF z5#lk+C?e*|nq1jSQyj8Ee1-d0WBOP9Uow#46l~}^<)WCPyb|$P?Ah=>zcy@IJ^4BM zJ-||ICed`cri|69^+dgqWssy>;A^@5?Y9;|w;pd5T&SPN2xo+PFKU+ze%8jif1^3~ zd1CaJzrs@r$*m@e)o%tK*68Sb@p@#<(dtHPmg2mk9z^4qMd2NrQWfjN8^g{L(yBlH zaqe?Pc3hc?E0&wWD9d1xZg{l^Im33isHMh^(7U-Gkx|3$)Vc}3xXAYlxtOd2Bk@(4 z`iRMHoJNax{VN&Sw-l195~bQzxos~ z|7RKA`_Oo8dPd)9Hr8E!Mr!9b%5+(W%rX&kw{AShx1Mx%z^=8%W)knm3v%olN~w-d z+%{|-v_;2sz1C$E|1aGE!wTonKPK35!Q)$%d{FupwmJ6|nZMam_<<`|&2Rhj&A!Ah zye3&6cA82jcz;O&GnV-Zo>CBx=(QIy&L$+v>^c5@hvzP-cV8mRv$nuZaYF2yqb=y3 zy={C7?Mhx*){_UsIZwN#RibS*4#`k_GpIqMg|JudLyxlZtVXb%uEu^nvv{#mmvUl} z@RBEYz_)%&_TN(xn5xpgDx;2H{%g?r=;#Z1EIvbmwdEUD-&3;S6uqs~oog(I(d+WL z+cp5tk~pz|xdZMBI~nzmN7r+@eV>-N@ISDX5x#qe-KR^f5V*L{>aH4Gz~BG=Wn6yA8{Y&)A#<(?YjS9gYU91S@#B(N|yHwrDE5Hd&k2 zmX8C?DKwY>dCKdcUm0&d^v|oK%S1#Ne>(|U-EX_`IXQzcs6*YAN(O!JFT>ZrLm{&I z-rorK>AJjuo>B$XnO2nJ`sI0Wf$a8jht z)QY&m3tb9AGTaScumPC*rQ(aO3#1Q0W`RI(127jE)R`|kOu~##6yzL2Y=B4ZFsYoY zV>UYu175(tp=*HD2~12@lQzJ@VbKf#oPJM<%qK(4{}c#S3_-PiW~Uh?p=+W5lU2ys zS3hAIpEm*P2QY~*APfvTcH02Y{6Q=^wF6H^ zRWAbCoPOsSBgA{%gDe;q8-b{h>aP|i0~>lJ!7Ui8_bu*JW(8W=iKO$`xGff#ey2f{DrBTRu$N z51xab8xRF35S`?Re`oVD7xMzC>-4G!#0{NepZRnp5raiLr$np#yYS)2f6`0D zgE&703u9!PdS}B(yl_^tp9zV+eWFsy_hnp@K60=7QA_M=s!8Hso)@=l&oohmtE`P5 zmvIOtZeni!jkgnSykT6StB)0**7B2@ipIvVFvJpN`R1!r_M4$reJ+dTs1Ql~OU91g zdfVGtdEtCR1iNoh2AWYp1n)9w!stiIqGSbUbRyJDB1Fmk?A}BR__8OI>s^UP?_c=W zPxopS&%1S=$$~^&*GK4&y2RI)>;!DZAV|(ra}V{|)grooF1EsauH-+msl+{U z^4|7m?lKi?Dy|*LkJ|>RJu&&Jz8DX4`;sb0ByUr22)=~kV;Fm5xwQP_G{-Ctc z&cWj8I{i1=a5RE;K(_^F+#+UgKfIbi(DRo-!5g>#h2w<6kkR*f@?cbRoLSZOSJu8y z&gH}vf0X3069}Y&NNrjKQZ;hXG!CqJMDKLP{(rNzKclhPRMneK6 zND@9vFXPs7jyj9Km->9mJy_|BW~Q#GdmXNv;iuc_<`95@kO8q2YRdI*Z;sdp|A7WAL@TJVsdYeb zHxw8+fNTIzFLI%+sX1qFdP;-PK9Z6sKz101xdNy+&+q&9D-ypW!f9?qYlqkZsR8y5Aq+#%fL?`PSokW;Gog$J=7mWONRk7#Zvwaq z=zagU%KEJx{SPyW=F0UeTsgPU@CTS;If#Qk0$kLu1}Hed;UKKmb7)%zy6@;?9@N#( zVFe1(Q}e+u`}MHsc9FcuB?m|gi1-c02$bbn{s#un#ypGx#}|tZf$dZ12;gf%y)={+ zOdca)<_Qggpefl)%pf%W6s;lyWorq~O**(DP}0Vu@<)~t!;5k_J}W_#pcME(nosw3 z-ES~js=~Cx2m%|Z+|iX;2*Y1IE^~&!&Nu>W=VuLPPOh7P5Bb^D%sD+UCaJ~L*SrD( zviga|3QWr9kxfg8e2DfKEEXfmh%(10ZK_!>qqi`#7D=}rwBUGGXZNx}LeS;Ue7XLF%3k1csz%~W?z4XIhaB5hm zu@_kFv&v-qK2kt2IpDpD+0OlIS2bH_GXHQ-D)=w53I$JD0MKygu5l%)vH>q1hiUvi zaySh3+U$U{5z8wEed7ok%S1y#Mp@gfKTwOnFr#PR9aR*Jl}_pJ-XTNlzZsnO(#q_P z_tk>BF114wP<4~7=-C8$$)txSSBTMsak=WjJQD6Os4@Ic0{NZ(2bVjLs^A%hwPbkU zksb?F`{5Qt_J?!=%?i{QpxyaM>&xB%>v^fpc~q@sf<S*wEPJ1IuTDGMGr#JW%XSp`2DGl zb>Zm{n+L7zgS_LjH2s^Ab7>=*KV9#)$=`2ayO}#>5U*ztEllp|s_g^AL;N5}Wx(zh0s-Y|i=d-qlfzOr~<&bd2kNXUlnrzMk*naUb` zm0l zHv%C;hx{vUd(TABOJC?HJ{T(GD<(0B`Ha7g^J=Z5*MKCxRq6@#d<$!l$$RfV2Rzy;ZTySc-fBrTWE1j<@_De>A~G!U(QWjI{cLJ`@Wq|tLS3N1L6EI;TOu^C9t>! zhR-l_uswKZp6a9!cf8J75Xc(vg8AfW=F?Klpo#6nYnkl*Srk2c&vWnmi&qZ!#hao- z$5RW8zCvr+ct|cq8M{xsOcU~{$14Bd^j;203qFf4+imaqHcn)j{)B@_&q)O2y}-53 zGM_UIHare2+>IU^8NK<|2J|iDeMdA{pEb1!cDJ}_GHmG&efd=c~24FqF<-=uqBv$JPS^?J)>sssvM4${IG9nB35Csgq zK^m+OERZMI^QR9X`XQsbpQVOzE^l|%c4<>=$W74@shNl6CQ|o!_w3)M?=BC{H_e>$ z_TCvqRD}_GII!P<=ApYJS;n{JJ?M+Lz`{y+iir;{$h1j{7FPas6|(#4lLgo{2(mzK zfC^6dUU;)v++j9^O+CbSNO)cMi_6eJkC4+}n( z_B&!5tC9#6Ruds-LY@2SR$yXu8~r<-in28Zd&eumhwTXB->{t3RC+897ZMnIra4Bu z|1C2i5Xd38QK)ADjRVnQiL3ffIaw=i#Gwm&S}?TR+}!+!{VXT%=tgKe%p71+sk~(R z=u!LX>Zdb(2E6E&hm80lbfwc%*2IrF^hmBzTNh`UX+8=^* zoEUr|u0akT5)tw)f!mR?27LFX0=`Pzrm zC-<8G2C!hzP$lM!^Kk*z3w*>6(U7sksT?g3#WcgY&f!Uq8`z#S!GPi zNn?s!O>w2|DOO6OeCjfb(kKtRvAD(>tRx>r#nIqp-MQDbTm*kQ&*Bb(D{kyM#pgu^ zn?6qOGy1#{_SS@c>L2r(<-rY2#fX{tQ*Fxw;VkM0napxnqep!w@oOCP>XH^W=H~39 zPIod=mwO&wzFtTf%f?54l{mC(f5@_*Cd$JQA^C(R`h zHz_2=)v<(bWEU)Q66wiDGAS->^KD04%jt-zO%k>ejo#{iu^|T0@wplQb2_owyoDNv z^h-8&sXeyq&9e)QU7v(ehAC@}uLky8+PSIF9@So*#FI>zh$iS!V*&tuQZ5iWI-psx z#D!W6ZDU>S9tzG=WXr; zZUUk~J7R;^`LN0kyd#ZSKrn&pR8n%ie(^!om=U z+zlBlfH@USpS&)n$WRj9H~Lfvma&2T;l&K#0n~aTS^ZY(tR-V>2t5|)+*F=13eof1 zUAe^QFBMrxX|xHismbgCQI3^-P;ts^}$>g#r+i+V7?j5TTc^ZfQj+L4z?#dY8?S1 z08rq6Box>86;RS0wZ;Hc1YF1dMJT4jw2FYu4h1+&G(j2%_`rw8SXe{Nps@=SVyNSn z(x@2dyt5*pd3)A2+z{vNFPcfTjQ82eP=-S;Ye%4+q!nnWnE<@s#Rw7Z2^yOT{QJcOt8!2d1|watsGV?tQG}(7 z3v%IJ;S*tD5K^pqGr%g90k5srANgfndO)B6LI4Z*7xQ8~lmPx8N-j(rD#2~M{#$Xn z3It=oOX&g)DJ20#LX0MipcF-f=>T9bgxh+Q}WcHabsWH*?=7bL>W`6kfrKn3iIj?k|Ao z0rvorAZpboEZ$LI+k~w9C!n0`?~WuaP*nb~t6Y}x5B$V)4F)P6U*Ge8Q?wb(>L$~c z3=TYs2&AI^b*~8F4T75=JTcJ2!E6|DuEOkb0rnDLX5@Uyit;#O(OtO;)=ox>)pcvk zHdnSyJj){wghsAOh(~u>4jr0h_RhZ_aH9chFt{?m3F)&yOgNxSodfA4A^*TpukpZE zfV%`tOPaHFXAD6A`YFKnYvTx10}U#$nxMOY%mm~WM3N8IsQ`+Ejtw#91GXfB<0D#Y zmMs@iD;)(+QkSq?5KN+4NK2w=#t?!cjnj~C67ds$l4K}?rtsAaMGvY$*7um%kFZ+RjIYO@P@rpDIVW}s3W^Cs3ozduvW2u(nK&)aGI5kUw2$3?-==OLho4s|i{k62atrZ(&7~i{xneI# zo~^nZr65o&mgb}!9GRO+MtyaN4Pzkjd8a^s_MX&1EZ@jOX1CZ&O1mcon?RV6d}ysz z!l(a`h&yig?e(&(`y{*64FmSHa1;|-mRI~=uT&D@ z_#3&W@^UFn4nI9n^h$ThmJj$GC+n!dR>CKB$^V>;lu88$$6W2?2T{BI@2e7LMay)* z$oMhqNFIHAvGJ&DCSM^o(fTSH-yIw`ls0~~!9CLgsh&egFW3=qS0+WP2sin`Mr6J2 z^6hZ8Yq>RY?nrVhj0k^lB7Zx@BsROMq0 zSciA(*}I9Uuj#Rjyb-709$kl&ATULw*fxlJo7BwUqv)A|lZF#v@#!0#?Bygs&zWSf z1G)fq@KkL?<~%xTvu5}qPB3ICV7--j0ytw*PCE&1%3t_X6k&3P@cn?=;zUaquT>=H zWEs~ZP?BfF%e@g_nYsD!CI#%LvytKg95`Pyrv>>n^C&Bs{{u;u9Dc1JKgAoBD zpcn$|OTP_!(=MXGBL&IJv)%u6hKmAEijV<<*8Fzjgfn4m1dGLKwejqQcRI@|+_vh4TEWf8tcAm~lM5?{ex4Vid4mk8pZGKw(#c zrGe_|TUTSsmx|~x9zZnFphJ?r_!l#eC|8K23rDB#IY?x}XeYWfTQ4VXR$LF)JN;ms^H|+*KdE*zfe+ zyh(c)&HsE&`APSCUi_MIdH=Sk26Caw*{F>$ZT)Reo&1mUWj3Em!m^G&vD z{-TrCaa%O)**@z4m$RC1m4epmJ-w&<>71rqmr8Q}?spH!$@gwyX^4FF%r`;^w$zEa1`jjUb#Wf&!c25s3D8xh^{g#&=q&`mI>!7 ze$G;hlttG$iT8^qdLarQugGWJF(9zJm`A zDbCt%k|5T&UG>=8=s26#K}_L=dBU{KiYsTY;#!G6Uth5z|BG!q@Z)2bhm3253&uY= z-~0?=2TyV;?(ekblq&0WtS9cjlURH)9(cK>=kuM4<D?LgN>{xN^Zge>(u?=h=%>bT{>Dnh+s?4+h$(PdGCS=k z9)|}Ulge266Ax6DEI%lJM>bWG|?*MD^Xq?;al4}*Mq(|Owhi?kxZUQ zruSN>d4}0Zv_`m>Lp6=<=k%B0+cgi*S!xHgvEA`>gIVTV_*d1L#QO1m;fzL@2_B#= zb?v`6L48UW#(dL|MakO+CU&_!jMmpxUZDI4Z{guAaatcrG8S8rLZpwd=xh7Lg_a<7 zm|R`zbC)Wl_siY^OJ31JrS(NCn?c)9E9g>$^Svf&vFJ>Zzc=l2mx*{H@`l_U!~f?3 znBqH;q-6~(_(E#f7<%+%nt}X6-;E9%U~|W_1%Gc1B0?13;)v&9QHt-!NiXG>GkhPx zF!jydwu%a8o0gw{O`6>I{bl|vT9K!9a`#m?G`vJyiKYD|T+8nj1DBk(Usv^ppgUPk zl&UDl7VLLExOrn^1OuPg#|Lbw9qI=bT{8lK4I?{itBDl?>a%4jUw*B)!$ec;H%svM zpmthA>Fk)ro`Zwh5oC@QlKeh^4&&&k)J}!j$EvLkX#)Sm z)mXF>8@-Rj>*azXC;CbpX9rvhtiQc;)K_K!2gf4*_z40&5I`}4s(v!UWYP7jDN}4Q z8K>4PI4X&Og4oE45D2ON>%7J{%WZm$2X!g%G`o)xS0%V*=8z+ktt&knL1U5KikZ0g z6Hm71T}TRJQ@TPRfK>#@9b{K?*tLaB4HYilY?M0~ci&%Xp4@l`%?IRSxl-sQAfq8x zNATO=bYb<@5&xT*xH$EsOrQ4bI7~(0)H^+lleeIi0wptqGN1kp9cRxCR6Az}7Z$AY zXIi(AO;VcSl?j_{C9u=&=WF}8K8DHm31RERjoR{oeh*OAKL!GVho~cq2JVXfC%OP9 z`+4B%N{6oEnaHs2=}Bh%)+v5{f&I)Ol0>&*!oVN?X6<}Y3doI?d|%3Y?<=y>=WbivEzvD)M@YhQ04gY7>V&icFT0_ zC!hYxbn~m|->M=~Uum`C$M5e8m%wZK>`B3zm!Ukb8)S`@Bm3FpV_i9wzI9jOOL`xJ zC~_ec{HXe6*4mXLw?1Mi(u*`5%aQEWt8YfyvGYjFZs3U|w3cAmbX$Bi-CXcWQutU& zMTu@n{%Dd-bze ziDACI5Ivix(a)BDuZ=L)hb33m4DXIw@8FQ=k3|p)4)@1B3(t4+Pa2zbFV$jvbx51V z+Q4hs*6APmA^&*6P&!b4O`GdlqV^_6y?+CN{|t?ir@f%Wy#)eli{}}vr+H}C!`=p1 z#YD@>cS~XXK2Rr(le4m}`moj$KcPM@-N@ZE0Ve6l#6OPx; zth(8aoz6uc-t2_>XUi@5KHd;cSVH6}+C}z2O)vhRA;x0dvG$6W(Vh}|c*7#sO;Vs&v z92S1oRCa2^K}3sC5{xzzfo}%XziXQtL%)9;eWoQLrh2@4d?vN4Q3aOnfX;#lllB!m zApQZcOVbkQE|G~72qbFgu^Xq#&^Z8mvCbh+V%D}wj5*R|NbFUhMgw#NsCBn1fIC;I zo5~OgJL&Km0~aP&M@QbA1ksNHs^eq^pg(!TI_+!{`=|ae$~<8DX;%ZB%`rJ<6Yz_>nfR1q>@f;?EP+=c@WR>a71SKn}VHnp|v=0sp0C(-R)Tbe4qK3SJ z1}1HuJ^uGa2{y$DZ4FdZ{^!Vd>W{EyWd8=gIa2orj|pHJLX8MzV++Bs*FtUNQ>|X( zI$lm$G#xu3ny(@MF@Rv&3*}n_p`E3V&)XjDtk+MQT_bgYb_%4@jSWXQZlDyxpU{^e zM2WIB*ZN*SS%7H@3NWs|Z5L~8(ZFEOd0Ywr4KiE+M@<0XfFTK0-TX1D3DoF_(3OIl z2n~U?aVlDT!=5O%5;iQip)Kn)tNj!iblxzEWL$ejl zV+y7Ar7(O^g5FDBJJ9FbQ~!do2Eygy(T|XuA{h4FRlmp_g~-Gr3>iTwsasAh`}*(K z8p9L6_GhWCZ#eK%^}_U*6Rg3K;YPWXF%%yCsZJFukgn=jhd9-2!qc7vV~}vBZ=lbm3@O^$ z$ET6vNY96`*LSCSdMox9r*;pTTdQyP6(~|n?%%`7#ZPrab-(-3*yK5ftabdm{=?fZD3hC85RiotE#G4+D?9y z%cGrLT(m-W(jS6Nv@o2fva??vn3;vjlAk$SlIhRMvk|0dTOY$M6#v3FEkxFuV<)Wm zWub(IQv+%nZN zoV!MsQYdab(G#}gQN_eTCi37&X@tiLLx0C#G+3$IU)@N?FPK_-ayFl*{ubR!(exp+ z8#8vz2VsJwpZ?&qt^HceT)IoA?DT>-Hkk^0m|kd6dFZ3Rc0OSA#Cow5!U~n@&4O|-cSD*T zW0OrTpEDMmh96A-7|rS}5&K+l5jx#x#N%5##yM51MH|)pMp=P6EDNPP=Q-e$+W({x zYy7ydPVk@FmMv>}m%*!g4tftgDLWsr-F^PdTpK~#aKVoW2I8Da9~6x;Ib_s#zv%HU zBRc*k!$fGwm$M>+4L z>CYkApdG{2EU)8T<&_w9H0~`f_P}QwC#{5x1ilOzZr^TSa@pRg3uJp!^g5vEvEISk z%x0#&lkIuXFAd+$1DB?%+S=>k*rUt?LVpX{ z1{pV4_??Ki_I-A?=M+G(5s&f%K~Qmtdh=oFoU8|xJUyNc#&*l*WvS1^L9<4?TG+RZ^8eycb+~31+1#K$n!atS`%3ekMeNf=oy? zFyzbVb5gbTK#v_tYGyALUmjX~tg4zC3LpEmeV;!qDGdz`#74Q91@s{?*e1;n{5zJeyfd~b39?lpBDbi&l)s$PlKngS;mm@Gk z#hCU3p^|d(U}LhXt&MM>!I^j6qi8II;lneVfB=)tsiwo=!~7#Q0ACX3oVg&TCPG<$ z-1o4RWd>x;6crbUF1LxSpFh{XfK7R0gp)50krt>YeRsB+S!GTq1{bD0XOhCg!uY>t zyJ>;WJk_cz-IhNNzW;B(pJv@KG#t+%NcsE4X^3rKQCI{Sq!Z z(O3;(o)_E)_!h25+A}9_Zv*I5tUWy+0-dUBsJbVHF~ug^U%&Zq=VYzC-_WUrJ^Sc0 zXD4yxeDqAR6A7+IqpFluE*6H9qhnZZToQw&o}TOacqMVYkcy4tFNygFPOhu^KqhmlhjwsF|*V=Ux8(&#aA>D z1!uJFZD)5AH%RZXOwvJJYb%4#@u=egJZw`_Nl+6tfc_fSt_Y59J|SA*R?A_$3AM27 zy}HA?z|%U+1gWr##q3K1tPmlp+B?K7wwvY4+Ej_7gzAxQd)+kw#U7}=vum#`ZW7`? zyVI9K_e<#UWpq-J7}l=)N3ZelZz@w-ccv09^pmlu7gkmYlkQS_Ola4B8CO1UUW9^c zP~`cl{dHn#sKAZZNpv6Ta!mb8O~#S8*}8EM=d%5N@quSz9=bg^RK>O^h<` zv~s~Oj31gUzU|1QC-#X~YV0}v`Ak9D167^l*YomRHul5KA3x_O4R~s}t$6M5@i}a( z(#S4-Zs=QR!Ik*_AXI4F=&5#Hk3oEqT1@_~xRZu|Uewr=4z_X&wAj$9XJd{jx7`9X zvKSVx<%}Fy9E5e<=-^7w<3JJk}{tiy|yf=oqmoq3Q9kG+eWBec3e2uM6F-7 zDlBK!a&zz9yAJD?C6x$%wc2+PmYV{Vl(mln*K|zxw^Q~HpXSA-#4*0QaCvXlVddg; z`>QqI#WTsi7pM$3mIAY?61xEddbGlZBCpkIS-)n0q8?h@sD$y zM04SRQC`oFwf+2=t%$u9n>e3Hjkv}-W`YWXM~|Kg`j6p@aUO+GR* zg6a`oZH@)Y^08~#8-k!Xre*>vy`0`-TZfCl;|WIAU(F4sp6KZ@b7^x=n3Plc7#o_J z5{)_zg%iru!3X^ub}L>~j^O*$rEZtCw5+BmKbuhKhy=8yr3FZkt`}$C5JDAk7QlLH z1U?oTi>m5sHYAi<3DJZJt@6jh?{x)?$iUF>TGtY6{q}-(C30~B&eu#Ma`{9>MGMB( zP%(jLmfp*mp7PqyfGorO4X$EUVX_tx;ZwNJ3-4c_Xw?YGd1d5e866j}^ITW%+K38^FaJ``)zG z%8mT;U&AZEKICErfYg|{|4B7$Gxs8~AC`Gz;gFDTef;<_G>2&;bLYoH(WN?IqUzIg1vLAp=1sWDFnu;d2i;iSyILE@5+w5yD-#Y$(9+ z7w?*$#6w$nj0`wl{`|Cl?qX|u!zfR}?|o$NVcVrYQs{SgcjwP}n48b3w!L4C?K&2q z`+?*`J-sl=I{|0)P)m5vg;82T-aI*P1zF^q#R>ZXK2*MK)m;{A;$yz0Kj)tJ>XG0o zoGewV2u(#SZ9ElnYj>{z-T=INNQ}s=|JMIf=h)$xM&<}u&^pwYLU`o z{_2=};Aa(CgeXOIN$~j5*u~~tg+v$SG=1$UYK_^EsxH`y*MSu)p55_KAet%d=PSwW zB^3*uFh^D4PhAoy?|&=LEr=K0`wJR&=h~^QG zX(jg1b1+NPE(N{6lR3ij0A-WzWGihyeOjL^y8OAvT9GX++1j1^)*|}Q1-0qT1dNou z9An?%Z4pzxXE!J8^+hu49UdF0Vd(uyiF}^@m{@Z=7Hc!ijY%!X^rNK(Lt!qu0fX>m zx2)iOeYRU|-75w2n|-pH7tD|M&7T{ug?F;AjfTZDMdZIZxmWqh@Edo;y~Y_8Jt+e{ z+mZLn4@P`S{7g|hKYP$#NB0-+>Que8e#bUhmtYlF>J%?%6VfX5=%cqO`>3Tq=dr}V z4~1WPwP$Z-1<68}s)WMUa=p&TA_ha(-W_FZ{`oiQ`$9AO+qFA`*0gVr=xW@JuRUoM zPabICXsa^p8%GyXqyDExs_ERHdT;5IsBMnhdqu-Fwwee&VC{Inb33*={r32vnVs6w zt*`qsVdw3ww^LbNk0U71cj>G~X`(rQE4YuV+lJS@+3)8%j$8jkz3TcM-_!QO!Zc!< zK3Z9juCU9LqswGv!7% z4dsdP>j`OU&K5goSZGILqdDsVTK?9~%LJt!#}RdpYQ0n~)Bsz3KuXM+u=KhW@=hcdkeXlhA>5#oEyP zwhZY5N-2d;_~`~Pu4=_;q88w|1n=CTrP&IEt<%t~NA6GSu!$Jhx=g0q0!;zXlBWhK z$!LIw`o5)$E`BgQx5KG!1b1C7Pbjzl>oDR+C4YW7ljK*V-E*31WQSF!_zp8BD9hvb z_xCI4=_S5n$^F{Rss8wM%aW4UC>D&g`~J=MSbKQr0S}*rg{3E&K4EcjF+YNzAZz$+ z#O>X23smh$xP#cx4`W&RElF5IgDwUNXC#YI)oyl#V3(rxXJ%$PPYb`_1P1559k756 zHCd{rtT?$_lMA6EEGGjdHvbi_lHT`#?n)hwzCYdn<%=?x8-y&kZD`Aoax^L`ir;AZ z;v%3vTvSBF3bbpo0x!HLe*aE{3(@=Yr~dfz=q!i?yTW=A1nQJQzopwdBX{{wNQ(ir zaskp8bauXI-W$2Qley)`nb)S7noV*nzp0+Goomq!!U(}|q)u5mP-4d!hG z5&1jJdJGJD%5bUc#UbJ?hq+}xPqckYngTCdGo*a=o694}8KRVTpdSjeMs7|oq%trd z>4muf&%-jKIA{$-_8t{`7%+UjjdD5k*$*)c$R08iD0Krc&I-CCsMYz9AA~l=ivHG2 z-mohCMZE7Y+)za}tgbjqZD`WvhzKt3T(6s02sv`7N;01B9Jvr!OV z`lKf9_dsa-AFO%dUa1Gd57N~hkIJ0ir-p+>l%mbOTV&wJulIkzx;}YYV63&}0pkjD zsyVf%+Y`uTjObnP_B`C28nVwJAVunjE<^NrsZ9@`Bhd#1?b)nCmyEXmT%r`ay<4U9 zFtGl7$PdOy!sUt7{8!lV{bM$VtltG6Q7ulCCn@dx*S&FB%F7AIp782?TyZI7GRUvu zD{rWT^8-DoWYXKOIJOHdk71D}zQDDx^uXzV-SjhvpecLg23a=U2ZF0)mBE%P%R>(s zY2-hBt@K{=uVR#vnG-%kX9%Pod{wI0af^I7q(Sd$iw zl8aYTLfz|0<#m@2VM@RHzvL8j27HZ{C-c_-*nGp6Z0v9MRmU%H+jBdUG93yZbzdK7 zim@eH%-1U_7`y*9+<~(a@1-0sD(zc}rd?L*Q8a%4T6$+$IuU)aae*sE9_^>K?MR2? zO^pfW$!}%Zd;JPy{(Vi4i_XT^@%vLt_KA7RcBwM_fB57Jj|Bw0*=1s}B$8~9>AB<9 z9IZ(`NXye1_}l_tN0ZW_JUhRXU);Pu_{|L^wT87LR5romJ2Cg0OUpZ39?zub2pa#C zqztp2^M9O@U$=DPMry@jFqB4rGE8Ls6unLP+bM`ecj-!%6Ec13unr+M6LDzW9a+g+ zA_|OWq>Z)CX58ZuBN_AKBnx+NIDfEotnqe`BmLTP&h3i3>-0t%Sv|`oXA?ck_9qfL z+Svv963ot+r1^jBy=7dKTlYVV%0W?5 zRFISg>26R!q(Kmn8oE2BL68y&=|&_J5Rjo`XvCpm=#=g*k^1io&$-Y2`91HR*Y~^; zMy`GBSo^zrEg$&?wsvz*3M|A~@C?BufsWp6i)zO9-s_^VV_dSuIzAqr!%K3r5nvWz zKFaNX7JwT;A(oC#t^l7NAJ-zv&ucyEP`SPGxWuToE*w&WS3*2b~b2vbF$Pxe=^FdY^of>CGbV`e# z>eGp-xW_J_19e~R=+;(Is?cjiNaOZ*<@N=pftH<=@sCB2Ppfb>VAi+ZBEMS>$lfY#DCl(;= z=mHpw=z&9-vf16&R}bRFfKOsk)BwZ8^$D=E66q@f-$uIi*`ubWrr1+wLD2(fy5GMC zfxx4{OpOd6q(htpRCDXddLC&E1_6sT_V(5VzEU=D#*Uz#1N3IVv4ZPPsysnUCS%~& zCKm<0!;~`O6ZCvEfyV%3q>9B?&iH6g`<&XG04)OdWEK~cSf>z;h3Ycyf!qm2An#s0 z2h)ww9|ZoOY9Jv@*1l%L3>q69jRO1(q8i{*=mh1EKdiyX<_^E@XSNVnPBE#Bv;l*W zQqM_guP76!;s#l^KseBBF%4j6C*RnxNe3vem&1k()b&8)bVyKN0O3LL(0hSpPNCXm zJsu=VBcVdXc*?G^eqSKH!e#B{%E^mhyGhp{c7I2XQB$h0$mAGc0HTH4LPK1b?i7$_DR^_4=sS9~RmnfhIE~7!S&dJP3{g ztr+6LdX#a6-FBV;opy1yC3w~ha4xX73xLA|M+uon{os?A*geT*slr7-o)|vgQ_c7t z3)EU95DXT=`KF^zPEPFY5U!iakOs6hjbPfYKZT?!==6Y24LTJ^pJiO``z}l)Jb})6 z&)@%$e}gMjln{iz1^IOXt5>KrnOp9n9XKy=(^(<4vJkSp0Xr2?Mq>bl^)Z27H+7H@ z1ndW2v}=1l@bK}`gWf6dk`hY5(V&%f0wof^+2N>Y!K=M!_j*7zGpc_-VwXg*;}{lJq?#hRB6zL821#aZ4wXL~kB zc6u@M9mI1nlJ5k1cJrd6qKo|QaUseT2=|#VLoC>GZzi(L$d?8$%vsgc`*8G+TS~7~ zIiX|&e3A@Mcs_Fpb%%X2cS&?(THd!{21&`HehF~);+Jp?qE9D^-}mqCdRi7w5>srN zLqj20S}dg1B&dJrj=q1)XG^hZW$)zyH+Jc= zWwYJZrF)r8EoQTM??|-@V~;{xFE-ocWT*A@ON(GOG1nTUX*x=g`Z6z(Hu{X)aw10( z{j;SgtG3CQXn0I|cy>>^vPVW}lYv3{@oID~>G*n6`Q9gLEbi(@>#?4MsBMLDZ@4(+ zX6`qdCWA4{=~J3pg2D+aEXW}x?qq!%^kR>=gJc7ibxO9B?*l^Zxhi;AVc6GTvvN1@##wZo^U+qa$d6M~?JU#8z7Am{SrOwUkUMZTQ|wi} zuOq5Jw4}1Y;BwDzMhr>OO^aF|X+LdQUP>RItW95Nd|&jahQrEhRHk|R;r9ID!1^H& z81pU6W^iqkiyp?G%OG&3*+^cF9Fld!*stiGP^=5#f7mj>+TG1<2$m{(h?!lx@hXx` z-Zl0K=Q_h1W2(bzTN@j~OW_C`9lS{(^DcsFW{x1c7Bbbmv%vqLUTi{j*CX)m2Rs^Q z;7{;CL*0JPGzuDkJf^TYs1%tok9tF1%SwG$=_`hb#mHB{6DVKFX7^Z;2uyAtOZ@b& z7hG-@==ZBWKR@pyDsC7JYlZoMF5?3dg9y)K@y6%mKPzf#9>3n6#%{uInPuipS_j#tQWixqxdkn$mUQk94IVy4d)fWW+Cf= zNQc^@TVj)ZUJsMLi#NJ{C>{wCUS6r}j|(Jl4}-Es4n0VFe(N|Zkz?XS@ZSp*Am?fU zBz-|vE=^6%4?vlNj8|8FPf%%hhEq(84GizfKn<`(X6GXg=I7H1;9rJt9Jon=Ve09$ z*M2u%>Sqz2)f;c(yFpBU5Ny);|c8{twGH(!gW^ zpJ=&J()x>bTJ)_i7i$PFSR0P=h8=X407XW=TAT8$BzzIJpa|ft&3%_>f zp(*M89!OXKip^emu{Xuu0!pt9193g@}`RXlGElHU$)F}RgKBnY`)uH+)9lwRPYrNY9( z?3+zl)4_mo8-sp4I&xYw;~vVDR+rJM8)K!8+tXL3BS;&~y!itJG`+2>xaJDNs^Hbt z5B+&~c2>?#_6D>acYH6E)n~K_sno|>>D+zWfLW=i#gPiR%0rEHgIzYF z5Jz6C-pcEmBAhsrNY!T5 zt+}_w0lA`pd>}M=$(>>CH@4WBVB+M&bx{9hWQ?h}j!Fy!^_mzNQ6I!6-#l7%Ie|jJ zAa}`tK3v8Jla*(nonqqF!oaO-4oiCV4@thoar>>8wGf9Kdf&BwMPGl9 zO-EqCH%C`1(0rc76eTZcCfm+bxHpMPh(AqBxBfS{$aNr|e zm~Zw}a37eLa+G&>@^E@YH?yY?|FF7Bg%L9p{?Wb8pZl7rs72~QFnJ8QQZhw7zlfMw z4sJ!=aua^Va-~dt$-u`O-R)l)>)oD>!H2o6!n#k@+2ca}rEheUq2(@XyiV1NJkgW; ze(yW{Zb58zvjxwmiSNG`#79m}o-QATiL7eX%f2x#6w`=v%#9y)w7rqq#o;qy2b9q+yeRNW za94h*tByTK*+jIWC){`>Ce5_dLpSdoc^1q_=EQ=>-$jR>D)W6@K%=0#`DcDPZJ22d zZ|diMujEH8y!uSIYXf(aW-Q=w-?IzLRjgEmzFYXGbY}bBwWA|c{qn4lwa@;2o1OF0k6orsJ|r0Q2q3Nh)d zf*$94nvn!r%stD8i5Mq_yd|HIG%Tj4x_iBEtwto5$7{QvRL8_0Sr<8@E2Lm||1#u} zyJ<-h&8jxGDGCh%Xwi!{k@*?B=IL=~4XNnE@Mbho;pxdz3OfJ>GB`8^IfqFYI3ecb z+;Xe?Ri(I3pPY}HfOBgJtO=KG-k*%|Wf6{85_;zC`amY4M96I&*%9n)j3!*T;jQ%i z5#!-Yv*Oq5B>_kuJ+cSrl|bf)E}%|>kH{*^Dgz`V1G6_}pDFOoLauE#xpB_{fLMg9n+P-OgJQ>Jy^l#*Vor@ArAz1fbUhpu;pvJmJ4ju${Az-thaZ~a%)YQ_7&d*@DzS8iN=d za7Td(A>g|43h)b0i~eaCC<|xo;h_aNW`XA&RGlNbt^|!{VIc!ltrmx3V2YRW5`jAS zC1qqJ0HGVC7f||+jEtB7Z4WE*a}x~YN5?_F)e@uj1>l5{@oRx3Q=ncbkChfB|gTE-io`7*6s2@N8855{KnV&f}r!4qMJMvUN1KkHy*nhB`dbX%{ zkpq>9NCTB1-Zs7g1rprP4@UrKsHQq)nw5gpcLF^U|*u)QzU?)QwWty!)lb!Y*R7dYaLPl2`vd4qxLAd?>cJdzwaI2a4f8ko8! z0boHpVr#1iGMN_u*i(Kq1G@zL*3hcaQ6e4(Umgb3ZfUN8gl!0wfw2(!2eSV`QB|Do zV97wYvAxyocDh+fU#sui3(702r#kHs`tA}!lEVq80nG-La9sr5B2(+mk0yW~O$~Ca zec3Me*e$-#2ZMT0 z%{=^o=RvC4+F%}@9|Z2iqhAo1J-xkhYHDz>FCeup4%i{1TsP0{jf^Cq{O-4pbSC6J zmRD5JfherQgbKPZ()&ix3bR1zL%NZgc)OGtz|)c8UOqme=m(-ej{$`{a@d)Rj=u8( zr4*6*G$sHFbX;oK;dGirD8FF>Q84beQwQ> z0rLXC)`yy+t{YLCK4q-s+}{)sAP(FS)Pal&f()ulOQv5?z(E6Cgz_S_kdfNRtpsGb61Qa?>Z68As9*|a8eEGXLlKUQuD7ltM4B7Y-9ZMeJ4LN$$ z4LO5;^(gh>KEmOx-#L>>n_(v^y%;9%HTlAXWl)ABs|sN`o$(6IPU1oul#g=4(!^K? z=#}b6xn;~h-itX>k54garlc)w%8}+chjZL1x*eXQ@`_EVfM&TBBRcR2rCDyEp5;Wi zAV-)EQy)D}j-mI)g?NT-DHwH%>9)0yqH@e`ZcSy49&f#DfCC9D72_= z;-miQ>tC@_vT2?g$jEt(Go-ZpC&`CU%5F-B5h=%;*pL$?EJq#*t27iZx3jUq8xwb$ z=vNi?VI*1YBSwXq?nZ{3D8kQ*^}7*mx0{R)*R;&a`K;kguy(r5BjUtI*EAg`GRZ5Z zS$J4S_tOh`@acDT0{2pev@NFW?zp61xF*wTvfQyOYci2Z+a905tlg+ON^zeiReC*s z`{4(cnDh~32fTA8P{P8IcS2tHz3X}M%v}P?oo8AnSzOV1J;U;=Qap)Yz358GT;VPu zOf#QvPrP?YQ(8w9E$$%@+uL*W4T>EFLX7F3BG##aS7Xi`z(8>3*)Q*nC^G2N!TI7`#^;w&7Sr#(bZ5vjxHF z9)BNSW5`!{L;i{8-B(NbHJ>>@w`lOV#EKG_gilpGWj>J4m3STRk4$zaCRN|AELva7 z6k8{I85fhU5jam85j6K~?Lf`NsO`sTUrZ9e%=NzL@8NU^kCy$cvh079W zTYGZ+dQD3N|3U3})*FxNNF@PyZ?4)<7-H%{Jw@O0cBI)8GEwq_NM8@+>u=QO)TH|< z?i%=8zQ00+lYuc1G*FU}*u80EW5a^!0ngwG**ICwNZ9r{u8ltnmrDPEf-~xd}gXU!tKHCs! zvTyy{$J*h)PIj~^%wme(sZ{2L&jafi;fFGMPBL-@F%Tgn(=dZO;X5DB2k?awJ=VN2 zYQXO^1b4kaYl;Jx9J1g*A}R3AEP^PmLa!HK(t9lw7s@ctO`bn+4BC1(3nSb|DS4ks zLLQZfHpqqLw!H{EFjv+Z_x?qt3{e&+jui&{x}BYl>%)b3FI|A`t{RwV&VVT-9$*!a z)uEWCU}tl-XHGXF}gaVg3YL-fTit<5#|ESH%8Ss$fhmM5Qk3XWu9`CQ4239kWF#?$^ z0aN=-=f(^LHJ~ys%0T;I$fE*61>ASr2qEO#17E)cNu3h*s{pW90`ow)0jSUM!85FD zZ2B+yOp_fPm?M%zJOOj=2sx5`~cP=bGvw;uRwYgSUipd#<;;>y#NR8 z>Q79Gdeqi)S{6oX2K>~8W-ip=(##`TgrQ}@-h*g#AAS>`4p-LSzb=nB2K+t+{af4x zvG{r*q(nk-31@qqS9U?4->8fZhy~l)2Az*jpMxwG+H)U0VDKUdl0NIU^PvXLa|1Vp z3F<^3bvikMh6L`=X@dv~$Pol}WMAmiyMP0U1M&;rTB=yr1?mWp{Xn9l`>!1Xrbn8d z3uV(D>xDZ$K)M0iHBq{j?;A)My5%?sn}Fmr@Iu>}da^Zf>}HhHZjaD*h?64tf(0^{ zfuJ`?{?a>N(|~+&P|QMHHiww62Mz#zp!CTBdIjcTdY7@PpU5VCyo%!Dn!4cxuxV+C zlh6>IT34332HyoHGLOqrofIK26=1%ZH~Bu=dJ!KJj=6scNgN(3Bg}Gb zRI}qTdM9`5wwnWclOH&?HDW&R zb}HG?^XUnH|M(%B@bOeDdiXK1Tc5|!chv+8kGGHV%Chgp%xoZJ!bbWkqxdI&5?%l9 zoMiveA+t{?Y3faP>_&jxCD%>nRn9RI-L{kF@+do{jf10`*!cxY26Z@x0B?qepO$x8 zIU-KH@($iTjte(lpAL1BkqSPXCnR)$tqhgJc)o6XdvMRTS@UxD2*wdh`id?r9{1!^H%e{P@bgZ>zE!TzWdfbM5x)pBtK; z!PeIP4Rik8Dm}s(CKfv$sogh0-#rIkm){%V96}AS==t-HQvBD@9uazSyl)zRenva% z`)qG2Jo0$Rbw}yUNZ8*%S>@&;U$2WOnc~^JtnV|B4i}x5=dl1s=%OABUdUc^qZ;zn zHfm_--o~9D_p?0rJsS(2(&;Gj8(cn57Ca(ct#T zuI~x^dkSu{>l*>KFDu%M5X&o~d%Xf=#LkoUf$lZy?|dE~EO8c93Z#KbPz(V0kUOry zg`O|RQ7IubBKKGOEWzc-tSka@6mUnUewj2E=tsjM>u?6WNjBtepxgLZvB^_or8Hw~>sEw+vsv-)iJNr10pqEjjL_);m zc<|d8fCRtQZ=M8prp*8W?_aU_$wf5~^`f$tN0@+i%`V;et<0kD#&*LrBnakEq zDP>OHZv-fmS~#(7a3~(n68_lfH2Kxwjb3P-e(yDTM38@j^7S zM0cKPjjv~Umf5}L&b504tG6C)RP}woEO)Ja>#Ddr=2iOBV5F*Z+I*VEo$>CC!sHrS z^r~v-=al9w*~+~t)%Xp}sdd?zbv+YR4T-`CPTd$q{D+pF2WUE2_MVUrVv;>RmBXdZ4Zy;Ow zj`0zqwQE^>_@v1G`ZM0+FER-tl4)yaMD4{IgcRK=15+;=?sZ3_#_L#|PSAqVLN|39 z1C4W*QPoR=`>O($V!S3KBF)|v(}gfp4)^$S0H#$~d(DIIGRHRSLknujHIlt{T*SS?ac)R0rleFk|;upJvjFiwsjShlcvQaCB1s(7Cn*V z1*Rt-+#DoSDfsE*id#=T7?6Eoi5DS>%eoZrOwumgNDI08g!S5_jFCMBY1_?CuhJHG zVY4pJ$6VGA-I=n7m`R5Fe{!aMJ-(iCuiDLa16yXhd+fm94U09sm*yAFc^>1*i0|p8 z=$bKF<96YJ=GJa{+vTxaOzT0UIQ`{0g;M$182rFws$FJZS8nmKgBtA|0_%j@OE?gU zygP?F7E!ne`q2*n!=2a~4I0I*4o*>7&~bC)dD`30({W51bXr@We>O;eDf^Xuo;#KN zMMTq`;3vn4#*0jf9K83rB72F_;knnOJs%SDk*W>bFKH_%D8612rWA!W#sF5HNs;=xO*fKs9;;fT~QZt(cUv0T_yvA2|iC5k=mP2CFBp9 zs~UVBckOhuHtSt{U(MX*r1_r0CRN@x5Ny)+`Y-V$7_tk;kbKo}v0>b0%*w|vM?VJ7 zKFQ|E^7?EQyGT7|i>8T)!|G6u$!8zEjQKjs@~y+R*udteIVL_{?Bcb#eNWn!c)GaX zkmmRcxvnohN~DpePJf#?x5RH#9BPqd-4TLeVxENkRJ$h4)FlJs2AxE#%fW3_+|gE8 zrjVGIleDNzJ#xhB7f^ptRc(obXJx0>&$>aIswE9+-IdHti~rB&Qga<@N5%ZGab)HPd7$@R_Fo_Fql zK(=7rA^EXf^(s=nB6KO-rzf)i!O-wIl3AVk`E=b97rnF*Tr#iWyMOjY_%*{K#$H_! zD$8>-rVq#-S@nQcxk6;A=_QrSSu!?V#m(5%_yv6hScF_+65)E-2C34gzD}cMuMyGd ztpJPSjQBzh4GGoAW*EMHH&dbNn~}8kLn2Z z!dvCUvM2bSn#DyPn+kDz@>qHt5QoDl*rwZNUmsj5m%cwpw^hsoW~ z5B24qLm9>jOUkOMm)X5iF#B>(+>Sv;9Bw$K`Iq@zYx_?zLeGv{5+Q4cPml4h3gLSX z%AkSI&Rfs9plWn9w8rOIRty@#WZ#d84@6yT`FLI0r@IH}bT?1B=)uLug1pBXjoZ6;Dzn4qWT5BiCa_v%KKjA((j z?R$Rks`R(y3>!XWvvs3rqa5Aba=9``B}fje=mk`H-7#5`Zn}Z;TcxDD~ zSo&)o)Z_anI`_NzNZhyef8V^D{3(^(el=u#QRZ`wTHKxEA(@;-_^D{B9cN_dL;CEJ zbuUZaV87lY`|L#}O_srNnXkU%0rJVS9y|;p4Pzn^!%Y<^)av=heo0*<8E>!0YT2H* z7>ke#d2Ekhyd&uZSS6ii7u&F>%|i`E7GDox>jq{_*>qxQX3(>Uu*? zqop*BT#C9Qp3ys1Un*UEH}@J_T2^?I;B3?^YfE-tnHAl4y5=gcjfV=(dSl;Q4ag`) zZ206-79~l3+EAM$vyx1zn6^;WBrx$%f1agpOPaN@stA?l|GEjs5w+lbHLg4TNn7@9 z(m-1NfaCnq>*w!i!ZXRR2N!vNY!0q>bS4`iJ);K>U8aUBj2?cOzo@HD zhnvW$d5}|5Yelx*=I`w>MD#m!;yGdQKI!Y}q&Ay7M0wBe83}ff`3A*YSO1)^++)Nn z=drE$%Q=a^zx;vhjfj0><>N%NGUKE;UEH?X*B3<+1%B-@cJLcP_7fOJQGK>!2j@vkLxL;bP!PSdYjPUlhBGDH5-yxHkJ(mljs{ z>#=TK{u=Cuhe8ilO4-Y9+n^Q$X?Zn)-JYSRM#N9(s<Wa03*2EqaoygzjnEMRW~g zE>+1#y;@0NsjmDEx0X2ATkfx`oW@gMLTCydojq7fU7G%R2>asuRiC`^U1W?xe_?9O zhk{lCyXzfm>wOqW*C4v0lK`zJ0eamlAhB%ztR7H??d&Ln7Q6aa+vgIDO!vIf!cp2z zg?MF)%11KeKZz%rzuO5M{JfX)vYnYxVJDIA<~^+y36c~W{{6ITT&9;f54N&HYX@gu zRZ|vbBjlxZ3UJ3%dUS-B7ftb8LvT%fbkr$ZfZmHC`dNIW#s(;^q+Zj- zgioauvfD1vBTgzmI_rXK#p5epk9(7DTD8a{r!9*{LA^p@hnMcMVNWFr1$*lFl2X$x zW`19K=k%MI|8pk0PLt=Cthj9bhFKbXEUW{cx~BVTXn|8Xsobsg5ZmX2IA za+*sXEvcb7Y^#=)vZX27g|EgUoLqM+ECq5Q!#iJIq9 zmzQ!i?CMKR{?xKw=~}aUCv)WMs~}Ygmy}sj8L*d)u#-1AX#u!;J z_SNQ|3+&x;w#BkMv2cqpYKz#jrB4c}(kN-|*5f%CLg7sGV>Bw2&z5kX#VWHR;T4hT zx6;Xoq*d-6DKWSHmE0ZQ2XCUS3z0vS=h}0r1>QE7sXPjdyh+ktviXC;la%gTYnz44 zOaGoq66Ea#oQl4sTZqF6&RXcXykq+{-5rZGOssY+~Hl&Fq=*j+u>B_8ecMSGoJCblp=wvyeOCc?Jg%AZGRQOG$FG`}1h!Ij zB{hOnr3Az~8j&Iok}C6Jq?flgp+)hB6CSJ1kKKQzP!`pb(-#WJrI1t_kDNbd!*Go` z>M}Wx3$p4?Ss%~U3m7fP$287oQ!Wi&Y7=;f9n9&hXv}XN{}41e*CmUlo6c#`TH6mj zqKOx-OuSQn&n-_vKiFn8t5PI`w&}n%nGZGan?bmgXIU8Qaq3h&eca7zS_@Q7nTr>l zNb*q8yEi733W_?1{CU@}h>75DVq$i6#!E39N64AmzagAZHknu`JvxbaknKo4;5P`Ab{0>ngNYa7>2Y!S-S=oUH{5nI-p-hbXs(%$w6#4oqmEQhbqi9YdM3u&Qm`^!2jFPs?#>k@B# zHJT^jizG>?8}T-0SK%smM~N2a5K$9qbR8wI4PHcHNF~iCm*Hy!S2*&1T#AZ6Hr#o^ z%va&y?Ug7kEU>H9hnsAgLHhcZwKHt3sXp06S6F>{&x88GV74v$VvS=Q?3YYB?Yc}| zoiqLnI#!!s5wng&K#$j{hws<)SDb~};{rYPxr7c@GjzA;6<&~2&JAc9lFZG&SH7A2 zaT&Sj9i=}cNm?>?AyS3{INyyQlWft$7X@e{9}pa4UR-3IZu1|U(37Y>TI@b z-5K9f`9@wo7jHgqu4d-%+hT@o6BCWCxiBaxwLjNO%or&kj<|cow-sHoXxL?#R*>Q; zF4AP%RyjZ{7o2y`<~-3jshf}EFj(ov&+mi#GPkYMqW?Nt5EyqU7Rk;Pd->&gYU@wV z+NY|6;=1?4UJ2+HI_WQunenB?Vwf!!#L{Q)Z&Wxg{w#mBozS7pTuk>-p1?d^x9kCV zc-_mmkoT$Y^OxMMvyTPosrjNo_{oqt4YfuB-?Gk>mAdM3cs7p5Ue<>}#8+7_pOU8i zT+wnyByMq>uYvaNt1||Sg240lQipR{xywAIMMWFk5#rT-R;}ocE|^UY21ZLhrnw^` z2oH;JT^rA5`^h-_srm!TYWG`oAi8VB#{&uPXlTN1W$gh=s$AXZzssof==v<%9Rr8% z;6LI}b3im7?cJjdj|%)QF~Ois5zn=sygJ72A(O0&;=b<@&VE{X?PlRZd@^-uSyIsG zsB|huTwFY1MsCwq5$WInw@VH8jI|c3&%aq+d|v;7Io`lV>AXb-zsBzc94pKBtJrqp zN)My4YGczc`MG0{VN#j_IfN+G%jXilj2movpL_%i=d+pW>~u{P@XYEzaV>H&IZb2W z3!bXn;vzyV>8$CshvK#ne#c&r@3ke?$)qHh=8;I@8H=M~B$-w$o7FYMWz$TO^~X=q zoK^Xv16O2-l(}YeOku2&GI)P_m|{AZavUxZB0@5L{Fl20Bd={`QD)IG)uL18#MZ67 zANM;z%#(w#hlkuEQ%{!_{77)q{Bue44$9cAeBeS9olb9niy%Pic9}s+B_Rkz$;7l!=K3Rl}E&{8T;6P$Ae8q zBS&L(ZVe=rVeC2%DnYWRwndL7n35=*(v-5Nm8uT9J-uVA>Vc9*tOPVDZ|;g5qdJ64*(qLI8!$si`IBqOal?rEh{LH@~Ie)|5A&5giK`xKvr zmOXdD10ND{LvQ#=w$IRX``VKOx=I~dsw`72T0l8ye#n1FX#5&K2Ll6^=DZF{e~|lL zkbdcCNc>IQ9E$xQs{(EZug;g8d{*{l?f2t*gSb(CQR>Q?=I!rT^kf3kEUNeva_3bo zv<6Ug<8@ED*S+&5MH!P1$}+2E;xKlkMRzof8lz`kp~5EitoFFZbQ0$?txZ&Iy`96M}tXCSFV{G`P39coZFVJt=O0#^WBqF$Hcf~8dmK_lj82vy626*d033nuEAJ)4v~jjaPp@-QG*A(3pQjHy?X9? zC44U|?q~PRnfZ&%i-;wdzJy7w8-*Qb8`9ezQOOQlvr$cj#YV^En(HjCZpwS=(pRTG z7-U|ln~%76JmDZ_ee1Z;VYdvj+zmFbb7T4Qv#2+2dx)j5vhkWa1z15CkynCFE z_3l0S0eMnAawh4z-^rCiI(pVq9WN^v-}eP){hE&%p~F28ROD)3kpImaTc8X}J}pNn zSmJ5#Gn@Jl=B?w5ENJkG$RX0w#hwT0b1t{?h_sb^3jPIA-ur(A{0e!aB(7_>6^tA& z9!Fz{(JI8ccYVJ(X=!vLuQ_a!BXf`|>Dc0lbZGZ! zvvL8lU1t27P+7~%Ii+!lq+u3Txiq`nwsiD)c5N3oN%%?G>Pb`pTq2C@u4L3kmOIIH zZqY}%7joiiG5f2x*PZYCP{iA5Omvs8rBJV|33MKC-aASd3akIsW80g8?ku^maLN_R zI(co5W3)R^R{YK&<*B7j>9?;VQ>~9~+nLdh#4oud3%J}T3Sjb%p|DW?3~O2Z#*>ke zuKvxXYfj~3j_8f|F&Mq&yau0a45xH^3p$lJZYt=Cg`SBzG3fpJIe$)7N3&RqXRa;{ zvr=JHZ7vydS0;a_e*3;t`?PrG?clqp)Jb%gldl)U9xX5_L;tsTQcsj{k)d}GGhsA)h~&Vjh-6qh@aSl&HBf|S=S!8eb1oadbazm& zGj&Ou*4b7dBR-lfUH)j?z$%=u;H$#E)EHxybD*dpdS~}6p2BUOLO0RV-mS=LCdTlG zZX%xV_N~TKCZ)%68@9 zi2i)d^68$^UFin{6eQ_;A2~^0nFiwus*rrng+~p_Bxg0h5EP=Nd8`W`W#yyGxE&_g z-&h#oZTg05R@I!;wUFnXkhRZTUj~O?J1wTY>BL>)dlHW{ZykkVM=p9>sb=AZM{Z)d zVHMqr(x*3;5Dt|eloc)NFDBGwg}sLP^r_7S#;Lx47dhSEl_g zqi=|4xpiW#qCKvzQn5#Y>I^A>_qslmQJ3HQoERhOopIP_C=1guwpR6QcUIkM$u0>W z-}U&>EAQ!BPjpZDalvz$Qf#Ds&cmYsrG3WX20@qKBHS1aI_3(HPvOgx@Tp! z`m^mc95MwDi&${GrEyxxKZ$JfmU@roj-D#NVr4Qy78n$3J9P&oJZ!OLsAZ6Sj4346aDggZpmppjeVe!+*DYJLzCljVV%gEoRc-&8iHTJK9l4xfciU*V*Z3(>?yu48XWCxkY=9p_SvQIhdA#iC<4 z6jAi%A#m;}F(40A$kt=_32wN_Yn6Ix?83O!zXGWzD}>R?Vr^qzW<9CHdMIAcJ0pR| zE<$W;Ci^jBtfIq>kuCe1PYF32nQzsFY*?!YO~butt-guXvE1m80=En&r1w`45t{AT zZBSXD(2lyXAj$=U6lc0b%An|UOn(b!58`6#K&WoluSU4D* z#MmYa&pAQ*EIa8Bd-m8_bB3N1!A&)#I=6=)%8wYkO+e#wsU9B(7KX$_9E`cN7$0b2 zN~r`7ae_d2;QCL2<&?88p5-LaU*ky7sjHE(7q!1oDvHd?&o8Uzd9ygapF%O@VpTko z04pv0a18#+#M6_WjU8MBG(Vi4*WRa?(2xK5xLLA;y6OM@@zaNH&3}FVm~Q|5f-({7 z-(SE_kI=8s_TTT`{+|*2{z#4g{sG>V75LxZ(ZsLJcmICzZ$P8Qu3cn2_21v_@Z7eaTBM7}FaN7F>pFnV4wp7f|c3@H5t=ve?O);J=P zpq7aSeKJ5dp$>9LUG$^>`G=_qQ&W!lRFqvqYb@Ot;XyO`mUJ~j#1E$#Z`KQBb4IL) zlm+?ZCBNaV0br7xZH@`C0v-~w+}k6$=*(lPq+xV)27C1Ye|I{qd~~dyL}=o5 zm|l#DCKz~*)HJIfFaFw2D>Uz`4?7K*eAx2X{{HEOCU~BT3g)#cE-87iy$!vbinY^3 z^TCvD<*m-t7WAJE|20vp^r|z#0PW7bZyOFh2D~ZVUxq9{&>&0Bx6$;u|NXmL*%n&D zV!p0Rp+1{UPKoC?kLOx8j~fn1O(pq*F&nA>oe4US)ZZIo4>Mk)NN| zwlQ`U3k4_HvE0z-{I6jbQjn&--Om@D4}bW~bgWv|{Tc`i327G$P6{>weL;xBzkley z*0@9P&o(^))#h6lWB4~nmpn;4wL5>~x>6hZz8YS21`A7kWXOr8zsuSB?w?oys%#75 zaxE5!?CxD{lw0eIv?{N=JqFk9Aqph2(u{xh85If&p2z40)teBHFwh^y0V{ad?JK9TC2Rxw7lw+7Mg{ zx^8HGAt9MU4kt9}N2I3pC0+ON{bs4amH94}oZG+Z{BC6b&_hS-6$4CzDXyyQ8(#5D z6@Klx49?0X27Wf$5b1CQB#)@5 zKpe8JaAb36XS3xF^r=b1$=#ga;jOT~kbih{9siwf0w- zYwJj`akXX6-D2H(W`-+K_9OSa^W2^csVmMtBD{P>Y;@{1PU*y^#|-(;t5f+9YoZBC zl2g$Xs6XCa>tqvCmyQQNI#?J`PS?3GQ5{_j_$+ljEGWHN5kEf2_i5YbhX^t_t>vsX zA70L&nm2X3XvXq){Iu@e$(u? z%%IULLB|_=MOP+z(nsTqol5tk7g@WyH}7-^rYRb0y3*`JUIes80{~sqVd)}#dVAb0 z^DS&WI#QC{DcyJJuO-SuL~abu^_8Y3Bdk|mq0K6RjRLvt&CXy|IpP0DuZZaW8QMwM z6NYpYy1}7YsLteY*AFyszJVqsUOW;8+T7KpCndiFROXhgH~$ma*;IV-!)>XuXw6T6gBJA}b3P+OPLEuNIoZsvt zuq8o?wNtDYRAeQD(cZouzgw4o1i*DFC+^2yEpA6XwMuw0SkIa^ECfI=t>Sg|F#x8Z zXCvHNPddI`$K>r55hgr%@NR_n?`N2=FxG-Y(_p`6+7u4>luUH2F!tXYL)i%j8zTXZ zerf%XilGzEJit9wDS&;oEOL$dB z&&yR9-QmGtkScaQLj1@eyFVMlkD;WaUQbQaiJe|$&6@(I><4ZQgBmz_kfu3z*fsd_ zY+~W)ofQMAFEo#_kQi?}{MQJ*_N7gyG zc<$rl2K*t>Uyl*6;$O21;F{AaaS8uEejT<9j%JPqO%i(cE~pJ6^%=zo(@RVV15`t+ zcwn3#Ckr4B@9#|>#VFPh_JzPRsIzvvPEB}19z$6aAdLMdaG9KIr{)eJ+Ob|>KnB18 zOyGNpz2GJKadoPVAHiLnb3dxVN-d}~}>f42AP4-Ekz)2Vy#XL;=AR#pXW=?`M=^KNh0 z&{=U4f1r^;qR{Xtp-1}-D96CHk5u~yzcSs@a#!m!xUXnj-*Iu9us1y=5@5J zVGOjw2M8D&NClzl1d4MPdiQo*%8^@l5dRz-KY+8TLsdRE*@F1#242TXQh=!$$0B#H*36A(l% z;$WC;x@s#!u2D4hOboVH{0`M-PDU({ctG{3-yB>Hw1BH;WKhm}(ym}atSrp2{4d;b z((6dioURT{pA!f#)E52uA$b5jYf86iXbjqwq`-eSO_3g)`xT$US5^1~P8oh#^(U=7NiYU4(d5-M*r&mRiWzB)4$-r7t+b6h5a{$~L!i^S1JYN2T^u-rhZDfV z8u1BXADI}gWmcQ&OAXFz1SZcweceOFB4GFhF0l{ z-#0oC*RAZ<6&eQ~ZwbFgrdFX7i2@Y(8M?Skd{Y9h0qPk^AKl;k$UL&?`qv)`$7loO z0k@SBB;amZ&xD5{2okPf2kjxW2OqPJ=f_0Tdv^6?0Hr3mm;*OJ)ISXFZ;>y{>PqBmGp+`t zQ?6CmDuedxF?1G8*cXAeHb2=KNyGn;3i{s%0m+E}veEY#&`HN>6{_RMZXTWPE){Ci zDslVlef$bh)-(xr0LkptCK8b;>WEr885Oz}jjRLQZXCgf_JZ+B^8)u@a>It6AeIdA zFKMA(=>iey4|u0b{$EC_Uj-dQaU6{dsC(g}r|jzFjabP0u0$TY_#b@Ie>++4UF()E zV#lRvYj$cYc?*dq^#-7Y8?(D|d~J0-D}xZmkSr~rnrgSdL7#{W00LEN73l&vFLP*) zkqXMLoc~bNXNwv;9>J>>wX}zJws`+)QwN9x)(_BK7zf%6Ny~DrGOfb7!|`GDx`tBK zImvm8dRQa?6@2^;fKZEy9*Ff{!A0W^C?xVY{d1dfV7HKG3KIC^X=GFYhw-|)Kds<* zkW(Wi*=pNBF#-yEDZ66*mqexh_pK+Tn~~@BcBOm#8Qd=}QgDNBgJlLl%X|zf7(}9* z0AU%a8lDmGRI_&KZw$st0_PpK4Me>EV9ibygi@+PM6n2;`Jj&*M5My*W44uY>9?Te z`aK1IsOPmBOsmML0I;Z4z$n39pY`qF-rG-4844*XzINEiVc z`+JAeQG-1>nhN~3C&W9OAouTPC-H>?z2AD3#?5W_nbnwP)%)$+ zSqH&cMj?+Xg*<8+EUdFo&n%beUv++8zs98xn4Uf$LVkf4!aVzky>RZIA9n-j@+{PI z5}xe|1Y=6_;|Ct+ia&@n;6?wAsyd4fCsFaD$mNS+t$U0w&8Dx!y^U7_P}BPDOM$#16Tx>K$Pz);Mv!^5bn#+`%{g6G!nC1M8ohG@)TAv7OYG ze9A`rWeN!}iRXf&-yS$^?=FLg1;=fHRNVkx{j_8|H%g zRW+NNkzwbmpIrH-y3MJS93m5?j@jBa9NYn0?$2XMZSADxOim!$3edN&fE1Sy)F$5X zj9tgv{3a!(&CXuI{(9fb>?hBm{hbzKSAfa>e4R=95&1#|OCI|E+}>4gR6Ih$f=vw! zrUT=QL5Z+WU9$WK*K?!$^gDpcx{TZsLq9+#j2WQpE`hN;zJBFQoo2cDJ=ku5qm1+W zXk_5E6M$em%NN23epZfO=H%-9fOr~Xnj=Ifkgq%gnhD*e2$oo{k3IwU^2gA?y#RUm zGej2%qg~{`y$cbad5K0@49eoo3~zV*%iCd8hr2=_ZMg7;`@F$fQ!NFsiX%WQxio?78wc%1%#d~BZj zmjTtvJemj-Md7yL<0)#f^Kj@3)5~mFuY$rdO=J^(iZiyh&i!q-9zhqv{CoQ!GQ_~C zAP9(5L>#+poqKkF;yVw3znF!mb1ox#@ zW6ooGbdMp#1B&#rBRUwTWCR4*JTyQ1-#|qM8Ic`rhd>Z2Ivh*_Qu5ngf==imfsqoNKZriRAMQ3c%rnFei{^=H zwN;8ake%SLOnVZPUj+C(A~C=`*vhuv&QOT$iV$71OCBB7Gl-~$9sWClTqy@Y3~HZn zWjcU!|MI_TDJkJlJH&>rAU5<}98C?UA{4P)2k?X#9vyz2#ek{G0nC0|3Xj};z#g&- zmwq|h0Y<3yNA7L#KjN)w4FuW!9ZI>7wOl@`M;DKqnAaoL5lK6PlDPOrME3_m+JHyp zLwr}3Y+45r>@i(=c_Vw#(dX$%WDYbdAFom_c@Rh9yJkav@5dIBT_H6(W{Pdl!;d4=ph~UdxWt!$IDoBi>#W7d@^cW%!Z(x;Rfi!1l@LQ$!Xdg#ZE^q$cmHRwHPbZ(TuVsY9BFwqf4{Z~qJ zI5+Ep0Mpwnw1_6u!15Bs8iSZ>cm033J0=c9MBM3YK{OCV&EUi>E9>s@A%!RbUWF0r ziYjD^k#I(P7flTvuyaRphEO_xL}1Rag!tB`5*4~ zJaYd^aPYtimU?UJM{h!%2Lh1-5glWKR~je$_gqGoZZFq+no?VioJSsnDEPk|u`4ns z9{_hzUhkXVcw%D2FgVl$E4;*}g{c7p^|E9C#lwu#&g#kn=5p)9C{ETcI4{>`HQ|Q# zHVMukyxa`i=JRhEF$lpFl2Kqja84Nlw>4aMOp@{a5px%PneB9cR}O+k7HA4M8MTX9 zYrjtG2^$WZvR=mub^I+|{~QK_G=_Mm3kL9`CA+@uONxYjTmTm(4+g}Klhwd0Zo+Z) zqT3ue3s{<{9RDe>tHYow4886_y+uiTgI&IR2>C8qo5O$DgQrlB90(>ui(Fb5SCa>! zSl+yYR=7tdWNcQ@`>(JDL3di1^LncZGj0cQq(;$`aAi%@2Js%V50sjV0a%2r2 z5q|Tlp_~O72&?@cpa4#{SNu3DH?nNP63DW3mc`Bew&gJ)Ra{`_dV2icC%TSlE9fqK z3B$s~cyW>)H^&Gy1zIO8-0+{wn+^$Vk|luORID&2CMWCsgy2#K`Gq6{;DG{5i*2U) zRFJk<1Cs_gLNVKQHs)q7nhY7BSGViP^6M2H2(bsDU<`rrm6{K&Aaeqkx^Zm{p*G-I zXKjjQE<&)Hcb=WVFtXHaBq#e@i6GZ_oPDNj@-{9F;~|ROH~nW+kVeC_51;;T&%AdV zF;>LT#T{D%jGrH@{vA-3?Y+Kc=&se2oH_Kx4jIgu|3I3&8r-1yf&$!p1x;o((Gae` zy@m|q%M_`T*0Q~N?Wx59RfZT7+9U56Va42z{LfT5>+;)-%*+LKx>#2yppl!KAnlge zY+1l=Ox}*z5ZD^)@xYPj>bm*9d?f$K88i+-`tB{aS}NGWw~=HI;?ui%eeD1c9Mh{A z2C7nq0JMt?XG4x20h0)ie;9OicOu#Sz5@XW&i8Ol{1?3?BZ0k+Jb^;{N>4kC(CL@F7gk&3aVE%2(>tCTQgE^K8su+=s-`JkN{RaccxNz@ZK?8 zTF0#hfDb4&xtpg~4_GzJA8AJs$#+H<^yd_2UD`WQOhC}`j9onDxLY=$D^$!K5Ohp4 zF{kT9yx78!JKXuR-Fn59{{_!+iQO34zumU+>cigynvM4tppS_a#Cdo<;DHBDrw*B3 zyHhwGNUzCj&rJe;Q>=#yxdn;_A>laL2%;{E5?LmhjQ^s~OSb_m!>8S9Auk*cbi@0% z${&m%yKGPfZk2Ox*pR_P}uG;+fNwBB` z$_6T@`EKD6RtID(w`mW&r0G4?H~%t|FO{`aS^c{bf^WCNT!?@jtUGIl>b1<<#1EL( z)CC-Wr|_p1piUeDkhA`c*pA^v>t9APw;=s+`#Wy1iZ}p^6asja28FRHC@k$wPowFM zpxoj&mP-BWVc2fhfR zERX(-wFf~HqO8Xo#23BeAo1OtiuZ>oR(+r<@@hJ7=?SU6K?)UsnW0ech`?)%jOYN= zLcpHZ{)j^flmdK=%B-H7Hf)HA_5YJv-{9=j0a-QcrV%UStQC)p^;tIj9!koX{E+lt zgLl5@gZ*+N9^~XhH8pRqZU7tLZ449Tmvw^>e)juz5ct_33lDh+MjKZyP@Sp-F;ST! zpw-_N>M1WLT^#5+T@Q-IrP#38iaDF&s?O}EIa?vxJ^%3gf-2XDaak4=-Pq&bNCb^o z7yQsM;H(>r5|IN2ohLKw#z)e$wzt4pLW#_2f~C1hR)`0`GpDGsx5z{t<%n#YT61Wb zUGt7ZfK@%Y5#{d-j;A7ZDq^~-%EnhBUEbydooLo}(Lky!)GGDdqY9j+DqfhF`8zUS zbgTWPj@vF`%dutkSc|g0#TuC*yZHY1v;mDc-~W6W=AHRA#N}$oBYj!qD&syM=R$li z)iV2GSSFW}<*=LBR{V|o2Dlmwh9>O^a=J&67wx^msNZZz9O_0?u;<@EaKxV8hV?WX zEK>Tdlh$CA(+CBPi|zH9Y>sp4^84;ynecaUqCu{?RJWYwDe~li&~8g=89h2k#=0Si zDijSkd|-KMNA*A{G(XVQBM+RfY}wa&T>^r|GRu|kE{je^J&zwEQejeaQ>71!#_enj z+YF$ov-`y;x4&TJ?-=|oiXKikMhJSAFyaRm?v zL6+@uHgHI%Qq5)E(OQ|_Lti!x^7~*t>&V@YAlWp2Q{uBRp(jv}3t5l;te(6p}6 zS0VjnSUJ0BBks`cSI8pWivuAwt;5^PYrsViLQxG)oj8VK-OXmafW`})EZce1Lv?X? z=s4=julk`2zMrD!5=wTO)T?sf>sP9gZGH`6+6V+9Zz%8r+V#kFXCCPHl@9U5xt8j0 zuy6#RK7T0?LsMV6d^sKvCdJO4pp!rhuk*58o8?eOrQlXFcK(g)fcEl^>!uSsb~?7Q zW@9_iX%D+Hgw?9DL{pb-96=FT9C$NG6M?BiMABK`b?SNI%K`polLtXu*N`R^1faA) z5zRGFns5Mv^21+sj3%pzsG0&Ww3!L-q*7t6qa2YRF-DNCM z1XfP~zs}AgE&a==zbpBM6`0ZYgWGm zU;dqs;vg>(I}9aAvYhs>U_nQ(VKtd`%y@fPT+K_z-c1pBgp zOZ&13zNTu!2C^m_$7K0R4+wbQDhO8yMAAl*?L>!O!V}ZcT_+VpCUhy(6`vx|jILO9 zS$GtLD!u*5)4wN^^1tAAeC;V))H_BP=rtJVyEDEb6*k#aoSXVnj?YkKe&7fnzXJL> zBKT@yea9RJqy4oHTz8!C%j_29@!m0l^ih>FuiK1(B{-M~zElYfO8CzQzeyyIg+0I; zepD}B;=ys?T!y(3^SYwC|HuP=M2N)OIQQR4g0h!_q^PTRWjVc(r3y*|ai_U_w+dNi zlf?mhqM$8J61N(Jq!Y;@WUt+(W(kq1*ds2mTi?-#Ii-GbFy1R!^NA)U@ zIli+1=br*0b^7)7#L||TfX`%^f-hS+m&W=-s`0HHwx!~7F0!HBXoaN~Y`%gMAAUWY zvJItk-QC?@jP)Z(Ur|Uxj#Q#>D3)~ujshh_PRf1)qoAY|*lEUcyZk!gdM>$as}W5{ zN{++`aMGZo+Kq>()RCV+5uJaT{gVnTV>oUI8dT&*&k;MVs3(s!EK1c-H11zT>O)JO zn+lX|WtiO;p6h!EA~C>BXZ8BBy?L|K^(fi^oDG41u!*$xDcS!@u`5(^n^%2AxMDKH zbz^ZPr&-V+S_UB!pffx-vhrWFk&zNOF1owyM>cY0qK*?|E;7*&}LUD5l-+`}+c8n^IB<1! zQRyt=B_o}wm|^oge%B*wV}Z;c-y2xHs{Hc3c^%%K$?~lRo9qkAPzouyIqbeUm(x4~ zHf#<@sh>|iF)W7A7!l!6y``MkJw^!B!onZ|Y*Mg1I)~=>;G>16>Sf3hmVvIlc@jQr zM}q88WMgGB`ZT+)sO~N-O7%(Gd^^kQS-7!eHV?(Xo_gim9T+fsoY7t(b)!QFGtr@c zN^^I!Yd!&BE8kngP~kGm0+6pIKql_<@?u*XyDxHW1T~zVoCJ8NgV-4)2#PL;I%nn1 zMGkE%uPzSZ2C!rw>#}Wt^g+gL?%PZ#|JnRHasVtCu>F6Qu3S8T;g4Uzx&ST)G(bf; z0->{Jt$e$0b91nUMuxKpH-l-QE;`{Cg02VHIFygz#2Urif@3tb82D>+(xHQC^LY4= z$~Z(mu|MJ)2QtPS0W1~mbzUBb7%0CwL=WCY0&vu;{^G^{x3O9~m$TLZ!PEdZ0}-Xb zW?t=0(4k)m2c`A5AHh}sQEB;bL^yu2A)F0ob#Z*xeZ0U#?#r(K!{DAliU{>QczIqI zaunUtP_K|Qmqpu(+zev4bKm!6DP8v#3RHXr4lY@-BDHm|b!Dap>7dB|FpBlK@pVTB z+-UEmb}bPM>>pBg(Ty`Ygkin{X( zPfrHtD$Hy1wGs_TKyAnZ(IE%7d~<71u+C!k$Ul0%ct@ZN&P=^}gy@0}0w!7^hlz-E zP;&<&9c-}@@Q_HD_PP+vFM#;^8WRJ96g$B+i0|iv$l?K=+HFMV>#Q{Omia?n9HdtV z9gh)F;jRX<5hNuD|FL8F=6>&3VxgX{3&=#BH>Trt0ic1D;6HSn%y6c-9C+w03xZM3 zokK^TF*63%4l_KCm_ihFU#(wF*nQoyniE8>-}&8sBRbO4 zloCq(khE#5A}Wd-5LP)))HRz!rF*BRRo%{)JTs*&WR1X=e-yJuT zBS49e>mjcrAZP%HDU$##<&k$t^{Cs0&i^dNB0!;<4bkqmkhQ589=6GbMZJl$Igeg# z=!*{g_Jh}%$1e|Roh8p->!}5S9Um5I$goP`)pd}RisUts(dVGF&3l8CZ;=1ryaecsb)t`K;TYE`$-(G9InXUu4CKV*) z5k99;th|03_2m`R&LD?u!&@dm)OQvvpAa70UfI3t8bafMA|{T#fpdHj;;rhFYdhGx zVLnuUWP@?N>6HdE8dmK=u+~pM zN@?EBM|odAGWrjIdIxFxY>~q#+WwDb*O6_>YItC`Uhm${>jESn4J$7o2PaZhBMkj$ z@Q?|j?H{hr%;rjV?!nm0yZ5!i`y5}d|Ngf3asWLPj)MsSjDN>3sI~r3G}G0U%f)`w z0VZl-V+oo95)h+gs=x=LJbLA-3}70pXU?OpYk<%Ojp)IrRsQ;YwYqA1-X4|vx{XiU z9N(k(IACAFPZT7(KeSB?gM;?^iC2g0&A0AQ$-2v0g9ufZwTfhyg`1P$u7kxnmy8xm zau-Lz@YFIwz0SDlBbp)vr3;*MLbzo#zscNJTgFJavIp@U5jEk5hNv?R+$;*%Y8yN7 zXk6mMUxm3$ZCTiVF^w`Cv~sAjppiQMr2qjypd*TTFdfXFAIzUkF&PBeaoJuyI zfuHDd_|L^OM9;1-HD9DpqRczhQ-hBG@_z)Q#s5R9A9&0?{01GZL#RYNsPGI#Hu zKY#Zxp>qlDSII&?v?g5MQ@wMPAgi8=-bVOX)(gV>a*AJ$>j)7DO}FyO2mc5hJb6_9 zL9>8s`VGg8ygO*p;XNKYQQPpIaL2`kriD3MeH|IY6%Qq~+{a0J&Weh`9%qQ}o`da? z{P!D=-tS(Xy-o$26@?1BrR6IXId=9q@Kt4YZ;Kyr9UrP-ysMYI;3|Lb`1)Z)E^&Y zT~-=9qdD;5PMtZSa3>r=IbhRga!j5Ug_?B#^S*c7U-cNbTZdsAq1>(<+H7C?|X0)`M=+(e}2gF z((kbZa1~ujy;m&ffik3MheVo2mxLe1| zF9;t;6?G=lKB38`ikObKD1Ue=GZY4uAjd z|9fl!!GRC>`x58=EbyP-{O<=2X5xS6;eY4h&z?a3`M>sXFdJfr$}&-?vE;XJ&s5da z=(Fr>ZKWut$P1(sxcNvudK3j6=yJj;zJ0rR?h6eev-yo1^78Uc7I)k(UYaQ0MqMvz ziV2Zduncu~ZxkFp53Q}=R|Z$k=?Mx7zCISVs_ly!{uUS&n(%q`^W1pcm#c*Me=Wl= zhw8rvSXc+vH_LqRxq>=%X@CsH%=uRG`0xj9B9DcV73mOW4W6CF5EacO>s-_$U4h+S z_v-DFppBlmjLZi7YKYrjK2=MLUZZ!{=WXyr)0%Y#>Y`GbvY1}|L=>B02l_06uGEl4las z^nNcSHkP|cN%+-8LYkKSOZ+J*@-=>~Xd3QWO-Csbo_1U7!?LT+yIHH17r5(Hw3wJQ z=tHjmEaoB9-tohxwdu=@!+3Tto>#m}<6fae&n|zhYRkpvgUnOE_Jk_#uE0i&afaN6 zGnK3B!jnT^)D=Qq6Crc+LC;Vn9n-wOc=^}~kIhfY_qzhATFbE${P1Yp-^7JqZJm{y zZr#%2iYou=p7=;(YzEE_<5s|}6*;n2v`2$}qFZzHW%icqStfJwV7WUoHPjm;xqup! zwkJwl-r8aN9*dERU>AdSn)RAUc_uX2O7`;li=y+?m#P`)fNMBdQurZ0KBvohcd5o< zF001rVH#z+zRWaVpVrovSgw&oW28i>gP2CqgU{t<8^i9cuTFB;L#x>Rat=3%ioFd9 zE$5J&{&>$|23b;W%_#Oer@0#WFeaO|G9mTKDy4N&?PWiu4CRV5cK4o%I-9I}q&Td3 z(&dCP2rGAX$uua|20VwspqM4ir0tc@hFzVC^WJ)d}Q-Y@Ws_U1kl$InHFEZV! zZr0c}|IHCvF)ITUB&48V5nJBa=o+c==>Vij(RJp&nDP&qJ9pebQXC!a9oG3|J}Sat z)F}ytYv_cyxT_gJkMT&@f0;LW$L;<_YpIwK!EP8Vyfe$Iko4|_vnq4>BX2)WEx8la zH*U)H=G5$BSGl{(OQ5p5;1$*!HgF^iNM`m1IhK!I!mH zl)S!(s>lDS1xQa2;=)syb%@kYu^ z&iI>{n7pDL_v^6X+UMH5PBU(3g=TSdrdMjx$e}9dM^q?PwEP9@jT6yUo9!>=tliCA zCGt7T>%r(FmKokL=EEQ-W4T1DbdE9(b(g9e_CMUl_&nO*Z-rN6HOAZ=9oOFtTt;&< zY0Czf&AOkaz)f$7$0_I)?YKUb*Js)WNr{i(u(VVr(LsTM@5`Kbo}NI9wX!wy-MdQ6 zXfxOS{x}}VMV9pWj3&oD;xp>anP# zDNA9>_lxk2UVV5rUKdi9d6-$ArR3L3m(8D^bAgMnQP(CS%`C{5sjuEy{;;RyP}DRQgt;vTfFa)I`p!sFKcOPMc@BzAX4jSDy@m<~9pP+XMyTyEn;r<|b{j+t;-AG)Zh z-z<*LPtBw{(&s>EUbTB<^^PYUe^UMT2HCq7QGU?^=_a20EiK*m^4Qrr_pgFq!JA&P z5mF>%-u=AGaDP!Nw)D}pY&7}8YI==R%T6buZtn2cmTq?*V%Pqz4%D#7s9~d(#7gn% zY^oT%mhqX|cUSLI_1VX!H)P1|g^NZ`Z5Z5QODwoOy=gwZSe_^qNnK-a)|np2V;g#j z3H>cRxA2G4YG81h&!di1F)OJ~y;&-L1<}l7eLpaP?GM*`D5!ZmB|K6<%?z>Et zH(?v^VoAJd;mc=(j*I;KkX=ZXPxQt&Qm!OqppCw_lg43`@Uw!(b6sV$MuLn7+~4ab zgM0?tt5M^_j}68i40W8ie|a85HuPp74HFUHt%n!?$tq>FO{UYpO8e*HB4(#oFmTdI z{j72Orai^8@%7iCYi(Ulm?RGM)O+!fD{0=(;n)T-sdv~HdIRwqo_0~pONw{j`c;xM zeoy`CKD9^cq;U+TY4>roEh0x-ZGFn0bR)eb7Q36dj%T(E-YCy;F+}b2clDT3$3%QV z_TPghcoSA(PiiLg@qX65xiCRvZE99prReO&Rd8Qa=mVJNYd-_#7nVQLRoNP& zxD_fq@N)M0PP3H6L2EvW_L){Tt0~!NNJcmo+OJH^R4EZfJ=VQ-F#$Bf)F(B5J@v3{ zN%-tO;Tu^IfRBWDWYM}m^ZIf_V1w+ZTelME$V4iL*&k5ao%hpuLR>yXoGCWPT-?Ct zIk~>OA}{W3He*SUrk;`|GJy46u)USqlbj<$PZebInbk>PlAnfpvO!1*V{rj<_zF=- z!^Ve=6;jmYm#x}zMalE=q1I2HmZh|>DpGVzjVR@&5=*Y{EXtdEzMC>1O)%+mlFyK6 z`tg1uZb3DIi%#~?uS@w;*B@Bfq6&Th%#89>(Q;NIyM zQ?^}~y^t8Dxh!WQ8%#q>`&35guZtIJR+?o5_Y%l>Z8kr0hPkO|afnjZn=ER+SPO>-rAImo~*W`Se$!?n0tk!4=s&)?aEtq4LCt@yL zDEs1Khg!IXU`w5FTU}{qge_BAmxe$6KafqOb@glzMMb@(`G4#vbSx+K(Z8McIniB1)se!&AUI4ZyGV!b`k}dxg6yr7DUc*vFro{~{sbxWx{Ga{3Pn*WLG1 zQ_rfZtLbmwehAN|v@+3XUC)#s)%DpnD=RC4P2Z2xq&Fd&*LDW7RN|77iqD>X6c1z0 zfVTJYjS(CQ@Ln9@`ST-dHu)xfNgBmAdMvyybZBm=vE8keTT$Ecf}5@n#>f&odh`opysNh_=OYtf`n*k(I%~^9nrjeD#MlsTgB8I>vIM zLC(tRGqjt0A4DgUs#}Zp_V$+VNLA{{dLo+ptmW>ZLzA{!0kAY%E0adxw|H#k-swDf zqLi&G2A`6EcM;mwy0pxCV&Rv$PFu@!<8E#!>*-b+8NKSt%4c6+9_vB=vTl_|W*&Fx82q#TCr4_vW(`P4Zpw(TF~wjs~jWZ?Mg+e)*<*?G*< z=FsII`}DLTYM<_?W!>emX?P?p5mXm^6HCG#(3>07WM2L~^xbtPO-7Sm>iHh3swy!E zG1soir^v$`%Eyby&vs4<;#XxoY3(n3dbN3Jbi(QKix={W!B$)2@{ydazFgvy-TO0p z8yWSs12iE_v)n^P)~$h5-1XM8;vH#|jC9lw+LFX1Lf;L^$)igY^xp!)QprF9HQPh07Ru=_hgKd+JqVzrY;Z1iu(m8W?QG~D@U zNnzT!_w_UTj;(yr=Ry{HdD)#rHah8dYj6EHn;G7`k=IR7EH7&>Emlkm<=D&A=+wR* zHQ(na9vZw*EJMQ2qd)LbuJs81#clzYk;;>~W<#2hoF=VMT(a7(ATw@{xDx=aL7nNU z@i(7TPqm0rtVN}G6%@~74d$7R&aJ1;`&e18&6W&`h^uAq4;CxW+G5(5+B~g!ZYqnV zyg7CHtcvin1bP7C92}V{1LD4fvUB|yiXi!B!-@r^?TslLGJ#yJH#bg-i%H4LKK^vq zU1G-jV`{3ky#_~SXaA^TU`&*_SIZ2U#Akc#@haNtDXVWcj$J%0oATqq{g4t#snq-* zaAk!zajeaxmLtjITJ%g*Opb**;q*mi(!62QVP<=5JJ_zdM}}MZ12r}e_chQnN~Y;v zKW>@M280GCSr>;I^}Uzsb#w|FX^QFW2|fx}2gV>ze_2k*nt`J=mqVTYR>N8;hU=EE zBw#rqBO9i+H*BKTJWIiceU7C*628yz(ZN^kQBUW3WJY)19g)n(VY|@)AEhNgW^H>zQCI2TmoyI%!) zpJ9lPj9gdt={4au-T0BRw{6sQYo0sro~RD~w6XZh)>Z{Vl1K81;=&(Aws=yt#z{ER zE#|q`xI+Fq)h5-o-s)dp)}Xnu*J@r=Xs~#Aw!H59cUkQI9^|}-450t}_D@fWrWEX0 zRtpz;ztFYjAsiIE&ZJl40&w3@3# zDZ=wBRSnx&Sz4MqepXD(uW7l4hwanJL}*;rs~7KjM3rl1HfR{dP!Z6X$x*D$X~tR1 zIx?ErAh}}8tkT4oEJeC#N@!UeP)v5pP|$o=dZr^NRf!EN$giL5!lj=dHHF5t|wl*!ovW(2#@1>dd=$l_wS1) zV;tFaza!zacGiM=I@Wc+CE(gUcB4*4d!Evx$B)kdT<%E2l%>|Ql=sixLI(v|Z;gk| zu1>f0%!>GujCUM~14JdhG34sHZc%JAzd9NF^u#WlY0y#b>S{7j)S=7R?B(nTVL|x#S27(SY0SyoJgU1Rv*el!ejL@NhWroBhoi8Fwg;b5QlL$ zE9Pb0pxr1Q9vKh2W1;nIr&@^}^lX4|O~U%vjq~=P5_iFJ9m85JU2M0=%u2}53eQ;} z0c$+Y5dCxO8jT*jwoc!!gCVcAO0d{-yi}iVP2{lq^%!{mgRft|+SAi|EfpG_iHh)ZtTeOm2Q z&&2Z6ijZ*2lkj%V4XjX8-gVeEu#CM-#zf;lIf=%P9X(S|{K%RK89`OY zr)1WPrcGvwIZ1`P4Qx-FpM`3cCQ!JpJ{l~?MyxeDpN-_GpJQs$*Kdky!Q<+W1Hh+` zA?0`Y9Ah_f5|dAG`EqhoG_QK*HNma1pu;DxJDRtmnEKh-9JyKJ3PMW?>!r>%%eN_X zxI83F)F12D`kXPOM786*aC33GQeoTXCtXC5;RpFvzWhn;Yd>e&X0EN7Zry>MayFJH z&fIdS?ZZ@$xb%wC*}raR-qpY?ymvIc^3j68-mx`r_Perg^d9v8Rlk03p|8bF=g^Ex zBbmdeHa2g1`|vKkgrww;JEUFLuiapF9EgkbNU=>jp)pZt`dkl_&mueu!r zdA0G|&4{e^6Ew7RcKynCvQPuvamB}N$k3CE3g`*bsHB^&Z-2Zgh-YpSeihnsgzR`q zjrHC*s0leYP8tfPXVNroG&9O})EiC|?(Tka*$~Iu-EHCQ_QtSQ(|v+OOCAH8wM&f`dQm=1=n{naGZl@DJ|k zaeTD!?doHB>%7?+*frffeXpnf$%)L%LX^nKD6!Nl>Y&nHzQ zt4yVDaa-*|v~)wEGzHi5h#8eKwLbj&v*DP9-1&NZD?4#~8><1qe2bmCASu7dyV5 zE|Tva9~ZHcPk(2B176d$$C~<4aJkP``>vSsuC&9kK}xM$Cm-Zj+*QxrdvncmnmTV7n3Wme z^;^n?DojA*WBx_`J{;R!u-UAhl z@xqdCa~AZK3ujT^RU|D>MkPZ?39%*$9Njc;j()i^*{lMd6&S*G%u5C8Y4DmPoW}1m zi)QHeR+TJ;b$=^4g3D}yGeGi|;Nl4ir?`Flg0$Tc9~R&(R8rAA9kbV#Wukc!A^R-R z^~ll}4hNgO>HP5B+6!r8<8*4aFCT#hl7l2@N&N{pnp#c zyH`rTGM_)B41&rU)B`wJOQREjEv9IdyBPN6nXG3GXOQzde6(AN3M53M(W?M|#tldZ zyFm}E_NUN#?5bd~af?t-NNAlPtK^yM+IpXSg~x=I?_ilimQh$wTU%a6&*+42Eu0YG zBNkM0nmVXKMXtt=L+fV)NL4>88r?F(*-CdnwT44_Gt}fE061eyt+(nJO5wBApkiTj z%N=%1a*}J?E_m$iG{!XbD}?(IX&ej>hmr8tb1tv$+z++rau}mK*l(a2r6CYwB zn^d|QPEA8yWzgTh(Xmr%(`#M1x2GIhNSd6ovBPD!?x9tB3MNa=J}EQeW3k}WGt#X3 z=%p0_S!|0&BS97)D7k>Ci(J%KN*zku)Fkp7R*IsO`Yx*;uH79=KI?0`&V$|Z8Z6gz z7PbC?FHz%2_=+k#)^f0V$ZEqg`m;mL`DWt%AOqc*kj2;^3`2rH!7$O%bTREa<#=tw zW)zBs4yn>~y_lT4-j0GZHgY!X>v7xu3m-OINoSCu>**%VZj`&oV{H4LEmRvEdsMNq zGMdd|4HqwgfhS1qbQ*l=CMV%C3!bc`FLAzo`^R>|CV=u=x7s*#M=G{WYbQbAPQVIu z>GS8fV_I*uuI}dJ8}^sTA-cE0;*ti*=6$nyzLFl3qW(~`Jq7+DgN#@er+MV=83VbJ z8_w+-vCXi2t3qdo#4Oa%O-a;Kg_y++2d&VCp(mBi&9l=iJC0-zXvI$GtUrVQHu#l~ zuPS1*DgrFT_^bWOepAJs47v5<;K1_oRPYT2tBnC$M}7^xPA}a;L@ydTQhTbE@T@r| zD{Ep(bm3yB9yUqp={5ls&W;Hh_BSi8Xxv~~^xWMq-U_dNyTp9w!L4#nBMirpt`ZK% zJdS{dW|`$|pMIUyXE~9Tk%*H~N>^fFBdR79^^eFe@aLa!20w9}HqXT9xTD?Z-5HyJ zQ~HADPR)F2j;XG$j#tBZUpwuSW9sEAN)HEo z!^7o=$|hoqk?W_-E!8Bdn{oJ))-0T;EoS!mw(t)hId-IGdXCTf{ORvJeQS_&RD1alL4A;WGa4+h&zt_sGLpk6bbD^w z9YmCY)RfZuyI}6era_JC1%(nx)CE7XWd@`p*Bry2`~2r!4cq9QX=!r%F#_kMs>^w6 z5YbdX5l}31vQJD%nELYKh}x&eFV0@M9S}`>^QIiX!|IO&@D-;{S)Q?a26;YuJMQY7 zQL_+`k^tLI`SC7%-}jsCNK1y1Fn~OE;_Q_lbs-EULc$1|C9~~+-_RgA0A9BTtC?%4 zq~W~QL9dh=>_;J(3F>?IVfnJ11>OPcE{&PajL5zs=@>p$f4*fe6Qrmtg2N~Yu7z9{ zWD0LTzfMpB8FvQZu{uB~%TUX$o1c2Pp0?&mRRU@yHf=!ofSR{rs=q5_EHeX)s2Zp#VD_42Kqoj#Fo#dEhNsZL$& z%$hk3GgccDdLtiHFhpuATJJSdN|Gc7Ra*p(yy*J&`ZUwf=)yoTs6Gr#4?o=j{$Sl- za^J!to5yxxj{R{4;CHC!O8M~NgVpkw7?WzY@CkhKU~M9Y>BKNaxKh16yuOyx#JACJ z>9AP3VLS^;<3}Xv;LVUJ`~3MQM9Kqs%@E|ZP|NYwLY111FOVC=o4+`dkuhk z^~@$ohNBm2AY_oP{=StYCCdLA@QzC16j6M(;YNiWBcgS= zA=B~!=a~L0u4y22{Q^2@S@`hgiqawpM?*|*G;iY~&4%r}4oDK@sD_1U)@|jdVL}bN zIO}`zo3HfLW^t`gCpX$N)P>n4k-3&@p@lO?z3+#T)~l4JM58 z3q@#t&G3pnV4Zw8-A1QhS^9}JXEO8dF-vSyuhtdEB~81pQTUZL^B90G{&cmwE*AcG zh|cSrl?sSVvp?aor!+IrH`wREt;3#+S8R8lo%E6L%{%H zn3dX&^lnDz0|&;U2kUOiCX<8!CNF%le&~2sKUj0d-G*t0X)J(=%s7<*qc0`dyOI<28S2i52 z7ZMtn`Xm|OXrP?IYHs!C96N|c5J9L&1|2`E2x+_SuXySeYL3&ACr2`n#AaTp3ucs`4Rh-p6ZYYr7cv*!dJ0@uftaeLsz~^+H2LiTl#Ls3;l5 z;qV@~3#epC5n)|&!q13l5@R~D+B|b1DAzxbH6S*CEb!H6DY5p9#+`{~&w9}z=3U_@ z`h7?G>Vp~6X2uN}N`zmXS2+K9<=4~bw}OFti{TK*Ef=jp7#z%g561u)J{n`cmVksRTIIB8SZo&YRgx6ogc#2qHL0CK|mM`Qf6t5twGmMrqEHI8ys>}uJ%G&0s<8#{4@rg+bIr~bvbq4Ka0#5 zqsfE*)B*(Kv0$F6)>4u)RUWZ>4^MXqlngMj9 zVU6H`;?vmh4`KmJl52QHq z3$@)jOr9nYD-w_|*tcWeTxhH}t+`s{P1xA1SeR|!Brwk0%H{|O>*aRg^o02H|vnsCqocpCcyX}U`nf;`F&$3)flKlwb zWD`d*X--0txb2Y1pa8G^(J{-{9Rt_HzuGk&o`rl!ebKH(j-$bRZh#mg4?CBl zBa@l`(z50z)UiE*8lyN;@M?9cr6M4B@AAcq!7P1vczC(S8=>l^=HcrQz(rEz6B(y{ zF0+`H>~GJCKul`mgZNoJ>Mv+oOI7<(qc{(ebYtu?P*xz9C{8G`&5&8}?VW&g5vXH7 z*`Zea>K0UvX}Bac3u60~^Leaih$KQ8%_9WZ*xKF!Ya<{gHmJQo zLSi^KP~4@*?V(LXOiV0dXIDToq;6I^&M9MBzPBDpV+PUs?O>@RDf%r0agsFUjO=kx z7H^uCt||BFJ1rDWzJ(A@f_@9-RwU)v{bD9Fd3p2_~y=lG0?p|FeQ)FrMr%$X;8s6Qk?#a0cy+F) zO<7Y{HvzI8H}dr^CD{%+cgdIE(yOxz!F=*l(wc5d_HWy>0F)%%Mn_Fegeh6}h6KD> zZCio)6DlUAMiW&kk++{hlwiW1AOP(1^z?Lfn3hYpbCl<+S492-+aGDnpgLn9l*@VB zO5J|EK8y=u^T_g}Jfkk=c;}tr&|D6X zZ_LOUuY&b0Isci8xy4)9<&-^+yZ18stlRcU+LG1V#69H7O0*@zb%-*13p9$)#5+4W z3fS)4cPP?UOwo~Yts;E7#oVh!b?qywh(G6BG)=}935SIS7hJMgFuyB9nylh^%RWhX zxW`TVY;9o?wUt*MBp#mYT@Q;pHA90q+Y*ywvM1)dnpsno8@C3|l7F7;Dd}M~?8*z{ zHP>mRVZv^l!Im|$a4ab0|Vv3OB!c5<9U?EOL*7+Ew=&q}VT2@$VtZ(DU0 zarH_wsYk3-eu<&a2UxvXbmR+MM0yT$i-c9X>?PuAW2>2PG%gF0B_U4Fka|r5T0e zqoeFQ*2$*MxT{^UyWj!v#N`O=HKGkZh>4j7Px>U+`+(zT+J;a(x^pgmThBe=BuC!1 z-g_*@$9F|SCfY4kK!9fK)_$P0fiK3(qjj)`^XO?LvGPb-4HrlTZSu|LPjCQXV|3}! zSY804nT#+D+wRk0Y(~Cy+PFO2{NjwcV`cpl^&rqPl;}49cQ7jMj4FM1Xq4GUAP}~5S6fm z)k2@ge6!&xaA-Kh=6by}aK)s|Q9-2Le`|fsE2dcTv}k>{!_%-;JM(>iU=#S)N9<(W zXSw4(SdFwEty69#qA^&ztT?XQHC`>d7?)1&_v0q=9fjza$mm@Jj5uu3x zs$0;viQ%9^fq;I`tm1*;F0ah$ar zb+ac4P$8tg&7N(=93^Sfsb#*nwz|~X)+*D?Ss-52yd1Y4>7eI{;fNXLUR>_&?J#(i zYtDLgcLzKC`+ndE!1iU=W4?`zU={=agJZu0I^;Y9kq5K;JF~g%55djtr}kEve9k}c zf(=&XjCBTfj}?=7=T_hUNU`vtdQYo9^>BwXP^M8a^7Tyg!R%mqh*{fN5ZA&Yn8h~T zAfDP_ElDoZ`Nf?v-ZrFXS)R~y)W<5(B^?$vbwx|?QU3!XHtxV^N-*d}uWc}|kIW4m zXJ_gy;E_JSwtiuq4;+;9da^TsZWjXw+&Wu>n0NAD(-YhBzpWmNVY+GXQL&sD6!X8s~!TEzp@rChggE z+?h&i`uh5AnaQg?z2FFVHI3aUQSPVkM*8BrT!qNG|!-~N$Fqh(ykdP!kzG8J# zbwEME2DG~L7C>cSoPO!-X7*tKjDa@a3_!_sN;3nqZ^McH0_zEHEPjAYI5_)m@9uD3 zr!uYGzkiMM0PmRC23Q#})zcX{Gt@c9JwSR>*y-zMkNA;;`pC8BHFeF?31-olEG8bF z1@rl;911;fiv37U-De%g*7Gu;qdT}&-xHNr?DToEb_b`LbL!?swTz`fhZ=%z1Di6ra#dau%EiSH?ZBtFAH@;K5)k+Pp^%{ zpkon()+}?|JX2&H`)+$c#dSmwV)4qcCm~|ZclIVSAd~gGSAA)y>=>3L`e6QB&_3HO zi*3XtN#g?hv{$*;p76`{-ENlFpC$zIG&VE2Z*!Hz{zK3FHNUUzp91!Jbqam2OCRVh zDnS)7f)GwTyAWF#PGx=(DYBS*YVFY+LsW@c5pOrIMDCsUpdkzv>0ILDMX_t}hVwnqIGEWTc4P$KHaGk+?%l0F590Q?_O(edD$$}?B!Qmmn)pkh%G?<99^8g-)KoJGn$-ASYad^^Q>1}EP#Gw1vkoz3PJ@>Z%< znLFr&>@0K^nkJtK{^mq1gN{Bjm81ObV2&$ts%T~R;YQE1OQJV;Y>JX{F@SS_?#9c? z;Df1t_}1J73eRr7>vZp3k(cA++JVTe*)uuxO4izuQ1R& z|9iSwYb;9xzJie&a*e{cAESH670m-r(-h5jJdu*=9RHP)y@oL%A))=HxsMs2&wZ7+ z+8>TvOEhW=mmI;f`HVPfYNmp2d586h$XC7S6X^HD?=SbZ8Y0U)Pzd?vYZw_B$FAGA zcWyI`aRB$NS!cdcJqlp)pYgryDuU0qd4pb}8U}==9j8Fru8~*?h!^kc1v8*&_tKas zk|$cKK0O;GYJIexDw0=g>vdKGt?w7`*_IQhek$Z07CY4zYF!P)2tNPJ6EB~#i3H?S zz2(e#G8ZxNCk#rNFAgEq1%fY+PL(5-N=4D6q@?r*%LKl=xi(7;nys!j-=1XCOtTVy zN;qXR*C+A6})-*Qhs4|uP$Fr61`*-?d z^&2I!_-q5|tW47ORd+n?=DsRL(SIkNEq7$*OeA-vU7B^AqP&-V-SC%E<1w9N9>)co z1oS=up!D|%bK_s*i<{eftA}*t<^*~g9=U~m?nW_NpfiiW(wJLu2;u2yr{b`ZLfI8# z(6!FGAmvia^8EM3=@?mlAhKE>!~I)h=VH5-qq(okn)lA*+tm*rr_-q@8ksum1smlQ z)aD-wwwh48mK4kez`FPb?Nm6&h9m+Fi!^b2 zwndRLRp@rKr~&}MUve1e=(#{1(A0KAw{L2fY^gN|L^pC%gdgh#JyRR#S1OMR@bH{3 zO3EG?vRs0NK z@ysa9sM*9DiFfaZ_P-QclgHF0?XkFDF40yMk#{Dt)MzwZf+7fA*kYBx?6^wY2JCZ* zlPGkINk--N(sNyT>+Zl{+pwqJgV6a+?J7~(YW2LyJ-~tvPWY|p4?c2sh;nJqtlIEU zh)C^~dk)ZWGk@O0*|VL}HAm{50KKZltV(o=?UJvyg=T4it?lAcjV(Zt>I6;QI%dwi z=ok0~Is3Op_}7%w?Ij!UXvI`#MF_GQ%9cRO$NBM4P;uk9H}>x?v#f=tM@dDgx6yTT ze?o=Ynr+%gZVrCYguD_feJ-kt!Rq$>4??Zs24o_5*^ z*jFXazO*mylHEP*$~1mueGc4t;$JZ#9Q5%o(AuE|Pi?oxwz{R<9vctrPFJnvHtwyk zD=O8I4+4;qEx9r(F1C)PCM%#_k5A3qCk=4|_?3-D^lB%g{N1?d$!a@?#UJvK=|mtJ zp9Xt9YsL5cZ=C!-2xqJL>$w%h#qRvmZ8tR6bPWFh(>C@%>$0cqaIL1lEq`qDglWYo z#%=raX9>F(u82xt;d#o~ig(p89dD2mrA|?L$7y@moLS1gd_z z@}!tlwn6Vq#GIv^svC^K1(%oG-gHf;W$wNE1O6n9`NlkKsNO1hCLlw(w&hg&==`1V zYgdbHHZw#~0(n`JRbEhsrf%tClA<>1Y<6nmo4Hswz`Jd|Qdym$;1MV;6J$D!3Lt1Zu zx~FpFM?UDPG=Nu31z;FJzgsGvF0-5oydRYvHLj7XPUHL~0Lz%$1~E8#?`f5*${qld zqEo2X>RN8n3^YjyC@9x0d}aVd&D;5%<|*U0;xe}|o4}-}>$Y~(p){$o3goJDCihez z6%AnUnVH_#8m|mL*qHV>m)k!9gVEsf($pH^LP}3B699{RPHO{N!sGTE-H{fc={5&S zAa~kYYMN1_`l@oR#xYm?S2dCR;H%h)egse<_IC?~a`mqkm&j>;-Rnhw=8u&64J_9X z-kTO{)|VW&957a1r~%b6u$&c{tbkae_t@CGDn7t3!C|vFU1R$j_d(>x1sc#?Syi?- zbUp8bbGh=0;oaoqb!OU6>LJkwx{xPfl~O79c_!uJ*uPbJ=KIP+3qBk3o|%K!YD}H< zM=Ms>+Q%z&JQltQv7|h8oj~(L13JL_nl*hhup(6AC48<|r)79v30 zyb1&Tafjbq6M%8_rj<~*Osf*<_QL`xoC#G{W94M3|`A~Pw#Jt%w^ZZ z?~LpJSxES6o40`@uCw#bnY1wgu7GsnIkUEBnTd@xf6b@1;$ZgogVP9}-QTD5-N>yw z3Q!o;(qZEHA5VL6*-Rr_T#rfsdSdpXrAnMqdvJ`{eVn(%VRAQ@=z^B>qopwTf=cSu zQz9~JRO`!o;?F}qv^K8SuElSx;r2L+_NugGINE!2!1Iy3DsXOF;*a-H=0qh^*+eXt z+x{H3>i+DGw~Yl*@Lc^Tly_+@453ZB+ALOgz2~(S!t^am+hl!8445qn<`~f{*n||) zO>(OM@=sOymlKsMyPITNOOK)!_Ga1lq;&2HH#Le$rH%{xi7u_tEj}cc3YXSPK7U$g z0(28x-1q3F4}u@sq&!J9TCGxmEu*fi6-a9}pxpWPmQ4L@Rz_U}v)oqBdoSx}i{_$A zIA>H6aNQFc4`%pn)&gojRRZW(XK(KMg|85vhOlIR`|!x5GVz8E;KGBC$R+AzpHMQE zcUh07RWKMv5=LgfB$e9TsEZw6+8nr5mpyDT&FwM`LbS?|DK$3yJGeUep82DqyRoz2 z<$zVa-L^@d0C%PA8kwJuVywWTTs3hUK-2`z7;OhK?NYMzBWbACqe{eYJPDtY2D4f#YYhJm_(%n~lv@`;E^%JiP?=rEJt-2=1l+8Guq{B!QI<@D>7H$%CWiT%xTTcl?E8#A;Oz&gDiqJVx0FgO(J^iUuPng8ULg z8rf_i&a7hbUB$a?E0h<})Jq-*udI-3BvzLD|qarA#RKvUv!I6oO% zA(O(IxDDzB9SMn$fq{W;0tODwo`Z8WAR0kJ!a&W~67dguphj%jPSj%OoXePw#9_Mx zCXSD?Cm;N_Ej}~bedS$L291;Tf$i&DT=bnzP1_*|3JNMdGxMUbe#>08dF4k^D=S=* zj%&*6^h-9t^DLLS>^vo_dqNjG-RxwhMKurLRO>t^9cqLNbp~rT)6pvWBx;4810!N! zxx8|oQBkuvm`!giFawS7Wi3ziFz|QsF8$IwMgl!6fMG#R^YUsdZ+m$<@zsrLN?elV zTFDQ?aQgT!E-tR#h|k{mF~+! z)&lf*Y_1jZ?M0^ebb6p0vUY4y*roA1Uibr3lG92Js8+j{=8;S zRGhpBIDej>W?k+ko;{xSvw#b&an(|9*Jkzh>+YIEvEmM0*zWK`X|ubvugjF| z>VKcS_O<0(`S?&8i;XZy^$r;?wX$PZ^yb(!#{HPEM>OJaa6c%Q`DP@8w;+zH{Gi3z zA#*n6m&C=8e`^uWs=b$C+!gyknp)2IR5FVZxg|CMBIkEHAH@tC!%8JE59cpTOEa)zVX&RDzCc-wCJDw4ur*sU+~ zSy0T^IWt5NVXxlL1mnt?#Y-sT(>7*aqWo_j0ylj$Rp!yJU8aHv_6Dc=;iCKld1;XL znGre(G)OvPIgzyRDUyaJ3yPc0sOMWzdMtz3j(hKTXHgBZ6_Xs_zvJ4 zjTjVF1+>Od@ujz~ALvHZX2#njqsn93@hPb#V~BotBUqL(4Zm;Y^c0$C_(pG_s$cz0(CwdrO80LvmkC9$B0SW0TL}L=-0_X5*&9EB^1z5WZGx4F%BW8> zP^eyLqmJQyD}#$2qdY=F4w*kM%29el;{N#q+mNukI}eEba)Lw`%FM9HF0_9UNXf1B z)`Ug=!z34bUZ2G;s#g3i7EcCN;HTAEY9A1`|h7 zX3eR*-kwHO_F;{ZH^8>O#EyieC?H+!L&~N?d@OX4d&6x-T;Ke|rsC=XTC;Jdq9`T| z15yAioQMqO4Bm z_e`ul{QEZ$D32$g^u--peV#l_5F|NoG;E1LCCiN&EUfS1Qs&~aErHEh8s2u4b8hPC z5$3m2BXZU0CzRH6=J!5bxw*aln#o~9RGg(!Y#`VOOibt$$0dF%VvO2NT^dxpym-aM z#gVKX)ZW4GFwVAs*C{>Jv2eN7EXzAliE?MP`hmi=Q}j;Ivi?jkAzYn>QHS)nv)u!d z-^2bw%K2D3K{x96-Gz1|8^$8c*F~7yMHs6`QB|z!=@f@Ym;)Yg4HXwvz`J?xr>ld$ zlF^+F5l2Di;^W(ce-iX&!s|G`Fj`5s4fWHvR?$Xb_`dEZp2!5g3aYSG1A1|pD!#rI z{fn>zdZi?VI_LESKejjrua+@y@3G+r6%)vL(Sfl(4;-vK1-V8DF~KejqX8nV|c8 zc~cHNh9$(N4b6S2Fz6r(_m1|c`wBnKaTH~?-yov%0&DNY8msmDO<$dX04^*C z#&UE9K{6*1lNynb1u! ze(|Y0{@yx}Pe7F6<;}=znN6_~@uhGC;3Z}l!ZqiP22+>m_?rP$?rdl{>=wd(^ewj! z&=FW?MB@8%&tg#!aEZFlQCv+lgr&Vfh<#o;5j4AfTm*kv8X?y^2qRK*_1b=AY({X< zAQ4EtA=7DrkWGuNbJ_{!Pna~9Fs93yPhIH7Jqko+ncOIeh^NFU4mC27vRzFlmwt!1 zH2U?frpY-h@sp(!+0vWIoB(bI6Z4<;B<1DF>1Ec(*zbTIYi@2%7{NsxMXA$dn6~7gLdVe3H$tkmIQH`LTHo0jct^KdlEYG3;GC{#MbigW}Izl=$0NY(}e2lr~bXmYG^4|mNJ5Z`mMdIso3W&E9`bp z4C&ws6OUcFO%G0Y*6Jozr^jveiv4MpBafQO08LrN(3$}~Ic3)Dd&8P+;td{%ThcLj z0^hra`al=CJQ6*<`A~dc63*XcF{ssJ`{D1c{@q60eyuQB={rlhKw9j&wR+#zFoMU` zWMa7D{F|iakD1Q`Om9({L_f$fhTLX zFs=wb7ZdGuY4{ud$j8(Lbvzx-EB z!~XkIl0xKzyhO9_X9>@!ye)a1A$v=fSD`Q%u@&~iG8S-|i~{yf=bwBW5~B9S&Q;V~=CbrV&3GU9`@2HXK2MWSiW1;mV-l># z{4z!o6eJxU9;={jwf{!d0$4m{!Qjpd)+w(SU@gJx<#LS@*Us)P85I?r?#GJIltX2WcZ{pk z1t5IFzt4E5#f>!u2{2NTMqqpC@*O9GeXJ~F3NID|o5;kKj`h7rCz(7jb|{oWp^@Rd z9YH7Wxjo|5P3>06X&~6x!syB?JUg1pawsD^-=e@e_qTF5KXNS9BG^|N z$&TlB4=5hR^4qqyKxL9n3Btg}?$&-h-tl^hh!zPh7#bfR1hDllkSp8;+5ljhjH}?8(zm>B`K7?pki%{KKN!HESv0 z^-HHH+Ye7eW)$=3%*a;b`>lZ%J1%lFs@ZsK@#xb7d9tS}7K{8pIg`Y`q0U0uQ=87`?WFk@q5 zGXjYn%omBPs&9e+J(=H=6VMK!jsj|gh#OYI)~46()YQy+w74|Y1GTj8!A8NCKWu8^ zmaAh`8X6ffdRu(E2=S2mR_N#32=9}>j?F{fZ(1|GykjS9AfKNj3`r4SnDrr;y<3>) zEUwuYlH%SP6?Szr-Y<%VpmcS3_w}cYYu>IyR=G0VLHl7b_&q;;Gw6kY++rGZOo$c! z?6Tu`l772r=Q6mqADQLY+|+bacsfYb)f4omNSvL53+h34dg3f;&cn3CJnN|}G5&ix zEXNacM!^zA>rwLkRo_yphaqbaR8^x{3$iqOG$;yr@>v4h1#zX4j7e^@{Shz&!riPQ_yB97Z*#Tz`(rDcp#G=U@$AIU&jz zdr}Hs_||bzqnl=Ph)+*`1OJxms4`>zg}{Cr$n)K)eIt-^w|9GR>GArFlgNJ@i)FPH zpcF5N(}<>uk8D#e`&jiZgt0$c-Q;;$ShQf-Yl#lA zB2B+>!!VHCM}r)lMbbUysP3dcQy&gJ71T3gLRI@T$4fBP&r@KU#u@bR>>bfxHbw^r z#V0%tFG}TJx;oqpD+mB=ksKMMEmt-wZ0}5d_Fy#wMN0N9nxOyp^}HF`J9ebz6rE<_XDoVR)ms=uq+P12zqRxU$)lH1VEVP|LtU?}CQo0d3az(V-!DUbo{u(6-{pvCU$| z51BY#hW?{7*YV_q18scQ(hPQ#zgD)Wxs`$;vw*|5ymkwl0Qq-H%9>qx1*IBA zIs=c=GGdk9_Lq=)wHT0&EpwB4XgO`@p9I!y(z0mK$gf$$7s_P}qs0QJCMp2j1_234 zOCW9|^kue|$~}rLSW%MH-Q6=z`9}tC+~R-Nx`SIK+$NG$$kI=|N5WJAZQhLpa<@3}8El!^@s z0#gYz-aop=VL444YyAJKwKBosL)7vdQU&OM+=#^oHfx5FX$hr6nOHGd$0bd5<6wib!Ug#zfl^_9*5=qbOydwXGGg_O8v8$)r5 zA@a&5d%yH&4M8GFvY@X(Q5)#;Kk$8J1{horFhKWCO<{ln{Dn3lvJ*I^NrpbFF}apN z=Tt4#wzs!SK2&qgdZ{uXKcv7&(2jj#Q5A%);;+2ptCmF*2M7U<9{jSWT86pLp(oW& z$Jv#%q8L^g8g+u-XHYyDT0Y+RKgr-(0SRoM6u+;)I}B*+HSqAC9J&9IaVDyt4Mvfv z+IARKWtqs!cgbuq*-7zUJJH3ZB!+a)PMZ5A>A|89Y(CExAf9eU{I!z&@(zvt6CfA4L(U zg;!ZoVcr5gLkA)Dm-}nno(CV!!!L_2qI|!iomAj_gFF&j@BMb+ep6`-PokZ%jJ9u< z>BU+hN0`o9o@ho$7iUW7c{~g6bv;P_Q)6zmcL9-~^gdVPNcHV`1u`nO9XD-8wleiA zytVT3;@j>*iK4q`a>?yQbIs1TYlGyr%W zyl5{gRIJ~z3pOKrF#~Z;HN@?o;#BA;)qt4Un10_zc}E}5LR(&E>uG{3DBSM36{0Z| zM*Au!KjECfjP&Kf>2&f)&FR*~EB%|+ZFFwi*9%DmpDr=-te+q6Zb51kU6PIDm+Kid z@?Q-F)jL+5itsWS2yG9H_J<#;TTlU1g5Dawz%wA*|ZmSJ;RM& ziOY)Eg_i|xmNRZ1SH5LISjvekOJg!VN5lNZMEXX~@V{!UjQBbfkoWWkSSfRIAQSU0 z#%ME!l$JW2IGUN6A>nZ%0rN_LSe}r!Ha;-G1cLc`R{lH+o6O#kjrDqB8r;1%Y28nahqaZ?wA`66~lhJi9i7AIk78;6?;YZ0v|= z;(l8};l+FgL&Witf_2`;YNJ6zkadE^L#SuW+2J$rDpvNNHOkThm&=2TEhNX09#+qE zc)d@rqzm(Jrp0AskbwErw&AH7xG)76by|$8pQKS9R^MY|90byM(=6G@nYY@zQr@u# zBa;nAN022piG=vYQAuXZe-{10y~nr3wA)m!35kX8%Tw`9lcBhlVkN0uNEvfZ7#COS zSSX2cpt17!iutOgW=S64Q|?(*N=mLZSt`wKJG$63OB9}EtOld75O47tk$VWGe{)CI z&`?u<0#0N5bK@CtTOAS&7?5xPtm|fefKCsx<&jVh*XsY%sn5rF${T!BJ_Pj+Ov#W?6b+W{q#vfU2 zNdL9c9gPR&&!m~stWd0SYq}&8{dRX|%!s994$j_zeU)h#rtsEjGfZ{RO)v6?miZ@p zy%M)bY55b)6G>ghq7nk zJ>GA$SeUOcM%Sg%r!p(9VvXZ0O4Gcqog;I0DRE%n#d#mAGI{`3HYH5M=^|57oc`uY z%a84)MoHY!-jHv;FWbHu0MWel&fw`qP8@TSGaGx$13k6w*^g~R>SpEwQY#A6B#~H* zVAUi*f>>87$ETGR@U<8FDBgc>$w-E_N&|DQ^tImoH4}wmD&Ae;ZDBHTU@DQd!C~altL-Zb6|JJPGyAH?0Yi80hXmVnZ4BmZ-I^%~ z0ZBtvD}mCTzM-Ko43@FjafU3v;rOi-T1x0qx0Almq1!*6scaOLn&n~!205ZHnbfz( z8DU3IWv&LX2}M0ums>I40^q)l%B)v*mXyu6SkFV8Ms}ueX?}g&j(T{06Wyua^u76T zPqKsjZS{Ak(GORJhQsZ~gZq^^Ta}_&DsFC5WSts#G)o1^${qI;ma?68Ef4xyKN#XQ z)v~_RQ&I+#keBK&)R=q?c~58nv@9S>gNR;HP|HugDpt*y*rgT{Av|S?hqom>Yw%eR zVf^25+}YHvV72eHiPzITZC%COkJ{rk?1n94sG9@0hxA)TrBsZLx@-#Ck%*ya?UjhX z^rpiLYP_967Efk~=o=89G@7df`hHL$=h4u>J7toyqy*53t0!0ymt>NhM>L5E!<>Ig5-Sy|4ujGwzP*^I9jGad<4x>r*Z2;i=!d6gP*d_}EP0^R zl$1CT4S+I0y(W;xRJTeWQbaJ5U zxs>?d8q;D1ZSC=~_GCfxJyX|ppK&5P*E#%886I7iKI7RBp5*Lq0Gtfh$Tnm}5GCE8 z+b#Uv6~~TWP9r*NHerL}QCr*LJdcIE_;8tmj_9Z?W ze^xEuqok2Jx3#-eK^5A9lTW5{8~7k zRu?1>;EVwD_!TJ-X1JU!Ri*{Tm>A`Z7|pP-1}k>9pxj(iaw;me;a9(x zCDChoCQ^(YEj&E@zlofH^(!KNk3ayoi)jGVyc8@v1wg+jnJ+akY;JAQB{69?=~o+p zWQb5DO4VhcehE3WHXu9(R;2XTM+8bD}D^>dR?#;sjf2inpexhtY5$T((b3rrN|me613Ovo=Fs?|7dWo`s_A! zxJLTMkmrB{-eO37jBZ#+>Y6P2bWnSq=5YOJKcdW^w($-$gV0*Za1DNW3igOiyq*ZF z9aZ@dT(K1hx}DK_Is^BITX-UQG=o8{oS6rb|V#6u-+TrM#TI~`J^INb*_GD)ccNa&K`^NX;Tz~j1feo;68+xoq|=-5}zRgP72*6BoLp>*^%jg`v? zJRxI>nHJH*6}eUx%OR#=?AMQ`X<#66;VoutFr=*JASFv7?V?kYS&E5vCxk%bbw}|1 zUHw)u4G)j=jkEW!{_xh}k#Bk8LFHC-Mlo;xN2}7Yv*HAik{m6vh%^!LeSHUR;+Ylz zlNrz6+3)W}Y<; zgoE3;IG#7xg$#=^M6Bt#cKwheJ1I$ATCJCpwJ05zgF_v(m;hRw(qHP>oc=>#bzuPq zWO1UAlb8At>*QNcS@&oeGiGvPH{hmp$++&1`(Y|MsmIgj?Lc5mi)Ls$`^^`I~|# z{`tsg$8Kxl=py**@znj-y;9ZW);;fm6UD}j)KA%JZ`*XdaZCm)G#Xw?P@03Z2bo!J z6be)g^p^EzD&X|8MvjwyL-LOFf&_9p2??MuuS87;evp->LF>6WK*czu1kENqw|9d<&Am&oLy>DQ?meBu? zm#h_j1#knEzow{sPe~b)v@nkZp`!yeip6~(ByE(s)$@k&6{rPlNH$2OS8ue<_}8*n zYdVAw1SLnWmIopavQ_8`9h^bVPHvtd=!mg^Pm&gxWJ2QOF#`@}jrunloGoRG4fKp4 zz7z-I38Dhb7Idx-!~Lsq?VdNeRo~NKyC&{i0Ew6fT8rFhn)ipHN?sCIWtsswA|Z~M zCqUU0zB&#-aTcI)JzT7hAY-2?&}y`e+y;THWNd74z9v}Uq{!W;Od4SU5o=-#&rc6H zlSn~TAfau*@$=_5AoYj(tEX$Ha?;q_@(68|szsRV6YQ*(s2Rq0XhQT=Ez9kQWjcs5 zDZ<(wvLAeTR4s%25B8Vx;k$5st4)y|hA?^;YP(7+V?A(jeF+G{w$+lTtRJ^sim+Io z4OjVy!>EQM=RIrOm_Q{5a)F>)HvPOUCaM}DBEY$%r1<@he37Eihu&gh8mI`HK4Rs= ze~V(87={)?zyp>3k;2Q{yXpbEL*Qqsa_AsH%OS9_v4OQU>0*pD5Ojqyl)WH{&HvT2 zRCZPO-lHDBOMQ%Cc%V42*JE~PH%q$p!-y*aFW+1w&LS}l9oj3_yAjRA?9>10@Xjvc zUkmMfseu~p3cmmXwtWTla(i|p%K_>ooK`g4s3w62%}p4u=Rsreqll~*Q^*x~eNynr z=_*gtsRKJ4hvxDo+dU64k&o<;j^^-1ZOeY4RW9D9#=i|!& zPrAX-N1VhWTWJ`?QiP6@6Pkc^b%*6Gden>l3xI*PG?Yg7^Slxc%T)5Yy`%Isd2w)2X zkV>WA;l(4DB@kuT`J@_83=c7uZcv!?Q>h4Luondaq)*uloP$$?ZmQ!g5DXXr*T#IC zJKL()h3p#`m<3ECp!kB0FKTSrI8;^KwXM}Q^uZ;+Le>H*+qHW*

    Akvs*jdx4|bo&@c5nIWPar-cs>PH9oYXH z?T;R1)Q`vd-Dm#pb^f^@qsunsIrD20+XgrgI$!rQaDN8SUw{4?5E;ZWNw;SM`FhNd z9ofrsX2zc}Lt9oG?=gXAhC@Rq{LbVJKO?ffqR(vsrS8(n8YfSBfF6`BXUG&Wu*aEL z4E8>SqS6&V7pv`e0_FG|;9L$9yFuodm<1k&!8%ifF4cZeHFzK#P7+6WyivKn`uVH< zZvWo-#r29qqoA#_%Pz(KKb|fBjGjT&W>WCe8sg&}gl@8qqiU!_TLge+(&*St!Se;@~ z!Fe9~dTO06EEDXG{EuV)2(`PjIDBlJv}~tm@L^P*zwyO*dx^oLtM_wO_$w0j^D&S2 z9E7kMaYEv~l!#$yXl>}3;b9m^4h}54$~pJMTD9zOZM7SuIbik+3H?%ied2t0bUbHb z6t-5Y9;BTUCW2!xapJ;{YL5tsqNjEKeEppdv$>R7RfI4g#R22U`n&7(itlf4nCBU# zZTN`qh^t`VH>^3MLNE*_FT8w*s^b2UaJ${HEWY9TCz;tsGk(4`#8$0`t0090NrGNy zl_tbApbY`7RK!LAd)#>USnJN!dj0b2_ZNKs{v98;5B%-F{0%V)?)MuFrfNkl6?td7qnIMn z$XZWdoK$Jdk;V%bA8`hW4Dfi3xL#f{%~y=mjF77JxZP2eHK)tEqF8U=YCTX>0^Z&L zeL**q6N_WVDd94XR!cothLq#!Htw+kZKHHk)oPtegKiadE!b}v`;GO(A3uNLk3YEK zRVjRMBH8#>4q`$&#oM6RE$A6~02@;R23xgSLX8$z*g{1&utHVMcxyqrDbgO%OeR}$HVFzrmuK)|^7a{mVT|nI9A?z(jJ&^E_CEqKbwF8a zLEbX%w*^0c{<32;nu}2|3^U$_R}AAoL#=s28m#?U^9_N)Z?!&=%l(eq#|`T}BWI;y zPX+c2Y&*v?B^t-Y2*gqWY)Fayo3G;)m&;^EY?S*h%ZhEi<955FlO2b ztbECeZ7bN;jD0U=h*hv}>5}zFE6O20CKkg{-|2#T4S}OFthntVp z^D&Une(b)PY3qR&VD8EiKoLP@{qQN~KeCLctZWYf(dU{7GtM{#&O9%kLv#tXEfx}k z{l5KbjQza~NIcB8`cd178$6)rt9CL*dVtS+8T)v7f7a(r@DUnuY@4gr{q&v9w!JI# zbs|7;1Un7_I2Je^0Bm*kMXd7-E}x}y59TW;0Qq zr6@{nD1|Y}LEe+pVsBRhkzp7x4gNgSK*v| z`}#aBt#;+jGeLEH9gp{@i=%P06Eq@3)nlN?UgN6Lf7i(~|2N0{IJP@Ot7`AJ`_=2K z^~Rsk2XGA7aUNA1;-u#j$b|ZS;c@@t`r&0cB7k1rR|Cn7-8hv&Ti{d6A~E7_<#ku&Gt>lG;~NFhwN;Eo8wmNVP7VOh*XB`PlS1!;`f z_X%;mv-z?{B#B5uwtq|!dk~ZuDOqlb<~GK>S9Kn|u^-g{q#+^Lg2;9r6;;WSDFiJ9 zNK3t?5T!IjUzEJZ80$nB07qMB$C)?3prPa)yJcWq<~R-s*I~wd9m)9A0VNk~V}rzk zF=Yael?>F724=rTZ~r5J$w9|4Ar4nMe2x_%yy7Ys?1jL>oqZ8lryL^d3ndIlg~ulV zj?4^nkk1LhOi94Yb;3Mx@fZdNf;8yi1J{_b%7q!#b;EMc`1#KjKYu80cc5&HCoUg1 z{QP;t$HxagJ{G*ZOc0^-X$S*iD9E6zZO#>;C|TTOvfdCdUuL#q2>}D#j-H!$9F-a1 zrqEoGy}xW(3Ba-w0CWnkCV3hM!Sxa`4lgtwG6IF!@d5KNBBh~QoVQBQxG%+8$OvV# zm78(Y2&f{j8T)+$azd!WmQ1Z;Ypm~V(IlbvyhL;P7Ry+sNN|{fA`X?A`oP@LUJ6-9 zGw`8G%WD<~s0P$huvSWHX}U$gKMxaR95GxbI`&QzLKpxM%W$&J+B1rDBNn7IV!mGK z8vZgL1clf`AAm3hwx9BPAW0-uAlTP}X}kf-#fWXDDkSiEn&*-7;nyps*;Nc|0k!XJ z2UbtPWsDK?O!KLdi_IJB8)z{|N*q_;E7rAO-`}w;EAHzJFE1|`C$`;+A<>1`E&BJu zK&+Sv7JLIY8L34|WG2;WK`X*SwMZ_7YLa$rzA>^~;Cg*A=k>vYF`$(VId8~$?*JH} zqj(zFgEz$iK*F-@_;_C+SWwFjAY1Qb-%QaLV>iP{QE<78`1bu3mrH_5LoV0u!szBl zT7|vVL!`Nl>~=k5V!b_15Njodf>KvZa|B{VlZ+-A6$M2K8Y<@~2o#SECBTZb4fL6- zw*|%swzUTVYmx;~>EaqdH}R^>vPa9#h(5OH@VaEx6W~>aN`)ZyK;zgJ{T%GEY{%xV zy?z^XWp|J!M;*0DGg)(b3P|}ZxseT@iQ{$ro&y#OB09jpgB+~`+3*MyY3%3$lmbe5 zz1sY(TDcZAMbd<3wbZP+ZoMpseJ?AtF@OzfEpXs6(!=bAwP~MUT@HMDW}oH1U%h-> zo%sAbM*sSC4#bWi=4-HfK95g{>(lZ6)yv&j|6k6xn}+?Hubx4KOP>8Wq(9v0_~>oR zr-r9=5DYPxpTgiWL|_~vhCz@a6&4!EH9lw7)0B2_RY|RU-*9P=KmhPG1qpxiE zL~wNy;?wsY&-47Xf6Ld)fJXw$pBLMeKOHL=I97E7E+;$PIISMPYsrY1(qZt%Y10YI z{o7!wfqht~YsBR;BTnWxTdeb%ZgfT~<~o}I z4eYl!%>$CmD7j)9fN>1CUT7M%yi=yDs%TQ^HcZ=V)_lfuxMlbm$9hBO3*U+S_ux-8NSn1Oq16)7>h#}+nZVjKXA2#U4sDWzi1 zJMu;s18zI8yaVg~7w#W7ynbUn@HCBF9Ad;Ujwt&7arUlVZX-#O zsCm3V=0n}p+dJp}|9`i$ccx0EOcFpm{C+U^07#{(doIt>Nhw7VKp+s|ZfO1YUfKBbU)4fgstTCbf+=MQPP-&c&lO?dA&Qc4FaYide!y;X|)0H{@=?S@vf z>Ffxq3;=hm!i^Pb0dp7h+Ht=(s(2gyFT$u;u@GHd75hHW)@oHm{uyrPX@3xy=#~%= zUS!%&xJ`}((nnJkqw}&#-bX?dZt5Wg1jzsd5(*SV%(+OIPwZ~iD%veb$LxogO2-(i z#5eZUdtcPD6pEbv?Gr&rJR%N3WG3nUtKFD9(( z%JI{NTr%F?Uhwkzf^s3fzO{y-JKT4bffMbXu9t-CB|`OjEZ7z>?X|Hjq8;dBYaMNL z?6qUts7`oWzoV2tt%_Z6y}Tfo0t~8&$6|dQ#e*ZA0Y5DzPfEo@Xa5`|AmoUW0tyNM z%nC9W6~$gxDsKxDKW-MxEETi~nn?>fL`Zvv`K$(UCG3NSCDINQ6Rec5ZQzDf6zQ^H z*@0RU^5udUFhLawf?k1EIVtl}u;f?Bw}kiiZ+L&Z;qO20xPR{0R#Metj7X8-!{_HG z)=d$T(nma2jL^`eLW2TPktHE?_U&jenk_7lijnLB+q}l;lNu&7q-W(dA|q(TXaKrZ zWNilriD9-0YrMkZVmh6K$6et(s%hPTyGPM(E!2 zPqeCWRBq{p8ajVdL1Cdp(L$OW9i>J1CJnc zE%MiMRrz1hkN@iRSZ(s&{;%Kr>*H8`&d0&;_x~VyW_8soQFg8K-_FSJq}P}dppHb! zwznp?%;UNpimuftm^7XeX%mSWz;1umU<7uR$aF z;Cj@mnle56hldK2PAf(T4#71MptT6qiavJKmXWJbqP^!ZQY*p#&ejn39X{fTGX>O> z{+tg>$tVKBF%Hcs!+^!4e$V}0^aC(B1;;^8tqWt2#S#P9h~biD1tq z*ECTBDTmI*#1jOCuzKa|;3=U!Dy2B?%`YgqkH3qycEjk=9ik>I8&31^p*4Z`U$q)& z_x!z&$DAtKJ`U6RN+)>t_&OiUL0bbfeN8(Kz^7=A!@2s&`Q`ViwT@(Lv|&ZA-Wz() z)*dpfXBRVh^0iSWXcLihv3LonDWWynMRsi_jMX0!YhPZ!PW~U0)bo1i_ul8Ef9Ba= z*+2h$f6sI9XV$^-xvyT63GpzAAFsjx-Wu(ZoIdZ*-Sv8X5YbABMY!IhQK`d&r|=m} z@p15Y*7vL<5P$T!_qc@Tb<%Y>26w*qybsQ6J>3i6JN^ICXoBH_0_Yf8p{iKdJBCta zH|LD&%Yv8d3re!SnmcWS+P;&k-*!G^0%QmT8M_5QV<`F#B8Ol_ZFC^UhM0YDlZj~Y z0-!n-PG__EP((-MQ^NIf!S!XK=+go!+`cBfyuJXDs6?n8IS1q=p_GJmji|LE7kaXG zQ$~x)dfiIE5(-j|C`-grtirfbENfkV;Nv6UqqnROp^PD5gurnyAJJO71zB-c|9JBlG`6~7sM1$? z-_d)RN^Mkb;~tW-O^^%!-qk470qBj^IVlr$j^=sFz&=5BL#x1T=Xc~x>aM&AN?J&t z5G5s1iA<{dw7E~On6(l%J{X|_P>7OR%8DIOci?_k+&_2pwj)ONjpl4s;0WY+EWRl$ zM3f~XC2pVqjQXsoJ9|XiK8yhnh`&S2 z>sFnDdsMGp*u%@EhqzlW`o3E*;=Etp zqbRvXXK~QyWCjDQmh81*+jpeTj+i=BD(*ESML{3!2p9$} zZ~_X->lN?s?|8X4} ip#q64&g1{sBb?W(ZZ#BOB_w#xEJ1?HcnQC~x{>PtR zoumEZ_&#u~e|3Bjp=ggE<-i$!`8rp>MNU*0OG1(*esW4qjy2>Iyg7y6TNR$JPbbyc z*Hiw^K@-{=HjLg*<8^!vIQobA?}*WbRbSINQ2U7?a4BJS#>i=2GUnSWeOV>YI!U#g z?O#Oi387UA-^FOpRGf+J*@E(%1jlH$is$PNM-O)hMzNflBRT=2<9;yie72c+X3hKW zSQ&j3-a5bM{0w+<*KK`p@9ueS>I|6E+z5c{Bb@K&IVtkr>xd>A1svu@$Lm<*JPCFX zjDe23s+`Y>hhbtFB3V8xS`GRdOPmSkUnP7$jmhbp!qY?YkUSf(_^_^c`@=)>YZZ9} zxJ{D8_+*h}tPAVm9YcYjWF$W9B}eSgY%d|Rz(hz3#dB-hO#_75Cg)f|Ps!s~iK>t3 z*OlVq^N%3Ic`U{9JRhsau{*~9Q9Nn_pNfNF@T>c!95L0$bN8`pCVdiuSbW8p$8!?@ zoV$UrJ+YzpNFd_0)I3*V{c_LeNH&+9$HUkKf)L;{ZQJ}Dt>^hB20Wd|_k8WCZM&(; z^5VLf+OH0@!9{Z4Htg#i+p^;QWuZUk-k?sE8qAUr^iOzZ~_?U_B8R_HTCJQdX{=Ew;MronVQMuA9wP{Bmf+7V#M$(GqlJWNK zYL*ym-fn%z)>t`WHHS2voG-{P1ut)cZQrrqR-=9@VgQAI)*H%ZbPNP4HTMtv`RAYb zKi~fopP!#5?nE!w)*E5~&;f10UX{Rs_5YSEC`LE!1Jk0#dz+63rqiplZE*F-ZheqZ z`1za)QtHUDVM#lX6s>YjeR~hMz8Ac{yyER|FSuSW2yx5=xc83xM&DU6noh02?Z&=N zPe$L~*nfPzF33hrPgboTW4B&Y(wuio;CfgY`sHp`SkCtkh+&`u&`uGox^rAwW#YcP z0x!#jwC|KyK?0R_qc9<(r)@{SH{7>7_I=~x*Ts-)qQSJ~i3qW?LW>R=KpkMExDH${ z4Pg<)RH&|;BZJd0jK)3CtkT-40Duq^soD!|hhj0B)=;z90bFKZdWUE?s(XObm9}-m z7$yobKn3WXebOSNf7M!XyM5xmePFLUKJOp+yno=wAD{UB_l}Pr)_Y4^Uc>~vynNul z|LYU~@gLvuAOG?H;Qjp_z#-vZYsG#2gzCV$e&X`6V0odEcTNkb?m1#v0!ktSfJ)H5 z-~zCXby!ua?uxJxO>Qk>uMtfnN))R~4-*1cRF zn8W>+VpwiBz;PZJK>-!BbOP0&tv4%%0P{;a>~&`^(UD}44u0zW9u!0K-X%4phe<8F z!E{zq!W@4+2T?-s_kr0a@>DtWIms5B7}FH_OD7s8)u#JlEn^DiXca@Ow;~dSOqwu8 zBMm(WB&vyT*;*KNCP}=WIIm04AcLE~i~#MG)$PFXd#<-|EWLmAXZ2@)-p)xdx`KJf z(O2l6p0m<09zW}Ue|{aw5YPYo`{NvcPE3J=N#L(vQKFA)u^{kte$UtXaBfe*5=4G_ z->mjLB}vf7eAn3qUnjwym^-*;;EeGS$1w1&2_ym1K{iE?kPeJ$07URPZvBu3USjBi{;I@`Kdge@m2=0kW+)d1!&=X{?DfHAhb+80iV6^@D| z@BQFf-32%$k(}@6q|5()s9Bp%*aQ_|VnSTwp62;;P!7y~t8rrL&&2Jt4;__#PhgFd zeWHmo@jmweKg~W@epa0cr~-%6hb1gyoG8)4R*D!2EQz5!!PJq@FJG&l*MaB6eIEGq zIv6Al(mmdz+0PHyo_ZugvzIvtLNW~;XOupGf@f>bVZKK2TCVTh6Y_XKJK z?Y%-5R+p`P0AtMdy>msKV{(kobM^NayPvDVNAl|9$$vk7{GhG#`~5RN(}m~t;#i*M zx7z^)K5d^EP&l3gRnIf3#f!}xP9E8BEDj}$;|7azu|KdU=00LT<2dy>D=2UV17y@_ z(wq;1VCUFH?LOLdDdQ9gVzx_PEXH#_@jFr;k<^&bXp)eq`kPBaPOm5_*oMywEy7JT zNuW5M!mP>&K_Qu`!6=^sEM&;+2B68+H?z<%r_ih3320$?C#)nxJK4v2U z0eJZq@z2+P;@jnoHx~5Tbzfl@koxofJO23N5B#6+|A&3Q;DX`(8X+x+kzS0wcj)w6 z0$4R;un@D0El_p$a(RUt!>etYOnlX0i7y?Awm*^NxKZ6}tD1*nJW9J~{eAhlOHk8jYskSF~24tzoaUrP2zFO;MK( zao-Tr4M=9svn%Qj^vd&uu+kAi#d4__@4^agOt!cXxNs|+(RZ}ILA6uSImKC>tc~-< zH%L;ZX@5j8f(g<0AAf?9_7z)QvA2eOy4(5a?O132*Ojczb_iA6L0fT3%WN#l+a$%W?D$jE1g?Ry%5?3VCa! zXgi%7fLTaIl$?=Dp30OSYyfVV6Rr9$SaQO$WR%6Mc7{NEK<|omb^9K+T~J^yV5p)t z-`q@+$t%XDYB;7Mr1$9!AX!TSFrQ&HnwqNl&`5+r(3@HkJf<+%7ex}ohNcxARCw>T1B@k6r6Wp(`;~_n5pzN;38_=;Ovm6gcQIfN?5$SixsCzRiZC)p z6O2Z1Km*%4M14Lg+Mq{rH_E`IMV%1)8Mu0q+fSS1U{VcLPs5q$byy+^OSZ@CFM0?c z zD?t|cx{5v`QdA^Su&bZRR<$vbLCZTaa70cO!iT;8DLDQq0X)BVC=`7ru;jrK&`!_yQ70ACH5H|ptrbx z&Q-|=9Q9EIGWHBWC<##VAsuq49UtQ(^BH-pe0eq3f9LVu6Im)&aYzsYU3wG=I8GoIM!(w zSyVMAgDFgQavc%3Q#zfKgIs>cEfMR34i@+O-I!+qF_Muc_WcmGd!L{hF+lehX&urJ zF|K1RbUOLtz4&^)Ij^6ObY@S8{e6$0oBx8yVQKX|=01L0mt>A{0L+@uj*G`Ra~xmh zn2Yqe*Qu)Y`(grDOo9&|YPaOlIF95~6|L3d7_;*4?K~$i>Zx)qUh?((Yu7ZdRo(a5 z_5e?^PuJ!Erm7-cW5&QhWp_GM6gft`=Yp5l7ra~w6XIw=>AqoGH*_?r`30b9b(RexK)MVpOM%9O zZ4C$+SQhphZrg^AYK!8qz;~a*KlCtWCFy?aSl12XlsJ`A@Y~xrl=2PV{{Bi)Ff63! z1i}4w$8Fp2@#9bYdHaq(|NMa;KR&VV9nRpH5A_L6j4>hfEpS{t}tu6Y0ZJ6>Kdh$5t0k7h~2 zKE1wlsEzr85CyN-iVg~b{q666!*9R+6aV|4{~Q1K$3L)?0__96?YMn@VqJq#pa({y z8goK`NMYYzThWwM@1ZaT0_mzRFM^jVH=ZO{TrXE#E^o-jGy3ffNHSmw-?LUal7=BA1Mz1NZugy;ihA0VAIeCZ&k`&BQ~jXV^zK%R+DC>-CD5fU;)n`yG8W`)tF$ zZ%C2VCh9l`$mV-^Pz5ko>uYKqa3 z42{GMhSW5HG(pmU(jrt7ViK|>DvY{E0D>$4Lvc-{iks!J;By>hZa2R6_+~lf|IJ5J zl|f#s18pZV>QrK<%lRfVlogf;2B0}*T(1RXNk$*%hC7C!)xqA{Az0gny56wg*(*Of zpZ#D#SMLo$fU;y1p^#3@v@eqgXtO9lGC+(jmI%%U1BA}@RKB(kRr(q$*FPPAX8U)e4N|ZGmTJDo8u5!%mLc5@FymF@5ffot3Tg_k=jV>+v{0pU`u1`Bf79t6-b|cZh+VE7U(7=P#1}fBW?p z~4k_$badkoCyixlTzBBSy2+{0QnOfWD9gk(W}bk@WvCz(O<@Y)X#HHKBGTruCy zSp#j#{GLDn@4XBG(VmSUgDp!ZzzN_ppgYY||wrI0}eNU*(NXqaI}iKN zX}z#bUQfy3@exn9sQ)th;Vs_{6m|Q-*%2NN@7fNJ52;>#?yo<$Ae>)J=3Ot~V0k>8 z(+vOZclMk`nAMP1(~NnfN(N;=^{gK2*Etz_9D|>Mqw)Am&)#4@tELq6nEd*B4onbW ze%$V_LhL!3|MAl`KmR%I^6^f=bMG_PuY(e85mmG}JOxYaWd5YMXk&$Q3O-rk$$F{% z@D4P51!_DmYd)?H%Ab?q@UTvv^CK&G`~@iSm_qaQtl9AVj^}gsB8?dE^O*0oQ}TPL z!F#Jwi~%VoC=|6GAd<&nL4!RV2jhVjmj=ABM_^tH9`3O~<=A`Y7<0+R(815cl4^S@ zQVt1-z>*3pjEUZkFD2u(yx@|V!549~gyJYNfZ7H|4JJesXnj&if2`nS*l(;hY?)>A zUK&!0$ge`nmMI`YPud&;QV}4h83>C|oU7FeU8po$tfyCn)au$QBzB}2kS+-?DWLU? z`)$Sje#hti6Whir-xwW`Q#C;k`Sg@X^K21Dv!kl4N=5IqMaeO-k+uy{=9!+-!_b0fJRC!*G+q1B+Uvo0PC#~^T}f$gQ`Bv!`2#Z>m6I&A?T(HVUtW* zX)md8gIHdn0G7O?lm*wzz_#rO2<(-Pg}t(-tX=Dd&)Ww+?mzJPdBeW1M3bPFm`7Z% zSGHYm3xn#7)KFam;6MuaFjz9kEcYJ(&pzW23crK72XpueFTkmLV z#Xf*GxZsrnyuJbDvP?zZFi5T5_YL>^9s6b;#ZAy#N8J_MwxjKe?LKC&(`dlHGnWK_ zC_pI#Q5s58Kn1y6P%ec*YZ%C70iq*^1FcnT`-)a~l(F-n%&cx?v!7bB-%l=fAqK>p zY2~FS>j_X@{rew(;J#K{uw>3dAp;UE@!p5vVpC@E1O^vAG2G%|NP}0W=-JHqkYk}Q zYlv{hK&>WzGKR0H=$(C?*DF;zMcy!m^}2MnK|s`~&ero>cZ?y};|>WNaK?5DSOr1N zuQ5gTDleCU*SB}Lzu&%Z*tQ+D(<*2RQ#su;n7D#bb5kDE@(CF1zr~;rue$gZ`{k3_ zJ#f<$L*2P->R_OvRw)b7sGs4HiZzcP0r!a|1H%zWU{a{sKyN_n1FccG&gu4Q3$QBC zTE}|7L&Ct`feRw?0*nzMaef;BPO5BTa1_K7p#~it2-fWHL8I_q za4$4}+ms1Zc5dh)kxii5A)u%g#b=TQ+^{j?*K4p$AGRZ#=U!8=pRg;?2ec}51jwL$ zTXaz?cwZJnk=_CN692qmpAm82@PY>|@C4SZSLVNMgX8W9K`ShwHGHc8b3H%X7f}F&=c7NZ>GM2nkK-Hg7PsQB>r)Yj~OiB1WqZ2q_|FMJWlTD3&E5Uy^x4 z%iLeo7L=oEHwR@t>#C1Iw07$+*ADG%elED37oVW1S73wQUGH86mZ?1!%qBak*X$P(2t11i)kl zzrZ5^!Y6nxjF0!~A%Qvt`oILC+@n;$#PPAVInIa#El&^Ev9l=awfj zaVEmUlz4$7$@RYj4u%Im3;Xv;5YPsB*uEyVX3sejfH;o%u47;b1^QHv@jX<=e}1k3 zOvF({~2X?)gooBf;nATp`w9JnbA;#d(>~^D}ApHHN@^ zq!cU`7qzMLLE+Y_6;eUBoE*%mFlX13((JA?1W55lgusWIkxul5tH1iz8b` zA=Iq{RnbjUsBcu2YxYwISShd#naZINiv=095;gz;AOJ~3K~%&ebd;2#vLg(mECzuH zt9xR7QemV61s)Vw$~KT81nYskq05ccG_3T(U5GgJ!OHKSAK&rEAAjJ-$DjE8{6MV~ z^?H3>uq*{J(I!VCE7CClr7UQEQ~#HFYRzphA=@i0n%2)dZXX}mw!7U2qSM+l zWC6;hAQuWjy}iBR+uz^u?b|oR6tUh{thXD*m~MA`|KmG8K7OFpI&Gtp&}zihpk*ES z+#Bjnk&bT2_NYL*CcG>c&X*QY_i7?aH++7wuQ-4S9y9|ZA&!U=GeYSIsAywHtCoNc z0FhKJ(!(0*xqE{~FreMd@6{91F=i69lsA04CcM18AYCaChCzx}wEjn0l5~V9tcHhZ zvhaMkee-froN`&PlmdwNnivJe`iX`b0;$0k3L#z0s#(Qk=!tp_uyIVe)rW{^B2Ens!=+H(G=A6KLfIY(l^X>~lk&>bmP&GVf zEHUD8y)dw``B(R5Z35O87MK)>MDxZR2th%4eO4g44ruR2)w4dem>?-Yx}kIcL=N;7 zfjuO!3ZUCP%pN9Pnw76U zgBG$n>_&5S!?Z#Y7;Iv{7bew^FZyuRsm#LuUgcWgE&$!EziNd6!Jsu-<32YC1^qN; zlm7Na5cO9=RKKdmK8r2=e7s-WKN&ObJjbiQiff+1g7C%RjsWZn+TUN5yz#5#_wjqr z-{az7UuX?|{W>Y(o`bO&K%S~93>%%+Zz{9GWHCXea39Z^)ev_uzy$D}0?hS!dPalE zi;B&wJ|;bv0lp#6;2ty(46Hi)@e+)seHTo1o!=dx&>+r=wo4VO*o;Yc<$g90xq1T^&KTdn0v+SG>ol-(=)dWdtp_>ZrcBeR>yR!^39w*i|4hl6KaC_QE zecwDM^aEVu0>ZK0`zb1roYECmMO`gvKmhUAS1 z(%$%B^e{*jE{dEo!lfamgqAj*!Kg$ML!X>|@0Ez^zEFaaGOo)7uh%PLh)|{IP1nW* zsqYwLgG51V9k=xppSMqZ-o9hoHf;Nbb>k$7Z{Aybg;@wghbi2NLK~0_#g38oPxL5V zAmpkV-E&NJL0=fgFa!hnoPUWYs|$H5U><+d$nE+BO7JwH1j|94HAl)#1+v9jh3}4>Fqft>e!>Z`k(% z$q{{YRM6sQ2*r%hc@6LHSEPK!a>;moy&{yz#I4;>*NR>@_T=^*V+<@y#@pK)@^Z2H z088Qom&*lz|NA!z8kGx5DZr#(F-RW5-ll3js>7(Jj>MKykV?Yk4Ceq3I)BZV+bzzNqed(bix5nF(XFz zq$UzdyNL}kuE?2&>ZN3aWFjSS_4SA%*~AlqCBI(P3y6V@W}_=wujt)cC;C7)dNVBP z5iqFAYT_L>zUReSM43^6{B(+{j1esm2I;;={lc7Q3lCTs2r`G;}E>BRU%cN;X!>vkZ$x# zis*O{L=7xUc%G=gKBoTjF#)#V(&h+bfI}FFfV8^4)&qUYzVN3Tb54xH;Cnp&6u=lf z=W`>~Utu7~7*tI+E0|#b3@Zg3Z%-^pXCs&e@ELb?O{rA6Z07YmEb-9Bb_m+hR1CA| z7~O*)C%^XFHuuL3C#D!mFOp)>i?@KeGKV2Yl7_1zBu@h=nZar!&g zprQJZ3;ZfLKC8=m<^HQ{@?-x`Y@$vFx2ntWy&f>nYM5D&ajp>rq_#&uYuv!RuMWU` zmU-V@Q-UBA#-aAjN6Hk+gK)4TtV%^zk#>Rhqk^L_;hxE|I1(2TuKf}e!N%IMW-^n; zD)7>Y3x0N6k$zsBgu$OhnL&fV9zRP|-T<=}%)mwSa_xKEg%?g_*VKWgut@Yt#RWxs~|KE`aJAk1$6uU9l(g1UI zaIj2H>(F_g`l0<;2cR^LbDh)f5vX!1^*KTPxjL!yT+bp`e$QNo!TUO&6X7#08epua zr#@)AXsfJ;sdI2> zYrO|60bB1t08_h$-rpHZ$|y@giEOpr2M_`#Xl&l)POFuGfq4 z-PxlNq(Z;|>Grunm8xAq!t_j}$@Gajp#wz%A|jGRbVQ?wnL?%olB25yL<1!!goT6j z^6d?OfBzdU*B7WN*0y19J6apqwvM&3vgp3GAM2l3w-sYls8XHyWf{n&;Qjp_*XuIr zX1rNWIRl_=PAb3g-KxD^E4CO>!aH0c?)vhAf8sxISzhq{_JRBTj{Dx|%R4qEB~bLH z5a~$CMUDXJpt9a+;)js1th5fWD!PpAX`lz!ZjRmbX3SguR2)zYe6}KxzsBSl+j$|1CbyG+f zczvaKK+f4j;7Fa#g^N?&cLE!uqV}DlNy_={!W^DRN#Lej+lFl?z4P<)1K+>j@bTGE zcdmbBQM|qimP?$A+<|<$MOVbKD4+2V=R!DU16sqj?I<}T=Yo*9Ai4Dt1su5G`i9_D zV6I#&r;fg&*6k2p8HQY|Zb*LJ?NmawEOaI>2m7QlXfaTRD+tyhFZk)ffAx|u(6CnEx|p7m02EmvF?Q+!St zVxH6~$fR%O9Ffwo;E&OfM@Fn0!oFdv0*r>y>l6SR=x{5aXq@Wa6|D~JTSu+5u&TSV zcf1<-A=Y0XO{5G7F=S-1-m=riOXbyyZX_&$Q2E?~Vt+Zsboe4@uOMM2uN0X(=7*dE z08lK5lS=0NqdM#n6r9ym&%I|qRW*!#BYFhT{@!rf><^(02GtJ%;9Nco998}aF`M|+ zfZLBaTHRX5Fslu^6dY@`wqQX(oaaybI9J&80OhYsmCvfOKK{HuAK&9ze)W2;!g5{U zK1F|S21z2My*kL}$N8&oKOg(6@a-WnH=42z{mUyqC%>Nfo)enq<3dPNeeh0x8n6G+ zOBG%z41pp@F-62=z)0X6ZoMNk1p?5?Eke{oB(W?1P^?O4ve9R7?Ur;7AlkDgVts-E zDH7CD^G;_AilCd&RUm3K=el2Wh(H(XNi`upS|J@&+c5^hpv559NzAG+g+GnrXbSRb zRiD-g06+suCb)aKT&Q@T92`AFhGK}OLvyr0_&t(AV1Z-i$&Jn=26I5H^J6)%y_i5ihZvW^zY``BY|yCF;Q29&qy;{$UcRjVpOO`_U*eXfXZw?Q)MjE zd$ZVq&j>Hcfsg0)#P^u9!n0k14*UM|d^j%foc#XuIw1+Js{RcA9aCFQ&&Bb(=M~xa zFaL5E)aCmR(7~^py}}hOvLf6XS-B7bxe6e}h*SuC^}+Vaz4E=IbvqIR`(O%yeFV76 z&;!7OM^$LQZVVtTxo`m*!RVe8o@sj{&C?pzml!8HpO%8_DD?MSsZz=wh2u{6pawB- zs7Nm{492oSU{wT1$C@pI0`08WKnGG1T#ylmpx(WQS8?C&ShqXYTG3iX>+B&`Au{-~ zyyM&JZ%7wLm|J|E11}?0#ClN&3KTLo~Dg{ek7G(v^dUxO7-*J6; z!OQI(e|-Or-+z1{hJ?Kv;t(4|XrOLRK1glO*0bu1WK3M7b4UmY7zSW;rEjl@ zmgEPeo5r?^ol4JvRgk(xNSp?BPs^;ewbV(xo8hf-b=Vxz(s9 zH;P0#;=S*v>xONu*!F?_4t(B#y#hIRyj*WsmW%{il88`DWcXB4OG0uWeZ>~*E>xw~ zsJxcIUXPfVm{XZ|$9-+6ou12WbZ9qKVM$n)7hFO_Sr%Nb3oe(-wC~|+5?RGd3vw!` ztwBT$Nww!BNBZ3c#r=Lkhzf{e^cyzNBN?4ZeCr*1-BD^mxe%ociE70dLQxVKP$7Up zMO`KazEO!$Nwt&YF5kdwekPh8Dn$e$|4yd7-ih(f#ZH=M<3m}bN49yOwJ~M7Y)i!!2 zdnr&ImQ;BvXtxUNtKxnKwiRf^0FWb$(yk~;DM*HJ^lT#|NC8qtZ;HN~#meBZMOn4- zjnOGm+C0)e_umZ!wRJNFj4-U{mB*S?NgVg#pf?^U_5A1QHIqKus1N!X`-=r~P~*pA zSUKYb@%~@0yp7Xb@MQAwxUAm02+~0}6<`9Ro^-3K7s?p$frYaG;j^tSJa?e&v;Tc2 zZ}M>LdEGY8s1^2Hf%rFqNjxQ@r+;@(hW(fmgaBBz(w{28zp7MtTZIEvr;(iBIlfRp z{p!03`r+%WT4YWY!{FyQ{K~8NuU{7FrQ~DE2x(|f zz?95{XkM2b=S&g8N8k~s`kxEsj0%6yAeoVxLTaMF?1j?0G># zN^0uQ3AOH4z_aJYz#aFmK38HnSG|DPr^wdhT75cKc;fig_5AB~`J5Dc5^WDKpIKin zEKcxv8eb2itWj4T|A^&=>D@em)B~vqdM{{0~ zmn+48O2K8>@$vDAw(`Qd23z0&_Ago=>riT>>;t_ugzSMho6rY3bTow4X`#^rw)?>P z`H3I#4mCBlkpYQMDNc^_%v*$C$gcKGKO{x~enE)1> z01@Mb)Y2i?`X|~3)X|}zpSZ;prSrOzT0eDU0xq`T#Ll3)ELU8vSA>O$YVCr$@96s- z5u{D`!E+Ytp%ws_Yq1_(L5PV$9RRw@On{fNAe92ZM1(r9-*!}~a0(8jg6Jp(Womh8rp`6-Uq@a=%1L1ogoC|nAwYKz(cuk{7WtX zfI4268meW; zV_0&X0+NzlQDH(lP_vqdGqLyQd%fLpzwfx+2K}M|TrR-NJ8-!QmL;N;Off7E-VK3w zukKQc0VQ0>#u(V^f!K+N^?60)l1^xHpi=v&*!JBj`#w)1+{X~GkXOM(e~6*0!2mU@ zN(=kadgHjxz%dAW@vY|>V(lEYV&6@zv$Bu3_l{mWTIZq*04YW2!k)9(F@>*OWx98Y z;<1nApdy|VW3fOs2C<%9L&Rgih~WJLd!chE?ByP$CRe2bYqiRPi|a+JB8I?4UTscw zt1LJJrRhNJjlJ%}Y6-!Fs{&%3845^HqYat>l(G*Q>b>bgMcU!B z=1~xZ6l&ij&lEJDPkzi`LU982yW>cT?R8F8?M~yX3a5h_o^1Pis!n6H@edBzc@imM z_VJAvxdumiQabI9Vn+uE^zXc8@O%m$JrFu41n1W|pm?AlKPkELy-e~BTCypmn$V*@ zS5XZxf39Gt!?nN2LD{-={QKN9{2V~)AQGy^*zs$6{=W0;|4;Jkrz;QtKGOv0C*C^O zk`RI=i~uT=jIJ{K;(flvcm&w-U6}X{l zAQh`Qo|AwfS8gQ;fg1S#=A$K~&-Rdb&E=j^~i)pOF}6{?@^wI>G- z#6I=zI#|VmlFq$Ap6JGtu08Mo5QRw%J_B9HF-9L;@BF+^FITd6;Nz!fVgkpH^YvN% z`CzwI;A2eEcBuN7Ok)tbmn zctxa}Qm)YYBU92|LEDeI(Y}NtTNU@VW7~FYO3&1uJH>Ra$vlMpvIYgMl3*_xd5h>< z$9+$DdD-z=FSxz{A<>s~y)z)|bzoa})Vm@?dOViv1rmuOT19)X2^TE| zudi>oyioNyED@IrdoN#K-*9<*L&_O_kaK^%+$=#^u&yhhLg2s*@4ea@b1A2qj0d!!iz;Xeu3wy+KObom_dxv`_m0yC|23klpJ|zYKH}2ZUw5bZg zCDmafIzWgWr2xwkP!oT$(tAM;S43Sfx>fQky>GiwxUNIfoF~G5uh6yCZC}wZO1iCdvkjQ&u z750><1U*zOf$Er5*8vI^f%h_{2uTq!kTS>XO;kM&1P%5|&)gUV5QU;sr9By18v^G~ zXD=?*ua!#YmB2=Cf?5amy<-m*V{>XhFuGVDA21&F6&KU!XgvU3*}HDG3OO+$+Q$xs zRRime4#Cdt`yr?n5tJOU6t_}gpfg4%wP40iaL8lj^Pt)hs2vc~E#N%x3Oy13 z@vw<{AaQK822jX};vB*WytE|G#MyeI(zefePmpK@=D?v?PpBC9!#;FR?x$+za2o1k zkmQQ6XR0$Ca5#+#{3_20=)Vw^`s(GC0Kf$RkMHO{cBi7PuNh-5aL0Lh0<81w9?$Em z9^vOI#rbvgVg9;m?CQ_|&g(hR{pELlk(hW7Zy!p9W>FwC15TfX;RG>Sl__}Q`IIU6 z_mWf#Z+++d^vc^wxmAy(L4sNQK#z(ksRdRgR`b{;BSQ_PVY`rmiAaEIwDnKu=GPS3 ztjZ@24sl;p`>q(x1}sGr#Tn+O-4VhKVOoYIEX#tomv_9qz2W-uLW*>xm0n5-DbPE9 z2L6$EXtv}i;CcaLj8k$IAJ&3!>H+q->@Q<|HDXFjJ8?KitVotmvu>P{a1v~o0Y}_0;nK3KTeK3dY-d}5#Fz-E7tBS4n zjmpm547P<8);J6+HzXBR(3(I@2~_F^9T9CPN>PNKkn$A($1sFov;k6hL&yj*Vp*=Z z-EOAR-Lcly=q!WDjhcm(KPVzV46GVAf(E2930yp&k1?wkBT$ekB^V9lc#yn5DH=@W zJuR(PY;8x74XF%DqX#C`u4)_|vb@*;03ZNKL_t(_P}C~{rDXIAm19LaQd-d}k5}>q zB^M+UY)eL43JP1CIZxU!kK@i{WQZeA_V5Q`b$8)Y()w;l6&Q>RpzofD?YtKaSnmTN z+%RAsv12zX8OJB4fSePu$>^tKm8w92siEvMfehpn0TfnvTf@HXSY=0R3f0D>v1E)< z(Yhj3r9DFmCQijO6az2*tZ=3gLMVR&*`+J4_TF< z57fcx=(?^)!Ycv6dbU&#gZ80{S~v9m$?rdHj_%1lD*|v&IKy|9NCZ6<4M84&j$i={ zExXdP;A)k4r~5P5KQ@=T?`X{u#%R4>ngC%xS%^HUC*S^Rtzos651wZvh@n8Qthj^- z1o!H;1l?a_kY2oR4TypcAPqsxM3{4CyF#QB_GuO6celMw$9a70TuLq z4vfqbFbH~x=M zReWk7P?V74Bn~D88U;=IdjygOuCG=JO3~C=#oAS@s^;@tOaM_;$-Yrn`R8?~m~gw^ zv97DNp1n>%M=b@&1yNvY$I-LuJ(D_2so#6&AIACga{{**%T!I>c zzp+jrfz|YbeU~#GWiDl*pmGds8?=2m?_}9}^_WWeC&tzpB(#5|j~{nzE2Y^zL#LE{ zGQ%C#bA6WJs5L2~o0WoA; zuWyJ}k;yqT*wR5|=-$w_75C2@)*B~pGKqIqqbv4GI(+Xiu*3vfWbk|vm1TPZZ~;Qd zoXqW@v&IsT@?ydjiq;C^uBJNMjq<$NqN662K4u~dMC6=sxd3SZSu*NQx_uOa1Udjo zf{;jsPk~7UgxAs6Hc_VD8=BjPnB7j43v#;R`ohXz8=vUCnMWckd+a$^jH*~$#rn~p z^1%hg{bWJKKn?7>E+wKYnf{I=Q~Xf?iHevb5C&8;QVO_S7F;eAX}er5SS|(2Qt)}Z zq4&y-B_(K};`z`GaR_2#mD8(bV<=kHdH(=G8-snYCPja}Uh(pBMKbTv-dSM8OG#P+P@%zvFhlqgK0j5fkAHftw}- z#t2~0$G(}}#40NGZNTsw2!LD?-ripD8eed|T=DXH#j=!1!)hkBFeyu>=on@Up@5n# z&#a{Jg4`Zr-*@c$j#?XB0s2TDBVtsFLnTFyif%pF4;30)r=UU`fE1CJh>|m_)V|pY zt*lDQSV}>P8Bivcy){%*AJ;L=4u}CUZBQDOl0h1Dvm^^JF^E$Dtl;@{LrWz_ip@n@ zZ{;*Fa)4+DVx+<^q6yF>TYn;S1Pl{6q37s;w$=Ko3C=}OgF#}1EUYv$AU%Q{g-K0v4RB*Ms^RH#Txx7HR*))fXoLrKe21&s_$GaTdR38z!}6d z=sJ3cS;?|w+c)>qdDEYG%=tbNp`K}#_hb5QR zp5ph~LEp3Y@N-q}t7J;O(l`M$n-^a^53W2e-IsMWS(_=k-7<*67 zMQ53w&otQwd=DNHBd?PBel4mLa3QHzq$lohJ&58504_ef9OtKf@xb?a4FtVs2W>hTYvua+HpA7ct0|_;MlcjT5Xj zs^YPbYAUBmkR$zbL+1DGeZ{)1*xTLYtfNg>nFt3}G6g-dZ?lwwC1eKRwixMMaUTQw zy&}eL=JSg767cd8kQP=EB_I7@y*Jc*M>By60MJg$A!tOvz%>JMjYvWodEYxLw_w>G zG2(K4#oNVbY#6AuVXHe@ZwQ6}UWEzydwIdP_iyyY6)MZc5YPg!?>km)e26kD@VC!9 z*87g;)qr8tnV6AsMg$Z7v;-yykrQmYulV@*!206@`(Eeda}9!@21nQCdAuf9qeU$Ijw2U{<@tDuW z+xt(P&ljvK!G%F}4&D|hVm+OJKb+e`TqHO?#eJ{aOjAtzq(I#i zm3b8c8kU%l?E6#lKW6G?Rad?`S|JU;7LexBDsK2d(2ibq-0x?c&L=GEiWHJn8+eZ) zYSM**Rtkd+CEb((U^vz;r5<+QciiuHI>EPwuEDM*K|43TloB)tXJ)E+3C98Mmv;h?$M-@ zqMKQmnbe3?Ue>VE{Hs-xB%_%5gjEN$T7d7y9Zcj>3{V_ZNLar^LBQSsEgdyhR;W5K zIB1>K6G1?bY(Yb!ft9t+Yi7LDCM0!`RN)e8nTO{$;4aW0l<#duU_ z+@z(qFsP+`-ac1Jz6z9%faB5VYEFLV?|(Q}*U#VaZ<1f9KKq!khcJH^MZWy3Q`EnD z4I;Jb2zGz}-H+q(pQ^#Xb8?n(Hq-9|{=;>DP8gm8NT+Ba*9|_ zG#ezn_&9zry{-4O9>JV4f%L#Nz}^ELNf;)LuMzy&mJBq+^wu;nDnc;UOQ(p-lRtX8 zwgkvdLxOP3Hh}lG zsUfoQjwI{TTjuMt@6|x27N)V_-!}ecE~gLzF_svs($^(u zL+@c+1A!CQ{2up36_yh~f;5A#TxRh1Lxv zvt5-y5C-!ASZhOBSLT;4KQrUgt{v%*KmNBN3=IdBjx^U=EB3mfFId-%{_+hstI+M%QioJ&Tg1QxIE9FiGL{o3pqxMho-k{C8-gAS0RW^NaXQn` zf|U{`RM%Spl%_(pD$vXXCMHD9Sn`T*-@f6perNB@BKUa!z`y?cFZ}EO{uBGhX02VQ zAL^w-gN!yuOiW1;Ry`JmXecvjrozf*>*!krLPT66a)?;-38(dh5(;`@4@Kz#T6XNM zqU=De#6=_ki@7HUfUf4Mtb7Y;O(`=#?qCpHN z{UX}v#uaot=b|1Z1L9^ZMx#yd^PN#(PX~E0O2`}GHNI9Aw+!!;; zHKhcJTP82QW~ zD!NhXRcUO~q3mxi4OJ95M7~#9TW0N)VYbJod>UC}in2}ZC!f*q^iP}esZ ztVA)91PYOGy&ALi1r3gd>s&C%x0jD zvmdl0ppObv5J5*o44s|`LO|3!<(L4gK@tLTE|irSSn>@u>03A8qYIe}Epp9h&k1ll z=$|8L2dmghUPo|g0|1qPpw7k$D23*&E#<+GI|6ei<yeuC-swM}Q*6My zHLVwxw8SY{d32x_&X3Xh>v-no={~B-?&b#z?yWLL2V}t8kog}z|J7od0O>OJ#)laz z!p+8K-E=(&tUBckU%TuP+CaVY&}b3He;5egGS%@1jYf z06{)||9I~-){n>VXL1H{Fuvb^C4nsrv?L8_M31Qh_X>AyFx~UN`KwJ8G+tVs6*nDjG2%<&4!#!d_1+ zUY84MViI}NofW()=vjf*aJigtx}0%Y6JF1MqW6y5$1nW)^%MPeN8f;tdc(d|Ea?MF zUPxJec|ksBt0*nJf0k$5sz7fYtv0$ABN(->Fi93iy(;e452TeElVr5j%gYPSmov_{ z8?GN$Tt7b0YsG%s>A>9jFq4Uay=>QYMLcmq)<|tlX=P00-st{Xw}L$vEK7lai{Q35 z?0ZG8{G%0+&iCl}C7p>M!b7vH2@A($7F!_oENERq^2jULszT>tvZ1GCRx>8U}1DYaB#!IH2 zu(V38I}{-?h(QE$V2{}#$8wyk8mQm{ytf_uZ9{+ScwgV}^70Lr%LVJoMX~h)k&YOx zDxeXpYF2b*^3?it-S%7r1EHenj-k}%oJ}hmlP{pQkk7%YQFK#GY>Cl<9jts`-)K+* z$Y{e7BCxJRLG!vGui2`}lRiiVs?>3u))l2x3~HDe!Z;e(dqeGp5GHD5*G%0hwaW_X z(CVPk@B5CAk1K9h>g#L05F2`?`% zq+r*ETFJ1eMN#*TT{(wCbTA-qMP;AjUP+l| zr8*!i5eJ-*J$luW*Zv^84>)DHks>HkzM%zq%f8uj3lWy{;Ds-3@ zE(C;Nj3e~%T#Udr906DKF%O*caXOwm=s!@Y#9Jh(X$c=sybpefjE%eXZtm55v3Ilw zhF(pu=Oqxti00D!-0J5DkdHa_l_Ato1qdVgeQuxPwC0)atliy(T|@Pm9{qT%N$VD5 z)MjL^B0nX+U!CvoUjMH8>-SHde)eT>96krlbIYd3^Kv&)GZg$}H(lD52t&1Jc z1A5NA?v*XxAqYr=ZkC9M2x7{}oh-Rzed)BVc344Pl@Eb*39w5?*KDTVCM0f6WHHX3+HO%GdMZ__niE)JAkh< z_yhtxRJf;~`*S@1{5g3)lD`AUIFd*hN+Gs2&*p~&d20>U2GR-wmh7_w2mv)WyW;qm zS*8`#a@J{V4tjJ-X<7%G6&;v-9)^bpsB&D>Php}yq zl(3}@wN#{#@=0 z7o5tDobQM^p_By>LB|WUWb{o?ceTwSLhlN_b?o<@Ni59R%5m&*n6;}5*PyddZA$az5w5v3H=t)i6% zsTDx8g_-Wx=qqAig$xnsF(S5r+9EdDv9*SM+fhnG-70SHH>9*eB%-#Cy%gMT8|vQJ z^An_8<`|Kz`XgW~r|q_(w~jTEs{h9y-*G;#`1$gJw_k6dRM7)#nByIjjlJ&pxLvXD z1-STBk{4XgD_+9I5?^Y#)!h9GSm6wb z*VQ`Bfl?F1P8ahS0+Oa-Zo@WRH}tM3)vBQ88tIEtM1aHuO?fO9?4ir*pib`{sIx5| zF-5GW#dNaCD5XrS{dr2s`sE^7l0?1l`FcS_L@&Vob{|2A0im{Fg)bL2KK~fO)3ZTF zvn0g>pIY4t!1}$4^(}5YIxNwWju1OeIU;{s5yE%2cDnD_jRkSP@7VT=+U{uAg6*D= zGTUJ-%ZkgzuM^gnt|5TWL`sQt?aJg7y5QwSpc()PXiadxZ+QE81N4So1Su+7#HggS z;da=};jkcER5XX(MCW@RTnNS@Xb=Sj*2g_n(qfWbJ4ca$h z)k&8+5*<8jqGN>&I^H9}EP|$>U}zXs&77uNtB;QEZKj-!VJNmB(DmCjq^4VniS5bM z^!pDo*G5h9*vC3S*WT5@5(f=f-3uZk?Kbl2w6}jw2L0v9?@@uF23m%5?o%~pc9X_q zwc(js{1v*-v48&A1Pq9L`n~H@pI`q;(>tH9pU*P@@Z9R?`TJ$G@puf>KUI9cIM#6t z#zSOE31~pTh?2EV`gW*0X~Opd`&0V}Ui*}IHjmGSZ-KA(_Pq*tas;mcdxKw-j?Km~ zxkYHta5`vDmJEPEnyun+SNm?h5r<|GU^H#|d5r+*6QDg~^Lp-W_T?jO&8y!A+ zGSL4;_)Mr71~sm0F+`l#GhPDyKd713p-<*jDAx&N>PTl28pYTZdH`Kqi};L%#-t}z zI$TF*IX)$I4t&^*_;TKJ|FgO72nh}f`04jSQ|8`Ks&ts-i`{xdT&5kh} zkv$HdU({n_4+r^xg2MBAuZy5IyO+&F5!m-F@c;5^?i|Gigjze<>W9Mu3D8*#$|KF@>4 zs_=3A<4}+1;4H4=UL0#Q+l0zErkmrjn0lPQ8pz~ql2XdVB+NLUPqrpl(NF?vDo8Op zMUi^h7Zns7dyA!nltTCdW!-L0AS1?TfCE|*suFVM9#yrQ>`k1O#0_KxfA z10V12*fv(w%KlEhV-rM4kf2DCxG4tP99u)(cWC2SwUi(`$K!qfh3m&VZdbZI)5Vp+ zBPSKP^WF4kuG!5oqHg=B>b#s^v8D_?olsw15q3prid(;9vr4em4iwV@OG1(iL`7J_ zSir)^8`@s5x6XD}ZySI&h-5=(<3Kv0MDdfEH079(B(gH2irf8;vXKUqt@r3Tod>F( zbHs8v?iK%m~W^c}5tEGJUDLn2LMYow&_eZyW0n(nCEj*rgdBPHtnVgko0}bh61i7s?Z1)X81hqypWH~C7)Tb?2 zmj%mmhDczNuNd0^03ZNKL_t(v=myl+iqmpN&L_OTQ!h^azPWbih`f66VIjw~3Ax3+ zGe|}|qv;v7RSjZQ)Y(XY03oB!hnvHA};4M&gTo3H6i5_UJOLL-8Wo6Hr#F- zwyop7ZD=0_Aqtk9kz=<0k}G1!SP~f>=kpnBUeUYae!ts#=14j>;g~21+1HM;HI%(0 zmPlQ5oDBLJ*xIZVloAk2Kr9_`?~vG_NStRu08u(iH<+vE2JO`Bg+M7uvg-73qYPp| zh;5jGW;lDR2&EvJ_T3o}Kt~G!RRXK>TviC^l>*HHK{Lzxts5{E7$DmG*>3D7N>eO? zbU8+>1}4T}K$Zyhv?ImL@y;t!S`Z_hqoX}r-p&YiJsudW|4~d|vA|P;2kxt681zWwf5leYRWk$wT=YXN}d9=L=w(j^jjLM8ZUl!mr zG;^drDs~+*f;tE8y!zZ4P^*%ORjPGQ=%%&i9?0IzNA>4Fy_i&gPJX!_f3Eb*uV+&r zK!(HiIKJv=y8*wq{p(8g^XpS0sh=wbJc0R~KL7p^;17@OQl0|Auda6_1$G_J?;GuX z9#7@r`}vkI{*Z1=MqB6=QXBdvNIf7%KA#FtDBWXWERLTBK`Qvf|v{~atOgU4NDf%Eyydu6dj2oV$W7=THItg;lM0NoNW@VR&W zJs@<@?}stZ*t5D{rvWD+u$#s2Ob2lI0eCAI;Nir^watG&zmB#?E>}nhqKHO48&x*n zJNulp9mgDWWermsvT1gGdd?q{Wv2l@zvd+OcL{Qg5xpPng8V!Dzx~{v>ChCu9}Lo& zT{qq`kE0y_t(HjfFlGYxK*z;+)*r{go^Y}KUpxl$B=$&V>0o^H?H-JT$vK+s6^}8Y zS*QC#OkM#g+Hu?v@?Z*aEITlay?h?^ah%Wh^Q)gdCd!`B`|)Vpsnhr!W2Guj_h+8d zGeG+MvNfw8VDs_)$GOb&bsX0dW{A1H%h6S#b?fp0n@cQot?OzsT!LLe0@AXq}s0iZqA|2kuYsT>*k4apO8E6YwPHTvw#|+=~V1kRZ+GIL{efaDjjb7 zPU@j)NmCBETrT+WP4UN%Kk)ta73;bp=M}v-+^^KmB4jj;KwOY>1cdHnNncP)L(_t{ z_YLoVU-8d>{e}DeMz>*X2tkmewTVG8(obbIMg>|s>UD$0ikKQSMD*CHXWTxpUq7&K zcWm2+a;JfiYq4Wq%(dB2zEGhdpaCe?JKDWLszU$hIGs*7FDv4YKd>mzBldtWA%h;c z_F7SdXnZ=aNSW0$y7zXV0r!5#)+#lm+cwtwV7-8sC0o+9ARARRFQmSv6CESjuvEOMP#D!a_8AmX!vH;fRWr-Ot>nr}(A3yNp z`*-9s+v-S)fC%SfYp5XI``7zV{QC6^ii$O@IKQq~mW(Rw2mDb!@NvK5V|&MayQB6U zx7!UVkzSjcImeouDue(uMKRi$qCmBc;64Pa28P4!F&Zc^R~u{P!>*OIF*U8#Rx5Pd zQ96^R6!Cz(-R}k4R&ZK(&KF6;gk@Py`1bN0K?C-sK)XGIHYYszAx+0MQwvgDAYyLR z2xu0_w{|2Qt|5#$VM*LL@{*CP8dw|Hrma^>AUbL6AqZL()C$DNXFa8aloy;%q_?l@ z3H#P?zZcwYH%b$(H(d3K6f@4}3r?pOEap`H5O|CYz^g6|trxTg>{~E6+~qK*DM%>5IC$}!H@t+ z3DW6IAA)d>pI%YT$gFHM8tc5SX~9aAQ!gP~MR8X#_yNSCmrNTI&d7;P~@FxjcU7&#nhAOghE%gP&jXh8!ZF zX`O;C5A3??SUY_Ko&#V2rswlha2ldmFg&5-rUBO2#^&9%4J5xg$3BY)na~YwZU>#-m3mehn=)ziswL1MRt07vZ{~6u%n|*l0Ku6dbE+5pA|I**O6qiuj~ZiIY?$PEO+0E?g?Qy zzF$ZU;`2F;-LtWhsvc58JGY1DJjlao&ehrH*8v*MK;Y-kc`|$?jp5=X-~7g^yr| z|K6oLfXi9uBy|RDzMcbiS3jc+ASm?pS~|@k|CcB327ovnd@iQ=+}iiu)<9#`#>5Kn zQKFA1Rwd}|IKWJ)kbvPb7eW9cDT2##LW~JJNE;A|$aw{;GYN5_sZL0VeNe5Zlb8`o zQ_!V2BpM+ZBDrssZpu|hLS0)$9SEFNy3|YHl|6|K$qPmu72Ckw42g(lK$JFGQqT~_ z7npTEl5$(V?-^2zyA4-fBv$zJ0e(?j8l9; zs~z`WJO29XZ~W`8e=%{Yb!;{WoEW_+x-`p(8cI=U*>QWnB3kw8a(Q7}qu8LWqV9L- zy#Tizdf!k#cGSH90_2#XsiMb-kQFILXjU``k%>BBsG@CjpN_#AeT$Geno4QreR|JM603)H|sb8ZvXqR(ihZb!KxXO#2Ad?;V9RF-rJ}; z)=mdcN6vdQop`X+!UKJCaV_Nox9bgppIp#-Kuj4+W<|KyI;xT?tY9nV#JfXl8)#=r zigl&-`Lv#Zl|a|+RI+wMRu#qKQ=W57+!pfqvFF(U|p00$feV)Us-vpAvSeeAsO z;T&n;UW3AWZu)j3AZI4UfF%lA7POPi?do(Yb8kk3HbF^>Xq5eBNhlXeU1~ACZMPP5 z5Qr)QEHPHEE-`TFVy^I=#$^&BD7_(lSD=&O2dQta$sJ&AGXM(saXwBw zwELmTzNAL+{;G8mz`}4i;_r_~BK1rgJ_7vyDFL06-~S)o?^kr{ z=ie(ZD(=9@4MyS)SiordbgxQ;?iI%W+4;4*rZ0=A1o7+x-F z22!QeaURspT959*g5W&xpxx=9T#MZ-l~*^CU(5-x&3j((NPs;)JoL*BFj^Ab$)q4t zs-aiK-+%waUw{3LKYsjyKfZsrUcnc(6kJ#IMAk_&v!c+$2#k;K;4}$plwz?2bj%l> z))Kpq{%OT@e;((T8xD0#Fh(mWOOi%KSbe>w`}H$ZVf=TT8IB5|Q%h}zS!(M=u=UW3 z5$@dffrKCV3~2BfArN%@9>z*Il3*H=DTjUbfe4ZD zs#F6bJ4#`foKh;h_0qhz&G}o52W#Zm`j@W^yKxm54fdoP5bcfZ}PWqb9aa($KN2H0WYwaz%^* zHDpAMka|NN3T|`bQGQxRyCXfMkm^P!>^xL>~9QZEZoc3RVGXRqGdZO2wSAU7BmA4oX(^#pH3@cpi?{Butjqrk64!#rB>YU1@{{(!Z+Nx znS_KCf^AkZbZ$%%l>kZY)EaLcbyt+i&5G1i+u$(5s)3%8-Xt{fz+uqVtuL&0L6m|e zt?UDwg0U@lzcAB);TwD~{jXQ@2xgYv!Tzy2*1Z(jqf@(3&Hx!2;~oSsS6Kn8w=o3> z8iFL`6mULAn}eP0>#72kYm6w{Tm?@^yC*?`fjM|Bamm*1E7902W?o~mb}vo&>=nhjAXID9&^%xb$z0hFWZl~Y!knqQ(Jx1fBXf~`9G~O)e7^ioF4)s& z{#{}i?0NzHl%#%j{D&mqOLYH8;QYUVBf#PPkjL+ug59T+d-xu)-q&#ij&TIhc)I52 z%J1(IkB9S?&*%F1`(PoDP|NQDAiP>)G7!_|iu6%+4MA+LbDD1-l~%Q%dsgD$nh3`) z2Gcf9bYoALWw0aow+1puVv5MEp_MwiNl-Y#U`m`+moEzhW;NezYHOqeoRmRv;!1 z{5wS2sA|n-JANMSUOd{H*`B8(fVcTJ`XG7`Z;8Tmjh?u;Ua_e^^T%C$tO`$H+xYhc zK6z3$&Dl2AF3O;yc|{z?e$mF3i;Cg^T0{UvA8bz%YSy*upoPzKf3D89)<&Fh(7Yel z?cXIs&k3ihjxnDr!eq;|htD7SV3V47d_SHwCOsJEW3+sHk*JSzIsmS5?;yvqrk5wW zd>@{!`!K3%jS1t>28TG@;G_BcNDzc(Oo`sjT#ddn^IY_?;q~*Wa1FInfgh9M@G!Q= zR(3=v$IF2YeEOYCbJ-Kv&%d9OVI5WCXCTCmz!mCYUL46RKK+i@s_3RmR`Wid_V6($ zy(lx~f6nkK6{)L2CQiP$*Pzqd!8LamXA#5jjAp2f4`8qpNPV>y4fQ~>RM8FL_XoEF z3>uU)lY!ux1$c@HUg?9b4Cq=%Y5RjY!5EY<4XAz2^-VSmkN45&Xv50hDjOm5LDN9q zz1npjZo)LmX{Djng6gJ23bg707r=+Bo55FLf}x6iGw0#0T8}jLvWl7X)ip-+-mu-Q zI#mmkx5E39p~xxHD6k2yvs6Th=Eh2DkA@W*JK_>i11-Z<8MwF3#`L)Z=m9xq#Fd)I zxMY-4u-ywj?r*sMeIJg1q@xm<%jYvL=U1Fw&j=}?g#rmc3ry6z&yU(sLqO>PwG_m} z>x>}*9q1(*9bFMLV7u=4c)Owe^-qpvVmqjpA7}j6fBggh`13nnUtjQgdBN#)MqCo= zQgCfIy#4xxQtr6j?$FA)n?l6P`2z3%Rd!Z{n+DQ5;{s-bV((835PCpsz`L1|X{(l; z7yuFqLJGKTchtS&T+Ud}D>N%Y>nQDxpTB;gf^Dj**x#LhH{ZB|0FBG4^p1v(UaZ2G zj0PM9F=sOc61otJQOvk=!I8iikDjzSFVGI`IU^#QBXlr{gC_)Z^`^^YgBBo+R!9t> zmL)=j_wBTvv92d9%LzFp-t%F`&~U$RsHLOT4fh-S=axb`_5Duz(D&D0`1b9^7$Cvi z<&RcMwr3mxp0Ee;z8CEKj%8gefn$AAkf>iWzX7Ly_7+e}x3N-)M5NRZV>TM7&=qiD z`z7s)TkB|rwBDkXrcUN$-MVSztY>*^X8zTf>~ezyQV3Sb2d22>VdEe*9|*qT+r1bS zlt%PFpje<9kfK7OnPCMPEyhBOW@JVLJBmOM5hNk>hB&nxQCoM}`i#AWd$k^(N+;%4 zl)zLmZEHGOXoN^QHFGKf-79S^s=;E40MUSi46*95T1A2oh8|UFjB1W; zF&@YTmkJSp=&r35CJMC^^y*ze)1bs;zBRHcG@x~bnv1qHv7pqBWAlzCLG2S#{<}o; z`Soy(@W78_{``6f7N=zNfBId|pL;&GS60Tq=fCset~v+&bLHVk3b?0x%;BH;T@pLi zLkl>+I>+Z~*9i2cb9}rW`#v!*fWSGWkg;x%aKmmI0Zx-n$g?j)=kwFhP59hm9xPWN3`e-62r#mF9XrEIw0ugKXe zit^Rqb~pw0Ncw>UjB2(d(1bH8*Oe)87*$K7`;NOB1k(8)->aWp zoSE1^0!Yuv%jb&U@m~MiP1#%@{G9ap<9`4YN2Ol7nlYh1ya(WI3u1;=ynTMFjzQPs zck{fS&)JjU0T7I9f1;H8oapl!>$-lMTakctR?4;n)^|E6(0!~Ysf?Snwb?MsV?R%d zBSPo~NHjYSPlnB?4lZ$c1W)*P_igQQNYoQqhpP1H+I*BhgBv#b^BsTq$XuXtiP$qJ z^7tNwcgzq7R359z$G$Ml0|1af(5W?~l+xn_hM|TN3hEQf=Z9A@h}aq8V4HN*fRH*9 zhzT`kvUyx@aFCcp{Fj#(WmI|ftSWtNH8Y-0~LS2Ma45T=bZ z#KS#WgVEi(p!P<3v(ZB&_~J(Q>L?j0>1cER2l~_N_tp9cACq zt*7Uj=uY4mqL&rj^`qzZJZ_y<^)x0O+8uud1ZlE&-thG})1If-D$4 zI=wwps}<4(+kHclfCfP@-3|>j6w-<6mELf@U-8j*E;6Yh=Y;EhMcE3jZ}0fyk01E+ z&+mA-T(HQBRvS&fS{=bJ9m%-~F4jJ$rG^cH9Xo3Cgu_uoE*?2#qNN&4oZrx5gSKWA zdkd~orIYwcu%rdhfLhE@1_eEM(otxhVTff1D?jR+eBwgW10d#(JLr_QP}Mq{u#h^8 zrq0Dc4LMJS4&gxkmNg(|CgPXN8K)Dg z<+mG+;sjyPo<#*YQBsk^N-)jnJv@G75~1A8wHNfLh|!FsY*S5fMNTWey>N4>g_NV- zjI5@xAcqzAqap}2ITqPtZ9f7rfnVF9k?gIbH&!;fs`Xj)_mV~xro@c_eHhefjJ29` zS8c`dok|P{$r_QY+SpxbX8>b%1H`1DD=Ix8_ENFs9d)OsIhYH(c9XyK4sV({=#EV} zm%DJORaQa;0)&9xxhY2p1nW|=^(!I8Z0+*cr&)|Ij(3o(mbCO4n+*T*UPg&EazrS`e~iNCzE@jp#`zfKT8 zAM>&DHfaDw*iLK&n+|k+{+!3`;frI<6*zw$hkpT%=lH8$#m`RCMrfUqq34$eedAMK z{1?}Bx}1v@1a!FEGO#^bU>&Vfnzcl0pi8P(yaF@^dg64T4zuJ}05|KBgC&E{_dLYN zn9QUy!R~Pkf}8}3hP~X7OTe-Q00|)^Tibb`9zY<=M!8S(5<2*~-+?IO-j2Ct_b>{g z%N3fnQc_RGWc2MFdj_VcR*&Rt?*GcU&=3Tc_&6x^3})F{(i*BN#JpvKS3^y=KdNUV z&X|&oS>h3RKb|$Y&tsy$SvS67RD6}F9suW~HaMHN3@mY*-J|2A^|$|+GTX0Tu08iW zX-@Va0`Z-}9(A=FcO+KN$A3=NfUg!}UK;>3ghpQo?H!trq;~90A@KPP2kXZZ;X0&~ z!OTL{VzgsiSjae>qTNvMm|J4^{An++_vkbkbsB@``#0a$2e3e$>Tfa5luLd&gm|RJ zd+R9iKnxZed#f({zT-6Y(>#0F)9p(e8j>SOe)EDi%Vx>&VFIZKk`g{W09_75ia%(8 zcDfc@aMD$W2!9|>5+D8zUl3g<&cL?^rUh?>p|-4{Y0p>-7z{>kapE#kOx~ zg%wNeY~kWwU`t{z)O3#Q_xp0fpMU;|%a0eL#%6-hTfqIc;deoG-{ZqxFt8-_Tmeel6Iy-OPh3+bgw( zB#9NF9Pkpp;gslR7<0Fu3vx)Pd&B$N2lj2lvSd=qV?t;V=hGRl=ReR}$965)?i+e- zbiH=x<0goR*lHzpy0AZ42uhm18%l|o^K-U7%8s~O|7)ujX;+k@5bVIFD526R*US%w z$%D8R^#~v( z0Om0?*wU>6_j^Uz+t8r!+BpX#WaKPZPb*$uFSuOj=6ShX%*lDfzVFz!9ldt!A>wiY zUS2L())h`Y^`Ht$y&ttq!ICicZjPY2QwTshFOW+@kc8eE0jT>v7#Ot@Q1kX0PNV8g zQ3YUoFsl%o`CId46c~XNtnEqbKxl?xc+?0Y)FH8j(2`ax`7~Urg9KJ=-6R8w&^sVu ztj~R_^xC3IP)e+F9KFwN9PXJCgfx2rN{v`g5xx1C(S^QMNy>IIW|iy~K_{gP zLankfRNUCilaHCwCL_paML0UxDo3@$E9-7j#Esp9h=A5QLbpno3fQ8`E1SH25gEsu zYY#?a001BWNkl|Bo+AsCz)V?^>6Szf)9<8C%Nx%A5m^p2x9w!D4J0I(QCs*T4uG=D5%~CJqDBS7&}Er3nh+x$59|To;{CA z?N7jPsvp_e!@c7F@p}b1(-=%F0T-$0xTDmD`&|(u-^UIoCp(B6K3USFzU~~<+7Kdy z6^DnpdOTZx|2aP-fV%HMHV0Bf4@z)CJB_$BA?QKr9kL5yvg=+p$9Ek`fp*X%X3Wv) zeGazGfL8AhK!vxSn%m8d1Ove6Z3sNfea>||<}?P+&&=aJ`ka)^Kc5R_{<}HR0}jXN z-aBHBCKZF3b3Ova5}bB^->m%{ZBB^vBgYs?txV^A04ekSGGY*5R7#)6 z$z@f&vzRtla$WQ5Y&_KfZ;9v5?em`)>w}?W7%TyQ_B(2Qtipbs$eJv}e`d+59O%HO z#PxR|=cD(;oc|pe@JOsbeg63G0Kf~+4$O_K7!_$hkAvb3-~iWzAfvA>sabI0Z*ra0 zxNdb_%$&t{^!7-xpn6q~0Zj}p5e+Rg3Zb@Q0lb~8`sQKirhSi}z;SMYm0J<^npI_> zgN_&jDc0ebkUBT=?#H<|Ji0?4<|Rbtqfq+@#zWN7#z<5ZzM$~I;O5#Os?#{pxiFZ+ znLC0dK7M^bYRAXvgmnotfjS4|CE<@hF38J*%PHYSkEWCd_UuSIpg*F3%-B5Bc{u-(04#e_kdqSr`GMHgF}c<(}vNO2*6alhmJ{T+Y* z{f58(wc+h&$Mqe!-+{6NT7eXSlz?Rc@(Ea1LCVL*S~`>9u8LatoaLqCQzed#iS@CtOZ1 zXpPRuN59;Hy3^=t-wT3J?on$6c1wI)MX8NOGVMT>JsDFKwAvwsE4m7h;3z%=&?UJe z`Uxp6$Z0XNIX?65=B=u1U14pghN+6MsyHVL-L8HPHoaOxiAV!P5n@GJSZNd(Xqg1a z{C-ikCfc?Qdl1x6(S-@GARq;T2muk&1EfbYG2~htL>cs}LL04dU}(EWPpo*ax++1( z2TdKXDMsG2Wcsvj)%0#XQ-ZJ6ItMCG0hT44vtG@e?E#G6`^Gxj1$B2ZecWh|O~;cY z9n}_7RF7Sq2?qcPY`Y{hLGhq9gup5?Izq_C5;;(GijiEWHdRXj%%p^&vHVSPJYSzq z-!1*~n2oAx@bv%RyfloH@I8>PLvnTe9Y!^FjQyM_KUEOFO5j;>d`zyNs}T>!n5!EA zSq>0O2p@y>862=rfBL=vF&E+Igxg$NW%}cK+hlB)tVo&d++r{wNr0eCghTXa0HzC1 zNU@^if>PMqyEUuUSq|q0Sg?N1^SRG+W+V;3VE6JFObD_dXRguRwEn)2R0qVYGU=ZS z{tOu)%Rj*$#Ulye+H1Y79|Cb>Ibf>X`~TZb>w5f@iM2xaj@}DuV}k2F(J8SAs4b$_ z9i?vA_B$@;SFFp0=Bs8l7(ztUqu+FQ21q~VgkR^J0gUjYUrE{nI2r0VcJ?7 zV<-pK=ec_%OkT_}$K);tjaMiyndhwE?l6)V-XL$Y6UO&U#jJVW+O@Rahum>~xfG%6 zajYQ^>;37y`taY6*JU}zkUu?+>GS*iJsl0LN2J)%6H}-7GRFN^Kmf7r78n# z9qWcAQ#Nmd_&he_QX31u7 zU^RGIvKfiR1Mq-*pG{|P_eqZTe*yxIpZWJZOLm@DX&J!U zv4;A+lnJ;Q^Xd81B4eI@1%iqQQtu51nnk+CbjJKT)!{DaL5Q0(aV&x*4gfm)CkE?J z35f{FQHaK1t@qE(>l+bp72p{OW|hJ>Ue|@$f)fG|1F}sRg$thRapCc3DIo);_v5+w z46h$9oVN|06D2~^AufMBzc}6}UVTxgzv&2i0!&jO?utwLVdxcAgbvQF;p28?;+&7nzMom)%E?-^G%V+c5YAw6u0XXSM&OzvDaE}*z>3vrC6)Aay5QyVg7eD> zr}GIZCYp-9zjOSeX_}A>pd%^Wu&}syFhKOl#7P@3F={$OLC5fa@_Jr6oqy=biowSJ0t+_8KA~64{u$lywta6X+m2-kXi3Nt z5jE%e2+83{^oDMaaOb{n*zem&z-lEGn_8jSm}M->m;*?!@P-&I$U1biOn(~?40O?I z8#J}(RViU$FdhNZP|=i35hb8UQX~TcvMgrc#wxRPN-DNHbx*@(yD^au7R;(Db!iBe z5V2wnWi^VIa;)7C*J`M*z}uHNaxYIH?h$~^tGLt4=E?}Gen(K+Tcd{0gS@VQJ_dc< zXkC`jA(8-a?eao|%Y}kfDjNhE(y^mxG!q*>^Xyd#Bq zNi;;FKM~_9r>O!Aj#IV-HLyBcgK2b|LWO3E?gtTVZwe zbfH|SFaa*5B8G|{jWMUJ81NQOy3kJM-jN_4uEkKwc)Bv?=uPoZtsBpjB<+$8&J+uOLVDakMY( z2aApE+N=$aH~?(mVxSKW&&gyPmIuJ@v1%X8m}h|KbHc1&{`a$!^mFq3{PKOH1N2O( z70EsmV?_43C4NmTY>e+6$@DRg29Rt(!2xp|3)kcG{AloW9P1G@8)L5rt$hA&zK`EE zC;6?>r$?e7n0zT}8gn>?qbi(Iv?56}Sy~;j>H!pU4f1NT_gGG8rc&El|FA~VSK>HF z8sYgwe;kJcXwd=wJ|~`!0Cos05)zc>y32mU{_X>O)h7nloCpgjkNI6U1Rrw?5gz7i za>^FJh`}j8a5(05?KEtVBRD&h{>R0)-q=nCVD(qSI4)bhk%H(=m1mS|^v1KSz8N~; zx~)Sq+#WW%ZdBvuy-3Y`OQ!Q;8;v*w;688zVVZ7wG=!%`qf?n%8*;SCGSR6!^>8UL zsHD-A7|q101E9H+s3Ha?K}a2OB?YzznoP8^b5WAx*v;Hz^8$STcE zut88;!Rd5D>kWAcczHczdws>elQNr9!f7!r=z6C9F9+mhK~u%H?rqRiA%P&DGj6v#KJGV^TF|2any}x258ZLw1K!^%LZEK57efeZLX-3-_6?>)Ia|~h7 zKWi=6+6`JsiI0-d1A~SrtT^;-$9B8n`l}Jy%|Kqkd9nbfOUC80BBqsrfkxE5W4~8? z{CtCicY9vAKrY!5BU|LdPF+~p8us^w`&JNQN6xPKcaX`REz{A8Y{U2Ob zfNs^O;R0<02wgeSJNtz?Wh+J|!Gb{IxbH!5;~G-e6c{ElQM_6PAH`bVLW3SH`s^oWOcO?cOF%Us2B4y` ziXMOzk0gb`vp~C7k$>MJ$*;xtJwNwP<6>^YUmHkyfG1Dm@cRT)+;~Y2a3)%t#jnG7 z;6GKazfOJ)5SbG92bXEPzq1B-KF9D>QR6SVMNyVanDJ4td;3*Ykmq2(H-oDXJl;_= zgCk=mL?FdL5KRcC!_3Y^j$<-mA!8(GRy(;Q2t5`i{}I>1dc4zGBc0l{_!bz)AY{K; zA6r(un6NfX_ct12#!U9qz*b+A+_8EL83fj?jq8Oa0y7=dowuD5?emAN(SlLSS%DIk zd-**ci;Il$>77yx)s7wvkmzcRJ8QEh6?@pR?Kj--A6S+XmgNPf^@Mf3Am^2AHD|~~ zdaQ^jQWB(`5K=~pmQYO-w@bJ2X9tDW+1js~iDv7hyA#mn33}_`rW z^jK6q?l!YR3;5l{OGO?`lt!}I18QqXF&g{HC6N9cn4G}P`2vh(Amp}8=l508J12&- zan_OW>!QU7AAS02ANwHFjRKI4!Era&see>ICIotArKG#|ZALd_m`_DFs_23)+#GmJ zc|c&E2gEhMVyKg!7m+e=+qoBcM7$+9}Z2BRg{$OZ4$XDM0)@lxJYRTSeI;-x{AIp?15S~E=)#k41tre zR6!{nwRCJ-MQS<{;QMyN#~V$D-rjzpmWmL8bv@&Je(}+TNWf)1;c~g)ayr9NniQ#p z{rU4JZjG+f&1i&6E<``StvFfhn3NW%X;tEqu;eS!x?s&(8Zl-kv@8PFGb*if|`^{b2w} z52?CmqmD``DZ)SKBmo!<27l&F3PFQHI-mfMQ2aIkEkTch!x9crZh``2;l}>)>jQuM z@dxzDKz%Pe?)N+1_8(3IzoFy`$qA|*Ph%Zr^fxUfv+axrAJO&;m^JBX+4L3W;v8fd zJdP(Gj|bXu;5-}ay4#7ZeXx!ft|TodH(?>A`c!5pTY5sRLsG+DHr#&fxZQW$-U@DS zH%O}N33nJC$ARbj1D_us`22Xn%y8Q(e*FA_A8$Kud&X7@wo;I940?*3=ntTMvi(s1 zH~~F?u}-K$2w@8v1ySCiLY=5w8Y;d&?mK?|$mqWr9*+~x_XE#QG6Tc}c}v)D8&c(_ z#3NF5cq+-{xDb(sAO2GFs;yDU|OI(LtBB^hMI4<@B2`L4$c>QA0N=e z1F_jf!$510Z!?mzI)fBp~r_VXXucYZ!g z!EIvzriYPcUm9Ae(4Ej}@NLXsCg3r4_FNMWD?VyR$SSPO|R5bLSpeey}LlL&VE5(C0%g_eWr%yVINxYmx6=FKFD1L=r9bx=arW)P;bk@!%g$(@Ep6k{io#RKGEl-urhN&S?j=_iw|yRSZfJYazoX z0)k|;hcMP$4q*5a+%a=)<|?!b)LN)L0A=?82vVxZ*@cr5>!GO&V`zyj%K#9RG1s*) z!>B=yvnjp>1J?UkZ8FDi^(?%0S$OU6G8O+e>C7^Z$9LwL@x?W#|L>{J*R1n+ri-A` z`bz0Vut;>cy(3%k;t0!Nh5-zhEW?whxjG?Ayatk^*YVWlLLzgl!#L` z9e6TeW}{{RPf;M&1xD?=MTvwdOdBHO$Pxhs6kdLlJW=o9hG&*1`^{BuUDS?qe{H+v zHHk2%4g0gQ$iz%Xm4LiU<_EaO&W8`-#;8}W>SLPz_D|`E#BrsH0JK| zyp1Fk0P0ybQbv#CK&>Z^ z^%}-`)q`E$xc@%xxsO`^8311&l3dQU*1k@lhTmU5_mWBH0DACkKuS18z1BCwjDo-s z(2}`8Aia-HAHdoMDCagx%0k#QrHooJY-c>9-rLYU2@oRg zHvDs%9NF-CTnYjSq{qp9BBhDA`-y$>_3`tV6sqXKy>}QQ8h}HSN4ziSiLj-I;46y2 zTGv@KtgRv0bSRLhs2lxafjl|#PB)aO6N-lz8FF{dxOotdGh?>POd+N49yX`a^@i>l z;Ip0R?eM?bz@W&tjLhmPj`^OJ#+y8;L zw>MYIqaeV2-|+VKhWoa25F%js_yk~hKA-sOufOp5!9YCa9q;e&_{T@XZ~yomzy0>c zHci_be*29X`tvj#$_z(>OVH=aY&g3Q16o|mgwMK2rC~uqNtu*FBNeKvBAK^A$>X^a zBZ;7tjjGv0aEjC#Nu*8JZ39HG-#gy!r-K@NuDy43@ArG?6TLNjoDWBZJ@D;MX2x=3 z`M}n3f4kxS`;MQ#{lNCdUaU=pG+b}x)Ku{CJkZ}+Ti>w;W?yoGXbf}9zt zZ`iEC+JSy5GoA+>n<8ztrGU6|ra*11gJ%jGQVd!Exhd+FQKg{l1wYFj=lzG%q`@qn zi;F>k4k}`6H&kiZvEfH)IO>6Rb^=hXAfFXERpg^06$XD)&=ed=@tF?TDJaG1rQGVE zz2otC;Pd@~$NK~Aq3lsB8MW@Hw;Rf~qijKgCbh7)6VKy`kB?9M`R8Bw>tDa{_;^4d z_;G*3&!4~J?)C6*KPVX2Rq^?G;PbB&pYI1A4=TL(u7h<#)YVW6@Z+})|M>lm-+sQ~ z{5J`6yWG{!vC|d%G*QWN#a-q6; z(1J;8Dw3eJLCePdA*km_&`OX|m3_cR7RUs!?1nA5A!m01Nvxw4&5LvBfsE40Rw%kf z;5GxG(b~x1%M+{*t-=c{vrPh8)g<2f*g#F_z5RaE*xd;!Ln6*?Yu_ zT!Q5_;GfQr+i-U_g1z+`_@z+;{Ng|@@14J#|1_P~u+}1v9>|NsH8Q+uZ9%d=b8kNr zfgw+T|Ma3W9i1YW6%QK0FwYJGlAg2`m7N( zZQ{AYyFoxmiIH8R@}IfW!@f)$u>Mm(DrMux$~(>T`@^E_~1QMBP~=BvpS z+Yy41DeE%N{ma%aC(C^qM)Yd#H@B0$iPfBCqlTmjSr_Jskm2+#=+bp$`iAqr z1R87L!r#$0X!kwmZ-U8qM)1sOPY#ASBWd)D7I+J|YYp#cfw){#1Td^Whx=J+p{eur zx<)S7^g@mP?j_<{D`|F<7~`_cughoPj|Nx9$q2-OG0y|YFyCJ-KvT0Z_r^ZHjBnT% z0$Q=B&fs?q*5j&XV0_&JXB@^kATn!(&vUkh%DH&GZzSvrB9jY*(3Z|pK2P?PQW2ei zm?SLY8YswhvTf)n=>!2A;N>2^Uiu{faUZc19C|oLC1}Sa12Hu7&pw5s%H!42}9`0+(87JfEj4DmF*d*iYD0aUO@$ST>Zh z;dZ;>$3Nb%Z~LGL6$n&Md_KBgbHZ_)c>nc*fBoxU_}72^i<#gLiv6T=!~35Py#L{!j&`wkXlEs!(8RB*HodmK1-K`9AG6`UUp&tFgMw+*#U z13)Ub;dq|-d_VE)uO}Yw51bFGeRng66x6yS?*(OJ#+5yj1;k@IiWS`I9X%;N|9as6 z{qO&U|EK*ol4RVrP&eNQ#HiN>p9h|&i(i>RTVkszHKYvOZW%v+-tgncPu%Y}+-?cC zTgB~GJ@Z?gbznHplY#5|2OghKXj`&&-ZOVw3>Wtp?t$DF*i!B7?S}pKhEkt^6+9mu z$6vqj{{D{MPr%qlqZYxo7t~uBK{zw8!H&r&xuT@aYsSTcJ$k$Un?6lakgCY&D->cPuf_2QM z!}NDSZ|va!=(sLuH83*)qeazf3&hpFWvL||Spy>wwLg1L}{Kf_us4n%FM_0GXU($e!?M)w%&_R=wW+#Ek3>x1ezbG zTg1=&Y)TG-GT;^yLD@Y4k6d;5BgV z4psmJ97mwzB?|QA!TA9XQvEw@>PgIdk98gP;<|oE9rDY1e-*@vJ!ygsoKRnSG_PYF zpy=Pk*kM1?OX6$|!D6paQ?G&6d2IMR#r2-X`Tagt>Nd~I&kPU+vpzTuaUBo2jL87+ z%tqbrYm2DaH+g~LBMIfL=_C9w9cuZozZAz zHx}h8ijl%t(0EhUJ&%-i^Lo}8m?RxVGp@!ljSYsBoP;is{=QyU1i$Lej)YgDU|(M| zuVL`>n`dd$b)v4w>US?QI#iM2j!e0A*24{|qSz()o`LrK&U<&q2XiurB;-Qjl;m4{ zmODfa9Ead}c6@$((0Q~6Is5Iw;3a|T$G`uEfByat{Ql41@Xvq#j-S8(#J=wya4AHI z==6i_XU^vX&&Lyg{z-@U^W)QN0BB%ZGd!LL?2iw8yr0PR9sB+#_Wg$5JKmpcx1_#d zBgBv_1H!(lFp5cVkw^QiiZI48NF_5+GBYkL@vNLXWuj>WtZ-vqyw(*cP*HS=8W_GW z8y8Gum`5hr*#ki}4AfuXb&AH|@_xHv-;~B5KoWB?5wD4xFr?Pxf6!Cn(`+OdlwZ5esr zAZJ2pPkh<~kH;tbMw=^-W*OIfzf)0o%lAp`S3y6iCfd(NiDu(Sro>utiUPrdmxiVt z&vxQ*Jn{TIa2!u)Qj}V7d)sh-yP@7H>Q+3MPDnnl)X{J020J^@4AK=vGpS~|4jQ&~ zKzqk=H1r2>7D1}O@pYN2kpiDEjpnXdUh7czkv|9w*u%VChMRNI{n5{U$pz^hQx1C)hcACk+-0_foeXX0Wa}o-9F# z{W=Uih0WY{NvJ7DfR&*-TjazTu1cPoLiw4(iQR(Q#LbD$Y8szoMufsnBPa-9z}y<- z>7|9pjftU$L#u}GC}#jL`%%yOW-92e*EL@`fA0~F3|<6nY3gn;czI!1U5E}i96`cWoGUy^0KxXcOgO{^({Gt}`Sm5M5np~DncCN^ zhXXZ|);T1I9v*9^Is&+nQB#E|NbR+Gk9=-x5Tq`&cO8%GxMJozB?f|ku6QsQ!z3QW z#JlLrP}d-5fz=EPbwn7@0%Quul>o!a65uc}t2tY;#dD$Xo}$lEyXb3;$QCa(|1M?} zKBAdZ>?43nWCwL^ew~=mHaU^ZY$y5+Gt(|!|4aa{>w%*&(`V=|P)OgQmg3+J!6(Rk zKH=wHrU3$!AxNvno_BQO=*=3+I5upTxM#3ET&G4mQlC8Ce%ivXW5hD9>*Rqu1|0YvM=IO z>;4AdZ}z1)ACrTu@n&5x%cy{DFvs9o=H6*%%?|W_4lSW6XqK>T9l-8^bVex#mVVL> zYV+E5jYQ-ui->z!fz+3)_RlQ$`!c5^p*igWSMra*l<=-4P{S8&9iCJ!&|8-ls81M%O8npiY@6i4>sO53s{I zlIe&9`eL?Zj%8AO`atS2kce6evIsOK zVtTJMIuSunxHug>vE4w>`~u&|pwUgRYiXm3C9cs%et4mwlbJA11e_U(>si;c}y1i{{-=f{EP z@>6^+F{YK70Ixaa7xFs zcQos0w$yVOJnPxe`iZUy-3t1mz)7UCkJ_W#jcTMnf4tFNkG2OiXw|d76qf7kFRkuC z8t{A^cziyw?Kk97A*ta0c7r4y`{$24{`&O?p2q_z8Md8D@2MpAn_lQr&3im+GvrjT zZFlV34YgE+LaW4@_6%uq!HzPN+6lI>jS8TRnV=NlpZS+NfFqXuC}Yy@t*Xv8o^iY{r7+ZKWThkf^h(8b<1_Y}uw^27{0Xp& z%}WVX^R=l`JvuH}8a1I7V}b;cKF_%Z%EO@;ho7ZRfAbo9YoB1EI(R!Bn*Q=B2V54B zDgL}L7nWdkKD%oWY(_>%tcNwAScAsD%gB;-rZao*;Q6Ze9ZmqUKuy2D1g+B_1Ov{F z<#N6oowyjhW~;;Z@X!|nSPAWsBoz3}iAE~f5YAfN#FWA@HkMbxYuuw=b~rMgf$csY z{r9g~aNcJ))#leWpGVaHnjcSnEM}m$jDJo@nvs;ggZQmPmIW_!ZOlhypcdKIl&8AA zp?P+R?c)ZeHdKc_KvKItW2|eo9->0C;v506VG$w|p}KCc%d$U1@qpP__t<;G z*~scSjvHE|E!l57df&$WAg-J&pwGNMO`hL<#4IS5VL5zH2ij5yoGtSR%m8Pvx#XWC z1BfrlqzJAASoR_MHf!`pe|^pqRYk^By^laIMtEi&$>18IO;99nQ^gwLV^Jo@@BB6hFqe1bqTVK)9A5o(Ni64(N6@G6(TJ1CP9yj2$#+u=~JGi)dX zx9oL7|DAhb1mQDgiGJ?uYYq0Jt@71I;Bv1K0Iz{`%%-@Axi02jvDT-j)Nq~|wKnYg z#u6ILSfy45$W)A;K`b-Gisv)qIF8{fuFtQO49gkW&(#_!((}H*+ouDVG)#Sj<*|7T z{AJI_0!~|eW_gyL;s2sg9+_TT856KcyN@|uJTY^boO8%s2w_FT{d=u-94rD;GeegU zrD9+b^(P%RCf_SA5D1%y47$~d2ACS)qFRUs=P&3&D1HugHe=9W3+gf&e!tW@a+ zLbRtbr9sOe8YaDs;Kt0RN^2726bjLlxu2W#d?g6j!iiZ$F-N~-8bJn5L}-d66e*}> z$5s#2?S|X^MAHXq&A4q;cD-$i``aD&w~aK0nvrWE6;d0H_QdDsC*I#bNySwcuMk15 z726NN9fqC?tQ6S$6R97<6!OuILo zTh4jT@zKxFQ88$v1x}q6r+U;x*Ybf5bNo>QG6Mo#-?KYn<>>K$ccHXDh;E^6Ly_c$5sJx}P-&`+Qp zg7#!Kg%&QY{Jb{NdWxpeA@qaFC{ zCm!v@$Ft$r<3KwPbTjl*aXt?`9~q@2tPj03;*n*mP2PADj!_ zh1Sk~j=k2*T!8IFc|4ITOCwmvn{dC~*(b9IK0n{l^`yZ!8}+y>*CKX*c=PsaJ@0Vjn5Tov#2_mow z73f*~uivfKn2!Jw}00u@769u&6-${&LM6`Cb}25ErLyo_`2| zjks?{g;)FQ@9XjJU`fq;=&`%L_!uH^a58Li8rS$Gqb7eJyw9GP*Lws2TUcM(`w~y3 zFAC5AzMS{VOBq~8W`AU=M(w$0Ba%2EJMGO>icYw+X_8=g2%=mB!-31p&^2a#qXt(S z90Zwwj^}s%pz%#GY=Drd@frX}k4@EJQ<*!a1k|E8{CB=hT>m8{=4Vz{cDK&{q}c=D zU<|@RAZG<*Y6`&b)c~+v9BYxukuw+aic+eaXbVjW_dyhAL^uOZ7G_2SKnV_p1yBYT z*5lrKoG0w@M1C)LyFVae*l!f2tnKEuoxaBi#t<=C)W!0bIeCjo&!U;v#CAJ;U)S-S ze+NsPVm><9$A9V&tc|f};KPekl!&f`Jo;zzJDtx zAOa8s;9UaX65y}p7+1e*{rxNO74LfmoB#%&e;A9te*l+Y->O*E56K$@qK?fY)mchS3#Fns(>4JZIh8qtCMleYEpD z7g5dRzD2>dkqs3slup;GInNW1#}m)zfqg%m?N}Uu2#R!o?;XdHk<#H}SpiyIW69U7 z_Szl_CL>8d-vwt5@_nS*Plm!}yc{7405YBh!4Ki{8r84Y`C(=#y?YRrzZ$oc6U3W> zuj*{WQHa1-WMm|OjT@MT0x2mj$ptL3_Zf~1+XygxV|$uxkW)d1%KZ#z6&;-uyvy{)~x8jdPj0!E^OePv6^cC}@1lA^<0~ zC{6fn1zg^0IMtMMsBNMpxiC9{B68Kk@i{ACOS36~F)X5B&4@f8zdjXC~@oZSHXL zd_MN<&ScVMlUz6Rp#3?O$eTJOdzmxQ(j_)0n{87@)~8QLcr0!=;A^IZ^8w>J*;;_A z*I@>lHU?tR99;q)%rwd{^>d)drb;#PcH($G@z@?{+lh9ZfF_h&0ZTZ&w{Q|6^))4IWkb5NMr^Aa z9_N9hH8ea}A)MIG$L?J@>)7>mpunDG63-~F>so@UMn^+rI(>6(Gjo#jwOz++RwCAS zP@U(?2E#~)BP^p;PuMRT|MO2Nuu^g3z5#`1_LxqdF%swq2+gi#JR+oYGCdYYp87qB)cE=_ z)F$&HsHW3#_P{+w5HAQ-W+BGvisK&4`|iSwy!l?(=NjqUBM5AR+4vCK@#m~A6xW)s zVQsj--Ef}&AaztvsD@Zpv-$5b>ovf?B+#y(UY-jVQ1sKSwK9n8%>!UX?)c$J$HavZ;1nM_7o=i}VTF)O57*^xkcq~r(gcR|^har>>_aDV%Ox8E9`&jb2QzR`Ln z7@G(6{v3SVhAc#-^Q|!vLp9cck;stSLct4%z4eaI&jaUiK&>ICg!f;+@L&J+U#OJ> z-CILDCv`mMjN9#oa=)Y04f%FspX0ir7DFE!O&V0bcu{C0YPYX{9V0*5HiX)DD1G~% z?P`3&p+=zinAxgT)FK?>%m!JkgEEC#x&A%z-^Dft?p+5m4V!J7hASNzgPw4FHkf|k ze6TGR;A_Kz?u|jg%PB)j0+e4TPKX@r7u-6|_5kcbAW29WuDO8a)g4_8HE&3{;AV=R zb|^Z!bTn-^ozk7M2QpAtuE@87ecQ3+J4}J|spzMnb;H>@j`PIxdEoe84?K?t-X1sB z`c^^RBHPnggZykb4?}MPc<i0H- zF*-E~!|M|r0v$9$PVJVLx>b#g!RbzJC8z_SmW_^+62a{nt*_iEC>i$i2Y&nc#K*@I z&&P>&bniFVA=0pK3AgQzpZ7P`y0wmWHrBL1o@fV^ZJ{%8v!sZm=@uD*yuSr9go$pF3!DSd}eh>BD22&zI^}JAQ-p;#IcW) zd9v8u7sD=Ki>HpLE%S#G4&HEpozi&8UaAjqznF@XaAi0_qS z)wvxH;i^etWT%mt?TJss`W-9|5x)n%hnZs?{uwjZL@^_Pi(cCl;Yuj#8EG@v0F$PF z*j3S#jDc<&x<0*b^8Di9$Bq&p+?PO48Sn$``)d-!Se?FLP==PI88h4u41|hz9y_>-$#_>AT?f>%Q>y zd;^X7=I;X#US0tfQs;txLGKOfHL$r5)bGY_1*LeR>*U&L?F4gpYm&tfGhp3MR{z4! z4h+x!^}1ez;jc{BHHcmX9AEJQzHi!w^?H~AK5?EEwQh@WR$)9)3eJ=I8LdSdB-Z_> zMB&`tJNA7ilhg>b)ymJZY$_q8HUjY8nLq)I+5sN_#j{v78DdVDO!l$%S*Cay506d5 zJgo5`M>|SBzMn^Gic;(DZ)PEN(81z>-D~p=-fqO}CqnGU9BnvzgY<9~Cr_OP%%R52 z3@HukMAiWY%qvw7kKWnmHQ9*QvLwj;4gv7~DH5P85n8Tns6JZ3r z{@YPX;PZgv5h{F?LN;SHS_Cbs>{~tQNAzxDx@Vt<>X}-;-!rFPV>w%NhWaFpx7}&fH2xGi0yK9(8yn86!Q&0sVNmIgAieM`hNP-TE zeRQE=&sxx}`}(GFP9mtK;#(H-8PO>yKG%OaTfeOQN(s}iu zwkZSPvz>Ufj-z)xJgDo77Lh5?PQmj5lwx@LR}n+KWhz=Hfq-g@{rSZ4XcWN;z#}K5 zl97r)Dp@)uQz0Ux?imXDNaQ@ zJC4VJKmYuNfBowZoJVtkl!8)r-1i%=$AETre7wKo{m*wiA169HfFL2nv?_oE+l75O z8v&`U?AR(5#Y-s=JLGyk-m{NDfe84L&cK#H9{z zW=g_=;rZj4nAzBCBXcW8;WD-eF;}O@$hbzZ+hx{^l0qs-YDgjc=6ghx&!j7ax; zuh;V~_c86F-;>`@^ojne$uVEtujR|Q0JzZ6#_yKkf4z>^-^V}KKED4cD|ET8HDjD! zKAZG!`yUUd{3R3nox@5eE&hFF&xu6D2ZA>#A=QFX)kSK+c3@Rdstj;Gn0U;_P(MM9 zeVy4JEcqrp{gWgaB3#Ro$goTK3iynGQy6s4U_V_-eTJ{$FmRTHBu0DC`PGx53(Ij} z9hM2)$ha=~G8SX3mH-$s_o3v$5{;CXhm8TGv!4<{Z^;2EIUwlW4a|eHsn+Y1Ob<9m z2x4BZ3`6s?FzFIr^b#lC-gM|J#Bp>u z{+zE2(z0u-q~!Latw3LZQxWI|01^ObfFKhTi}@P&8=5-e2QytM&~sj|B7DJ$X=vkS zQ%bB2jUX6sYILxESYQ77`nz@gx+lEOsR4w9Kc238&>SNNJZ&axEI>nL%{f_AjX=b* zr$^Zh{Wm%Tl9tSJe5nnMpzmJm{P=gTX-gJhLcR-_*L$6y$#BJA7)jx)#(ZPhRVM(@ z8n%tWFq2BmgtyjQyp>-O468n2rZ|rCqBb4M(EvsZ#^zs5^Z)=L07*naRNl!dJB|Ya zqu?fytpSi|*O9Co&kffgb`5|BW!~m9PRo8jK5Nqkt)ifD%=l~>#pf~LjQB9n3|}A_ z>E)r!1>Q|@w0C@dezJZtk=izU&SBKn2C9t(UGFa3vOcuP0LNMsuj6CvR$O&B4b+Or zo{q(77E07IHWyB$NgInzz)W%W*n}5>B~@TC@N^=_tXhsE<7aIh$c7W1d5Kz4bG1Wt zO89sf9^|{xjd2coc%U<8q!m0K2hwrEaPYyVPa?XRiiPlYKU>~WYDL-ds6We@qEu9o z?l@aV^BREG3}y|Y6+rfuECTfav3GbhF^kwWY7qe-YPg-^j*^$)U4~;=az+P+@?OoX z_sv2X_mm^xYj{4Ncz%A2rrz2o59@Rwg9?BG%Ng5Nr=yCi0S4eyWT)b~V$5SUc=;MPafMdH?}Njbq7aWWGgwfJ8Fr$xT3An zppQDP6o!JogE)03gp4{UoTC#ZH)H#WQabDam2o}mEkbqcY=%=B`swr5r+sm%J{5Em zOcXf@QlVpBbAds5z1C6sjsQ&^`?hIgm~R_Kvm{+-kvIGd9_oP3gv3 zG)yNqWgu;I>Z&BvjeV_;-f)~J&fd|wA$J|U{`P&xw!a~#g4PYK9bE5Fi0dYFoozk@ zV69NOVfXb(Dx{$u4Y&G+f*pVT`3q3NFp4gDcEdJw6NK=Vnhp9XoIXZ-!gaa^!SO}FbUJkL zbnGRONZmUBUq$s z#re(oK_GWzxDie(JkWg2B1SNlsmkmdun2p}ryOe1aSk3|5DYU1fd<-Zm)L=cj0swY zvNHeXYcO;<+>S@WCwXK$dN;oWL6BgLFmpcV0Br%YjkIC(hZ#t7zp`P=6>$t5-$i8f zT>m0|wX9_U$9&SozcN=Q9Xl9sOW>su%>O;(B5K-ABCukuGzHE&1wC`9L#Gk!SWZY* zsLiwNm9Km5dT%1Lo_IdPS$g>O^>q(Zxag>0g4vkY&VcYlYsU!o0yxVhdppOBiVBD! z_k>YG)2DwA*JV)Ec@=J-A`t&_wJ*;GFY8rAF3;i$(#~M{a_1hq#TpDhJwWX^PSlWh z5B_V7K$t8LQlz6^xO$8*J3}x_%yX2IvG1I3wHBnbVc!5K&|1S$DxS|WM7HL$Cun7u z0JULxNPa733kBNuuu&qh4A}^DAuMrQ!K@h1wf-1DS>K=*wGi-37uAo6OnYssBUC}( zh$y}WZ{mef&YabU@VU^V`3iTXtZ;(=Oo>9lODSt})B-#0pCo>>zSwC(}Z z^NHR%5VdjxPXD@)M%{-Qns(17bHew?G=Y$S7hrfVJr^q%#5$j&yeX3 za-2=N&-!p$>kv^_8h)a+CsCR9-~`5lv<u6QBKv}~OW@e_;kdVCnk!$95CH2`Yl8AVXh|^@d!J=LzCa%z-9h;?4 z)GNc-jwENKl5xB50L;}2J!_4bB{_wysh%gtIZH-~-n`jGGJM2`L(J9TL6DHm;EuK0 zq(Aa`#iGe<72yhwummZ~hTrL zL|K#X!C9c*boS}|sP|fpeuRl5>I$R+NCh3AMn^~m?Vyp!Q4^Mv|GS`}qr1wVNCr&BrpP4ELTvXc71$aI>+R?C8(r@nj4Zr<%$NheXW#D-p_;~+; zU+?euczobI52*FAk&|M-A?+Eu3)-o8el~pO!mH ztWfW*P1Wa&go0Wa1k>3hnq1084_DK0NNE6<_IU&B@+T+R+lI^*5#P1h$leE+^JuD( zPABn2fNOCk`5A(G>)(QXL3>InUFr%?d|w>?s0W_<7hFF%bG@#P-&)H|+rmAMUOj8M&t2LZE&<+mK_2(~t8Kj;>vHTk)>klneZ4xt>-7cW zYkjR*>+gR5-SLML*8BYY3kW}N;yd4A$R@>a5zl948p!03oX~ql*97TcV!jzHcls}_ z4d+Zk>}<(WEEn!UiZfo^iKo)PV6?Z-v}@eoBjZcKH3=UNw8cRQR%f{p0QUL61XeSk zcH`rBNH8>vm}jc}cao=ln?`B@idJXXYyqzP`Frr49DvG&jK1|b#5l(>BpJ{{@Nx;N zm+ufjM|-Xb-pn8Z{w%|3j&c%%*-0Bq&wMe;V|@ti*UW^zvNG1p?i}N*nBEJ;)M?RXld?bEdYR8nsq2!I zNv@)v_{g&ihsm79Z}D+kgQ~cO*EP7dm3!UGCp3S3z23{5FV{5{44vM)cUpN+P^^g8 z1Q!Z`g3q_6V4hKz0lkymC}eRaEI`8IXN&;fv8u28-q+`F)kLu6eaZLqzIa0tOJai^IJ!|CJ|@$VFu7822qExj7--x$P-@#=5=SL zG8|df0qv5<){6UEX8+Y%P)bM3iIe*Lg<2md+lE|<_p$6aPvC5Z z^HiLtLC*x!3Zei9TK0t1qviL_8%&?GVM!|SMP1et*{i3g~N;4m6zyHJQEW56on zHMZjO0t^~_e4`I%CZfuWEaw&}Iyz|kbO2)GRzL$~ zo7XK)jSq?poliI3uz^I4xdMZR_^8k!j}ijNbt4oPKALldYbhsY>PVvxn%6b!H0zH% znDcA^>$Bpyk}k`dV>&QNX5hzXM@m~x37UD0rtmCWU2!f( zuXpl#+NP{&%emsV-Eq6$kV`>HKutgugIEW8BdxG?;5gBWqNV_97zd`z+Hw(rG#j;g z24BZu&0gymwPmbrI`H{%;`8Ice%n#%hLQy#Dq|o6ZQXA8%dEiFtugA%PSf<5+9{NX0uXL- zZEo|3?32WCg+i4EMarNSMy04=i56;|S@M)w{?^WfCR3z|K1HHKP9rojyb6PK0wNrP zMTf@%l(dE6Xd}3cbH>=stnjP9s+emqfb%sI{}Nmdz-$HT{cqtfX&*j3OV=nmnX-D@ zr|j9`JU~AHu+~Q+Dd@6sUu(ek?|`!T3cu&o@A~$w?0kVpAoyHyCggEYiw0Rxw}z(F z!H|*&X2?>@AGQe-T%niNNA@vZ!-w|`upUs5@Z39S(VS63N zOXAZ5;nDu+07^=LzNWi=kvgEJTKYd^E?pRKl{!aV-aDy&srUL=2+*H z(Q+GW_4T^O*bPmcXgN#ZB6(f>1n6E$Y1|i|%m%rPznP%~%9T>`?4*ofWul}?5Z(ip z^`XKUMdtLTXhCF-{uD`<_s0zwFfzz-<8vY<-^^v{C(LZ23G49M#}mMFxmjjrB4a!Y z`gJVM2ogrHqZo);l5$nT9sz1lR29~A1TJ3{Ft6{AharhMxDbtss#M>r2V;1&C2;YO zK-w%BL=}?Xux&TAey|12d&Tp3!1|Lxa?5DX3ef^+!I=zl7~bC>JWv7qfo`nJEgmFj zFMw8ru#9-%pppS8v)6OVV}2O<%vXbCUVH5Kqh36oGbs|{RALp+pbgP426%|TM51mn zkv1KOAy{iUjHi(P-o4%-(4YvIqis^xX(&P&4*ObP(UH@fZ{R+W-McF&ZCwJXbG(e&Q3uwC5ngR z@x&ph@N&ti}2-uo1v z8V=(Mc7<(T>Z05!%Q>UexCYMqt}-$++4mJo6TE$GHxxP#=70x)ORa0{i=iBva;Vi_ z?fm-s4p>c$5-rn_Clw~xgfObP~HZ%>`+6c?|FZIwP^SI6dnf4>)W4Hs|aJcKm)zDY)Hk zxZQVbm0b&TbTQz%Eme@u26(AjP-DZsz=awkP#HDAOTD6u@tSjS%=4E(F+Q^jAVwB> z1UeQO=Vcvw%PTS^qh#^APS>F6^)-C@YT1Op^>ZKoP0NtjBTI%TiJ(R0GLmXLP3Ua0yGuJ z5CSCe_wSI*^*thjEiapZ*%C1kUGd}X2hMh)w-eeLLIIJrh}nY+ z4CkU7Y0lPxk^wCq@Rmy90R||;RGa12N}yI$nzvfS&U*h?JG4Y z0zD5VF5?z+TGTgAr>Qui7Jr}f*t5!x=#TXW0LhOjRJzP1jnae=U7{1qaW9e}wRiy9 zk&~fR_P;&*i9g@}#It=k^=PgmRr3v$AcIKu8dnB{{RAL3SRdDykFi9op9b3_0^lL` zW$p}hW?ZaKgjv+hl{)B>WZWN}B}HUbL^8Z`7-rrRvne#0*SN*}56aK%mpsEVu0vIV zMx;0H(;soejq+Xq}$1NP;Fs&lJ?6Q>(})=6GLCJO0)QTh+LQT>j z`D&~IIOyZf?1T@$s7D6#Bjp5XowIcfghnvoA5Ifo<9SvMiRoZYphS^#f>|(+96+Y)J`FW^{TpXav5E0lX?)SD|2$bspn4U-7)$Ip?Gpb0fg3WQJ@@E&a$|2|~qL zk}Y-rvYcqLWB4Vk+3g7_mjN8`;b7TsiJP&_*wr879uaplgZZ2@V1l!CJU$=z`1nAQ zjI%mOY_4#Rj4T=2*?r?UPaMaA)(!{hZT8Q#5K>&I&Ee;!n5!{w#laBYqs%C9nG3qG zD?xyUlFWaGV{+W#(qeP2_v=8Z&*{)Mi2xkn*s`v|*V7o!HB-G(tZ8SuVc6sF0|AVB z^zgA(Kk47S*0ncmcbaozUFTz7uJ`P}8yX*o*udL7mI6~nvd%5moTd#1X}P4?zLjXg zXtN0bnmRN8twCeo^^9 zO-68Q=Orr~nj+h_c}BPRd$?yD$H}a4YdD_#9)U7jD6w=kc^lObGc{$)#^cFS&!8xa zGO@N|r|a{-+{3cf40`m-T!8=+P&5>xF4HJ5kes3)90aeE>D`5crh^a@P@FnC)b~8f z4*vB-b@QZfd0oZj5tu+tAgY&hnChtQ3Wt0?;E9^efO9%C90;etgoB!c`ok<|H?{(S zaf1pO{245Cp5Hu!oPnrCOCm$XdQ3@e^#;fBYUgJe)I%@wLtSg-?Q{*bxWk+?Yx~-xj zNj%FiGe|ipl}oEalHx?e@%g~xlL&0w-!!%{Zvh~olnwi~qof_@v*GbL*%#N~{Vu~Y z#3tzT!?Tlv)(N;n>G}q}`?{L+M{&AKfPU5iG&(QMdv157v)H>$0WwR_9`!S)QvFtr!JeQ!0h#SbG7L#5G9_w|PD9Y)w0}RZri5-(=!|t0 zt=_n&k=A#+3GU?%-HknwRoD*8G9+cBT#<4`sq817D+N&CObE7AVKx|s5eNfdTLiZ~ zW8X|Z##o*=yj9E)wprGo`?l^a62>zEXUPktzX-=9f&zY&g)RsH;gChSMA)AtGZ6i_ zm(PX0ga;h2>dDdCjKRoSBMN^mp4ZBGP`liOT){DaWeAF7G!MMO!I30LDnJ&Pc|VlG z`Nx3Pd@mNv-n-)9$MwZP+#RBk-iuZtvnO-O#k0V99B=*pcUhy?z4J9ooYudMTErKM zn?I-Mhx#f=#@07|W)_!v#}x>iq?j1%08XN;XZg}u;$o(hkMQxCVCZyk1N`6*Zu>+~ zJ;_i?Mok^LxNQ{$g^|KGIan(RR#+<3z4aO^Ck)z8`ViKk+Hf3E^X3#l4}7VJtX_VQ zP;x>o8Le(;TgBs;s08m#zw$^5)w26pk;oPAFj z%p03o<|RG|fJhUw!y(W}cAEQZww%wO$6EhLKhXTydR#te>&ZWt+y_ej9%gu-pHKYv zfBi2!J{9|ZLrOPSwBNx#=#`l$6`W^d8OeD7%6_tS2q+NyZ3)_ZGa&TZ8X6b8hG;Z8Q{4b^sx6r4$Be;n=lFQ&y2h z#EF}E;OA?qc{m4t^0mKMWWb1^=Yhh4h?ShsoPP4bUNg75@syj3P*6G4$Sm)_lHQ zQBYuR{tBVt8Jo;>gwq_2#jww;NMtVrlLpj6+{Djy5!v|t^!ZWWT%-Bm}&|o>ka)DJhSQ_fpzUG_>(!)p_+gYh% z(NKsl2I~q%KTov6=T;J+>Hrj`x#GU*Oc_UVoyW{J5(?Py|MhjP>y6{MvH((c&-*{> z%xuS&2<(qSk(84jpYLpv>BN>u3YS8mFmS~SuXCV%y@5_O^x^!hhK9orz?mG_kZl4o zNs-Qu0$vLJZtO>8@?A-iNua8s8wKSYR7Q92XuXu?j|WBe3S3JevDH?%0%w8o^LgCj5PrSWzgHsc z6Kr0>Lq$7xj;&%JY-uBC-6lP+dIk#Y=l}o{(n&-?R8O73XDfQKK!QwCEbXi$3Ql!qa)z5qP~`xURrIe}4hyuzc_{>`_1# zpMlx4nCuKc2<;H(Q*>nD-u^Dz5p-UQRYg*`?Mxx_kMXMWL1!geb8)HTHHb^>v?M zBim=i0$RdlI&gY}Z@0HjOYOM|K-wQnJ6Pc7knMD|qam`__4L`QdHBJ2%rDqg$u4oI z`B~=Tf9^Jtfc;8v_aqpYz6y7GyY2Uv$(AWB|H51Qb9LS7418zMa$m1&eZYBMbAQ?d z1Guk`2W{QBE{yBK`9AS_QNQSGd||}E`93E*^7(wi-0*xpt1!qSPagz^-bMk(VPoc# zv!cH5+x+44##T~nDA2`Gf`EoDF{7RKo0&LI1<7MGZtZr!*|_fa2elqJRa+w1k0qsN zRZ_DyNyg0}Lv;`8ml0LQ3&bDxQ3#rXW*H6z#0oCcC>j!DAUxr*48}+X1u=U9lz?;| z%~+KP-3Krx>Tfgg(*gXr*qY0#LUj(UN3C-$uh;*41|^?K4~*4u%SFo&T26yJrW4{? zv-%YbCBtZak=C(VR@zfZ&k&QX0*Xv&hziQYTn0FH~5gmJ|U`D1{~eYKW| z8bQ-q!|{CLQFHCw_>7*fH(sw7q9{Ql64wY^*NHqUP>SW~0of0Vis}2A$W+Z2nMwic z{w!T!XtySgsiPjIa-np5rkoGbVT8qr;d#(RVB^AJSuC)gI$}_VZ`K$^kks*RH z1Bq!Tb5ZVS>wty$^Z8LCqR4iy33&Ot~nL$ z)0|Tm6!eze@BM&F=9fBEjW+_>SHgBjTzRhQAox2quqP8sMN~aFXik}3`Q|QJxZ{7^*QK8?jxX=bH zRc%yBhM(!Cp8J)gasBqQr>P6lE`vNen zgg5;b7q7UC>z0!lQ1`v>{5P{WjX))yWluNTkQLhx42&FT!Pbk`MkVpBl*^Z$WQ=%C zrl%^vX0ku~brl0>0t##O=Nf$KDQt-zBMQC$svLhZX!Kt9_5BX8>T{J_MNKprBW8P$ zM6cNI>$AYodY^#OtO6_l%VeQrTo~6t>kS#X&P56Hz5RWgICSBfY@R*uWD83Ccz@e% zth3>U?%rnNsDr($Are7bhi#n`|F)Q!9GS#1Jlw=<4B#5md9sgWkTPpA4G(E#9TYXN zZyT|1-e*$C_x(PaNG}E)_k|g%YA2~-8m2xHR6DMqL6q;gXrT&k(Ug9uU^3{CVT_ru zn;GI7REZPCWt6IRB^+|X?__VxI>4(EsskmZwlM~#k|+SUp(PDf^S0f)aRjJDyYH2HMOv;Tj{-j%@Dik2Ml46U2Z*X< zhA6j@bNrTqt1QntEBa;h80`55RMh^~-!j2#OyDa3`hLDE@X8Vo+LB-MQl#F4yfE1C z<#3JchJExvLWy$Ru0#EdN`U8D6iM0@99M#I58`=F?$4{h3ng7;^nxQgVl3)2&-Iu; z3prB|PkUNax}%kN9O-vMl%aAIBS(z_17L=ucc3RQoPmou#sJ>qh2LNQ;@_`-@H$^G z3-p6MC%&zzgchz+k&G+w`g#HB=snO73>N3S>QY4YL~d?l219lH=B&I@E$qEhu&Ipl z*tZOAw`6O{>x@>iTZmcGp*xS{~UOFrr5?=l)3*w1S!j zWDAP4nVzkNUO>`1!#oT6s)}CshVJT%mhg(fLHd061KpqX)#3dp>J$4KSHi#gyu^l3 z;A2^iU!QM!Hrp+c*%MCS-pd1>&%}K8^qTJ4)Uz2_iSKgaWBQ6^d-%-wJPT{R76`k3 z_s(?M-&>$DZR%$*;oJB7{Z@rH7-;V*@}z;0R)3zPhF#;Dqa<`)tTqk64A*8aZ`JCy zYeU>eig+c%`#riwepKrbV&Kyz{^_-|dv==P-f#TL0IDPTu}1gcmluosd(Y*fydc*w z=kF49`P{>GuLQQ2;F3P8wX6V@i3iNc2HDK&t^Qw4g-b}$>KRc$OfWU8suKeQDh5^4 z-^sOZo#HyFe#63sba^b~2I557<^}vR8P|G6C5!`^7Z4ZOD{&G0FPm@WGa~|4{lK18 zi8(l*yS5+Kg=+7}TYslj0;K>{#S8-Id=7V!qZQZ}=%r%ac1{`!oS$@MR(K-`W|Afz zMe841JHtKb&0E}4;Qt3-n=04rTQvX|u8MuhBy$gBOJuJWu>K&hC3_jXfiW7Z%5|Xm ztX{ASc)uO}Rh7;Il_)s+(P7PQYa<&*7Rueu_!gg{&XNv?MhgKHU5pWn7HsNQWg-hh zwXJQ1o4jTL$ZydZUs0>ON8mSb@&{XKR{NU-?KcO&d(06&U(d?%a&a?D=Y#0wHxMlq6e~{4Hx%~s{jVpk2FDGymFtS}kCLp?^9Ne&S ztPB$7xaS%J!Tr_T!^KkgG>-baPvt~|QT%8N;3HxI1t{cE?^}aoH4i%E#1yP$Rqk?8 zS0Y8fui#)JfBKmU$*OV-km1-U|L%mg@5xTL35-lM(Dz_Hk=ZK&s*0~1QVO+IqAa7W z`GurLw@%74JP_l;6&KEH0CCpb>I=WWUU**@hpZd$I7+++~K_=JH>$8i3qe2UgYgQ$cw7n>uS-P^Dhl#Q>@bHTJ}Qu^0GW^Xk?K7L_<6_FGvPF@X){Q;B zUgx11tYrm=R->(0t%?9}0vQAbfq>-+2d63^fgDz60Od0XCWw8c1m(8kl`$j+kPYdB zO8nK1qr_mIf0KEj9tpsQDF_UaoO5cg+& zTo>F+9MD9;UkR{zwY`i%Kx2$~V!V9qJlmU{+^e9xuGPl(r$qKMUf;i-C+Yj5G*27k zOCal8<aGTyAb6@rVSSp$siFB%NX66*nTC~LigVcjmEQP5C z=stg6Gy9lm5y%0ASF)+y2h85keK|532im z1q4{n!UUbBan;PkB~Ag34CXzJs8JqK7MlAJS(5n;fH|x`@aRB`2k?HQN5bNTyas3F z4gxXeH3QbUbl0F{{xknV8t^=rbfMO7NR^yrP`Gs*{Yk36`g%jbc`(Qu_ud`UGkFgp zRJ}|cZ&sJDffH0bZ`GGqtIXd^xm3G3Q_Qs{_#k8JPQXA)h|fpE<8VBVhR4B*e?}m$ z0gM_ICZ|=7++iQK&(>Gv#2{6g!q6K3D*o#ckv}9`Ke%Q3r0R)sr2;cVTpOTy zPZ4;`NJ&ofxu-UA!ecuTzZ z*Q~5=$?bk!KfQkH1ruP79QV&r!ip8p-2o2*XcD*L+S{@j?(m>+AuZqn2#LScvtK>H z)aGdDie=p4hpHn?ijN0%5ZJExktBvdQwDjK*W54p6yC!M^x4{>_t3xP_Hbs|5r^TR zNM0(Hi$A%O?T7?%U@*>->I#braAMn{l!|_R8`- z!G!bQ&y>j1UC3&F9@dCSrG@w1@`p9riFB(_Js-Shdtqu%Gy547g!XUBD3lR|yj j1sh~g*$>X~r?dEf%`2gA9uT!e00000NkvXXu0mjfG6SxU literal 0 HcmV?d00001 diff --git a/localization/ar_tag_based_localizer/doc_image/lanelet2_data_structure.drawio.svg b/localization/ar_tag_based_localizer/doc_image/lanelet2_data_structure.drawio.svg new file mode 100644 index 0000000000000..bc8ba297558bb --- /dev/null +++ b/localization/ar_tag_based_localizer/doc_image/lanelet2_data_structure.drawio.svg @@ -0,0 +1,156 @@ + + + + + + + + +
    +
    +
    + 1 +
    +
    +
    +
    + 1 +
    +
    + + + + +
    +
    +
    + 2 +
    +
    +
    +
    + 2 +
    +
    + + + + +
    +
    +
    + 3 +
    +
    +
    +
    + 3 +
    +
    + + + + +
    +
    +
    + 4 +
    +
    +
    +
    + 4 +
    +
    + + + + + + +
    +
    +
    + x +
    +
    +
    +
    + x +
    +
    + + + + +
    +
    +
    + y +
    +
    +
    +
    + y +
    +
    + + + + + + + + +
    +
    +
    + z +
    +
    +
    +
    + z +
    +
    + + + + +
    +
    +
    + AR Tag(Front) +
    +
    +
    +
    + AR Tag(Front) +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/localization/ar_tag_based_localizer/doc_image/node_diagram.drawio.svg b/localization/ar_tag_based_localizer/doc_image/node_diagram.drawio.svg new file mode 100644 index 0000000000000..a339951663b29 --- /dev/null +++ b/localization/ar_tag_based_localizer/doc_image/node_diagram.drawio.svg @@ -0,0 +1,86 @@ + + + + + + + AR Tag Based + Localizer + + + + Other Autoware + packages + + + + + + /twist_with_covariance + + + + + + /image + + + + + + /pose_with_covariance + + + + /ar_tag_based_localizer + + + + /ekf_localizer + + + + + + /camera_info + + + + + + + Lanelet2 + + + + + + /tf_static + + + + /tag_tf_caster + + + + + + /lanelet2_map_loader + + + diff --git a/localization/ar_tag_based_localizer/doc_image/principle.png b/localization/ar_tag_based_localizer/doc_image/principle.png new file mode 100644 index 0000000000000000000000000000000000000000..4dc6cfb7624e677b0ef8765b110c00a2080f39aa GIT binary patch literal 1479008 zcmeFZWmuM5|1F9xdx?#TiU|gYNJ)bVN`nFqDWHUOck5EY1f(QIq+7Z{1w}+aTDkgt+W>6=+k{81u^7qJ^CC|e6#>fW$6Ff%=@U|^z)f25*fJIlu2pO<--dm!}wS+;>^ z(T7>N2ZH`$toPe7EVQVm`Ysaf`WbMXosD%%>2sAkhi)Hr(Bn=*1 zRd}G15g$+|t4|Ys`JO~{{^wTChjo|KlJ`X?TuyAzf3lA`VJ@jiZr>3x9q-9srCdM7 zEvxfVn1tiXmuxG?>O<#$71l8EJabN&bS%-xj*5z+U-kRa{{6pkqcc2o|Nijze-95n zl_CrBKYtDfZT_Dh@VE19wEz3h^uGW5r;7aF7yMqJ{~y+YKCj=J%Fg$Y>yHaPJv}^h z*tuL`Mx~S_ck2BE)_ebFpUjmG2aT>6cNVG$E&tG#@xYFazbN(C>igfDz2b5185LD` z@uf>hj(`9BSc#Lm`NC$TDM2w=_4gaoD<0A?Wtw#rhi>`f-&f(|7!{8H*N^yx_kVvj ze*QlL>99}5|Gb_2?dbmzY5(^Hf3MH~2kYR|Zpr)ihkx(dxqpA+moLhtX@w5cAFH0^ z(BE=WQBd&f?dzj1pBk)j^N9RAzt1a1{FB)qERS7&eC77)wVO*26#n%+t3E{SW>yVc z-tYDB;m4uxe}A&~1>-+{my-78mywZKR)aFJ)fP53{;{#KQv+3rz3(0|$v)?A*+u8= z;I^`qlWo?OBJ8ncXtX8c;r;tpq@*5SQ&;cr?~m4c_b}eLB|SkUBj%vfC@am$D~Dr+ z|EW>l!eWTJs2#Ml2KM|v?;NM1y0sF#^Mp*?)yT_1s-?}%N{xw1N*(z&jR_PcPQwPV zl#~>eT}QeLBSpQ2r)z|oaTPWTGX@?tRyH=2Qg`acXvsY`c=5{eFTMlYsiJT6b``ms5tan1c)rhX+QCFe}r<90Aee6{BO;T6R1kS_l~ z=ggTijLNTGXlZF#FD=-3RBxoFrc4i1W$9M#7Wn@94_ay(yP!jEi&t4$S$~&XawX$O z(E?Sj&yRNuH^lq?_19kwshTCBTh?FE(t3H>^FaLf@8A8jtAaT*LZohHw0!O9xxqa! zKK?wKbu|@LJ5vC&TEMunv2oHF_57$;ug;ou;exLvLI*LXqbmVcVI9j#BrtnX z<5q6VKlKts*hC%d?e($0E!%zv`^ZpicsAb&K|u|yN$X1>cUq?*tE`wI<+ej3~* z)1Sx6mKb??RXYmolo0Jhp;P^pBac{$&vq#H_V+Wmxw-xP^~>mk_mO>^hJMFoLiO`I zmzREV8h<%kgro}cJj64CcPtZS+Qo=1C>6pY9l6XDUHG$R3xLH+q`;YY`0Q^s@$RSbXQ9k4c4hT9cmwVE& z7glR~3B(+|^l-1|($B&0O@IC=Y1dv}F8X92r-aREEKSMc)FaoWStUANYcV7lrP%qW zLXt8or)j>k6>C!`;k=_H?4xik(%2mS%j*F()RJ8BmAid{L zy}V>UF2=>3T$*b$b2n;?mp>t&wl|1P_aQ2Z5wAv;A!TV{B$ZJyDNuN%zbZs&=W(ek z?;g_7?AjGoRwh#F0ALV-c$8{WKPcpS&0`B4+X18Y+%$aCv#F)ok>)JtpO(p*B^n-E z4=IX>+_fC6PDVb&*^ae3j^_<3q-kC9=*_YG`eA#rO2%cUxzVfk_PHcXNv7-9zGPI- z&wOs*yRk7!?THAEcv8MiNImmss>& z?kIF%?(;GVhK-DkXf5((cW-u_syGq0pnjas`NylK6!pYE z)^9n9;tXh%-eOGBdJ_#})JK1&L~-Ba2^vND*REX)RsChU(1t|BA9Jn@1{D*{A}`=1 zp8l%krew85)ht7v1KZPEYa>M)Q`GtDCr`=81bQ+YKhDU=D4|y!TAOXsmg%wwep&%rEI>e4iqUvtqCU)X$WInhvThU%iN z%bjMvMbNU}6wCJ)n|Z(AEJ~917s_ixwB$3tiS^X`bX1E-sg0rO;k#Z;wLT93qW+|2e5}=cxzi{?da86WNKv zX-`sZ@^W+a$6B*uXkII(T#LsxduYEpflbC&Hobeahq~Ow*_kYaKO==vcw{Rbufjyp z{PQ9EmE|RAO--pVUdqz1d9DL$S%&^3WEdD23{Wliv1;Az(H^&DDg6GI;Loo+X-+GD zo;-9uN28KO`PKQz%TMZhNDN$9Lyzn*W#ak*Yrh%;Hrb>I`N{~2}F!J2TT zM8)K~BCjhE7uVM7NQ$dw+tM2U$T^-FuDEM?mYX(iyh^UbHy8CXpr@?x;=N7L ziLUCY8UiM5*;VGQIyzARB_p3((d2^#UGk4h2S>5%RdZW=rlzL;b?46PaAGQ>+w$U; zFe|P_lfP?c?jG)(ds}~OHEK-oA5uDh{?_V0{@^t4KF^FxN9_JkTS`l!V(#bNYf6vw;?1Rq4VLPgfA1|W^ZBbtdcU!)SvdgLaaaW}Xn|QwMSa7H7 zFB5_JcB_Y8Ud=zJ2c-uc9UOS9T|}AH^BXvxO8KDZ2KI=s4Jon(QF?m;xM=q8H{!lY z5nw^KOioS?x94Txp2v>+h}Y$Gxh9GpbSO*Tq^63<@fvPSjNPMQ|0aTbm-Ud(x-AFd zf;o+N{Tg)qPt$DQ9&z{X8iDCg?6zD{9cZR9>iO1Jkrr9VUk_gu*)ZN{Z|`lKCansn z^{J)Jl?MCI8DF`#iDm{1%o{3pyuxTmUxvV*qm^+5PS-J^5N+*f<`zqnkGI4u-ES6Jjx?isNGN2Iu!DfAedmnhP`&x+fZ@)oVuON# zdkh=mZt&{WzPvQ_Ty&5l<8ExCQYs_*7)pbxJ7bparOl*71I+;BM>T7@b;NU`ttDT$ zvu+4TGdm<8$JUd$z@e=Sbp!mATU|B zlhLigfmQU)=HzukwW?nsw-Ww>BWnGJ$D>Fm8@RS6mM^qV^Duw zV75V?z-?eC-yWOsyXZ@DsfAMyZzM{Ksu$Qw)A89he2x$XML1cR$MZ91?eCcD*0>0S zd7=NKzkFM^iL~A8@s5J#?>}B#xMPifvn~&JnNxXkP(am(L$CUPbTG%M4%3ww=@8Z9 zdoGEJ8jZK-1q(Q3_i&odzgd4M&iUt*W8V|5hA8o!m3bBGwjK+7t?G$(H*pX>JsZ|xkE_y=td1h#V{baA-4}vsvEwnvS zo~qBEEYRvIbjWbuddM{IIX%IEOAE7-Hc42Yh3}%krf=r+R4gto&MeJ$wH3*v z9~1S|Z_P9yD=+NNWPC1!q_&{TLYzz(?-tGSQHz#hmtTI_{Nm!`Nbmr`l|?IrGi?gH z+p;swDLIkUlI47ZO2U!!6jC+RW%(!X0zVxUL5x`?z05T0 zdD8WO_HaMHsJ?P9rjsX63Xiy=FFOA0f5yD?N2klYI^fcWan-e(c3m+xHcogb;(J`W z4jj$Q(es$e&afLz$0^E80MXm;$-`r)jW-}tchWYDKk3wm+4#YvBWPeH!J z%Fp>7z77n;Ac|GrTOn+o(6YbJbV;x_`a}HJ+?e#vio&9z*|MFoq%%Bx_^=LeYxBg< z3f~hnd-uknA5^@1m;0)uvBqJnmDA<>oAm)gvZ`RbucYXiGzxREgkSsmA_-ST*LI&K zIf*W1R2L;KqrM`enr|JyFf*jh#nXuH3S9c|@#D-;F2@;tf)I)vXW7Dhecjalu4&^8 znR#p2A`rbX+BcJVlWgBgdJ}EJXwYa~klVI9D}2JZEiPhH>tEmg!=~>& z;D41Z=Lxr0ubk#h*RETqdfbQM&#haP%*|gR0tc=n)g^DbMxq)8Y3#UmhiT1of#J5C zR1}N;&l8+{@jw}44&CM#VV>R!jWhjzg#tK~r0Vr0Xg4+lPa^k~!W z(}6<|OAUe;#>MJD&Ez!P{D7+g@amA_oGuI2VB9Tiw;4~J64!K|yf^d%WO)|II>d9Z zI!q08P+nO%@Qh}0(m(X(_U+p~rUDb8TxJ^Xu4nX?5F`Q2oN6GJ49yi`d^sp``n=01 zRI~@}Y-~6M^qP`XPWj&}upLXdvwkZ8`kxP1b~TC~a?xqo!b(psf-=u~ zz-c%>*1ETBBlES~E6@@e^uk?Y@V;ThbwEKuK~D{r&9Fkfk%~Yk;yocfzVriR*#4X3_rQ#hxCG8Ckb}y;}Cx z>i8075>no@pu_o={SSMZJLZaa+*;WJdMEXLc9xTlUGf`S+s6I0wDD-sPYwxn4rQ|< zMHCSj(mTH#;8{Ue%?i14bGH*Aqt|j@C}}vn8#nFAjFAaTKv{1Io1Z9INsy0~;RU{y zAL%kh2i(Vg^KplRii_8{&M41VU9=>*=z!BIKJjy+VA%~;H3G4CM@yKIO$oh0d#(k+ zX7bG|qZu`!g6kolhymnDl@q=_H`>Ct_le6*@$&>%quJ7nqiNQ82`$G32JQup5C=Bn zby*;k->1c8VW6l`*@|c!gitA!-UY-Hk z&pr-)Z=yU{7CO!jtLBrtSd$x)1pJ0L+x zwViF14E8l$Ie(lF{=+L23tB#Hi`KmuRZ_bo@Y}3RyQK+qYFGVVdt+l`| z6*nZ8^<;K-mU88ax9vn{GT`I>=lg-~T87zTmwyAP^EV&wWxa?hdv+1zh9cv!zFX*_ z4%^|K_&VwGPdl!CvK`YbaaAu_UPv@x+QLqd59*xs&Ntw#3804YqFx6L+p?2ErgXT? z>SLsXK}h?vK52P9cuCKBBb0l`fgn9O z0kbpmF;WTiiK7a!GIUkpLYmMJq`4GJTwR{f@ion~V{`Tv&xuJ%HGqOj)qsJ82cI)B zfKWUe>qPg;s;rhRrEq zLqF`gT=eW02~Ba?B819c$><0YM*+;OqXTWNx$^SL)Ib0T+_%!LLJe3GZ?*v_ozOO- zg3Ypm`rTH3g%2sm%7jUkkH2sBD)&0n3@|KRUh-?44>|GCx)1JNkLDuiWP6RDbC5RVu0@ zoZm@D7dB2!K{z`&IWh6_wwj-q0S1|cu)uWYOtpE{ix-E{3AiYH?tqd2IThclnz4HE zXp}LB{t6sBB zgnJ)A|7S3<&E@<80-P4TWeSHz%gW1*5a_=V6AvV|G;|v+?&G>+0{J`Be*O9tOTYSk zS(!d`Blkh5&J+QsIVqbYs1WW}>{@T{ZVY&!gNv&L#Ee2*S2Q+K9z1wJk^%)a5-RZi z=T=i+#fe6Po99w*j=S{Odc*?gJ<4wa@UX0>MnbcOhK3{h)ag{cjFyHpZBbB=GaX+b;GXtv z`-JI?2IMz8{c#@#$z7=UadB~eE7Hqm5Z~&j>yAfvR1dR;$=|FFH3+MvUh z&Vn*ihu<3f=r2ix253uuXKtTB=%8mb#)i8Z=Ef8$GN3IsAuZ(?PUhw3C)_A?Pf#z& z2Km%#9kxJZJN_EWq3+6ETK+X5o!WwyW=*rYy}g|XBj2D-a!Fk$f)KcnUVa-7(?o69 z{UV(TA1J0#^eWl3%yLop5iq*E&uLG{guY6mYASJaBLUyYikuLb`f$wg>r+twFBzSKx79 z6$)Q*Tc&>PMKAs-G0*o`A}>=TCTlD`pFMlFxU?kSY8hkWbg5qlA{(oEDx^qE@j^Sk zKqZUqEOKHJ6zm*t|CH|7u49uPuEHcDs>RwnG!%a#+_`SN5b%{zv)DQ2ffdS~Jb_Ea zh^RuDa6uF99JIP2RgrzHPR1rJ>F>t#E)y}wV{ib#3KIs~{I}thbWO;5@8%gx6zHRM1;1hdxt@ zqy0adfo>ba+Y~9f6&!)yjKc8nT)cAr*$akDBo z+A)KW8i;h)^Y=a`4I7ak(CoA{+f40Sdd{TPugCH=7z;Tem z=TNWFt}15=fn4_;w6m~CTfFtwP@28EGqT{++~^#T&8btTD$J7*J3~7v>V{h~Vxd0k za0j4IU}$iYJ3B?afS?C=|E(mjf=&~Dxmj}$8Cz1?aPd}MZ^YPQiK0aJS1^~^_-Fpa zrpH&WULEpO5ty*zxP1oVP(X8)M2=Fp3{&FHT~&-XPOuyCnE^cUZV?#oXm3|Qx2>Pd zOfAnb?J(r!!j2Kj*TIqz&cI=@@Eth%Z!Z8x!%*32O-)UY1Y_NRmVtfZ?u{8%au7&$ zZN9Ce-p5_22zD=BzWk$aYizGi`o!<8vApc;TsTk@&LSiPO}Snc68>RvRkT;aGlxeY z5~Vpk2Y9vY|ET*zcQ$w%72BPUI=6g}9zDtd0PZqf#T8@a?Ci{@Q1#(v1_5dxL%32q z@**N4Vk(Ti1m=|U%Q7-00#3)1wu(_lyk|KIHUgi_Jo;`+lD*U&5gSs>%7zFZSnN=U zj%QuMrKF@p6lUlb4?R7bP&(z8QYrVSG9(mzW&kHu-y6OUab?p#N$>v%g)YziQxw<44YUCFnhrnEzk zv8!LLH%v`WTj^`G&Uxgpx30P2e^O_*oj=**pyLP2`m2hQQ&Vho1&*_Z0UDK^j-8#I zGRcEdZ#(X671R&j>o@mYrD)X(<_B@sLv>p;n?HaA*HHqp<&sr73zGShL&3s~no}Cl zy{v)#E{TYILz3n@Ovez-_s5SPeyL9HkXhDXR;8?%(qTf^*^`CVuET5lb4nM&fZ8&j zI8(uIGNWP1f5cdf({bk8Y0q_3Nw8!rhNF##ctSQE zT9_RnD0pt7%WPplFa5cI6Yp${E*mNBbAblY(yI&9fe{XwkTXDc7{7c-` zWA!?O^6x!3KQ;C7^F;ly@RP^c;pPJe#qE?vTXexIV)!~A?O{m)kmbp&KIX;$5;_i~ z8_A*fP|s|Be81t*)h#=R;39L|04qQpX53$C_z}<&C~BjlC=s-~_w7r-?4f?rDc=9~ zvE+jpA(W%#V`%eXs?Cf&H5wu1Z7Nv@K1tl9iC`E42a=GI;z$w++YTJVL05_SM}6aL zl9p`c@O;qRbF3~mjYmdkvQ$8=8w-IGppThI;+1QbJ`|dn#h=q^itUn>7`~hfshY8~ z#sbG`Jko3ajfK7zVvfdm_UsihUPkB!k;S!{8&x5lf=utYAM3DnuP9UYSzX3}r?JRs zeskC_2!?$8s02kZ+6NCF+(JoZOHBEF^L=7B8?}0EF*7;`UOgIE-<;(`HzpXGCmLkI zlEs*2SO67L+M_wG#W+DO`k{eMI$AJam=s8&K!Fv8*_3>11CaQ)=KMfeLx!ZHRwSuT zRU{Cy$I*5*~z3)>2@K`oF ztDBM1Y)&Bprh2o#q}t@pCNiZ*>-wAP(;r*WaNk0gfC{-d=<~rxg~69+I@jB@$aMyB zzm&5d60Kac1W%!c?Gn+k&%dX{%UvRsl@1b74C;Y36cbEXuEolRp9^!s5R96ZO(a9F zrrPt$ssfbj@8K@V>$^)HfHVB*&#a~h22g2Eb4;(*jXrB=OJ_oE*xomFOU6EZ3jZU8bJ!>%`A(76j3w66CU`aa_5;iE@Z`T}~~R$h<4 z>WsGZLnDaMuFgF5)KtLplTQVhX?KHaU2-f^pVzb14?zoa>0fH7KK`HUqTb@A)?_!%xPF5r)0G(H)1rdZ{rqDrv> znZ$BYTcLy4O7A6b%cR$@&wC6IT`QPX+kIhv!ffH^M}RUy;4#}c%T&7NfKTo2XH?$u zWTGhsn8#t!D-x^vBC21?L0zxwgY9LAmuN-<4LgUCe>@yDj0Ptl2m?^Y@U1*Mqn<#d zOQ?X>+$l)`wL3o836HkCOIUp?!^Ab|;33+0j&6OQz>H)ET+)H&IiwfLTwl-oTqk&48u=<4eFF0ekND!?R7 zmmzVUI`pUA@eT>W42hYqe_VuA^y^X8P5D%fB8(eRSuJN6T!#V>vt#E@ zqVf|927rMg<_=*AtwuBjFl-#O@4oFfv2*9nEY~H+WYsJQf|c+IK0ZDQQ1K}V3gQSz z?~)R?7!6I4%a;v_gkI#7vy34E~dfd07E}-H?7NZV#lT??K0JM~K4%nyg4nvt-NF)Yb6 z9w9A&uP7$cKQ)Pw_LxAT^aT(dOZzYs5uFPho(3KHSq3kg5jxh3KPIJeu96wGzqj{w zZU`*saosb)Kou%%Tw?-EXy`-N?Cj<@Q?3@s6NS0HEDjh)A3A3YrD$A%voPtpzf{2D zg(s0?7m^uu3UYIm1xdDj?`q64QUZ5ZB*new2ga~<48A}HGDM0D6@p@8GuBEW!>qdK zN2prfhR&!;WZu|6{RN9}2p&p^UjMo@jC4;z5FDFNOuGQz#8umOonTBJ8Y{&M!-+$lV{JJsjYeO{^a`Rp7rz^ZwlYN}nZ_+_Mf06b z3lKKxg2UmwA(kXakhZz|Kf~?O0ESYU25~XgI*n*?3v*+MU9P{X%*R1@Qgb>TC5iA0 zRnspyq>w6V(5HSCmEE5h##E;AJ50r0fAbgkLLu~xgzoO^E-Op(s_8o70rWoNP0WYt zK928ZuO8iG8zcRosENkFZ9RbcrY&2tLmum9wD@7kLE(r!FEnW@ei~ta;ySC!~--eWeW*Ou?klt8z>55Xk z978>;sM|9nSV>V0aB2easj_o;E7 z6!xKOiDi)mZ?H5{|tnEOu3f? zE+k&p5HAmP_s>$1^vvaj5f*p^)QJ0|Bd;PxD(EP{IJBm&2%XbIiu2K1g%+=naSwb2 zh>a8{>l0cfYM}y7ia^CmsK0bF^uDG7$H8Qb1Qx%S?&G(AB^R z&0|3ZM}St$PpD(chS17PO5(l#nkp}M@5Ds9BfEW9u?rCd`)A!S%yCLkt?hV$>J_6+ z97mw^Iw}-#AGih#T5MSoNufoBZw6?lE`P?NnUY$(Ac3ifrQ;Z2W6|PNlyRWQltQC(*S-c?yuRb_tXBQfYe!izn(zC#?m{VbaO)vBPa4wk{_ zFVK`Tt%u}FCpF!cD3B^F^qCXG3sA6WA8sXEPp#Pah-eMtffNsa2nNGn(zF)<{K6g{ zVPlg+1*rw64&`NO0oiW^ULaHCfVIp?T3+BVH9{-UL9To3Xz_XX?%fd4>cCH<$dKG} z{QmZ19F||jJep-jfLjbv3dvHF?TndD?>pEL|7Btwwz{6ZhQIIgx=ZZ9JNtxO3!!~S zLgi4+*3Qb;B*Td`?eYeEacsUhamdsN%!guFEunO@dkajM=3eO%#|bbY&YyS|y@pU1}P<#&{JIZr|`Or;Y zcl3S=VmEBfjPDZQh*E?hu|8k~*SY|aeKds?qFK_G z$`nXCDxT}tt~IC*<&jCIJ#;7)z~#5`#EQ(Bq0;eWjgO7+rK>G^9CAIo^t!aX{De9w zM6!)ZD)r{eh+=8qaZ|g=-b)B8DR7VsKCVQN&r-IZ^@h!MfI=vgO!XFef@dZ6%iE?o zwtoua!vudEa0m+i4fhm4*jp=tiG$6TQ-2Y1%PWK(^gSV~i1*5~u35V_=(rD2jR1pS z0;x?*Elz+jr}Ab-bjThw-7R#y%GnZ`4>6OzcHzQ>c#S=|1qF#{!|u%m>Iw=9`BwF0 zV$p9T2hSKhYFGXS2_*)z-6$C_g{*QKT3p$u(+R-{bXoIQW$8e#Nj`H^qx*B6; z4^{FghO=rSdsvEQC3awGnT5Rh2XufV=lf!{EY=*>I3&Igmte z*@KuqbT%&MJ8cR1(@3qc_u%j>lqBV=f`WomGcyWka})qP0T@cQF!1Q!g?FN7U8K(3 zK|7!_cDkIL%C=GAzcBUrJ=z<**#P^Xe(+f*xG!9w2-!Bgh5PEO+hR9fLiO<|P1k_1aB=$M;qtbY?gkLGE~y8kN|TW^CMLQ+*d=m&?tWt2E2-kDI3bos;e=j1aF_zARi>W{hKy#mNH-t3P?;$#8ihkt2%NmgrQCo83m-AIk669 zR2CDEvvgdEWh@;F^Jx(4#B=f~5M?Aua1mLpS;I+s?Vr0d7lYV-xvrrqhm_DBnbi79 zIcs&r8PB=3Iff@xiD9N|1z00ScHrTzQ(8G=5tK(2qqZ#N$CeU=1kqP0;mpCXeI!u70+19t0OrLUQUkZTAHvP#` zcwL#bd!QWzp-w5}!k!%wb`MP9fs&`t_yq{g1`acXnvy}Z0`);wp{)a+6yPoyNq5I>^^xq=vN6$h_zg;A6V z#p~B!U_)oS?`#cz-iG0|pF@SF;(Qq`@PEVKV;g?{Ox&4t5ZfhJSJzV^Pl$CCnP7+~eUb=jh z4&A^>v9V1h$gcdYU&f;fSZy;-*aSi6V4z`C5CbHU;MxsiDW_2rcP6_t zF-q#*PgID%7$ON8uPyka`_5^VL4PHUw2;Lk;=p_g;EP1DD4hi6BYrRJsvO4lH24sl zr#Tj_dmD!u$cz`JdD`c0PHelDOHc#iP>xUW>D0p^EDy^{KU^aaa~L6hgTG7tbji=n zjf05_CY<`P&1$HPs_=(mO8o*~Q|~}p9K0m`re;p?lSCqunM(&Hb6S1N-n}!xMT2?7 zz@-QCH!~_d3a%^}nqXQWU6Tr@m%+uG0D;gD^{MxseQoZHu1fesBe+9j+*RRoA<}?N zpSil6BQdpmf3`LqqclKH^Y^aG>v4}|nF(-shxCKi9~5wmGw*pzY;*{nFvFcH@H*aD zO=MSM+riXLe0+Rd0)Hq^KE*K#r<3yx0LIuse@HIYphdu773mWBkx-+P!d(}{!C=L? zcBB6ikF9pOClOUXmSlnA#I(LKje_MD($^{0XawG}rq=V8;OQOF-CHu*G%iqCU9VWYh;HruFKh8(_t2`Qg7Bm2c1x0Ba+%$E##APU`g z697H&$hDY0G#MxM z_;cF*)*d!`McJAwih*m$a`+7O zZW@2?KK&|m8U-;p`z6MYLxS60wKBK>KoQZn@vOW(SqDQgD#gfenWt&2!8xENaoDXQ4pzI(r`5$j4_l-T=*N1~N+&NMRlE z82ntvS)nr^xHKbQIXLBGjrKRzQJ@5pBt2WO8SK#bYH%1CUqg1mBtWjk_6cYxlVq#- z%y-JGus#`rsK@W9AjVC&T|*R00J**T z$HtPe?y-s9P^QcrI#62@F`q}E{XTN@=bkg%KX$52&&)JHgqBttriURJeipP{g)m+l z;;UP`cCE^BACOE9yf4ey7{sBwWCVdqZ01?8muh$r|0zw;Xsgh2~*NH+n z+t%Rp#2~d-O}LPdFy%d>JsveswK{K!Q&kn3gnLctdbBsmXJ>|HhU!~O+)9WQ6+!R~ zIQdn($RN&$EV#adheew z_FXkm;=Y+UG9j@C1RPR476I z->mkavpVU|D*Q;0Xu;$@i-Ch3CTV)lhzw*sid0s_%#u#^_ZXM1EnW9fhpChSZayBz zwQL7fDAJe&K9p}>wgJaFkHI0yNneP$X@|WCedl5s(j-Jq!pFU zID~Q@Yp>M557!KRHB~g1vF(f#Urvrp6LnC1NVqY zy);^M#x|gFP(U&Kn5xChL0v`Lvghg`0{XlIpNu+C>y%+*abJ5ZMWZMI^&$>Fj4i23 zNK9)J`6v7!cQM+K1h;5zJ^!8%mpK=FJWGS>JISH!mID4VzSZCe39adE$wHh3g_p^8!xC zjE$SyDayRlfJvi1!5W6j_|`y2dwU&mwjg>ieANQGi6+#!&E>+v!o=(u+vJS-Ia+*G z(gx^Dht=#6ZZec=OW{GsNg-ZgR(eE#IFg+1`3m3#_hSBgM)9hr^tmWF`e;bx z%mfsnC`dbG=7UonpHX6=o`z5PH_{Yh)O*>IZEjSDQc)e$+zbd!1Yy*G&E+uBjwrAN zVbCNzox~`s7uC;1MINQl-iIU9sc`zi@Gb_7NUITxdxZF(N=^jE);xLiNFIG-d2w2n zj>obr-U_l_Dsi`X+5z?rs;?(NOtu zSi_SDh#;PfLyAs6iBlTjoSfl?Rs#J06-W%FFcIpUBh2&}MU3Cayd=@km^BKOQT1EV zok)9u50;!}fi(+&?lvs?>^4Pgx*xy6MoFw-2`EgY)^6ImwHdN(|G>a;*kJ`g*2sZl zgUTK3t5&U2S;#4U_wEt`ULK;f4LsLl?RoMTcS(qep-kKZljDR&-0ht~p4I@TR7o zE}^bYgF&O+`nnl9_;?%plt!Z?iOqSS?e#F<;&9DT=mNYnnu?^+kDJ~X;De0cV*SbR zkC)pM%g!W@a2GU<9WYVbbodvZyRf((MpX?m%>`U#_Y=YS3<2VEjXx1!0K0(^j);?i zR;JyAhDS9SgA3xR5S1skpc)hXfWY%SzMr;a$guv9vv<0r6HuQcq!2n@E~b8kQBpi0 zhQXb@DOS7sG*WTZAM4_%?mG@FEiU3L_qKwfA&4F0T!U`u~&k5CFT>_VTSYOlVTaq95l^9Ycp743=Q$d}wDE4NGHQ(o6S(t7ja{=>Ct z+N=KD{kZna{k3;|wy8ZH(`G5#p>6!&_@+${_Awc1UATJwjm%@M2$4${(ym6`nd#^{ zrC_w;7l=k-RZ;vx@Q1LzKuf8^P+fgBjaK8_6#&MupqpFJq( zeBZ}s$Ail0pUyMiYX5+P*5lD5$*?k!4M*;7yLkV!grwx;K-GTw6DLYLJB#0oB+blN z^SdqvT0M`9j4U&h!;5~u@(Twir%{qjRCM%O7Z(=}gSs^svkN0tSur$$q9k#I_1o~U zMA2y_PR&a`oIz5Dw}}-Q8yLiwIb170%*M6@KJBFJuJv(oXLJn>H>sl+yfOG^G( zQBi^E?45?RMv;J$?JqRan*D=!WPkklQKwbIW>8c;eE#mX#t0p@soGZ=8NxU>m{9r} zXL?7he|dU(np<0o;DqEsA=k&vshY=_nEw3v^Jn*@{aFqU5$twtjP(9{u5Xlz)l;IQ z@4<(l1tM)f^>rh8!{f)BaS5ew->!ymb{U9Dw^J~@rX1yU5?Jua@#E`YL;g@vvE8Kk z&6|i;u2gX5C(sa%z|-O9r>moL7oNp*cj>D$U1C9LN_BO0Z{c_E9vgeIe(S+*WZ+3= z=6ewlNAN|TadPZSYil}hCcs_PtC|Pd+2^1}dSMP285g$!dXbo{tf;N+IfUB{efdCk^{^>y=kqEThH*=`GyLVGJ%85TGxz=uJMp_0k03X=2VvXLhE;sW zMDj#ei5E(~Wp(}M&#%FKckMnwBAMLgthSccQ40-m@dxdtUn)lc05+*KefV&n)dhw9 z0VS{M(hi?FN_MS7|i-(9f@w+V_(ACx5wqcF^@*Q*I;sK-1+L07e^byu34K2}?m(FPqbn!NAo%+4^SW|U z1nfYeQUhlyd-*4IA~4i_P}!v5!i-G7KFPgP*fVT3nr>-f@syk8^l7Q#F}TJoJZ07@ z9AHn7x-3?DsY2)9YO&!66(%7bXbg?H*N~uVR$s`f3=9tL1ykoNZjt(DVWVz*!@;&P z2UOm8i=~$@kK!o7v17-CwN`tb-U2^H9~)riC4iB#pO_VCOX=zAieJl)>8gNq-B_(u zR+7g%yw?f)eQl(%3`4En!Ve!l7f;s38c{JY_C?BG-nrs3}s%=t_;1c2<7Xhrdv?CI80i1q4@0O zwLYm)Xn(|tAM;0hm=v-qlVF(bEdbuoX2&<6Bd$BCOlLJ z`RFYicHf&!y?*_A%%ARBX&4xs0_xW2I|myd{qYNiMn-+`@F!CqBdRa|_qtM?C*SRX z-+Ha<;-n~yu9p&QemDyPteHbjz=phOZO!+Lr2jYWWbhb)TbQ_8R##S6yL))7M}^@T zEPwaz21Zpchtkv8@Nlti9D@At@#96D#nwNw^)!-HH8#iv?;WVjf3(fHHD2*+)%27rg9UXTJLf31`HF2OkJ8KK)X%gI0 zT9>kb-nH?mJDS7UbT>htHKaRsM8w4)k(cT}`?AfZbZ|Ni!~fIj`MXdIN`VTzy}fTG zC7ni7yj9-!=EH{#0|Nu7`FBxSI5>yG1gK!)Ws(Wye#2AK*{M-c`)_PdEyC$!ZfkoP z>uS^qHt{*nO7FBv`Wgr%9=C6=0(HLwkfn{e^@r-}o5_*!@eeS^{%}AP281iut~~}v zi^Oy*kX>&J##tM%V~`np0O&Ss*%FXjjIyrRe+qzb&AN4#DZXK0PcXOD!r3PDs8V=W z&Bxn$V8nYEFw~yM-dW=21$2XCL!?_Y;N1G zUG%IK$-tmrK>U*Xj@^ypLM8rBM#f)838>99kl&04MKne<{Hds@*jW7L-&CZgKv7IH z?cjYti2yHJ2ZSD<1M?x<%t*8B05=}E;T;g*j?Q)%O%|S(*YH_HX}AGTzDiHm$|9;M z0Fm(J%j*Um$>w3u$ul@KJbd)*_5EO>68zXgQg_v~3^p;vGm;~aFRH?_4_2bLHwB1X0y zJm`t6X?9ctjlHC!L+=Qs_!jENuqPvGO;k3X|53f8;QYI)e@n_gp}FD6A$DqNYU9?- zjdOEz%IP{A>+0)uRl5+|WC|)p^Qp`~AmHtrH>;3fI3~AQPEIaL6%R--z{3r1#l(CK z=73&iKRZl=nzBCPigMpMs3WiNKo(LMsBU2@*bNibdldEPU*#vg6STH&-YkONKiN~d zKCd^08ufL}`t{mKf5ZtBoRK=Jnz(oLhIeQ#H%v^_MX&C-*g#D|?1&{p<{)Km&`niU zHDQa_e{SNRCC}>a@4tsefziy?Z*|dsa&T}Ys22mb;N0pZ*ea8ERNQ*Vs6zD_E`qZ6 z?@5N7Wn=5TrigEJS(teP5!?b)5161K*99jhu3>D}dgQ?D%*4!ug*2kV|Gkk>5t5RUrASC5#qoVxp4JRTLPPzAWCvzCQ$L5Z>7Ox(sCGc~ zmP2x`)Mq+%>J6p>ckmD#9X-7}HG`$Ct^4rXXAWH$zt3($bYGT`*z^wobaHaS_+>xp zX=6%AP|yRM-}^c^7>OaJKAv!6Y+{m_{5VD|;rIc9RBwe8;*!9UD5pyl9GT-%7I0^zdZf@`xP6p zyW40YMppf&s*t5ZcGsP!p`nS$%v9h=PELLToRfI=cf`a+LXPM|hmm7W1XP3M8G#LZ z_3G8Fd-v8NGlsb@Uc6rjwfJdRSe1T8W~K;8hf$Gvq#l#UFECMWI(8Jlyw3}Lmj=1P(45c9%ZsOq(H)?pW5pA5a3Xm%<{nqg z@7~?!fHwUCPnY~qRi&HR_T|fAR@Uvo!C6cS8X-m=+`vsZcC!&#Pe?W?m)>JdUy%Xd zx=Kpq<|yJPcQM+yi4+yOtsGolUgoy^x&eX^0sZ~&O4}LJpkArDl3IA zTv!Ez#-+xyQc_Z%({&}CF%taNl)Qfi<|evxKgDo@l3@7Sn_%sbT^k+ShK7bvZvERw zjP&)-%gSzb7CdwuPmxNLLHqaU?bV7NtEsNu;w-3X@ax!JZ!ZcU2Pz-=TIBmqR3cJ9 z;f}cvk4hXbe>_eCMZ9=Hb^e_lIYF;*;He=<^$})fYO3odCd{+@ldKmT>M@8{exP&y zlHLjoyJxk^HqeN?OOA?KgC%LHL-+5!9Sl@Dbq=ShV-<-D67) zfA-7+f&z?mzZHq;X_#7s=|m*{D-V(LoJV(U+P-h!L&(d0Nb{3SOumllCMG7<6PM-I+8~$VB?mq-kk^J0=d)4mQ_?(!p}GyOCuV!4?wLPjDHmsbo93%ztO6)O?^4Aq!`0G#39XcuYnqx*d0ugt`oDx7LSGquO7$mUn_P>1)g06vc0LL6Abb*9J9t<#dHw=00cdOq^|N9fc#mVoy9JX$T23DFQLO5?p?&e@6{|Ch36s4U~u>fx*(3c zNi;^FqFz1L+S;lNU^mDgapit!=z&@naomJPiECA!v53eToNN3GWI`&KBmRtVia)%! z4|hZe+7dwIK~WWF*-|N?H;k4H}0c zMM6ePLzD&~lv!4k5ph31zw0{h>w4Vx<8l6Ro=)mGzT-V!>yyh1IP->wdRTb41B};w zK#aeCzE9bgYZn$2)C*Iwa`PA1x{NK2Lt|Wk=aHK1i=Odo_1LC{Tl`aPuOI6xe|ER( z_DRT!5n#q_`~Fc>ytp_OkR_yHyJ%eqSlXeRS#ka7JS(fcw5(yHNB1;4qG?e%#rJ>l*mJFiisA_5&aL++bKyY>GH_Bd0iiKAe8EJAzGbl#(+l>|#pMAPN1!_?#=_)O4nY2R3jaQoCPyxvI z0z@{rRpJC?`k2#H@F80*qlgqUSwhI$Fq4x`_T7W7f2B-PRUlz}2@C^dw)`=O}vezSnxe)K3p{pJ7Q3^MybEu$>~ zWF&^Egc;5u%T)7y9NxUX`=*^2FkuP+9((%(FA=xCP0+j+=dokUIf3@RIUZdQFI zpFsWro#M8bUCA|)l2b$+-`r1#MDMpAQW(>bgq0xYr@UzIYpx%!XamZ30Gzk#k=6>7 zX_ljZ@skLQyLfSo2vm4`o(7=$@bimox4(b3Z}IdTs;sZMb{aH zrK{iBHt_9_gj0+&V-gJrOX-4sdS`n2IHCvC`qzKqqId4n<(8m#66e~1Ke@5&r#V+0 zYLqp!wUtl3cyXB!+`jD`RKo*{oh^Iy7;WuoTej$(IC0`-^%-gwi2^+#^PgmTn3bQ5 zjO@<*&pKVHzVd&Kl%l@bLWpwRv~%c4yUP9FP*v6pq01XmW7%^z@!XpU+sjbTEk# zB}XqiSB>&loYL?}3|dr#QNsPIDI8j^HIrFGIvn|<@mS2o&1yg#@2xHNd5OPfCI@S%W^Q9O{~nOvCb!zWMnpvxYOh&WA`Wo(*4 zmrV?qsHbP!^p|bXe=C*R|L4EU)@moG%9bBg=$Cz=2xzSIaK7EyJV{dD_A3-BGNR&AcqPC~*`9?-6 z;`3?`MPVfO3T!5CYYI~^yKqsu>sDaeF=x)2N3@mF($)3B9?M%Z^4MkAs&rH0o?#9I z-!8{q0rf!L`iIAh0FJDG6BQdgT@z5|Pmx@cPG)bPmom`Q{ z%G_(C`4}`UKmDZZ-MEz?cd%j0Pt%bOa6FKJ*8#ijPU=+2Jg4tp zzlKZL2pIDtXizucA92-D zX}*1MwkI=6k)7J&;A4M`M4{T=G8XX1htVA6`ffHs5P|g`YrAc8`;QjDBbV1iz47~M z6O%5OV0Xe<4<0h44gVOPVlVF$0@R&MINA5_&#kx3r5D%n$vSuKIs-hL?-~>y-f7-E zJdd_fXeh*Z1s1uY`Xd5J?w-c6b!D+#GB>=FGXh8=z==F14Jh9$# zyTPjZdiR`}a#gO5HC3|z{fb#kX>tyXFXm;oa}n;7Cy%Mcil9&mu5}2VVF>y-YU zW&UHkK|C3-FD57MS$Da}h*AA=4@#QlNN4;@mXCt$*>m7P7b>^kr>tN9B=7YBy!p}6 zvYf}?KU_5tZGU^Io0XM)Y45jD?&*goeboE$^XIL5_X11%%F4D?3Y_0iC-MeQpnw}Y z8B)upc0nBDR4t%i^gAx)fna~7Nn3VO>1%Pe2Fc$;u}})JBcL4USK091^OHa1G@=@OPhFO=^w;r85Y?tSTK~utG>08@ZR<@Uv1~j>&?R@H+$RG zt=j(@rFTMS2?Ma{L5u#B;8p2v-K!R#!jkO(9jmwPnyUrTXmVsW$8n$QzcX!Fn&H z14=*23JB=VOyCQIvkdl8ev0=bk_ksum`%gb2dIqq^I3bj+Wj((8QtdWU)C@+Bf$&^n!F?iku6^4!=&|<_)f;=} z%+N7odS_;4662`GCSA&Y&lIXtd1cdw{(GmNUR_OlW1~!NEgGh(x?g*dUFj~?;F~+! z_$!}dr%N}#Pi0!3(P*`%L==p*vl0ytn?^)L{D4k(!#BcSdNVK2D6ttx zdk|oGH+_Bmaig}8$ZmgiQ+M%!k!DzX8yuXM+dNeXqfn=$b53!SXWCv^-hsr3yDgEL zCSU-JXDVOk9>v}8`P;WVn(cb{kN)3BymL)sOV?a@Ns`y9GGc_lHZo9jz8znR%XBAH zMPgQV&1D=eycPP>T`<^J8g}MUhsfPS&PNt1QD=#_x5dRJKu5l z7wjFjRqv0feyu*O+5GN=Mdh3L;MA07g;^>80m!3k#D-;FF+@RNs%I-7udS3QaKT4> zZ$ZuT1M<u?5(HE>cbMylJqxkbk;PR0=4@3a&2}az1Sz4d}pI zJOcWcH#7f@U4#qvhMB8(>J*fD7h z4UM>*5$6i`-T_XqSZHeMCq2ya8q|%0;12fhU;2BZinfjpym4>wGb2I@fqpIkmH*~e z`zLx>BVp*eY11Zw!t=Vfks@)ze|*L4*|XhvQX{_22Jl1gm35mpO5xdPe&`J5g7oim zU^_;vEIxXxUekpuNMe;hk`NON8+O-_2>!wk1!G(WbRQI(eljB`>pO;#H@ za^`{s{T;Hx!sMJYl#)*$;4f&Q*s!sdW~*rW@VFl%n{Pyf0)H+53n*Ew3GLvEN-=+s zdD=mk7`JGuqjBrNO0e9zpscED7O_N2VU5`JQEtey)jMjs6I9S`kikG!xRp=b=g-#h z{Pk_*FpFmoA0Dk}yi?cMXVdRkl|KV82g>lJkLtNatGeYNg%G1BF9?nhuKHe>y>RO* zE?lPd?(Q?leo+3Hf?k1K{W^1HXL<_$!Zz;i?qn1^NAtI(wPhTHJ%-^f%+5AC2Zwss z8EcFiC&$kjA9MHdAjs%L1SvF9vT7+iKu$@r@TZP-*gQx`=`co0v||0NdVn8s>LTPCh=S zO&((cWt-x+mj#jOeEs*2i?HACz3>FRJQBZd11D^ZuWnu68i1+k0)AU5xzQy8uNOiR zJ39p=tm{A3Og74mE6h2`TE
    7u1KDwmrB$T*q@%a1`U^i#7vT?B`&CK0v4mx|OWn zx9{E!unzEt9$*iEAkxy(no2bw?ZFMtv_*#vQPI_jR5*U|GFBJ2DfR^`sIxjF8r6C4 z&HwAY?>zTU^TJ2p(*-OlV6E~&0DWQFy1FaP-@JO2p!wnqx1CN~JJ54pFlAq$U{Kf( ziQKEc{#31NV{Am>5dERUhW!^1qiWsEiYj0g{5;WyY4x4kx21k{<3&qxdsJL(zV=B* zFP_2M3`F`#ZmRAX9UBd^$RpM&SqMhTM9K;7JW)B-lyXb8zDXrS64le$**T%Ih~RU$#DJhM*aLidqgO__`1Ps)d#oezVFp>pX^f(0R zw}|AJsTjp(bQDfooYi5|*2Y>vLE-46tvbVkiXT3dXLroQB4+!2gLv9F*F(rpEFKGp zYvtYk42~w{HXd(Bv}@Nc54Rk{FX*OzokdP#$dMmz1w}>K6krQ0tM=r8;s|d?9bFmO zZ_S!Dz(9s5yyIuX)nmV_=;!Apss?Wn*$D#dK}SkJTN`KN z()vHietqTT?-*~?8b3at?aQucJF)EkD^eLb>(FQTztFcv^Wjr*X59?8!eL{^gfuTq zfXILj7|&*)-@Aq66~RZd8d@y$@|r{->IiOLR&^_rdZ0&&K2RWwyr0kXB%H7y5Dq1#! zzh0-32<+hio-29LK1ufPfLAYHK0of7wF}(}pS=;0gtlzNF2Ao^xj_Co$HivNpa1xH z^^=s9*XB;`+n*1%foEkRu z=YQ{5#@oL^x*9Dx0EU%QALx;;8MJuax>3X0T<3Cb2uz;Qhb^tLeqVMbpYZmU*9d&t zK+nn<8I~W=tdjM({*fPFdGI)s;JL+`D)k4R_MWjnc>QGmhiIY8>ZonmycKo_RzNcF zr8_Y*XzlppwPo8jhtJP%NqqfKHTgicoSd?wX6uEyk}?{he(wVRfBZsj}{SDTqVl6TBlRB-3c(n%w#OL9d8bSc~swhc*BqNYNJN^1P1n8HPnvB z=mjJ#9QS^ou(s;nV_UxzjqWThz5K%-rA*oB{rlrJvpK$Hm9@&QsZwMW808A(hCm|W zexI8wx7&%yvX1>mFg`Kc0o!!Chp3(7&F%_1;+Q5pu41`*GkMh9M#YAPhN46xq3`6` zim7fTRr;_+ZrHsy7^>S+gieHwMPlqv6S?Tq8_icI=lHE2BfJNBk(&A&tWw(+HQ>WKr1=Lick?r8PoE8cWPu%bPn?{L9( zH&%rs)&_&0$-m%kR9~bY zQ+zMzKV$CUmSS*B*tzJx8H;NY&}og$O9cj(el#lRoRPq1(5omp0)|(ZZHelJRoU9HmcI@ITuY&$Hr_U@?tltAE zFoK@Q`G_dIY#7c5N)V2baqdK2%jTKJQmw=xPe$ z;l@RaQG+qVZTwIjmi`+Ez%H^GC-RH{x&2q6<(QXYk!Cn5Hi3@_Szb(l#*ouxST=Lz zZ6?C?Aa4c@aa^=dHJ$dInmCc>-xH9?diGRleq#U$8(0*{Xzk{6--88E^MZMV--%<|Uwnsr3xOCxgG{Ra;GD}@1ZA@6$$HJoOyxg2M{xt`L+8`ebAe|?&nr2u!M-YZ zmT@nO8Br5kA0N087tj4cd*Q%A5+@FfWp@zj1++*#ceXAKXm~caAJ~tBaaSq%aZY_! z?bBtPv+)Q;e^I{1E44PU+nbj!V|N?(Y537tCvjQ=dYDbti}G-%ao|UkhLu*g+o_kN zCl>6f1@*C2>;>A5lR#=!hqj`kh* zZ+3erb`RJd)9a)8FEAZPN(svKPN)jc6M6#7zB<(cy|5c%9?W_&<_wuP`)Fsa^1SU}DMvsB(V-L++Byxo7PmjIgGcRncW-~K&?or)w<8qmMW2^50 z?%0Jr4^43L)tlQWRdMUqwAwG&%9eI}G+3syZT9Ab+hD0(5Zl^Z{jusy7Djvn4Ap*! zHL@Q(=uK)xXiH6C(u9+-FMUM`(RcSL>F{=*^Dbm0CwKbd`So>ohiayp zxG-O6z!$(29HG_*Y2O}1ujG9UZf>c4vuN3})5ZB~0Ve?7C2so3&*tz_`apUWH>_N> zO3b?MkEl`YK+B@nu#q#ORAvO4ig!~4FS&?CmepJ@yx(8{uI<~hbwsFZt2R`h9##I~ zgvIMO#*Y~No&m4-MJC$8Cj6mAf{MpTGPxwCrSzfl2AUyqSr)I&DDJi4q<(J^TO z-u7j)Ihj+s1kth?QWa5`O_k@x^4KG6r5p`QQ6UUVlNl*7k|CM_AvTsVtXtW7dE~)*w z1nn7r5noK-wCPfOfb-h|zCz_;gOevu>Wp{<8*(xzej97oij^yGgWKlaxpJWAp4hWz z=YMFG>WBV1jRrzz8{}{mm!!losm8gj+>GG`WhNQG)X+<}5X|wy!8jaNv++fpW0VX@w{6($Q@3E5-o^79IZ*Mm-Jham}J_~>e}Ej^l_uMt60*JA;dK0gagIY za`lBl+?ScDbVpae z>(wQ{w>?2f@H)|-VLh7-bEcvNY929@X`Egp3j=FwXJ>MKisPb*<@+)t#}xh^sP?Pn z+8D<7si_Y>opaMMr<)Nce1tsg;nMU!StNy$IU!{$WW zei`_kIsOGu*1z)ta$USdLW>uFLE39J0#5k{Xc;6ga&yB=A3TT&TGrWO9$T%knOVEJ zr721AtA56A5=dnzy8)PjuTYF=YX^g1LQ{dd zPQitpJ@{S6Cb9l+{2Uh>J6K&^nm1uXZtOoWglZL!Pe|$Yb`j%EggGo%UduE!mt0=} z+hy2;)RT^Z)Vk$uL~<(p69KG{J$Yh0Gv-! zRnLvkb?FZnCUT}*B||EdN&V`31&wBHO!j=0#Dpd-sC{!)GNBbK{DAr zXp2t753M4p^>Ff)1NI6`>eE4I<98^g#4e}fdawwINA^+B$|Gto;>#G(6e8Eb+pZcp zOr|q`qn*)0dbwkDU}iUmI8`pMj$%8k?YzrciLW=Pj9Ce{LCY-7^H?%hF}Z$p;d#(+ z*2~f~8gCYMwEk6JzkOS&9C962n;b&R%{d1-MPjA3X7WEkTJZV$DV@SNZtzxO<~QxS zuRn1nG=}$AKhX15k2{+UlD6sCEn3vmX~u7_Al^G=Pyw9jn8&`4&@b+o4tg5QU<&Mz3j9?l<%*{Gp$$AYz;( zbG^8lKoAGdsA*3#NLAV#wY(`hQBaV$o1-Ys(g)2ZS(tnEmuhe{Pj>8Vp`7{gjw^aK zJ8n<9K@Ik^) z=G!uaO3mKfX@v)ql;*s?{2HZgJD?4tq4qo%dyI$wf(49Se57GyO=3^=B-uG9w8xE` z$+i(&6HcI-X>b8+YJOtq+y{G>GjF2>tmW%QUlMz&NDpXv+!K&Y2$MKX^dMGa?R6_L z32ul})G>Q1&Vl^s0fv40?Ad(dG@!HKjB8su?Et;i^PL=)lbyXsC~gOJXiSW@?`e@c zadVrGrai_nF74!Xt7|!TXN69q-m3$>q?|LN=}&NOIcX^ByhEoU*S54YC73r<2=@h+Z3P!rFiXW46!fQgXZ?FD z*|B5Cm5>6dZ!$Z+An3Y{sODrWBhFYfY>NaXQm&r;uhZC650wFG`yJ z?*le}et6@;==102o_;)kI6P;|)6T{QpE6L2nYBI+ceb6prnl9V%2zFq4M1$0CDFRi z>S_yClm+YBC0<%_eN%ipkBO_C%qstDX}ktEGS-|F_s@-uFRu9l)9auOy4$1rKTt+)=Fh)g_=bER)ZP3=k?kFmElQ2vFQ4=Xng8?3r`)V|99x zxyj%#2)|t8;YlsS7jKVaE`_f&xjrc{e-Bu;LxzEgtDV7)KPR-GVu*=Q8pVbtlsARwZAEHY+E_xBD-&mI11_;VmBhwLZ?4$1T(Fx+a8C4` zH^oR8X+5N1B2#@%;m-+OvxNEJ$mFR|{=PZBt+k$8LRiC`Na~BU&-Oj|Y~lW%38PY& z=qe}I(Z5@mTKfKb>A~lR`FswtPh@ z-R`2n#Btr-)UwuAd>xNML8vOB_4~+0o3q}ERw>p{$)PnSXeadldI!r77!X61{^Aoq zmlcvTY;&POdr`xinl>^P424}ltBUk>hMiqRahD#o`Ps-VU*G!&$INM1!%8{-`g+f~ z16W4=O;1!@KN_trG?AXo>K`#9VqXC&ZwK%T93m6xjwevsM30#$blW0;#RwmdBOR-* z=dnO=VY^3MR;igbyy&`-i*HjxlC$rGxtHCIf-_qNs(t-W&vhq`(hJMB#5oeHlGys0 z3x$+i(hTxe%CWS1`uewuin?;K9%gNyNE$}5>R1F_olulY_f(p6c;ch5u>;W{CiZv{ zqx{LO-;N%tA3klf+dpODOV3JGZ&za+W$|a3h7hGruUID21KobPAEXq(sK0fF z^4-+h_jywHMqk@6g#`u6wvT>tb#vgw#AA~-xVzIT?cH{~pW$$4V$Sy28Hx3U4~Cq3 z|E0P1l!%=uvQpVfQjhJmEf?ZFqoxiPG6e((gWWZulq`GdA4RU8m?gk6CLzPut!Qhz zgX|yi+=>Y+%xXe%Jshf#?;@Pn)2J*z^5dtb>xP+*uR42J&#&53jfCkINXg6xsmc>7 z(*>MOx02KsdL-z|T^UDd`D4GYVR0SXmGq-an&10>@gCmLQhmAyD@CvQRi}nIF1``A zeTiA;HMZ=sJ}3zo!im`ld)Y{;$|`q5G2zH_MbM2r=`nFc^&l>FOxL2yFdR@oUq{2Z`8a z58oy9PByIAnog(g%|G5goe@U>wp)Jx(1uns{Ci~g?zW*vj__Cvgx1%&k$%@>(#y%G z)FS+4$_^hG@wwfT?1|Q!UFR?KGaa5(B;RJ!341s9>yKtT1tw)%pLB3px$?~Z^|44^ z1-E*>`ueqNE2i0>Y&Aa#mnE5$pQ9=7i ztczp4V+vO!o-WB>bZm%bf{wzF<~MVM0d3u zEpEK9f}Yu~x&XJWII$9B=juN-)vxO}9yzaObNtd>*VTkMHHM09h2G z)Vapp{OWW11zySD7^y3WudD38odA2=&- z!A)K%yjS-rWWQIrx(34OmuC!W{AyS8vUg_9okPw)j!*y+HATw7QeqXvF6F!!-L^JP zjg9Xg_Cf*r{Hq8e@OK}jude_^W;5-j$DW35*I10C6GCsMyUetxOy9G99+*MIe=vhX zj1zUNi2k}Tg22NSEw2dms9p+W`GZfa@PTb0d_sgdno^$CT-au+voB@*<*QfI2Fr*~ zO^p@z9%1Nx0EGp)3nLNai%l$g4gAlQQ*ON7b-;|GdGS6SMs~}D2?BYO4Gnm27bcPN z$6dR3cf8g#1s>00hYc>H9!it;GiVH%JXw)VRp?phHc3yZo+W>-&K+fx)tQofBAvIgGgsDUdEVJnZC0S$|A%8}rJLpj_!^s|$r<36C5+fSb= z^5IgfpE=ps^aXd^OL(!evhsfEp#nnz@8{8&$!ety9I@cW>i&ZU1@b!X|1&adbQ^hj z`6x<(@I!IMKZ|4zrzu1P?DzLK#1kqUAdDE4D`C!J(-isylD(vzof{T>m=#%mw&9Sb zaCsEw3hyj|YcFe7Rya@R5;*`n4{SJAif$ikx z!?Rgu4onb6XBwL18xcu&(iG9`qQRE>4V!}-`jGwjaGK2wk(IDu6Oupw z@vG?We$Z#P3JOeKw^oke>g2G5)i<4UN&aegvPXNzllS(@L`!4xUuI4)le~BqM&^gv zC#`c;am#&6UEY@tc-&ABo_PU%$lR#pBlP0H+`^q~C1ei{>XA;T94JpGL9+g|OY&+$u4tPU$~_ zS#hL>%|f=em>X+oeE!Sc;OpMa^x(eklfX!FcHk10#`_{ik$TRz{lD5)n{9`T&1&kDkZRQAxYu!@Xp2?=V5K*UFh_&BCR+cqMwA1zCyd!H_&pxlvl z9VouB>OooAc}|YO;u}~xT3wu`EG6U-!uH)g`dO-h{pJ;6h{;f@C=Va*SB)}7Z^_{B znI2XBag|k?r9tde48QBMcdxh~cs7zZ-4Id`sih<<+1~J;{KkFYm%qFsYh>6Ng}Us0 zb^1XMH+?7o0Sw-$uBxbTbcvx(SURSe?ooQ}meevnUU^Px;Mnn2ewOL(NtVdG>&)gU zVJ1Mec9WB`oYEtYX)ehcD2iP7B{-fCK&p#ZaD&R1icaEj#xj>AVsGVjRtTmcP?Yfd z_hlw2^~6hdzp~Qj(4ih_>FFY!C&7D5MZWZK-odp zlc$T3is_6Qf!<*XLwgAm}lmGDd#3Qz^=ZlsfjShJA$2wP<*Xqn#M14_5bJ^OK+KIrfd& ziwdE#1*W;cNsnA)`%0|_bH}hRtl70VLPDG(IYlIjb|>h1s`Y{oskQf37}u+=Exf zyec^yVZO3tdkka8S(3WSlL*F^oAqErTE15%;=#gC(ZOK&eBeN~Ilp}1rR zAfZF(@OvP;SlT@{p}4T_T8spx8MD%!M)N0t)-2EqdjB3F(^<$LjifFQ1*h1@GA2?& zY_q)db2r_YdTT|jr2^ut;E)hE&J!_N$Zo(ydCxeqsCjNGa(79$m4@jVrc%=F+s0K5 zYkh9M2o;y;Z%Hn#m_;qOX+=Q4!2aw+N^epv)+buc9eMHHS8J&~6uj8N*kP8{F-^2B8(5y>SArt_k$ z=a7MoG5Q=f?xwv`^4PaX3!EO;T$Z2|lU#x?5pbAv$_!=MFuj)9)_${G`;t_v3$kTd z?;HtsNYcZ!4STFL`#R9ONI#xZ_+%Ib;J6S;sslO2(uSl zV_{0Jp<0+&e9M(Bu~T?(5~@ zDYUz=?5ZlgTmqS*Kt;+vsP;CtnLBqU^52W89m#D1^=d2RBGgG#YkL`eOcZV{9~#t| z$6zOomE|NZ_50kuIH-|k`cKtiB*hnTnrn6E-o1Pp+4^7KT=F)+P6!i{u*y)@?$}S6 zuk{FwFiid6xsR>uU{n;wHj)+03hC46N#3?{n<-0NucpOL$riI0y5II2iEWkPnMcEE z2$zn=WlH6*zfJFY!>Al$B6eGOeDrXc&cXs*GBuSuDCCw5?ORZo3rv;M?WS@|APPmg z$zY9C%*jYCo$hF2+Q{=Jj!Zm ziy_f@yoA0xcRNMl?3JML)k#5hRJrgX&Y+%zR1bjjfQjJ2EBh;PC zlNSx(I)U>Vo0v@7utCS+)E^`^Lgt11?q$b<1BOFkCv^&=+b#)K$;ix%=9z@D^EFn! z&4B2}s5@!fH-Bv*3So3zYSY|h4MMGK)=0ZwIgCmO1ZME7L5Y3;Tlkm3DS|7McuY8U zVlcBg(%d6gBMYZLc%$ej*SBx2&|5rdkXXh^v*rTd|I$hM+u)wZUmM)_pvnX0Tgmg8 z$?erx0|5h0>KoD`SG$)r!p(8N5T>xqhlS>_=0CaNG+TgV(UHBms4g10bX}| zEi)JbD9ayhS_uo@&lw69ixyc$Ao$GdFz&NsA2+7fK8t;$$1l2Ka4$|jaCQAx;%|C z&u@!d!$LxOC(V9z^Ey7o0I!s17@_!0%hOPerkYQKR{8d}=K4g^3{?IlkZGS*f0i0A zK%fP{ChzD1RqWbrpx*hMUd?ix%3y$4BX{+@Z`W0Z4^K^YcMNLYYBOB^1w)kdJ+q@o zneTeu&xGTJ5nkf>>J(RD5BH$06!d+75L<$a@tF9oP)c?`ntE#DyW(MTk%EODI8eUl ztn#0e7uy^&*es(vd(f<720NU;WFC>R)L$R@fVbf6&qH30@E?+A1>8X~+%RZnAG?9( zTL@mEEN`o7=%G+Sb~x+RqZMWtx#t95DB^MAo=#^Gu$?vulp&9&Or>gHZV}N;79YRw zYI41X*wVP8CQ@Z#D_V^^9mxD}SXgfVG^zLXmfK%)`c>$Gz~?G7?pym}0=gRs?%^?5%B ze&H`tX;%zw?@u?guD*P-S!zAO zICzk?I+h8sG4&xEk|ETqU)Z2m&cj~)qb!?{wssjM!_LM2-PpJ{No$9#OAi7%)0i01 z6kst^HTc_nx!8vEs(6cbVw4A-Fm2u}sMMKJwwg!E(``loHDGbfyEJoXFD}3JyTV0? zAdYB11=5adTYyL=rZ{*KWmux?IOX2ZAmbM;O?zc5gM=XyY+_kDV|!|2d7J|Qzu6tuhz2F%p)XYD(KxO>2-5aAG zgJ)o~RvUA;n-rNe2RNZpC>8y`p-plx87+H2i(Gc2yh+?;VLJNwJRb?9NEajwS}tZg z4{+FP@57UhP5Pwjj2upg7GhF(Sf=wvTU`oB%>@6#r&6%m9VHBE+!Y@uN(r|dU#Q5m zNr#hNZFVb6X8;{Y?vjAR83_dFB@#u$YN9kTO{TjA3=cYV@-NaUtIAG8k2eK&dABh^ z1!azZkZ%133?P-=)0js?)#_$2q}av{C7yEZhPq6qFvrasc>mr{ z%UFiYFfKFe*MvCTa4cGz8@c+GJYndofmpG)MH4J;_z11#q%8rxc zw6>tvleiBEXL7n=x)c)CDy~%{32G$<4t2vD3^PVl^Q1+dQNOEVKXnl)zeYwz4{z+4 zvZ}AnnlQH;W}Q5|c+XMAQg2{cZ787 zGdC?$TJ5;L`)d)Eqf&C2BxbU$!%ByLk`Eo__zAutb3|e8&6`qOo>ghW?!dUC6CUJ! zGI90mxY}pwxe?uHo`+AJy4NyN+AHBplZT`7bF+>g_ypk@ig?9@52VBl?f;Rhf7QFr zKDjyc0?G50lLLSYUhMe$Ye_`aIa4Nvl~(N@R8{4(5ZIZxWITNQ7=ZCa=@FW8=cr*z z=4vUF>ammyz!d!q+9qc7SsZ3xxNfD};uci44^AcNK3sb{E~U8L z3E-%)LHjqp>ng`j2s5-dJG)Z6{?rybo)ody$gR1~hHe_7a4<{fiLHncB~qJC|(;9}`Iz^AiUl3nEP+ z7t6+r+S=QN)9A|a=5y=m`kbL~G`fUgQJ zWpSpCTLB9NDty7VII~nWNunN@@6h4XVk~}`M^)C1o;dNi$Ee|j&e#crdD|(F*a&i< z8c`L+RVnoD-45@B&6!y76c;{`TG}C2%5TRk#{J% zBc#3LXKaWKoVjodOS|S56ddrlVHx!6PFPT8$wWU=?7Ipx=jw%=v@l&|#5gr}ACcsf zMw&$og;hEw21r*jxW={FeMHX=A-w{SKS>Tg$7>Y-QmU1$GHGp;aCFAD`yA(eb)(CV zGQ$(7F}gxWO=K6$jc-og@2Xw5XQSy$*vmMh*-p`h*`Nn@!$e?V%EqO#;rum56~EFm zh2=3{fW3-wB9;#CBdzWJ+Wg$ehSS}W5865!y%pMJ3)ifNRY4!hV$A~a50iOqcKU2%?@e^raoyYeWWw6W2%RC`GEMF&1(51!?a76j4;CLzd?B+z}dXj zW~f0qc;aQpP`JANVcT=d%R|FFZyasPn!933=%&AGGzfO7Y_37wDl}&iMS|YJI08V^ zHZVWr=MF2mcjn7bqs{_~vcBZ~?&jDFwvr3M!>F~AUd_ud$P1_I)8CTSD7Wm!|Nj2| z(H=OjD@6cLJVA$(BgS;R2yP&HTb%N? z;n%E}3o|#WA$hg^06;U7pDx_NCH^zZ1TjTVix$w*&a*)KMZW`{pf|7?Tt<|=X*Z)k z;N_wN?>8JOB7j(V{i|MW|ES&;HPmlV2LDUQWyB>LyZ!^x=g;52uS(nM=}8)sQCw^L z!Z%N*9WAWWD{K0>Fr+Gd?_s|Hjn4}v^bR~TZuNaBruw7Q3~?ASr!_@kV2~dD>FwJ) zNBM+GUtG~`qAE^Ni>^K^d}?%!Qtd`0X=+k+&w7uw=rQEi@Z z(9ch6^GAD|2z|0=OC()HW$647ao=+gTxr)aXlzKhy2&J@#gQ5apZ@vS@506@eeRyO zu6~skgwL&E#|AAlkNi|?*3$7EROP>z^d)`QnrqUL*Z0X-Zr%Rp zw?a)#&4#}Mdk5FL1yP8fB1bp~T{SuMh=IDRX@K;C>z?B@LS7T}C5&s3Hy6qh5RQYB z-+J&M#9B55jD#GeperL8<}2IX26|b_wH3+>R#JcDG8eMuz%2@2pV4D*2od;CXo2sT zkOxTDW%~B@VUxO$x|>b*WJO>K=Q?)a%){krtr+hSp>=>i-V4k)U0L=tTRhveh%_do zv_yTHtddfRwA1L}lYi7Q*#g*4Sob7j7Y{HD;DywLBjVLX#K-`kQ*Ai37oDsV!aZ2E zI<&8ZJm%7RFSyki8ATj8d|1XN>WccmV^#G=ATO0OS@Vt9R_q@AMxI26Pe}!pT=`UQ z+wUJ2Y-%zrk2D#7r5IwXkwa#&@^@c)1vv=PZQHdg}>+S$dy!E@@8)cSuH0iODX@YSPostxma+xo=g>2o#8ua{ zJue0RYY0{$Tvo_P#Uf8^{s2}1VX&b`oTkU^KX}mLTy}PLJNmEA-#PZ z!ss20d$dn#;dG_|-icCTSGgZZ!N)Ewz6yv}`Q2>h7!e;ccpbD3MQ1ONXsYSJgN8%J z9?K%LSNK{_`eU=_*Ct%ba%%aXvhd*FvT!gdEn?`NytIgoQTvURmrp)1YP9_$-#Sb*#l$u^ ztnm(5(gol)%X4#{X6UGezjo)0yIV*5O7D|$68g{@ zRnxNsvcbGLNQkmOum^64X=3ZS+u4AXLxhL%{Fps?jme~!jLgj~>w$r-g_7j8PT9K| zu1_*7YBv?8p3qI@=z+-lC<}a$Ulw*(eSCHEXuUNh! zOy>A3HxA4!PqaQ*>dk=zv;mO5wh)oxH{k&h$=7rjac;N&&jDjs??h=(GOa@{v1PWy zI=PdRG;m-ywtT$_6QU6(OZ?-cwAPdPsleIcFix{tpv9R9JpuVumhj&&;E z|L+w-qefro!7SlReuVguSO?6ETA7FjFqF>EUi{-5!ximyF!IbWh3nt~Rp$vgXE2uI zwaMq55c*L94T8Ro?~mn)CNA=#uMErCHCn+pcE_(sefN$6*G5|*j>q70;wlj#Ou^5z z2~QL5j&9w%+nu`lFZ=P186y0sirGRJXzAw1DL)M600qqD+$N!(#gib!FTfHaxHWHk zSE{YBzst2xF@5Fsaj^L-w}ER~exEC7z>1NZ8>Vmaxb4o+A$_Fv$3!{Lu$D)f5!dlm znxY-)VZ+ zmDMM6rB(Bo@u2-2bva|!EZ>Sz2b%^zhPaF79TiDWXwZvJbUCRJ@2lZpV?wTg?W0jQ z(wFLZL~b?}=!Re)f+ZYZ(4P0)+H=vdp^77JHUG3Qq<`7DR4?$naxH#c=P^S}xet8> z^~TDnQ{7W>f-swpMF)a=C?5P(D6QA7^@n_WPTLiM9YmyvfsFy8Mx(k+-hfw0Xk;A%9#C`LtNSNoVT`xk2v5n8* z{pa+CLlEjDTAtr+W_tC+rDGUm1%h>YuId`5kK2?naS9LnWi)w1;9(g=){7J%lY&@! zym)LSRyPwju-;d8ILV1&Pdb$rCW1y%xpFh^FbWLf5gzfi%^r1h)#AJoA&-kaN8^PU z%3+MLZdp9;oLDB`d%%(iZv1sgWLNgLf|-}7FJNursAYlLO+PKe@hU$!xzetu8QbbX zg0P}Mi6kEyfu;$4WaACi4KgO%X1G8}rUITTj}MyyO-&LVhc3H3TLic_B>_TWe8@Vtyb>4yU8-nRPO!LtNkD@Bz2k^8V4_0 zWzu4C6RH=itw0Bsw(hA&G(A!*@(y@p+ekHdEk^`~*-D(jA-BFLmx)6}`#^ApdhamQ zrTP>{PV6U4%W%H|#2Z^q(d6LS9B@Xvm{pE$8#m?%h#hs%`Bc{%cv-m#%SS#SkegdL zC)h*{|0uu7@kDO}Fgj{_o988#mc5W|y?`MR*{z_;3g1VdgdnVU$mOwCNbf~j9M!@8 zT&rdv{HuCko$-S=uCtfmDpVhyEb(0uex;%#q$=nfDa^85mqS8KhZTjU#zRZcM)2=7 z7g>okB6l6r$XHbRHxN~y<>O!*yKld$GIajL@7~zaUP`j+u-|Gh)qQh%M12VD{-s@3 z`e7f@$G=`ArNVj!3 z0LF9Ta`c74b!CT3KHrg>d#-b`?A_GDJntmcqyC}C`N4yUT;RPHko2|TeGdi&2k#CI z4YfS?m%FC#qTB_SQJF9T+XP;Sf3RO zQltoi!s#}RnT^qyQ3w-6Fa#ab zhss{rfK-WpCHa>6af(Z9N=hJu_Y0wrL%oBLM8x0bO#<%2nR5$iyF!G;jUGm-i^J6k zIFD$KvYW8yXd*df%kjSbU@KR4VR{vE(IoTmOfK5L6kQu-+z>Yr)+@BzrQUzmtXU#L zi^u38XN(lPFF>cDjrv6Rz=;D4Nuv_cMQX+I8GI4>HYTW3CH|E+!`NIJTA`X<}LJra{Ocu|pdh>H(1t+WspjdEz=n%!(5&J%FWhm@QN`d^O zEm~w}CN*u^?&T#sz{Mx@djn*LD%^p*oh-^Aps-_mm+Hrlg~N>;q@}Hk-+cXfBIdM) zU+phT;XOm2EIMfA&p*z5K2Dmu3F4u(`u^asBML{(PAXB{n=pyM1-<{Kb{p5XCf7;( ztM%lKAai>fmlx-wUCmRqi)AO~1^D~hx|9{jtWf)qKGpH@rzP{MJd~>b#*Y2zY}pu|AD}6*4#KL2>Khvq1&-qg8CTlvB~3g({L-0hyXV2sZ6?2{?bRn$ zB+Mb<;kevErcZ2cc(;l)^vxTS)WaXFc;(RXlX{*5<3*T9SI&9sL3|NL=iMwkCn6&eOfRVa>I9~O zipLM>!6dIAGV}#NDG_c-CowD5vu39f`A-z?S&UU8=n{Uumgz~Hl1B;RtPpWJU0(Ln zvM-H|yU5wWFM~KmsCPubF;^K)xj0IR1|8Pp_xkngZ!%Pi>}aubiws*tClG@O>Kqp@ z(YX3I^k*@u54Z&TgzrOUmkxMahW&Avf`n5q0vNxdn1*=o(bd%28@2fCNo@NL=f`d` zed1Rv@&lKi$}wb5ww7=G$R`Xg&Z%AjoPZ zdDW^nI$=hrgKxv*4C#B&4JB0UnKQN2WsxO|X&T?gw3ik zWB>a4HAR$`yD889zmq}_QV>`Vbxww@p3xbL?tkKp37G=~rZ}liI)N%Fd{e0;dxORfXc0Ca> zZTcj}jV9i+D=tY^@IUy51rM4;?Vh#cIR=`~MGH=K;@k-|v47rMLS|N8&_YO4l9Hm7m7=MX2o>5%gF9m zKIgvgOZxr3-_LlzU+WFN?ZQc2dBZSw#Hu&ei!5^U@1AL|iDH z#RMkL16yj}y+G-bV8|_DYIc~U2+pwSXmuoCYVMt0#hd%X7>#^MxaQ|Fb}=%zfnL;O|(x~%U^}8kt3gMm!6Y=^bdZbAD?Wz=7lo}0XG@Z z6Mm!^4SvkLnbXD>{klCtcoap|5e<*sp6$|J85s*jPk8=;FFi+%DzI}uh)r+J#*Jfw z-B%;WNLtd;H`?JkSqBI_h5^m@NE^rsvfAP9{`dR-DFgWYq$zFR>S6bAdvW@@AFC?8 zT7_TwdN!@?2Y=N{mV#+o!@JUzoEHsUmdoI64D?Hay9A%Xh=`PcS0Et{Wd;?Ol^NSZ6Kyrju# zUpG4u{BiM}TQfgDF~}V4^fmHDaL=19P_j#DRYRXv?~B>D-}EY?{g-kdbW=l9Q-;#iX5+CCgFvCf|MWw!-(w z7#egB3VO4{0?wcsy1*9wS6`@t1r;Sf^tvJd7u0L}59`yJ{eg82YtcsNm7yKgiA&Z% z1Lrw>j_=PhiSm>_rEvgXV!P8@=YIXyMn*d6Kkg|>mHAYBK0W_H}41(m<{;-^f*E1dcEH(R$~=V)X#bm*E}_ctB*9pQYbjFZ+>Q1;!J zZu$H&bSHe^+Z~5M$!3?FHYIVhhA<2wckSL^3ZMUu#zvf0h*U4MSaz}JJ2Nsc=KFR@ zEM{trz)5tC`#ak7#M3NL1<<8+_&K}M1A~{wT{XY{$#?QD^;6+Gkco%g>4aqgQ~Xz^ z{RA+M_p%rR+@*Qu=!7Cq%{r*J&zE3Qo=h6YTnvVBQD zNn>~8LO|d7VUqc|D`NL<$y_F6TxM`ckP1}~uP64#dwRv0zDHIv=6ZjU|MnMD7kI%E zpB{^fj^0Fzq37fF?UhRYg$Ucd;XOaJ)AgU-tlz3;=Eva>OC2kNF(uwnAH9S6fW{(U z<(Vw@S5d{NV#G!GqipgS>)?}mV}gxS-0!H3o)B4kw(}yzu<(Q1+bV`7Ok-%@t*jZh zF6kDVo|c-e*8%orHZfD>ujAiqr=_OKxFH!Ur7+FE=E&tdJ_WXXTyAL%Ny8lND5I^xq8yeTV$aMWdgQ6XFA@LZUpkjcxU2pNU zqH_8Vvw~|^-dEr6K4CIX#i6KEaDK+)o}!&j?v?U;&j1P<(Ae<~5kV?|coXLMfene6 z_QB~*S#;~B2kAeP?AtkUo+Z?qrE!z1ObSC9q#+#l+DC{K4)8kvd_{Cz_4y8!f@`B2 z+H)XTQd_Bvo8}FGYH9pi>t;u8+`NyFPu31*eTWn(nn34u%R9*~cDk8)kQF_vTJ6OS zs(Zi(Rf^2v3_S_&xV=x^ae5j;9rL|r9p6mnX*fPBY@t{fC=IX7ZppaBxf-eDdOwQc z5R|%Uzb}p_gSQPk&+|vj+t}q0nMvvhePEB;Cc%#%F`@tHx7;VtMAeAz^1j^cm1Zd zNdBEp>gL9{hj_ldWO`6EiScxA7@x^AUJ9uzgNl!!?EDjpzk~}jY<&W=nY?oj()TNt6 zL8J(zDKraEvZ!?5y}aFp_y*Cpfrz$=ii%pqi_Y_8_U@WPhYmGZIZjFUvB{tJQ_8jI zq|+3pHJIg+IO8X%aURc9XFiRdIe>}w{9Eq7L{d)q6mV)WWil9M>c`d&#|Tu@>-ifa zi}r1*q^LEc+#T-Mo;?$}YghKQYnyI*;~R^+n+hr6;2nI~=B}IS^oC&`;av_pB<-+! z7|a8k^D9jR-V8s{na_dm&J^4I4Ged_nLIp;k;ogv#@_#isZBH;4qcqZ{|qNuIGeUax-^GJ z!_76ayi9)rn7UF#dPX#Z9#d9!+jv8}$81$9fBQ${B*r`3GNbmL;2Eq$DV%3sTk~uzer@oxmH-Cl| zpOysWsKVmoS)lwH(G&GF(%Qr>eQ{&WiOu#yCx1Sh=04;^@REH?S^G&Vf{nQSAr)L#*ciy zi+VBDI+-koF$wcC{C@5V*FT2J2NC9Ed`G-A27dRM`%yqn$vVc0SSD2(Fad{;kj?-# zkY}o3-ZPywz~oVu4ZB_1#ovVkXWOodT)02M$G8^D5rU(gTR)`T1%CP{Fp^}2)9H70 ziv*u^rN3=a-B-$=(=tvGXH@bl2TPgEgms)1Z#V3^lIT;zc`vW%1Lx zM>F0l)^EwL&i=EH(HM%`DETu1j4tRjp;E@r@r6i`bVG_G$E+q`m`{KBcG}bTDN=`J z@1F*nKitjhm+P#}=1VKaOwMoE2H=;kIC1tP3Zi3mdvo~h-?SjS!0&gzVPjL#Z3Uc6 z*hoEpbtm2q*9Uh$7#0@h z6gj3cl6*nKhr2$`iiEe;JkUZt=j_|`W9?}t2kcdw?yM&$NcjZZZ;ov9;TG3zN zDY6Nh(#0PQl@1_cvPx%>xzoFmfvSvAp;`Y0*Q8cbSE(-CEP%DyW}C0Mn_<11Uqy`1M@_1=<1- zpBgb+qF9kObFPLNE9Pp8pm}oYnMy!7Ng)>1F~g(@YAPHaKsmPUFR(!Kyf?% znhXkHI6J-FrJ#v2VBG5A>N@o_-gL1Yh&mNW_u}2VJ8rhYlYtT?(P!nY=PfO-^`yX= zIc2>J&uQ$tnYR3~JoWvDIU|y99rs^LgjVGNdCVNC+=Ss%?{Z*L)8#V7V_#sjTI>Mo zLx~tMN!EZ038V>KwCRNm;~VkS6zLpF35lri`SC?f3^VkNax;nI0OiFpCRian4B)mY zOB!&MiE$?rO>#sidWv1z5qMERb3`te^y-BJ^;@WiAL8t^#q2I=+&4{8vNY7DI1d zKeP7?Y>7lj58&?)7aN|^UpU(p!1&{$KXT(-$nut(20nKwuHct z2? zf;U<$J6||iaE?oFJV9Zjqfs6UTl871HPfjd(Dtxg`=08_gq6G{q;N_q2qbCuwIYKO zjUdRD%(4aS=mtj3S9cuQ3td_ucS7pPp7sA^aZhwM-;1SaPzQ^1AclINs&K zC*{0j3CxI|ETOB7tDUHosXIIvP=2?@SXGH&kA?)8gA8x1nFLm)s;-`$-a57~sERlp zwCha*D(nW98NOI16l3+!3i$(*H+eGipK%e*lQCj=b@VJ$^@y}^~M3%bIdWyamSF=f=H<@q7Wo?*J|tgT(Q>csvLushN`wPq>a`6 zQUt?U#l_9>rb5mMgMh!5y01Zu&E-kspjf!Whh1NNLPTx{$L+m#S#LRV2}T8sTyWu3 znvbuqQBh*ntUVlz__08XjRW|^ADR@6k*lzh{` ze|Ag6BovD-fW@%n+0vPi)hUzJG0PCavW_(|2Pf8}DgPOnBz5-|v(&V-Y?z=w*^_~R zGHokv(q`@{RQnVFtjWlTXPwk%&ZvV ztTk9@{=oH8I$($n;B_H5EnH?yv<^r~vOE4vQN4~_UcmB|QG%y^zNXEHj*V?E?Y)9_ zRy0Zr;e1(_@2ZLn^H$`#GHl7rQ77uW@MTCKlc%0*A*9RmdJ6v~HBoHPh^ZFe!|yVs zeBQmIbwn8Wyu&WSt_Q#yi-&95Nkk=bz|y{szalP3GCp>x5ANU$E~5-gF7ee{6ULK+ z#1&|k8G$==8zSSz)0X;d&@)@78rze_j3T8GRT*`3EJulqq@%kZwPwbFY(i&;u~Khv zIxKlpqC+V>9Ii%xOQ@7-+|crW>=L9%M*(q(WvRwUz5e~rsz;R9EED0H+`~xFMP>7{ z;hBHDCzh}hl?x70fJ2ZsB{x9dZH-lS{zrxMO@pTLfBJJYAXH6m=8 z>O-S!vtYF&I&>K<%4K(v-+kEE_~6T*jBQ>_-y_kPQ4bmQG;8~ZB&Cm^K1p0AZLgZB zNdXe(wt>LHx+y6vlqrWhZW-Nge;9xDq;HNowf&nrUD}5*Rubi**)IF;6>J!#<(6&R zVr{He{>zJVc`$WiYvI?#35P>~MI;1h+Yqy|f>h0xEtS#mTQxE-8#O(JPILcN!nvhH zm0%j4VnFmMGMHW2Ibewfy%v->y0&vNUAb~)6nUv&U!uNxdVVk}!hEiZ3QA@%Q7LZw zn?$LBvhI@$ry!&`Rx-rcotXq>Ku$ny^`5`Vb^16%2N^17oj;8|BX*tMoJ3z&PGB~$ zQdIw?o9bS%zR)Z}q}%9}NJ<%mHr|GPLz$nLQ|COm$-iMt zE;DBM^WSAXdNkGD*Dwj3#re#VMxZ1>mx1_WDTgjV)hX4Q3wLN#G zj+!FQ6{HWs9NfJ-VWxKmK}S~lx$tMHW!~S93^_wM!eZ7I4vg+&I6j=}37X77>JJ0q3)?jZNPf;&>6k0{7t7 z@bG{iKYU2Q6I~-@4L5cGoxk-qAAB1XJPonlb1|*wdur?GWIcG$0sx4ga#-2R(k`_m zb5&aj?&5h7;^^Y$Ru8x&u5QL&1b}ElE7)vM9rXdVX^>zRFjVed_$(u?vBv1nt5Ex} z`@VWhbN25(l-IZ=B#%oB+4Z)UvV0KL7+-3`pyh*Vm^_b%>NfO&i_7=?_m=;>c9S^ zoHG1Ji;eOW(5G2Fq>z-PqV$4B0n#*;a}h*Us#995fB+aNPWSL_5}VX>b_C1$CO3vN@h zu>o3?cGi7>MdRNO_}_nF&$&pM?;e@9SyY4=v~T$_XAV=+&=@a!ZW($|DguXzy&K(Z z%;lN~g4g2=>LLq5)~D`&*wLb;?f>@?)WZiXgW~VqzpsBT87BuH=_V?=o*)0LhqY#5 zYIa#ZSS~Qj-n8n_R6d#AR2j}|Z{INzvEk~N7?-}EM|>xyqW$2()6A|usX3o;=OyZd zP`f6Sos{V&m)eAH9MRF7vTgrWmNpP!<(>TtheNu#QLk$AQsDT(VuaypQF@S2AFETtgH8$-ZUB?^c{-5Q zw!ilGq>f6WRT0) zNY859`z7aAHfMH+%W;|gM~LB+zMoz^+(L`N8Ep0d-fkUA@bK}Q|L3h$iaH8ZN*h#M z1ns1P0I$^(4GB^692uNPf59N1%{Xg4B3)En%a^X%vQSGg%wak^*q~@w7usWv;|n}3 z1Qs`L@84YKW(Ic?+^N|E^j}oiMQP_Sr+1rk{ng8tF#u3=?rYtg3Q5Un;(p@Qix>NV zEDat%qLCB~c*0o%vH_N3-@j)2%KA6RC)S9dIfN?!Ps&z?=d^q)ja4u8<|@yCiQg@U+vbw!e8H_ z8u{qFpuIDRJdZVyAg2qC2Z@hp@v5!7i}ldcH1MLPc{D{nlHShb_AN<@N=jaz##LMX z^r=5*CoEM{(m4&PTI;^w!>uO%+2in@37x_&Fco6`pMh)i1|ok8U$|lRDf&@2{Dx6S zUK6H3=QRHQNuvHlL}#VyM%KfozXuq1{pSccP_Yt*?)>*R{pHx_YURtgX8gk6N%JZr z8X^10wX$2$QZm};P^8(ia(cE6N?zk1K~xXQwe62gbS;*H)n0%)=y~!S7bXLo?cE;U z_NQUxP8w;3-byC7Uil~#E@p*1Gmb5{pZ^{zTi)**|EP7l%2%j`Bz1)SUz<3no2pOAmn(0}$}aW{Ze4QR8u=MZHDf{2a2{&kwv zvllP){9e69WF?^?eD^^9gn{OW20mBbbY~PJwfA%hFK8TKZ9FdM;Eme9{&}X1fq`;V z3xqt10kg4R<+$M!1s%mm*pJ-2yd6s;taG`#{s4xI2oPA!pmY-uEttCYe3*1mh}fTL zJ-<5&!G8utHwBY2eEY^;iD3w9hP1P}|BZ1uN7B4xDO)UtBavy)J^sE`A0ooY!w>rf zLnEL5PF?!Q#kSS&wyVa+B`itZ?>f9_;K)gouDi)z2GTmL<^|H_g#9>YyPtY{OxK5}2-tpZ>Bg7!)ZA*-wh~mj_=KpC7D|Pm>6u~|;qQlM33!>!?$GJyBg$YI8lt&9mFsOLH_&UGTCKsUlVCVu0Q*S_6}PeS(fVQeOy7)c5F z*$~I7J;vQ7J!)uW(x#&W^^e}Xbt`e-w*NdbJq_#1p}8}rsqupsfN|@$7R@;~1|5SU z08rYp1p5&9QvY+cEfKb{>39lEtm%yrPjLjU)(r(ZyETr znml8u%o;-dDwh85>iXIuW`W7?Crn_AL3!0@@iUdwV@6PnOjRDGBDNZ@O?ZZTe_?@9bAP`o$!RQBcz2{^Na6yqY7*#V!3Kqt5 zPuM?8D3=lAn-KBmo8+z9cI2v^N3U$9| ztf~AJ6cA_`W`zE;pJZFv-Lx^)Q5=$b;vhf(M#r6M&iXcW|Dy$11!59p5o>LrS(&*S zFe|lx($NaE{{0wpB{LK{=<5f6aONn- z;n=={dng2`U?@mrf|(zo`Xb=gHGg=<%kZK>-vB!uj@vjRI;bWJlDqQ!Z6~kckKX?8 z*L>e|XsNT^j60amfYXJ>b@!leqI0yMOIx5+8RgGIN=^1}S31Uu)C!70^nf*!j|tc6_9^0ujaB^49N zlyr4ONNj?588T{AlJi&A%KD~EEIwhBj9{tut2`n8EBAv};rMtfG9#oN(`KocQ2DM$ zQICvu9gV0Y{#K=HD`4bW%R*%0T-OaNp>@djf+0Tqak;XxvIk|cl{36Lqrw{oT;k)G zbHPaH0_PwftVyb)3h)4BOe~d%;K9iC!%e3BEvUaB{3a$%n1~|{B)A>_%w_J}4WMi+ zXY)5T)6V;BZFKp7oj%y8b|#h|RlFdfr}^jR%42AHl`J`z754$q)|} z&6Nnss;jH(M}C=AJcIoSi(=J3%9nVDZ=q0)THdv zd54Uq;d*J*yg7&C7UEwTi-{SqtQ?(`d|_HvI!6KUC1uR`dZ2ki72SCmpo>Ux`OaHF zKe<7qN2PG59yg~>mVjJDaO-QAA4^M<96=|Rb4yy&&>lRmEKYd&duTFv(XuA~kx5^~ zpm2k@y|^Q<0mjhV40Olu^CW{f{-v_| zLTCf)pHUNClNy3~4TG**zQ>T%Ar}0$fWK5!mYp4LSPr3R`Qw&JT#XLZl`wmVx1cK38)zwQ`2cVz!n1Oy z9Z%)?h#@uidiCj}P1}iV*8)I=pOwxZwK4^`g!8fWrl!9yUuV%iivv^JqxuZ%K7{Ws zTN=ZTAjll&8&O+a$jYiiY-5zx5&w52JPM%z(@L6t9_2KuXeR44Ao59OcCl|P(JT~% zkE5d#Xp5aivUd{>a=hsQT!;M5zZkWLpr8)mh{36qxu7lrUJ7m_`*7PfNuA|t7kq7z zr>BHNi9*w}a(~b^zmxItBW4DSZogGEv)=E8aigQdpVDvW8XIp^D`rt~al+LjEy0hQr4I9FojuU*(0St*wfkMdX-gG8O)9~;}oV$lf<8{Nq^I)YxkO`4c}V_SJ$Jj3KBH;j%>-C|0b6}gL$o)XMT>n`xA(qii{t_9LfE@y*S%Bxvj5lm}cTfy%2 zJlt6kg%n)o3oL1v^PS#UDlW(26sU{h6rx!=4ePxK%y;MHoNk{qgCko0Mv3gm>u9i> zx?e$WL03AkAyh-#4W94_j>4D9dFXjNYLIUW{!Y>KXqh-)c3RJb#oT4r=D~>spQf=Z zIDCj}ebvuT&83;g-DY+q>+$2Z@<;kD(Sr`TICrZN*R$6p6uKggNEnf8KF#mOq9HE|0LWy#dv+Z6{a|08GO>w=;MfJ7eOKK>2M`-ElZe$d$I z$H`NtE)k|Web%f?hMNKC#JeGm-IImpSwuZZKW_F)#+}RDN2W`E@QfQ4W4}}uH6%B` zsk{Hq_mXRhsWBA*YwFK?Y*$$C&dPJqFJRggPeNJ`DS-gtmOnS#%pq_^vt-uHnd-H7 zva;5g&Mc3e;X@XE5WSMDKhL)kNz7JWBT40Ou4^+j2NP{9L@1f>FtQQ57jT~_tVWdN z#+4DJd?(SIaT(M!vp!CSVX~03%*I9m8-q+-RLQda8&2}Wy#uVwDIpSk%$UsduI_A(m6d9b0r%QI%Sc{pDLP%<95(0%V$gs!@?|avp z6P{D7hJ@S2ZC1kdizjbqKQ9CC>U&v7AMN1203VPD)Try_{XnL54ziV&fx4aeBx{;H=M{hwSWfmD?_euC*jN3fQVFN-tN!N(#a|0R`i6`_*i{E zY~u2OeO0wrS+qjQlHWdR!Kz6uI5;ISgf4gD*|Ov9ZI@1VUo4}&$vh9O>D-bsPa@jU z3UVya>bAc6H&=VJ%(o@!#|j_o|4&g|Id|Qe^aI_>CWTH{ z_B>5Okc19+Q1L$si{M3HB<)RR08b5Tq98N1C72jcF{5;$6p`qWh-Zj6J0i!6{j!+3 zp>Z}NCYaBh*%?J)D9}Z|x5C6;)wzYxbQoUw-@;uzmHT^F+w}Qr5^gQ3eZ(KuF-J!@ z^;_~{NVWMuGR}|WPF{ZWu(iO2JTuSRGE{)NiBZdrk>+W)`~w1{3%hs5D`{Vv>zatX^sz>kNfE7aBy=dXZdbI4TrYu-2}F}&T7xeUDdK#RpQLx zNQ}_$XjslgFPb2JTxZ9W0#{z1kXE$h%Qjm=#~+2G1JF+JYW0QNiIlaIqjjDB#zr7u z%a<=-;t!A3w6r{)8L}_!!53;@n2?t6W#%bclKlmA=JME4dJL$nyB}FwPs3-q)A0!F zLO8Bu-DbRTCkmTVUTM^McaNG1OIll*+v?u!_%OHKNcL|6Ydw z4B7Tnj3{0;{cc;w*@oxKRr!-Hywmsd$6BRq`BF?d*7djzG}O{<&m znM}GDe}VfOpYtfX0X#<=`N^a@7 z83zTjP7OtZn62;@D|2eiaCg@oG^h>I{^_H$J9q3jy&@-AU@&mM&cE{<6r8VjNAeCm z{AZGChC&Gxt^}r2T77w6sSJ`Cd?lM&nMK;oyCOl-HM@C-9E^)AXC;sdw7P7u?~gCG z-oBl{r>}S|_M+Q0ntU=e{*~aSa0fQH(`L_|`-Gzt6-{bk@<5vbTQl%q@yW`Ir>$~u zJjnqiV)60!?g?m0{24+4kh@&|h>mhc3}qq|N9oi6RKqC)J=>cnHKvu)m^ zM~|Q%Po6x%@?=i}XRz9lxHv^Pa0!N@*{4mq$Yy1(LH=bVFmBAL0VB);x~Y7$?$+5; zqtMqNq&{~m+t6KKE$lCp>ex88eCjG)%(!vuS*vdskBqYm3>e5DO$4TTokIReHwrA& z9NvhraN@z^zLbI-%w88v8zfZ4Hh>-n8Fv#3f>6T03p4I{i72hPiSz2r%uJ(ea2816 z)oi$w9r0CcYxnjU{-|BGS?;VtRaXRfy_iXPE4;1 zmU0Ido<&A@xF+TR(dz(Km^pt`$bIY2Mu^$BZ(n}b8~MXZUtdS-#9!FZW}ef*j|aom zYv0C|r_IcY$e;a$p=0u85T9t*@NQ%%uyCLJtDI_9LR`3=2^$Z9$8lKB$ya2-QGkC=cq7aa3#+w&wDrzd&a$69KgMH{1j?%ezy$eh`6@$#~ zn&Cn3Jsbt3=m%icDCyN7D~K#yLQm+i43;z(ZG;=z6bm0}yqlS;R>@A`Lkc@XG_4H7 z_>z*z@gYuAd~G}W{yL9SpP0}Qg^dJsVOa_CCEo#&1C_4$Y*bRGSy?r}1rv;5Rcz+& zQ*TpLHA;G|z|^q*GF_6`Y{*k-4#m4n!(4Dna1-J^sH1IXx1Ov=FWl*wj`i84CypQQ z==XfZxP}cHsC#s}8|)Cg#nUp6rlbgUdY9W3-gY{YPH zigO+kwFs!#a|?t@6kPt( zt$9fpsm-bJBwLIA`+k&pu%XSqWrb5lWN$y&Sf*@p4RxrvT3A>H5eWZ;a01-Id_pZX z!)lS!^vc{GnAG%7vG0|0{rcuFAQP{}ii#=n`Tqrmn&-~YXyANy&HW8s;u@e1D*HeP#O-Jx0pHV7yitmrt1rL$gjn-{$!_HLdP;K{_jn(WnjInB#@Nstd5tQU0bA>F-^;b72N< zVeXHz=o@wzIn~95Wc2{kgT`7HpQ>Ac=`a4Q5I#`ZW&+ zIzwr)11(R{V2gqeuzkX}Nup4QP(6GK7X(L&CE_-nCzIg0fF513Jg6j@BSprR9p)Ti z@1Wy#DwA(e@T)Cu_lpJ_VewsRP7bigT*SS9Gmqe5MY!c`I~(de5E5~kN$6^%S-_VG zHsPz6AgdsUpw8+F(*l5cqwlCp{7q9T3Lw2_)Or%^O~QSLysn2if9Y7k z1pJpB;);|EhC|AOc+kL47YYhSoxBg_tIES&zkk15Wc!&hdg{90zJ9Gy?{_qFBsa58 z%N+*mfG5!<4C_3T+OH*_=TiK5z$cbyCnI0LP)+zhD_9xsjXFR)B6P9nKft?Mn;S1r zwKw-pTgpfGGn$7lpSf(Zc*Tk{g=3CTnUNz|{^Era$EwfQ_lh7X9j;-H8KrbZh*#7w z7aly=HDVe#2Wr1&vI5;YlnT>HEwjCETmAYD84JmZ@Al6kCD(&v=nIiUjg+euX6$Y< z>eNFdS<;@6SsT^zbz(iuq6uqUH!F1dbhJKYjI2eeKOTIbZV`~mLYNu{Z1bGFGNzoYw<{z3+@Zfp$?Avn>+;5tuw*MfB$^DO1saZeI>#7WnW8& z$EnZ(3*`qf@;o<1l`_*PkQ2p)&Ii!&lyk8)RkS2~K{Vy;+!stJIWqb_o6{Mm%$bxE zM4_pDa^d4^ee2k6yAJRofSJ_~HpwEi|JU3M8mG)UN&=X|1u?5|B#hP7vB_AJcVgWU zi=cyZa08Y-dzKdj_|WX>Bt<=~K6{v;p(dtt;v3g?e+_(~6Sf9&Tk?2iyuzskqSB}B z>ZG-cja0D2fl&+VK|#7#h9fi*@}z22g^({s4Hnp zsN^FI?~$N5uu0oNqm9fT14C1hbnQN_aoidCIifnPN`Pr)^QGTCBwPZw))OqUZaI(7 zE>enjxmwHx@u*?Vq71IhT4^t&#!^8%Ad96o9( z{MTDn`Z;)@_|H~+P6PMu;lfNc8b!y;5^srvdaqhrb@jE>bRN$nA5rSxPk|4wfeP&Kh$ACmOv8}rgZHZI z-X~H~thweR8fa|pbP0PEXsPO(Oc{q=9N+|Qa`PHWBhk6j-`Fjf@;3!C<%9XWoW86# zdhd(N3t3w_clR7Weq6L$(jlI!6%}~Wjkv=mKPhNcM$L~~Ui+rCpx{BTfJ`Wt`{ec? zQZukEuZ91hefKVDsNEP_$$kj?@?}}}t`qG?&96F`c4?B_A!ur$mIA?cnt55HZe-1N z>9xR;d=+XY)C?E+%17}JjZGT<*zdcs>8c%I{vf#NmB}y8TyFD+^xVV>w&*p^xXbz->xF!GgH>?#lU2bYGCY={iQ{mw(uSE7 zh!=?m?-MX%NKJpr;=_)qu8JK7LErK4>}PotSy^r_puaCvnmcDs1+|XEd>_(FW=~QJ zho#4qz^89LXt3GsU&YP29_tVPM+?Az6=#5!M5DpH=K9!|a_ZYQf|=`F_~SPfREBry z91b52+MJHNGXhjkUXG*s%$PDl^v=D?55>g=Fv>#Bq=EJHaT9vNQ&OgRb~!Za34&lz ztX1Iauy(whIO25Y5fqUim?1n>!vTJH=l!?n_3Jmuz0&RC$u^xyQBq!k1>zF9=3b9( z{XJ^3L){QdZ+a-Zotv@LqY1sfbJ0)mnk3QS%1)I- z4Z%g<^-6}bb^7Vks?9!uCK-OvUfwK$w6(^iK6HcG4FLPh8gHHq2&miHrR$O%7yPbCAQU8)#xqe@njZ*{ zj2wBoWWo;4hjR98=xK@ASkn3~DRF_y9{ZL(32Lvb>aa0n-YU(ZmZxes1G{B2y;qLl z?3%kW>;O-{f=y(%G;$C0E|3Y=s7{0C0Pqs7t>b};V%zRth~rcu!iS`W$Ab(R6rxvG zVr{wm^cQmxka6S9nvEy6?%uoiCF)O&Nmucv=E^Lupn@w`w!X6d#FET8RSc`OJbgeh zqeCe;ZJQIbe=#!pTum}X0pj9~***&UsItup!dQi3r9!HZ8|lqfP}$I*mQI-!te;*z z5p&ExBxOVOFOfZ?P`yAU*XQt-RGcfiCHh?*kFGAR{mGLJ`fGLg&+{f6@C$?d=wlKx z4v$)~a%HpKYP|c&2_FLT?Y7SUM3I(r+KZXJH)P3N}Vs92QD$)G@gW(-j z+6>sKwiJ{#+rHnBGmnkVCGBhqb8HSriMRp3h(&d0#gNiDM*}(lee5`Uamxl2Q{A#L zcd9IncBlj5An@13Nf0vk7o1mr+Nj2UD4cLm?oOa^#?YxNPwWI5=tiR(_4oY^y^;QA zAtqV=ya>DuImTYKODD%Vh|J#fD`8l(A9*cj&xS5Sn-QtJ-kgJlzNf9W2X$ccr?KI4 z?bw?iqW(_r{I-*NBl^5$jSk)k0AswlzDBbIpW(JN{Vz)WSJ2_cY+yQCXg0qH3| z_kk={&+g!E+{!a1A)yh(z|_Bi4Bqi%yHz|jZUyoidxU~=a91@2n|brs&UdhH4U8`t z^P#8JCt8NwxP7}reM#4H`*^>TM3%@sCq*NtyfhXW#?6mjs<-;xbED0-Qu?iN-JnbY zX}MQ5;YUHW%N-^~RSt7Ml^HT*%KVJ@_@LQOK%a63Ze5Sq!X+*-aX&{SXLgNsQcTQH z$AX#4y+>X2K30SpN+!lFz0dHek&Y?h&u`flkp(+3M&ZPgNhZpc&PNY7BIEZ7)j;Kx z6pBOjma918`WVL`CheAO{^}Vwf@<5gO-W(l0+WtnL>LDRwV+uAWkJr_s|va8El<8X z7#rPv+P%kq3Qs2uNzpSndqn1HP!?()bgR|r^zMF;ySuyPydV0n&!6oPZrl96TN|!) z>aF*FP0%!o`&dADas2c8MVXDR!m}2VAA6%bIX%O zEU}97zp02b-jlBWY+&ukf7G7uPb^|d3nNxD@j>@yHW__a?+Hw)q)=YIGedGd1ttO+URegJ?mC z4+>0jHo0eV`(DLhUBs_DBLapmKWaP=aLODBTh-nv&d&8K?<1=X4A1;$X2KP(+ma&^CvzIYbcT^3+52_8{y>v$geQ>;M7@Y|T?jWpley?OhsL5{OEZVfM{ zcO}quHM&?dhR9Kk)@h2EEklBSG(^|(o)E$BO_1YS4=p>(p2o=*E&(rRa?qcaU zopCbpWqpO6?v^|w#G*aYkiB2DW=$^i14BliSGmB?&27${#CL<%2L!13=CB!;?a8dq zl2B>cD^zz7eM}AjT>U-6_bdwjq~X+YLhta>Vi5cf>U!+yW_)p#-Z32V&*yiNkp+xo z2n(o8KXcf?%Y$6)jN9;?QMG~fP42xtNt=-MIJIi6an31{A3;kM_i&VHa`%S@oI!M( z^ed%eu258< zX=qn*uYa+CI;1H8oGM)#-=?~B5fGkTzP0+pffg@EZc9{X+uJBEfy{;u$@wd<1;A$$ z{ifqF&v4m$2?^ZaX723Sizda?3)!puu;ko;h!poMFO}l%vnJc$ymO~xNvrJv6kako z3W`KTPLv)K^cGbppPdJQZ*AQ9XqQjuxUM`*bf%_F%2|Dab1u}cE792H=eJ3cYhK;S zTsh0Sc8;(2S-4`gYITR%lZD(<>#{InAnNJ^8Es|il#;@qMprnt){h%=d(+i&TsBe{acc45qwSK>h4;L?Om{T@|8Q_Tny8+&f%} z53V`ms#3e}kkZyonHjf%S)o=cCfk0sQq580atjkkO++%Dy0=urR)yT?J* z&s#AeYwHO6l(Yo(l!f)q?|7AHQ2F{*fRg>a<>AjAmsch?_PPmpwD{WCDM#OKL_5h9 z8c^A_DHdKtVrCWFU%uik4^w(}`rDZ!t##*z58OoXw?@Ybrlpv2i1}-7`J*px9M|Ha zR*1*^^R7qQ)|BqEjIsH(+s5?%L<^EGXeu>-0f1Rm0G}^!MSZQ;Ij=aODpBuLfis$6W zIc8sfVrJ~vh|?O@UTaCi@;@r@ECFi^nBerEK#{wJJr+and^qSU&uKf zs?@K@xHE<4o-((4UUmlI>W@pD+bhMy_EZoyBX#_)g4g%Kw1a=WrK%CenT{b>KU$;l z_rAU7+!>LuwAJ@P8b}q8JXRX)HYiu0F;Vg6rnLCjBhAg4Ux>b_?)r6)uhHW{hs>&6 zQR&v7Jk4Iq!RJz<2w=@eCy$=iaEsgN#Habk+N<80Kud0lLp8(JtL3GCF{AAbPj(A6 ze)@cOAg|tf-vSeT6*MsKfS6o?9^J>bNG*+1$hNc|l3J-pwFvK0Pyq`cyoB0b#xWio zyC?si$u!l8%BoT5{keV~&ZZ!peFl8Z5inL>niffj2 z6YTRB6(t=$ypcmc{`dgg6?7keJoF@c_z?TU-TSXomQQX2$j65Yf6B}O{d?g`5d{to zlY;lzB(`7%qf+C>*{GpZkFmfhi*i_4%CRB^tLd6U+lwamitnA zUHdh&yP27K)I>IbSW`L~pYe!ES!j|{^Ar2rcF)YbU*0woe><(US=0K$PZMFmJCIT~ z`hc3jhz22VhvOF4j;)hY8+PzuXF#Y>biv(>3>m*B=?e7J(hmu1hdot>hmr8BZm;!u z@wLmBMV4^Eun{-rf z1n;mxta^N09Iuk*0Sa%?ervUkXQR+W^~9=I3TcB=LQ+lz#HO6w6&5zk(bj%uz1hp1 zkJ$aw+SvEL_qen3V}p4GGm2cU?lh0FZ(~2&s*cT%_cGZqdqubz zYQBj&rjaMTixz%Hvbh$M2Lh}a9`Z+#b5(|%vyNUVgS?^^%&;y~KO^#%E9%|L6E9Zx z@jiFN==7Uh9lK#3z5AsAg~9a^lIuY}5%YO(V@JOa>hd zupd%mrQvX)=z4;>?(SskvZ`74Kk1WzqjneG_ROl8#bcJ&=0Md0%t-U!N70W(5I_Y^ zHccIkv#v`QFP3D6n_>p2oIdzD>sRKezIERod}i-4)zf+3om)0AT$f+nJC(5}v{?;bEi zLBGBJsMQjtAqW|#(nZeCg5y47E+c?LoqO4m|5j2`@sfESbf~SkTzs<3K~3@)bUX8p zTSGO8aJc<^Xd8k#wLMVuxR0$${1CZ#;6iV|o^$TlO#WqFHfLd?dLW&2bB9X5?cK=P ziQK880K>GNu2WrkJHjM4e}~EnGgK_J&v`(j_MU@u^*$J3_jy09jQ(infaRXylT=K) zRxb@p%bx1hcy0QdQ~f@`!Tewtz%Q@erQtexsVqN!A0RELvz$M_0F0wxQ2DIrk!1tR5?0>-Cy={pB zY77}d3jDYQ->QB@1zd1X7+(5j!q*|+zx_UBaL3a9+a^{(Hnk`8iI&eihk#d3@z#AN zd;Y5Gyeu*3WPZ9sPq9FXL@EZ8##c5N-_pOn zw&lZ$b?t3;Q@eu-`?vM`QU{5Oh@^o@HO98*leGpj@(0k`x}I*{V>Abx!?O^ZDgB>j z&Xh1Sx`x2HNuU6WL#|-J(s|PoV3vtc@n+Yr`#odb%%(W(J8Ftb#CLt~-3bOMtxnfp znm@^gt6=eHk3{OBlQT_3w0Ny@bXowMyUn#*2y06>*G(k5r+s43Zjx z%F~}BDfzeY&tm%c@X2MToh1nr@dddK;ZYZ%?A<# z#2Ul33y;xdR-5YQ6okn)^7~G^Q+aKI4ilo9fb>}HRaIBF3+@!_J8*ZEV{_oBn?#Sh z8XefbU(B^ch&B=j6E-9qd_l98A&(ZU!Pwofsk57{`}h7S%lB1%E_Jq@A3nE@L!^gF z>x)u{#F;T3K&ne|R1zZA9u*Rz4N2Fg2@H^rEi@>v30WJW|Sjd>vrB3tcYDKI6i4H6yx?XpK?X^R(xg2NnV6VDzsk0LU7(aX^t<111|p1z(B z{m#I!ZSM%5`m;C;?aV(pS01wOR~@loM8~xj?QN}lghxbNQu@#{A%PDHT-B$4|6%R7 zw(Hlg1yl^0q~T1*c%J=ClBKv~L@ntO%?Y*>E&OW3n0R&2I*Di$rA_XXOuyEYJn>V` z_Ud5#FxMTiy+)Ii(+x(zS9Kj8To5?r(!EdT)5;RR=TF*Rapqvvoc0qDte}k$&dbQ8 zUAxt~ozJ4y*}qq(*Sww9&QVlcTUEF9WzG`Hmy8nCh^1zebZnK1O{=_z4Ue(c;N?mb zc~C$QZ_@40&p0Ms{JGU&`df?fpGyynox9h$c4F(V(vF&!U>cpyL5iNqI&Qwo^l7V> z=am#~J(B*@p?>0=C)AY_EIkr?R=;hkz!yK_zfEa)Wa_}Z9s|EeBe2mg9h~~zE9LuD z=`m$^IQyI@RmT70^a-4IQK#68QDtp`LVy`N`?)=TNQ4pZX#9n6`=-!|0%9PMveBxQ z%VTBj*w+59BC$ch-c`^KA}KX~e-Syr`q`=>z{-n;^!Nh*pO zNzZO#xFA2&?S;0~*?OA6D0;aiQsFerN-q-$sDr1Cm(vS1v7*ys?kF=s!Mvk=)BalmZU{N)RzY}D(z}xCenwkI+^O2JdCy}mt2;X)ROQf7Z0m5s zecy_=b3{w+R(uWQMaKmA%cQilv|!IHuyS;>g+Ywg$mInrZ**n#`?nbm2j4!K)1Tt< z>m;%6V$aq76Pv*>r|h{|^;cKdJD-^4*PA{t%XhWCfy1lz8*ww5uCc%CAC)FKS^g)2 z5G_o{SeX%^R<-P!v+~ZW(|!*7HhJ7BF8O6pS2v|zrEa)&!ST-@r>!Z~>ZCsM#Mi0z zd4K6loMPLtbG>~_rnszXS))n5c+R8}h*ofSQPT178;El8R-3+_^$BO_t#(4FEiGoIbn0_xjvNLYn`p1Ye%6)Onjb@pUKq$Gdd9*?#AJWtHBt|KCauq$<-6hexGnJ&@vx!FzDa$htxpj15e_a5t3c# zY-U~tyd1Ua?Bc`Mu_l^6o0RmSMVkO~+rhj#+r}oJKCplk_jVaPc<<2*<8i*n6*#OV z=}sCN(P==X<+Ojw&JT9G*MCtnb@luyO{~94I2-#gHwd@-41XZ6%SydL`dtQEw{d>v zS@gB={`_au@|B)VlMGV_>oomcp0`(2}mSZk4unRkv_$)a~9u}1YiOsdn2`DW{Vv-wAOC^ zQ#M-aL5hj;HhRGF?4aUXx7M;0;UF3yRie%hSad`txPiBgFJHL;l^`aQE)}pQA)*Z9 zKZ~?FZ*$x0FWda2lFmpDOWnADGrt^IO}pou?SxuQn1SAYt@!@k!pLx%2PJ zg68s9BYqec`Beg1MFuFpo3yuUJu-iNOES8On@@2{!vOQI3&nxHJ(hQ3QNlKrboHUn z(VhHdTAt(e=Dp04m!TknqMU{_ReK3xu%0txqSk~1M-SPn@Us4hb<5FfG5V_xre%(@ zT%=$+FZubab7##$BM@|&S*{3hVt)iY+XuZFx(G0XY=MH65hgYR`jAkhcdF&EUVIAo z(J%D-n@&3OQz5tRnX2-l;L&dGlkF-gTbNMSWV_42~7Zy5!ut^Wm5Y%bSPP)VD;GB_rOPg zZmUjn9@*HsvJ>?+Pg^P?kYnhsjQoz{?78HLyxVpC&Hz+6f+P}Tt4s|pey27N)5H6n zz2{f@=NVE9@0kF9f5GoGu)v~?Rau7{F%mb4?#}?A6mbbxQTeuD{uI%1ziZ z%d{Ls(ggQr1yi)HV3f=G$3!QI3Lj@x7IOJJ{0e-o6J32V1<+7bfqdq=h&50HWuHG3 zLzg0k5i$Y87|c)pl{}+KLZ;T*a8`v_^u8IH6Q3WR zNgdOEVNp?Yw7I~6Kp>-xM%t?zS9wmi6EEuvt3P7mhWXnQ2fK0lu4DgzQXV~Ys~?TCL$x3mW%Eg-PCF)l`YxzHnmg0c% zg^+O51nBQ?lIb3WBhF{256D5sNoMV#PaZ`fiSaBSB+fmn38bm52OgAxN zRmY}@sc)PU+=w8)ARr+DP+`Z60fP3!zeZxzB7Jmp^afqlcl{WBBEHTAwPwa6CLKq3 zw0>6_cDtNGR%%*uurK?AKKsg2&k7CWW$^%n9^!uE^LFXRP z)MT?z(lKImHn|LfqL3yD4|AQ-#dZ_yKSJNy*48JSzz_9KCQ-gR%}n?eB3 zZxeA8EYUY9?5B<0%?zT^ZogS%rae$danAk2JJOmdM4CfieYk!O^{Xfhb~n?uMQfj` zen;!QQw7CuuKOU}y2LS1NILP%H|Xj7ow4Dlr4?#=bQWzx0$qmBlQK_=vUTgW4@3c0 zD7Bm*6B)1?z6}3uWz_aTC3}5z7NHEGu?k`dqpTTtjCfDZ>N|@>Y}L~P&}?xFe%u6r z6e-J4klhL4*1^Jbi@^N0EashLz#JN)R1upT7bc88Tzrm4PYTR;n9=&Tp zF%gki=%-e*-P690HrsnF$AQ47W@wEcBBt!9!oeY6`~yLmz+i|h$y}!=?6Pg|E+S#9 zvg;zH3MYI})|gftrZ1q+hve(%xP9CoM)X0O5|5k0Fg1qxvo$c0r5O*fSZfRdF$hPC z(ziPFG9gOC89G76s5{rLGs5x7m5HuBU+fUEBZN3WTNZ8N} zK0w4U5gEzhhCR=Pz`L0?-NWNUGv{`V)oV$AQL8v(C$nFu|7YwHI03y~)}&Wvr$Wa6 zq8AD3c_nF0vHQ=NIv<`yD4R4_z(gw?B^#zkvU(pgfpXadTqP-hT{VCk`COX465Nd+ zx|t!7;=h3hjt(BsKN=_uc$xX%uR9wVI>-xn4(WlAG26#8&{e_k^z19Bu-E{mzdCzB z`Kcjbh&ktoPQ-ykb?^M*v#hMpf<;yF@aLKudTbqWT9I)&tI^I^^*JTf;ThJ)+3cLe zlz@e6*yeYppx~;vj?I%K*4S|ELeF23vXogIy0Tq60A5&ljuyV21LgI~wF4i8w&cXQ z8<#sfI@Y%&B3UFtYd3fI1hAL{$I*VHq<}@>oh*cqPqk!rFp9TlUx6(-?)Z{SKP1`& zV#w4xSr_mM^|wZGGN$z0(#4OMu9w z=;FTFaxQeGY>IjK@JOM@DVnQ0;>l6S%p)?yi=uTwGZ@JoRcMF16~34qx=Vqi!LaE1 zi3#_dW;pndZC@7+CF%N}QRs37K7afEeLcJ3p&;&>Itf3R855M}SAux(Ku9V-D(&mF z8;I~StzW?ZDSh3%-k*Xsun&yYJ4uO7+T_!c(v9!t(c;2M`uxnn#l%E(x1j|#SZoyA z@vA+%Y2aJp!32Q^X(C6Rlwp?ouxlU1!goGtq~QLe{T=sF_Y@oP40tPcWB}s@=&?HC zlo7o!jRR>D9W_i31wY^R^)*KWD@ji<+KlLEm8cjgZmk{0d#|UaKoi(sfs-rROyp5% za6N$53eq1!Cb74x7BqCPu!f$3 z7$PAZg}L8-ZxDuwCj!?J!)PkAQgy}fMHnPjrF#cmQUj^;UHPx z^7<>uK#@#t>!)Ml6cAH@cC-3Xn>*b7GSx&;P$ssz$OctQEDQwGG};1B!?n1yM-x}t zn>+Hv29%BJolodguXDV%B?RV0EXv7{?8&HBAkf^Rh?rdS5-)BF0R+xEc*LWdYR~S`>O_DC?HYOes_{RpxF^%KLYf%mH zD-Kzh&F*SHF<^9rYbgZEv^v-U; z85D$P-p%4PCkD-%?4g(P?mDJND_)#ljGoA0EYLbzk1SN3#YgvslZ|Gw7Odc_Uwz)R zjBXoKlami!I1LLazU{u7*aOL&cH*A~Zj~5pz8KDuY@4;l9q~3gv~SOzi~7RmjqunL z`hX4)$P%&Gt$wgSa-eX%-H%@=~?lQewR)()<;l}s** zz5BhkH||0ELt`&tmcv$pPTGnM)%%VGpVXQ{&U#YOHdl^4rmsmU#i?)fvns|zkrQL@(Sp;)PUSb&@d*=4eQ+q6^3F;ypdPK|@L>F{UsDR_m(7azNGj#wyO8E~Ybrt?&Ua--FUY6@E`Qv=5ET)9 z_pVur=@Q%^rpIzV`phYgfv0{2`1p*c<&>*0?yTaaOWF2qh(Tx(dVO$Eo0S%X%C207 zi*wC-z8)<6&u^zWdV5b4k4kr|==fH9?VBvkX;+jz6G59 zICqb97Gx%j-aH?7Ex(=J=fLkNm9DFkWh^v;W9%nG)NH@L?6qIQu5Wr;a(rnvZso$8 z0rYHNyXUZo!1dP(0{aI=_Xg15_hL1wue%l*YJS;NKs>ps12@Ha%&Z1>D$gq4Cy#6J znNasOvERd`s{INp?qai!-p;GinfiI}SZHKX`1>*5x$El>3<4w3)4AH%{To~9?1z2z zPi=w0d`w9K(&bpq>|@cu9ZJM>yT?AERxj}15|*6x{na6QwxwBvITrw0?IDbTLwhXJR(7x4l%?mG&d zSI2*wctW-D&nWQZ3$PHzgV%+0Z}XIQj<*srE-z19ab6aPcSp`M|udfSH+`51^z~IQ%qv z3VEnGP92yk{2V0H zG{{i_lAyZ!>Y0eU_wL=?^~H@^&*a+9ckkZiUW9Z*kY9_sobl3B=eLoY3n*y#j=dI! z^}N%CFX!p=h@!pA>3ngo_aShmd@bH)vw+M5PZMbH2#K zxV(26Npp~9NW;tZI~O6Sbsmr|?4_zU*lA~Ep1vK}N%|{KQ|)NXJHGRlm>hzAH01#E73v4)Mr#lF6b z#^G1c`ZIr%=uOQH2ElA=q-s|QMF*3+4f?L!zJ=>Cg|`v!gq^m8_wXe~L=VU9HPm>xfX-z&YnN)@PWb1idPur!rYw=QQ+{c;?;~laCeQ;8c z`c}uz#EgtJc=Q`Zjz7ACa?A+TAxZYY1RbXEddnR#t3bfjfVrD~D;hWCT~}tj_3xv= zx+t7^C((zE-f36BrLSSG z1`!iPSsLF*HYECVrPjyp;~>xQz|zaT@Sp;_?ROdGtfJ z2d5hg4W-HTpPR{}Ky9qa(ZS@z2_o`7i?qh4bgAp|$DKvLX&Ko$CzkCC`{>YJw%J1O z5hy!1csp%Js$*npoha5H>-t3rJi6HV zFatR&*y>zN+Qs3J#&xO30TU-7=ECf9;yd7nHiurUqFPJ}Af8wnP$)ziURn*iA)|fmG}vASIMAQpX{8{QeGUX2SL9uOBI6Xp3U9Lp==#g z`U@^#JmT^A=z)ll#D9j&pLqWKIZ>(Mjhrsa+^!1V34eww=V$hs5LlYU3x%9Afjr9!QJ5 zh&BO1YEcalWGXZ2u-TR^&H&Yr^!PE&%3`fTu9*$TBeGH9^9hBNV4cj7BS*N$57?vh z20mXkX*9w7GFAkUdk7kw&ThZp)1p|#1_3{wK!1yYL$mWJd^B_s+}Lze*^rN6`>NX6 z5$6FXBi`qGT_^5Mtax^Dy=3Ajv1xFi))3*QtdO?Ge^6SEc`@USAtU=nC$peFeOQj26 zuEHD-Ih#@nVl1=<@n|fv{O2WjDy69%b7x$idQu zIM~6@rqKt|g#qBI*WIo?K`AL>r_*)shldZpizSAu1NUz+LwuE+Lgc9`^n7-*ze2q^>)_3286^{Y(S3AWuN~q<-=oq+G;qx&zBjc45I;YX z&N>oCtlnrKST0=b4|Gmnvn9a$=+-h;1Va_rj{KR4eA!z(nz1j#ZW0%KVEM;MLznh* z#dDBAa6|3U^7(Vy@=alNx4~FfZaX7-3O@I*>q_BlQY_5|M|e-P7^<+)U~HXYnDG6G zh>?~Zc#;68wGA83AB|a+es=|GA9E`ucXZ~T&a(-hZ@0;N)FQ=9dleBb3&l<&)8p5! z?I*EJM8c8(>ezNe=VqPyeDBuv%@3n9G35Ap>5^ded&9w*o@U#zJJtGWXO^^x) zJv`)(96gEx{GU+w`A>)VYmksWG`tQ~3ywm6sBwpk75`a`x`qA;APVJ(bMObcJyz9y zL5|oE2^#D=u^*^}42^d-3W0>egpn0X02Ze{%{I5I`xNmg-UzVfwBI2Z6y@5W3|j(K zv4xS0slT=b5F+{KwV-N8DQj1F;kFY3G901nLL>g#_5 z7aP(DPwbh&Mpa`^Q%e2HmRz!TTl}q|g}ctm$$z4lf^a;8)7qh|@sB$4)s; zX+xHzzh!g6+ic#MrJ)xt=XwwtvYs;PoOhN?Z|l4u*Ufk+Xn)TV3<8|vRPxH%gL`#7 z3of)%scBc)$O{zeY za!S0|+zelQ|%Nr_da+(Q7kJzON6@q_q!+{JL&7er+4Q!;dNc0>_y3L*( z+N{3*(Y5(AFs|uKFZlAgo?PYFgbu43;N}|K!Xd79ZWEAQrQkEj)B5l@MNF5rbOSoSE%=D;P;}zM~(B#cr6>N;l#8wLfSawH*d>q4P@L}%JNZu zmWdC0Y*nhGE*do6u~dqbebJ*EE#x!ASeV$tKw4G-nOiAte1UF34E+J=Sa4G4YqO&fPIx9DLYVakfx&G&=84RgB zFY<+;m?jtwXKQhmct5(tr;%dy=XcugqkT5};E__Ckp3`} zQ-Lv?!ow(PXY*$Gw!~tFXTN37nA`&m(uYon56Ga}wxJ!S{Owg8XCuN0q;}>=WR|W6 zhgl0g<$_znGk~E_k?$x>_WWp2S=;9?`e>U|^QFC53H-!|6$t_tp4Qo%kEgje@bILT z32d;h^Ev;kti|6-Vz9qi&xB0I<}7a0WvyulcsY_?CtXb_jeuG_owkN_vx^tE2LuM* zjf!d$8kWC1stI}sGu^nmoEkM3aR@mNysN9zHa7k;REiWB>5Fbsx==njD$oj!-Pe4?qP zrD|Z>N3Ujy}jVaV>xJ-5uC9H z!xR^BN=@S=Bn2V#Un`=Q0jEaqrJ`K(wzixDLWw7DLtYR_94`osLRfLY3ac4rTW!`) z$hPHY-fThy)5-C&5Rb0+0i^FoRH*>%#@AA-m}sXiD~X7MRnlNzKgCnInIVhq0%byE$or8LGj*1wy{9#OSyBK#0MJ zyj9Te1#-wl7}#4o@zc28{lZQTbfo_^;NpDiq)V7wN{n_Hv(TW)Vt`-`RP3F-EGpM- zJ+9lk2uE-D{dFCjwL#y}J@?sDjV{vJMlqY92#fyZ&8-lq+tZ1|FP z9k+X`hQp+H*UO)pNe=pfiGDr5zwcVab%YcJD(0Q*0vXDP+{JeOK?NL9$k1!Zokho_ zmB(E65dk_h2V}mvS>6dzdMaWcLxiXx2Fz%~o)Ic(tgC1Pp@+9yya}~52s^5-Ub)e= z%L}T20i@6uPGTDX*?>FcC&}wVx9fDW!t$0h27$mD;?8vzu1>ohdnqtD^ty)8*GJ3? z`l5;HF@ePA5>8?d$37gczlY@g0D+v{?lO=lm4Z?b%*@g3p52(bq3BD>)>AP1ro(fv zoBt!dW5$!7J%sQ|C`FXzd*GOvZ?^)mzo`{~NKyI(#1+E@^OvgH@f_Uhv2uns-DX@;F z5Q-9KT6gz7;Cu5pe*63BN5^MLsZvyc1|orhqGEHT;b#kuZB3;kBQ_U0^O?bZG=F&y zb6qm;7h3;Dp|xJDYC!OO1Z0CbLiDKqcB#_7U=sw+pt+Qx&lbV#ZG7C&{s7z3HW8SS~}(|Y(&b2@f)hh>`MKO&LbH~6N zl9PqFxgrpu7C=ZsA}T~ql74Afq4{Sfu7S+qMnHvCm_JY@?(^*9T#YNw-)7&zX9lsr z3RVF}R?q>aanyM-Xh%TWa28Y9spsY8Ey6AQB03PF>Mf;?FARMe$Ss?6Dl&v!>VDAI zx4`ryB3Vah!9+4;bopT6ZJ1wP@E?Kke8%Q1(KwG2qYS4Zp}GaV#Q>BKDe38Iu#7{& zfOHk2Q8_{FGYPc#b`nM`j84GRels=setadopCLLL;j)XxPU)VLs&)boQ@7Hm@F{BBoTp8E*7r+i^9Ueyfu5t#-RD3dmdIC7IDW;N$h~H+m}Ec`2&&aE=j7d@3MDI9b79UWV3{|&b0N< zON8LU$?_$A4g@jM9YyX-=^1 zQfh5%h6adPDtIFXdOrSQ0tc&R7Je3+IE)7n*s^6fDqY zU%!++c9T2RZ8pHn7tPmM_lnm5Z6KN0V1G>35H6hc2c{Bt__klLpRwzRKxo~Cfzjz| zkz3T)gDM9`UyHH7c%GpHM^=4$ zpvtNS%UTLRpWPWh?c{iHVzyO1vpM4}(2HVDHF>Zd>edl&Evk?(>;Eoqw9Fy8M=(#X zF4o6|hB_X3_r9sA>0V2aGV+!`Q@#o@_s{WXo{U|=@=mtBHlZODAcTn))eIWom;CJ8 z-cCqM%gD?`>4)sycv>UXWbo0|ZIEhY>3_B#o>2Dpt3vwx_Z@{2cQinHk!NoUf1sPtZ+rY2PBwdK$MgGp zDjqLnx5p2jK>qG08<5zGIA04Kp5;1ej2=b~f;~}c;%NDeO|yt{u2VJYrPpP`j;N}h zhbOt%;V_!a)>LK*DJfiYDXy~kBiN9|@6irb_LME(F6FsB)W6ql?^|>BlbzmCCmwg1 zYpAFoY&J8OEKQUUK$I1E@#)4xLN@zQvj*5s&NU1CTG|p0#<%!P~{h#pV89>RGIR?OneP zpL>lzx8li?ue|3dY7o28U1J1Y;CzdYnM5{GIF?us+)-sxGu<^@mg9mW;DfQ{ks0f)}~@u=?$SIWe;ZuOO{ z6Rh=RIK~4d*!FZ{TeJV^aHls`!|{cm$d|02+`lEdxO)vL3&lL$qNAhJ25*+5qJe&5 zlK)z(Iq}#BXgNkOq&P%&{o`Nw`Ksr%!6h z+vdo_kRwZr^agcjZ9W=7P8c_&JD4!Sj-$8g+oe9pLP&{};zHw5OU*%73Y!6cx5@O)F`4%^se0|UYy;FmwkjC?U+HETH z#xf(RZy-szAjdo`iU*S{(@s8LL?C8-0U$a6Rt)^X&Bjg$dvWtGX{-T~sJBr$R^1h*rBvFXtstEj}NxIt2wF z9jIp_C4g(Z)xfw*i5XvH9ozg23hnB=2Rz!g$#3f|mMTVIF?(^^shVB#wB!4_GZ5C; zzg%|t4Grr-^dKJH{83uHb1Otx9WdBv?(eluXlWu-!Nn5bP~mS zWEgNt=EjGLdE7+S>TP(uDIkzM_YK5YL=kUSvk3yd_d1K{jcNQt3 zLbGG*@+BaEp_p@wm>PRQ5(9=yPk1MgzR2L#lW<^{qCNn^g zNIF-4aT{PJvVOCz17tOzUg(3`S1(fWLl_kar-$ax>a?cv!NdwMQLO&Mpi2pHriDO) zC)nIT!AG^p1(oZ6Jj)@b1+1pCs870~+6!hMn&?=DJmOxVDYjZl)1~2hR zRg;f^b0mWsJWyCe(pj33xc@XbV%T5YMr7syT&n?`zrk>loLSN6O&HY|y}X+jUJDoA zuveZ!fG74IfFRD*lSPAk-GkVPm6kcfKJ^cFtXkun^j5YEloQ$Bz{h+ZQ%Wj~amZdB zF8#^x1@LMe=K<@6RFjnH>OWis_9gQ=I6}iQ-iuI%qMOs<>(zSg003Zwv{A=bd9>fX zhHE2XQ?Tax5`6h&?qsHh4?5}>ET{veni>T8~2Uc{-rXHY)&A=xyxY@-iIOh#BnRZ_2&_f%LOK2AC} zCD|EKMj@(Lc~ZN;aV~WpmZPK<#XhRpriQRfI4rEHp==2zm0_q4h9F^)>l$|IAI*IE z8YJs2kdf;tph$5bJ981#-3xTi+jYR9tPdMl0==mQP9`x&P||Rlc`Hh6Fzrqwfum#Q zz6H%YNooNwQ|%u?^)Y}73u)j(@%IVO0$h8$SqfWEfM>e}{sx4;T^sZnT0pP{_C;!~ z-X0Lz<52`e8edtBDjbC;3Soj9 z3x(s`&5=XWRk)!}mS^&8*g&DvQMh5uqQM?=m;d?I)PjuTU-|-`*n_NUM%%RGQOE29 zF?GnvDc7tE)WCMfUd2;-dOWY6Jbfy(XAc+1E0Rff*%!z`KH@^!)5!S4LwxQu$M?_O zxBr5&5lJg>Y@=sK4QQK^0wwHMM1|9+tEacCT|DJE0wthgvDsf*zp&Taa*)=O^k@OL zFF~2<(FJ4|bSzVhfzPd%vJ^O1uohlKNr3NwO4?_k-ty~k|DnE&9rYD z78GLOFlmGb`+t7zr9&B%Fav*}-B1pD9NH+$ept@>^W%fmZz$(hojX#jkSU}2MK{WNi12qVSrXl){6fCwQ3vOaBGz8mKSd61B%JWP-{UcoVy z2T3g%Q6xzH76d+Q*=Izk-|D}EPJ7x{;dkXWtjx36!EO0=(bAzBVZx*ee);=*N($0z zgh;>bJ((p-MlWKNlY+ayXkrfczmMX7oLqi>!FPq#|4zX`t_tRg+q=L!x$JA$(J2BM zL4sP#hH5y2(m9I&Lg-^bdgY`>w8Qk{gsMf+k#tzuxuJiie6gPqs`roELh3DV)|_2! z&UoAe)X+ZYq^I6&3W+CuOvmD4V}n4@Z4wn-1y$W{+ATlw6zBg*!eKCnozq@$G^pGW zUwXoIISu@qi7Oen%W$;s%q0`h))neLNLDu2X%Fy zqX0_RXrD$7eK?2GB4~?*1fuzGPkjHBjt-7YK~!Bxy%C)XIkSW4PJ_^6+XIcm7#Rb1 zNp3sM^mL@S)leB}K`ep177qz(29nZY{n^Pxjh@0HB(wne5v0=Cjll0nbC@A*vCluM z4KW~?AfhlqI*Rh=ArFt=TaN5s7i*`H9!v3`s|&C?|AU1L>B7Y9xzmBtyMQ`?kM~Uc zY{YDxM~}XEZ`r#XGtns)AOztrMErETt-n#SCR&0%@UXXE+e;G+_rJa>E&k^Y{p)Y9 z{)M#v^8%>;&*H!<(f=Em{pXMVJM{hMdsY1Z=0z!@^!HIFCxPcc&XngO zu_$c1lVhO0a2b^So2&?0Gf9|6Gm)DoNJ=77&_Dwb%`Y!YB>ciG9NgZM2H3d|9sh0m}XPJ z33P04u-`EQ{Dqv(6edS?m_+vN3qqcecTe%Z-}Ss0*;GvjF+ayTUF;j~%q5%u`t*K& zLmJh1$cb{Q%pxaCiXZ2wAQst*dj0oLeV`(1#zqB=yHA$OuupU~NRs)VU$NFCb!zg- zO0CN=0BQ4oU&Hk8YnZn+Z~o8U!{1|>{`H-2?a6SN_`e^6lI|Xop6z2JGh;RXdq)ge zoZZH?PMhad#{b?bDNnWo&!sRIBPGmx+5UgtH;?A;%PNsuIx-`9;>?-Vp52D)|Lf{L zy(KAZqFjKH(SLtqo%Ydxyf0f@^Eb?X>IvBLzhX<`4ob59I#Mb!q?_$o{`Wo(=J@;F zZ7$C4-_7F%{_9=W#ftyECDnNC_RU+iJo~@5WZU0sHya!I@8t|ZD8t{^-Hq3^G!OlM zzwQ8e-A#M;6#YM5_oTYI|K!?xt0{V?-6$x+geynq_!hj?v~Nk))vsZEnz74Kf6l=< zMu5Kf$CiLZyPLHGUIO$iG)mD5O)@-5A5x`Hve2|$kOTOD)a0}z`)=MfAe4dpx_^b7 z>!E0Pf|`n5RHE3n=z7$pAz@1tv+3lv;qgvhou`@bdRM-JvR!2Habb1uM6sZW+6wc> z_Q_%a9qv!W0$gIKk{vGW(R`Bk%t`K0m@pFmkXmY#?H`FcmXsP#ZvVDUn>BABEu(RC zuF68D(n1D;9J_tp_O5SaX(vsbmus`TE3I`4>ISBVf`cAfDzP}t(mY}u`T2Z}-i=k? z6`VV?Ms*4{JO27UpHMtWHS0XJomFie(nRUVqXo?P6L(|Wg(>>E@>zwfv^DQ@ zY>f40pSO7}yTe0m%itH-m z^AAhbJgZ~S5xK2zXaGIK?g9TqKj=FSMyj0WE9eZm zlAI~&No93DBXMy>_xB2VX3e4!py=-90}<-|fkskDL9XV-6bCq~)p zYdA;v`3ju`9jSkGHqvbFU18b8G*DHvf#u<1)7Mv0F45~^ELR4#2K^Ehy{JsqwP~^2 zyj*UiS!3%GuKXtH%lot=Z?5r;Y+VueKCmh-&TG@n5A=dDmsJ{;8Kwngo%MKT;tou1 zQL1LEmerItJ{n{e92&@?yzDJKIXvU!_-J;8KPHa0avNLjSKKNWL_TZd4 zv-%?X`vix0*Kz;c=XRCnHDhI5wERx*M!x47pN_@E|BjzX(yFt*A{DfHscS8-&@Dc` z-A6GkvS6#*oq4?+9u|-5bWDw+O}mp_GU!BQUrn5(0dhC{d?D{KiDfMfe_cXq98p!q8Aw9)y!}}!Z_#r>3{Vn%YkCrsN z?@6fhwRCvFU4&NC{oa`;gSKveC9bT=;WVXeQFk!%%X^z@iR0C$T~h9CYBIfbU_w(0 znk$ajsG;3a_1`U%|3TsH?R-EoX<%`j>BHKAPvVx%0dvUyQ2FTtmqN-r7z9G} zw2a3Wct2QJU^dK%yV6AAt-# zXVjs>*nEr_0ix>cyc1Xu)r)ONSzxiV20c*F^?5Z8tD^b^b)q)TZz#F}<{&wNg*gF( zTelu(R6Qw?J32ZFED#8?5PWfbcJ>LLIE>eV1ec*UFsaI8o|K@T}ywj^{~kUbEu zZloB8P=LYR3Fh5H1=0z1kyE<5Hb38BZQ%2wi7q80!>8sf`BW(8lGY|ve{d)RA>Y5x zios-rKzRdo0BAjd03qBNfEmIP#KiDQ^`6>qiDFX9^XJ~UF_Lw-_^kE|;H^>BszGVW zw4n3ik0EW;Cs&bzy0<7w5}?L|$il;n1Teg$nsq@gT2~J5I?kK=?3t2b%%oX}WF0Q6 z?#Nl_di;WeUn33HK6#S5q&pbv16c;Y z>jT%cG~HAeLjz@GV;8@;4_X@;Jxxw7cynp^hYVVNfiXcrkxPSA4RDddqf!}_U}lPV z)aC%*RpB;8D!Ew1@wiiXK)zU}*gxPCrr$|qLcmDshu{mz9B7Dk0GPAR@KxD(w(Qx?i>dKkZ?$S{v77zncW;T z45hx)Zt}PQ6>aUi`6l>Au5AJcc<+Gb-VB67XtfxTWHo1$jLgA#OuIxRWnmNIrE5Kz z-UVLAte_Lk9$r|QzVfyBcgWK3$N6tB$PMJzt}rB5yM7d0%G5-dTNt=lJ?>ID;H)x# zW!Xzv#zM`fb#!`F>s5ie@}2-m+i>ed0cDv70uO`_i>wy8M{`g8mPMGUTwwV}%av{F zw;rRZz%R_9R9HP!L!_riWL@G7SXzt!6t1MvzAwNaLZ8UxZR#TyCFsw7IIMZae0t@y zV1Vx7M6N_DA2EFafBdy(p}=B#W!xY__@MxOn8VM+KToK_1yb0qmRD>!b62p=SW)-4 z*U9V^HKt65mp>Om65nW9^f;Ku>N%b(=cbWV)@sdM)Rkr!aWo&#V8770P1tR{vvRka z+FhQJ6U&um+5L0NZ)7amnM20#$-FxUyz9nq)ehXM8~3c!S(}{7C#|>N&|b7ldd0C| zgM9(@u}EtBNNT6Vxs%3?l01`n zyX1Z^p{u=fzh=@}2X5Dn&c&KvQuNFbQqgX@_9XM$9KZdI{kimN>k`DM;ui~4rjLs* z-lU^3DW>)N^V`B(_~%TBdUnOxnQwdUS==7_cs$X{TkLSC@P_wcTq5^q!z|_p)q8eR zu2)r>d7^go<>Y3*%(2b`A+59pt<70w#wJ|fri**$3;U)Ed*|Y)joXsWl>@WO zeu*@nR(M~1U9tZzF)4h5OH`SqcV&8BJAWiJgr6ViUi|^)qmg85fPlx_0a8U3cnP(_p-lWbP zr>5;G!0>0BwW-k9@2n};)5RR0%sV>0od-?+%-eKI*jmrU?laD0Y9C!ne^b8MKaoaV zrds%c;F0nH(VsVH4tGrdFgmF^F0WT-Fz5E*J$qC=R`67~y)>}U3{6r3)t=_2` zrcr*5zI@K#yWC?#^W~%aH!m-BaA$Y+jM| zzOj+HGB)u>lo&nB@2$}(jf?#!e`t#b2nn3()iX6s=3aX?N@S7u<}YP`ece?wme0K2 zQP$a=4xTLj7JjYOBy-FwZSfsrX6tC(q}7{2&)&F0%i59S`(Bp*vGq%PLs9zYa<-t9 zH@%#Y=B-Wff_CKwbTu#IDAm{nmhK5jcuGoi$aXknQnjaE7oDvdo!fsrZ2!plxtfEE znZtidH%a{Y$iTYC6fVD=-jjdc-}u;9^8M#^;T7iw*GK*xJGDHel6B0NSq&}m+0H~(i>!o9{<4sH zu-v+Hhw93*2taGP`Zuhqi8@tb957+x>)BX6Zb@{os9vD^`Qv zE_R{RvuO@Xc}o;ZpCc&k%F3;quO68zDskD!ESB2)a+f!i+qs&RGG(9Em+2$RDO>qv zX}&3S%c)r}u1U1wNnTEAJxSpga`e^0N@mU15@Cg0zbe&Rie5lG z3Ja?B><__HyAOr-*zWWjpfoO;zwopu6Yfno}rKaGOcVnT@GB5}POHNG@ zb1b_d)C?QB_aR7e9i?Yh6ic6RHoainvYWNYGqKMZLE#sJ6*N_YFU+ne}aV zgHTF&_Uuz|3HR4k6d)0iIRaeY(zOP&>5t%OSJ*g=BmR>&8}JfQjb60z{0m4WB=Rn6 zu+Si}rci|9;ay$bU5uy2{ecl+FN)|LKbxWeAc*Ovh{!=k{WN?`B_*%?FRuZ{sxHWF z0(pv33N;0)rf0$3JMN8z%%=HiJ#IG25y1ZOw1Sw>wH~2a4d9UIlZfsIuo$&>{m^(c z8YnA!v!B+(Z2?$$_>db3CxJKwtO9jWsW&+pAni}rMcR*xva)Umz@ab^xQ*C9v!<8P zUTZdln}q|P^B==6h+YTC4@>~Tx^FGK>n$7SpP-Kje|k$bDawO>eg0e=8YmPHD6FjV zKK40U)ozE#0aD=4RATQfcfeniz&F6@dv9;S)Q99Ys6fCgtc9w+iJflanpFf($UJaF zYj`gy(x64+Cenm-4|+Y^cJ@0Qr(Jv`b~k)grKKw(R3P}Yn>5DzAYH@b4?&gyfC)J; zsZ5hb2P`Z=Ei%Xv<@~jPLjYg*TsG>~G3GIy%G5?)0#I88l{bW78MHfVU%jI6WS75! z_HJY))<0{;UC47Fm@c{=ujeg5uOI3F#0c;O9U5uUkz%PIolDHmX9qXpz8C33n6McT z_HNX<$V5wu@`$$nfq_1!z0i6EfStztT?v~r&m%SgG9h`;e+09t=K0v_zJ~fFX%jXs zu4h3f>ykS<^vMcc5vbu~%l?E#JunSMlnVZ$AR>qpIEu6_R@=B@V}%nEZmYDL za3$$#4NF`}Shi0Qwx@r5Lc$?eHzoI-t~TT86N7izXioi>&{qo=lGE5)$Dpci(l=(1 z$5g}rE`hE_?9W3TrTaXelXQh>TSTqXl~WXKI-1qPJr8cY&ysE-R-C_u+xnJJ*J}gr z2U#zM?|6?MF$gGL`!MF9SAHDZcw1dL_u=%!?1ZZA0@CrH4hlD!()JwCy(vg_Lv^Ki zIXpe!I=>h&(Lqzwh+h%{Up4mGGq9S(JfI)|m|Plx`Tn5E0jm3v%dmR<2fy!f`5 z7R}Ben;_eY15A5Ona!K5L}h6n?7UT0k@A8mDT0YILA+SKIi720l%^;By6pKP!7NQ? zM=e&$05Raj!JwB_`s--u^(izQ|1chld%>zzr(mMrM8P>u<2^yK7-D^rMv1PyH4s92e-E~ z?al=6`Q#T)_EAs!T>Y4t=p7qoin)JF3{gjWboTEnPi%86vo3Ub+i|HWDN&KW@ad5B zfj?A2ugXt0CLVOMxq0q}7X9x^4Q0g#9ECy3)e&_J7TP}aJEL@_!_~byx5^q0(@5EQ zBMzB)i9ULHfuSpoa=2l6jragtcdl3T1tvvCVVW`R>L-cMtD`YTZkwF>Xq2Yiz5cC{xhIbnZ0~SBxa&sm?QFq4 z#V3SQ-Z0Zoor*tKUGad5gSBwuuc|aN#oivlf;v}wIhrHCe1<=mIBVPNVF~TN%`$jq zAk|hZne9!-^ny`H^A>KZ#HM@k30+gilNM*5Nym-qW_-_KITul!L$jEn-Vt;-<(#5H z@Wu0rH$0qMDdvvt`O3FjT!)m(R!}wKoKelz-c$=a%(rMU(nHe=RIgCCL1>Os5NW!_nHKRv zN&#e3qYP-p!^v#L_SwevEEs+LRBHSeIV3v5x$w$=jkeQunfMRzLI{8y{-5oUxr&^5 z`?fp(1QkF$ic?ai_PhN^9>ypZ?C_52UIcKJ@k{T&T@r-4634-)k2qp46llfl>ky3u z>AhQ&A96?Of>Z#llpel0uQ{tCUb;eW+OD88L5u;H`w4ggp>|Y!u<`R}!mp@llm9}o z3eEu8H-u?)s8of(3%9Ct%2fa}letw8io|F#!LK8`i1dK<<| zUJkyg={b;rBDs}1{mw$hT55zgOn5Z{-pvm2E*QgUpE}ia;iwiQ%bc=SEGTBsg4IBx zOGL}4x$>Z}`H)HYb5z`zD1{t+Y+;gFO=K646=bz<&WTw?;UnoYLL&8c; zE*Oh(0JO7aA>nx!qY)KNhA-w$WY%@4V}l7 zi`eTB<6~{)#Vh3*9IJ?&1dl}Is?hHUpfr!qK@{7F5_tu~vokZKxf z8dKmHWc8$dP@5IiP-x@mjWhLZt&c~X!(ym7`+_u}f$?Ywc0k_VGV|zREuo^=y_@W% z;KP6@dK1rpbfqKSpzV>!VhOr|C>QhFWZjKvKo-2hVz~R@fxE_RtR&O|`dN%6#qyUi zzAPROE+8=;L=qvpgw@F;S-drJwrrQO_>6hx48`AK9qC@9y#0RM3#h>dJ{X zEZQ7Mo7nVI@btzS@f>xtvo9Wpecc(G`Mi%$oJv;QR>9)<1(SfW_xnBAgwJ1otbAya z^4;xcNh}O0%oV*yWTVDI1jh^HPnXqFAF%eYS&8~0_hg&n_(PpThudFo=>pM~vaP75 zrtraS+Xbc6OQnH44tp6KvN99$Prb|8=W3bEa;{G~)x!KjRnA&l6`|}PRxSCwEidzL zULOc83zd?XSJK~Nb>iLXw-d45i~0O>8)%NYvG_P0(f;w?Ie#va`iL~s$35~A45@`X zHvZ(B>oaZTqcT`i#1}F&^{Z8(n8Hh}Nss2&Pa6}N?2sGR`n7KCF=eT$bh+zw{Z`21 zVQa_tQ*L_pT{DZD6;FOn=bP-pQHFZwfru@W!59o^2XsKy5hec>d@@xfA&W2m$U9MufP`W zE@zt7-ETw~8vG8AzmL1i^<_5U@vl8?mJH$}56bej@5=e-##@qy}bH!P18A%mEy9&T1lB;!!5krB2~8b+&8IjTn+I0e0BFudA%Ea{yz$CU%BlX zeAwg)^ViHcp|X1CP{UOP^*?W1A75I}H79k*%l_sp`iB*cSQ&Hv_M%O{$jV=BSqMXB^MlP#-@O`P_+l;z9oGY{lNnpvSd8o2qk;TJV@G z4Ctoq{dIiFTzh)=t*o_fA8(F&Q#OQt9DX+U>+*8n&hd+Tq-(zw@TS!MpTQ#<_Y=iqkD1%r1||qs(41fP-1;O$ zh>hilGY1W2^|t$TnAexoY$M2|5`*a_C=@j4Cw1G;GFP~i)PF>m3?@1c*y-Eq&Q6W? zwwAPCNbI&x(ogS4Ly!!aIcr}Ki1&*7^CNlj`>vP%U~Ln7Ce1A@XfV%U@pEMPt>$JO zSjEM+j$SOTIq{5DUFR@M2&_L-yX^;XGFi!TN5#gfrR!Gz`E%e(8DGb^+`&VK_T*Ve zvfn(x&~49AW*pL7bod;qg%<-}9KZ3akxW1k3u-d|JS@u{LvLPg*aKtU-Sb`=cj3Wgc%2u|o5dH3PB8eZQeo6z#n_l+K#h=#tLyf?djsn0 zHJfa9-ZJwu&a8F(qWulMpB1EAZFtyvY;tlSXxEpDi3w@$px1W?Dz`%JviMb0!5=1e zDz>nCv+so(TrB)ZjQ4c+{Z`|vL48@@zMaE;GQDzzTi-TD;RYW*Ks7YNd!%qHs(=03 zd(*GTFnH;HZ#wR{zyIp{b?3g$x})32@t0P`37^!8mKJts=QjL*WPN!!l=0X8%-9BlQOLeVs5F+O5`(gZYze9CJ6W?Y zV~wmKdk9$~6jI8XEo&&*w@@To_U%3MeShCS-s^W=bGf3KdFJ^%&wS2(?)yIHXmP{L z8VTVfssg*Q@$nlK`kw*p!I8f%ZR#hvT3CeMzRVU)E_+KugOhUR(G`ySci3-pUhF*? zr__dUvi65Qbj%zab6zo9P?0~+@LA#=3AyI0Z?@I3*xZY*D#`wv9Pc8KX?>^dC3yG(5TS70My!So2)uEJx7?cSFLe})Iu{gPG7 zCY2@~btD;u3pgTTP#ut(g-=J zFOn~qUdtewEe6BMum4uk_DfyaHeoPa3pyaJ4w1Z9Xm@A3nSc4xr&Hdt-VvgG(2avb z^QZ4qpRCsda<>yjdIBE?5u|2Ms-(t_s5#^Bp%b3pM)y9tR!gAiIs0vUq=n?^$Lx>X ztBr5*$9vMocpxso z@E`dkh(PFr8rQo4NIFg((pdU96f>FRQQ}2+REO?QIYoZ`?r2WQmXc(Dy|r8`9lNc@ z?2EG2m_4WLPjAr9mj8O%9a)42;$KGeT-?H?z2jTl?>MI0B8{b{X4$<-@8A0}FVQiE z0rdz&{mwDhJu6S*(^q#RbB8mOAJ$`k%bsSV+78I`{#iT5N;y#z1Wxxli>yWMa2>y3 z?#DeA6B(^b3g_Q*4$>X5-(YmJ(|Pz!>FCa`?8|I-tkI(8h3LYK(y2`g(uOT11k!v2 z(EFCcthSPUutUU&^tlfre*@sRZ1TjJajn}>37yP_RTg_s&^GRo} zxERUM?$_|?efXX&o=WdKd%VXLyu$f^BkBJOt1n1RnEg-U9^iy7e#?#2j+_iIT75<( zcbB1S&@foHQSi`AnloIR>eGF?L;tMFGgwL|xo?WO1jEwSORQDjAzp4cqS6;&LPxo` ziZrKH4Jq#TzF_|I0Dsj1WrBpZL>dIVB3*eb=}xZf9^c1*{WoFrfR{CU)NOG5^S%a+ z->0b`?4XWzvyNF{H;>bXkjlpy3y}l%IoSA5C#axJv~6OdqKw_#5`$+;^{CCv%!oUh zWO~M4e1FQlkDl>7X^!tYhlKNg`h|suUv@A2&I$%yM1u_~`PsAb+S<-#qas~>mPq{b zq$I`=6SQ`8?xSo8n`p&glDEvlcefr+sX zSxYb@UdX)kk8Yd&^{Cd@p+X;H!pxhb>dgApurzFX+Cpona&1{VN|1`(Uy9DpKV zB&hF%xfshQ`ZJ`XhGMDL-y5~AuHrxoXZic$D6bASY56L{7O1a`?=aUCNgh`0&A1#4 ze6A)-`(|sD_G5;T2Jh*MMP3iJ0>rg9*RXlgXRp& ze_H(U%G_DKvw$Z8u_&mC|H7v;;)l&2TAGGlKZvd!7_{6^VU#<&?$5v_FgiB&848%f zVYxG8{8%5>A4&q=AyMlvf4cDAzdqJp@(DBmVTAEIaygoK$@CV$Fwec_Sw2EJMM_qd zQo(>+?RYEKK_i#3l@&#Y`H56Da)45C+NKb!;l3iiA*@=T<2zVcX8oJ_+RQ90axz(M z5L}(%@=2ttlNZ@c=&72(%jK}dH)%1Y2e@NhWeB&lLXj@985s8Nq6G| z3S70REDT4nZfs#N-;cDc89mSM-Y;h{VwUn}*5GKFVp5^(p@|q-fy4>nf*w;6i})!z zBn!ifeg;EHBqup9>bJ4jzCB*dWRh$@-tNYOBEl4cB8-qlBZ#2x zs4=cPjKaoY$TT(8SX<5-Cc8MPxgt7;%Cn8L&Q5GI#7s2$Y{_0=9>$V<6{UULL@=X& z-29}$`JS^>+#|vAM?d$|9$*<7iW&82&S3U6zXTTNEE;H*gvS}bLH`-J#C_|BlB`6T zN@$ERgAMW|szWMn38|uy*&G|BcsK2~2=A9`Ji#m&HUnim^}<{AKv!%OJqc3f6te|7 z%D$=T5-X|FPP(5|3t9E9@s>X7F{xi>am@UZ=9QnzCFbUgQB9f#p0_SvJdZ-_UvB@F zRN5Ikb%J3w_ADLVSye|;kS?O3m~c6+bxD?<8Q;QrGYB=Wl^w=|ej|_Skap)I=`_G; zZ4TFElnyH~zu_7f2{bpU=hE^(H7jveilJ=~f$I^>^nO3KW)6qXm99)3wqG!)k(Y`S zM$N{f45mihGU=ssDmJVec*?^nd-#8lHzEW~zEE+9$jS~esXl{~ALxM>z#L)eDo z8}2YMOjKRP@>8YIPswf3BfWo5&^0qhE-fWCcL^|hN4gj)oPG0v>xfD^@O&WR+kjkL zd|gGH-MPm+k6W;$&eQ=?`2Ll<4;W)_hvRYS#_5k6a=+;Gys&c43vafDOk)Kip*bBG<>RcaV3!#lJtiw(yueWqw}OLqI0@lSmLn zZrrn=ptab*Fs8qMDlMl2Fb3MS10QqFSt~Yh%4NE}mZ|(J_nY%r-I%2>{Cf_vvyzaS zMEgEQW^D00jfl<56&?0};t2HawtPppVZO?G)>l#74;KGd{b^ygO_?T#aU_{P5u{9H zt*2Ld>n13AtOK-Vf-iBcvJOP~)kl)!J@|M~SPqkLdb>HB@0nSIaXjnJWwhscc{@52 z6MaJ9(se)lqor5rHZ&OXq|HP%j-5ZFg|>d&o}7aH!_u2a1`!<-g~>GQ3MRM0@n6{3Yb;BHA)M&NYmN-=|)2Lw$WE z>MyU;W*x0&NqT%(&(UoD|7V@E>yE0}*tYtP3nfpna<_HS^PUB~A^0nqmYYvtT9sga zT!%R}jK}3YJ7jfFJ5Gm%h3V(0+C{^Lq$?ciDcyry)hHkl;)etdk}eig?g_bSx|rt`qwYPU=7kIDnehE9}(N3|J(P&K$0O8 z3fY>TM5nnJjB1yIy&ayncPJxy=@N_)!Cku+4TICT@01OhF($)&l^43g&TQIT5DpLm zyrAol1dK~Cgi*axYZ?yK8BT`og*2A>&re0Zg)tLw>OdnQO{eSCai zfEEn;n+n{Ync;;Dmc#}!Wx?dm65dBMpD7`AB*7JZf!VL+@7{&`%JjzJVSJp#%ep|F&YUlTFI!-phJ+?ia1eA&NYq8DuK6hbyoaaeG%9Gv=-QqDYLqQSZ3M_lV zEtv@Td<;)+C<|S#vV#aDoFp%t)C6TYamuH0Vq!r!j2GsXnp*a-{R}id(!Y1F1v2&~ z+-KqlwwEPCOUeZUQeNw);U4PAl8uG*4Muu~oq0CPxVR{cAm-^AFEj;l2yeJT~4 zrQz_c00#G~wM1O+0?SxdN(x|!8!(^_nq^-8B$4#LL3ncI`09sGoCQugOv*f(ErD@* z*Mf76B!6``+MnDKeW+6|Vw@c%_a=pAhF(n(hos=66x;|}_0Nu+xt|sk!TBwhEL-J9 zD}sGq9o25{Iev%UW%|)6#9O)Z4rK|!uVlo{d;RsQ$^QT!Lrja{q^21n~abcKFvzO2evlyC1(9GfudUlR1lHSHv zrfk)A>d3`?7E%9b`AnhgwZ2~VEaMZ$`dXTwDSlRxed(&mT&Jz1(L2kC>=115OJu~g z&jmYv?^B_VJoeH&6Ro4sDaawH(DxEcj?0xu@TIMDwAHn}gbXtDEb+vp+$6ES-O<#C zdh#-sQqmQXy44S=;(iVpYv~0Y;S=TyGGG6+&=Ocj#IJ?1N#8g{gDe${Q!lP;Ya0bjf!~Vv&An-3^TM(2%R2Y(!TFQBUmF;orPQ-Z~2isD*Y>P zWWh<+dw!09!8mXvy@_tCtgJr4uDT(_KOB`xf-nhn9ou0Jac0K9nT^$zREh32Ju5;} zO!1mr%yNk_m?1BO`A7Y@3?Yh#=?UNC7WyarSn8R-`X#mu8^-v8$lrLev}E?NnJDVV zg6mj&`E}br37KD#Or^A0jDtp--HTVs*gbzX<3`e(r;%59T{0SHm<8!m_dj+<{J2#q z@^xQA`t{UeYn$<1H^1)vks<#p>OnP$R9=50^9BZvDwOXf4Py4CA6SQAxl_7s)>F)J z3>C(+@W0_qTx`T!{PkNd;GNrj>|3i&=#uH%Ww)9%r)9$MRb5kUwmUqL|M1)MLsxH$ zxmcE=qpvcn_6(TkL`Fm|SlgqYafXyrx#q z<*si#>#&vGLh9V|7GS(LdFh7kMT6b%J#?hiUWX{&Ds-JBwXhSFM{S(|SIN{~RvG>= zGHa@grEt=B>C*lVp6#O~!-S*ZXsV=G;^79S$(;91_!=c??R#(43*!>owM%MmV`Bcj zO&wqsNIY5+RBL@6IAo2JT}2GXypyS3LLaNXI4g3=i_R)+ZSr{ZIQsuE!Tm1AV3`_>ZRb$9}0W%R7^oIX@i`bYQ4(l3o{}~Xk`_Cdt!Z8T0w8k zlO6JnACr?-7H1mrYC+EVF+NUa95lG=`@E5-f%J;-sa! z;)p3+dplY+zdy%6uP)CFl4+Q)j)DLHRGlY`9D%dnUeJPF(FC^3U0=@kM$iMs*w2sS z?%liS=GFE}yOn&+QO)uI$WVbUf81h9>>%#sj_zLYnHr9hp+#!dq4!SZ&S?2+i%NUiV}Gnu&0}O7Q!vn)?;c99F0+3@JaXyCMYhg9B-x z?41_}g+9+Z6MH&9D;;vUi@wZ>LD&X99!Bp#{q=!Z6-xS<~|%IPTT3lyCq0^7a;0S*A*lKOXg}s=Ix!cuo<=SWcX^aNQk%Du(EivoG#j6HHSTUp%@i%!KFeZupeRy6 z)xZKLOr=VVKA)W*#6Z=@gP?qjl@CGeA@U;D$OL@L5*4`_^9D7kG?CZ@5o49OphQ+V ztoRbTG`mVCK@_RjEfM;pHf<`oUvlS`Q{dL?lM{C(vwO8R(7IDcOilhqHOAa;Wl36; zUjOnnopR5+a1D)6^8J3NT}u*C?DjbB_5*o}^>W^nYC7r)r#>U+dfUG~Y&iCknko{c zRXBZvFp8{!BRzPXD98eQj9E?3Qeose*4Gcv4$QMK#QeJ~3f^^_LcPZWT z8@J8IwlATV@5SCZ^D0lEG9)bZU14gKdQpCrVm9);DHf%PiW^iMVXk{a*y%%Q@f1+M z)eJqs&4|mn_u+1|Q#MD4pR%~(a+M3U9g?f*tG(+8Eh7zHex#VvbLf23dBHhkVZR(V zeUey^@O5LtRqAtOdSv0Z_ofb_5c{NI#XkfpNfrg?&J?{DqDb8}rn<+rd2N~!Q-T>u z-KsVi{rV*>ikHMyhOAnhqWh}t`rtaPk;}eUHQDs8%Jq5j$=2a;5=|=K(#SEfAkFpEb1?E@^Y@ zaBbDQoPBPm(QGm`V?pP~icg)^u$Pb<)}Z}MsGnfS*14dicFt!D7#h{kl5@&0=?y6s zqtwqj_z_UeW=z~V#SfF($#w2txgkcgOnAeZ6S?!P)l-?ZqE+u8}*gj7g#yq!?IW_k1r|iE5@$FC-k*5o1|MF3^ zt))fmouBE&4!y=g)Y0p!|wjctAzt+SBfbEh9Aj% zd3tQ;x7o<_t}gH5Q?BhkL%z5ZqCRxuXcPoycxXQ33kvRVtolB7XDvl5u~hd*bj$5+vd-%t)6DM@zF?$yZNJ zH1GQEAF5a1)oEX-G2Lq@5trD{@bJpp)|4?^_99BgyHZU1`91Y#dgcnRj(C3FZ<|}2 z`&35HEWn4JD>N1o^0jv8m!I44f^^c%+dFMKv9$F3{XDIlY+Fd&YR47d4*#t5gJ@`H zM-5ydM8?t4QH&Qoj-2^hEM#V5wH|bk)Fgcr5D+M@s371lvAR?&z>z|x08OZ+^i{JH zu_(yuvyH{_m-xOVfT$Q18_Sp8{lZAZ%-R~g{3u<=4@Qe4vUWb7$xeh^F$jy=*w`S3 znhJe$w6%!|5(Zh8ytwiE!{X)@2-Og1MDBll3>{{mv)BxfjliW7C$ZM8hF+NRncU}u zsFtWr957g2T`jfw4dTfv*l(tx8N>~lEUOzSaOuH;0x1|Y+ocDJoERj5xD-f$>7Ity zE1pMm+?> z$0E*$2CWn;pRFlq?Cze_D2f<+_VD8xIRG_{=h8%;WOLIUZodCW#7Eopv5>{PypJMY zM0hDs-;kvOA-yv)R2K#fPGCwd6+~EI2=wpYSA@j@ZJXFln_Rvb_ZhmGR#a7mLI+52 zr(x*mW?@1Mx)}>ZFhCi3G*JAYG{+~k-}nB_A2vsvh#m+MZ5vS0ql;h-dVT*>B$y3~ z#38K*e43ruM9kZhlh-ZVB)%mf(9VmxIAYP4W zeQ3Dlx2Tg*_jYvI6zplJ1epFzyqo~fm^nFHVIU6S)C1pm!gIR2Je~}Q*AMFbF#u-1 zG&P|n{P!K;%E2S-4UzXDMZ&%71cM?Ern!!IU{oY=Rlp7|XBQ31F%h=iym^zEi%SVC z3(!W6K8y!2)6q`sF*E#~*o20~h!s#Vyfd&Ez@)$gI*=u_1R03z6hO4q86Y^oyFk(m z{bU&6lk^y$CG^9f`Rmf0!0wR0vW0nWNdtZUo39?UOdcOjn!(cLI9>tGg|OayfMWMr7wV5lRn7EEGZt{M!b*ZSNWUJ8ioB1bXb~|p(K#x!mJvg6%EmZ~8%_UCz@IP`zJL2Y{` z&@s%+xZCI79enbmu7Kl0KfX`r$EtswH!1u3PxJ2w^a-|*_7_trkw2J&-S21XuSUDq zZ%sWi)s>6OEGCR-{~Q#GsW{a1%YN_gzfXOm)Xbhm(ufMdGknkZB%^I^A%*onlfhi6 zA7>@9`78Al4Psv;SFe1O5)Y|d7&N}Y6qs(2o%^v}d^^JG&d7eoJ2vFwgL^8q%k1_~ zegF?gyW$|OcQ5<8etXlmMm&@G$)|}yy6E%B9LCcqYm?RtWCuoyhlB=65-LnOmFTEv z(jCbAe1yH|kLE4gH>Xjpm{i=(NI=bYRMKVU-dzRS6C?f%_FN~lt*L3WPv2Egrdf1Y zk1_0%I`#dWgP*Tr%mS@i!DeGRC0OG%%V{nkI6)Lgw05)6&G%9y_}G?%ODX}+M6J%JiU3zbpBe77dur>R~7Yu6$&q?FmPWcyYc8; zWJVm__93cQ;mCKZU7lm*8kZc?zP|{H%x9xSE9Z1vSF!OTmWN>U{MzNaFE3MSCVtRP z{g?Em$r$SxEqA|FS3n}ty!c6}zpqLJ4me zab^-20$O5TXvOAg%pt>^#3iMLsY2Nta!w<=is-M27W)QHO9nSrYva{|w!SjSzcJHW zWe!6=$w$gKY}vTlPhW{(B>%Lu`fZ3AA#k-~^OD{9-YvDf$v5mD&EcNi?}N($1yi&p*o>LfD4`4PTj&%h}P->|Ys8ZtK=)*(5Be{>kYy7|!IssRzrlB!2HHCm) z-$W63nCs+q!*fhT;&gb}AV!^oy%PI`EI#TKB-Z){292=8Sz&&=`=D>PJN#G)&-k1C zW!5C$qrTU8^59PF+O*&!GV?N}A6%DHxdz*K^1ajzY$23|-b{Y}`Nt1tCMFGIe}CEv zefHEY?9&d0l?x&GvZ1#1b+NFpe%P?vfZMOzA77avZmMeuSszhCWTq7<1%ZAw)}>#U zHxV=pPZEeDo^Xn_e5Tc@VKZ@?d4vkH&F~GwqJkPDZ_v@6xZ$ z)XRUh_Sf$#4St;ziP<^WzvG`d+f>v_O)7_3tLeaOYKSTyZ>%`VE|?vxcm})gxIf#z zs<&ryHg=1?;c9fp?0UKZubti1Tf1gUxsDt4ujOSuMHjn`t7ZzPlG4v`o_Z%G5_{pV z%%HK^r;QQRs_`3cG|Vu?Nl1{Ex|6Gt0Q?2*Jao>$KxrBfdSPj;EaJgz2uVA5>0MY~ zgOe@H7NA)WcLNYD6g{C>n1RFu;Si_@FB6EcL>z$Tk+MDj$b-ZQ^&m*@mX?;nGk@t-F6fH)5z5~!b=fMXe;k%+Cbi6gLu z(!dV(;X|bUIr4l4h~4PYiv{1uCMGQJW`|$`pWZzKDtv~py{l`&bX%^fG^Y|g zax@!&1^F;8LX78a2e+AQ3&2&Oky`!cO%T_?6vYm7SBn9nA2bIdECEymyi#p#t^R`t zZLmb}ZP5}*CLWdglnC6!oF>dO(8KcjyHPMk&bqw{tk{P2J@ecX1x5lQMFqyoj%smP zSvu|fS9-57nCejncxz{2RUv+0U4YOb27is(WHkYz-Zl4y5n$*?Xmy4O70M^#%p52Y zPp*br}L+g7n^oq;=%$TLY~0sb0$xFT@4QdUc}8+v#o zBeQ1LzY0Sw7x4&y-4(v+f}%l@&v3MTd^AZ^pR$g3v%u*>1jk?&Btj@)k-$wzbO6FO zboRfd(u2M>eYdn= zB#A@6`V~~X%||eJ1oF5b=#{s?e@|RcxCaU<_yav)G}qIZ^g*gvVW91#7c_I+y6X%r z;qn69{V@L5Oirw!%K*L!@t27!0}>8kVn9prM~JQqrxH3&2mAcHsS@<9$lq-?;X86r z4|qJx(-u=vU17#3kjvcN8RgNi;9>s&7Q*gA%R>tG#+<6w-hd-lkZvFgaju2hH6ru) z;BfKI8gw|87Yc>sW*X+g?L4X9p+0>gqOH2wdDr?B)oS@n3WMVAO%+mnZa;jc;Vv#(aC%D1j+ ztu_l8sgR5djyV1y!Ku3b6|k20R`k8~wM3qs85_eK8=d#6;Z&ob21|6Hgoo?n*J&{i zk7xz0i$k@}3|Ja{{>c6Dd+YbALGtWDRzqd#Bq3$AV2&D>>a#}i*>K%V!M|N$)Al2e z7#_MbE)m9saB61yn&m%87bqS|aEXYt6xhiXy#7qM?w}ixR9Z>Ne%AWO`#Y?0YBpp! z@_1D=8Tv_vcBJBkn|Y&-i~-C$Z-#8`y9CKu+@-I!>2MofUv8yv!jI;KpeYe~{ud7m za!Mmp-EM`NCT>yXGJJEMlq&@Qrl6;gtOV4lZHz|=e_5nEv{m+ORvON zZ&Xys?_rkN%4PE;nwny+tuwVg7`D>OoPCAtK1PK!-cUmxO$1vq2#xjH|9;N(vU)&k zG{kB{lYak9pM)-H5X)_`g!TUH#y?h{-b=lB)UoLAr?Fz6INRkf(L;k!U--qNd+!%A zTW!=kj*6v#e=a-AG%$f%1=Y;Vt3w`^CyBE)%X>Lj2eAJLroM}19=a&0R&XxK5Dr)Il*q(dWit7`2mZH>;C{E~}KoHd6MqcNAW*I!>W zO1U1Cx{YfurB4l}{L+84cCnk# zzgacJX*sSKSHJ9FSUWKGr_{ijCbz12>@*^O*;}z$FgAXXqtyAw&L^3dx_QqpJd!nP zaLzG3j4?4T={-Xy{X^3{;XCI?1?lRY?JG@vg%RLnGkaJT5*$nd!z)jg)$IvGHVP8| z7uBu6`6w0$8PLC``GWr%`Q$?0{xw6kX_DtB9nR<+K>SZ$(fNAKOep_TFDaUbZ~v>P zI$O#`KEGD>iH|S2YOYR>FL=|dZT%(b=6aCJF!NRNy6}Pt^9wFv42^};;-Cs~+;B=- z8jvk-+CY|vnx8*3;8OsGe@m(2u5y9;_f+s1K!2p{`(>jmnJZ&Tu!-51lxr7FDar1| zA7&I?ZDEbQ!Zf~ek||Cge^IG1edQ%KYTwbJ^Wo$%t1>zJ?FFU%0T0_d4c+o9rRQbT zLJ`Wj)`IcMpXp=Il$bsz3`|Cse$ttSl8OD@FS$oDT$Wj4`tK&Aj)opNECw>Mr_sfB zD!s+@=%g_Uku|IOW&Tgzx74wWT+2--gg6|{&pQ&B*?&kFOW#PSRB2KD@N9+byv@dF4p zJa7Ki0JdZJ2RuUps+3)@`Hj@g*xznxBww^u^_0I@z9kwqA$E7piCnngiroX43)7T9 zf$)UxpYf{sPT)-;vS=U@8QOszL@(@wys?YR(^1}p4ktE&6GUum3eXK`7J$DQN4AcR zw8R;{U?thP*$FHas3zPYcwiYIPy&a=bm~+^eSNHaPQw>7QqJ=iF7TzQ@k033KQ{wz zcCfEZSLOg;10Mi13{XLc?RsIdHx2PH&(|GETUo6D!$pCa0wV<&ad4P;<)h7%wt@4UmYlz8 z0aF+c&~RWa0Y(E*%sCh}k^5)~H@2K@(`8J~pnflqS-Dmg%)0&oEs3s!^Fe4tbyhX;U~D+&b1YZ$Qrg}*#VXS*aJo=xHg^{XA)G1 ztQ--6f#3#^<_O3s!fioNR*x3Tj;JR0C${m%-zN{pC#PRMI288(m&+yEcUw3~%6$#o zC;rk zp}0h&U{|pfm@}gCrr&iATJUqi-9;Se1{hj)YVeah8ornSk~j=qIg(?Q;QolPK&cMD^fDpMv!{IQ+wwarD(S`aBiM%&H zzHjW0x3R1Tf{OaXp0j4(tsF(0S#w0Gz0*YTgfeyX<=b2~1X^lym5wuds(8MT?_#J^ zctL6zRY89I@SV`9PN$@8V^SV9RcRh%$oDT*^MS$ybt;Y2D2Z!94V96DD1w{t9eJt* zUJW~Iel=AAs*kq0zGtLyTGxMeV95l|ohDr-p=94%nEi0%)@TqTT-#SVx~aJ;;4MDc zNa^NEfib&YI}!YrG=E84n2@*lf?mvtA1^dR%1tRLe$>WoC{WUabeQ}ZVsp2jpsk9x zwF%n(+bqfH*dUS5XqvG;NJ3pnsmV5X(xY^Qe1P)JRQ3x2E?#bXjq_%dUkYDqom90G zFBgu$2@N!9roN)5QWXy43rSRL?0&g+u{a_a=`+ds>*CI3Du?%1HXf-`s2WE+D*dvM zWA`tXnnR0MV$=DN{Ic>R%NYKWd(@n{JsPFoIO!Gop4-Mu<=PBg;GB9&9`@xSDlu^kJ*Uo^AT@b%C~*o1aeWfIAtb5k)-<;`&x?I_RPod}B7c`h0{cRX zEI72nKFxZinC4I83H6uJlqn(PXR$W5Sq??$LF-;S6nlU4-5YXeQW#38$lVx5y7 z(}Bj+9)9cBb?w6S!Gd)ozL=EukGs)$23z5cCxU*5Q>QYTKo#k=^>C=Ds|~IA zu5d@GSWX9<(-!}eS!&M3BwPuMMoQfJb{2KbnePVS+`_@9%b}>`O4RDJ^WUw<)$L^Q zIM35Qs;c~or_5dt)zUtQSM!pTTmD&v98GqzVo=4agyP8^174SDo&CwsCCTyj8Oji) zZB3HN^El|1Zh)Nv=~Jz#j_uK)9xJ~hgXZB6!<6T!hHY!9a@@l+e}z<1#aVJn*r`$% zd^K9$P9Y~T*B-e@x6<&6+|`$+PyWHHM)!#Q^n1ZhacsK?&f2H*Cy*ZMy6s_ObTrl| z4?E3-raQu&<94>PZ>z)$cH%2kCu1X9oC^D5(`^ETkNi%oxBR&q^00SM zq~6dXds2<@jmI6xO2J?*NP@Ju`Qql^N71+-f}1fJwx1YO!S}b;%yoo?6i`p|MQ^c* zwko7{@Hm~&@%Wy!Mk;hq8YZl6ArIa^okA5ae0sp zy6vM6H{GN;Znx1r94A;GQna<_<`mAZzdHBPegbL*xvi=UqZ=;4?hh-gM9wUPzMNv~ z0+Ec4OXhm*_N5bukIRC)n%Y;{FhOVY z^)Hv|3O6cGZ}B1z6muK1c83BE?||?#MXVD&-m@?@4I1dwT1|cq8V|9;0~$puB?kSX zKAD-U3Q`d0Uwu&I_wL;(!d>gNbl?(z4AB*CDb|4~4T>J7Z@k8t1V|IZ^nbbF&6ERS zF!2NoDtQ`t0#|$%Km<5wF&kRxob2pSYB~+`k21Cr6UTh3F1#T@9U+_oboS{5Z!F&x zPQpHEA<8@C1rTL8knIrDu0Xp?vf>B->yB+%odHfrIO&VobUPSTK=5OrBGc&ha&ih( z%w5yp`E$pBoX`b>P)7mRVEk=Lhr=L75gD9U-{PP|f|T3%Cb}`M8F&j40s?aU7@*PnG-SeF8ifkD)`F336f)YbLGF;{uzYfm#2nm;790BEXrqF7fr!}~3miNKr$Q5}|m$ap|-2J#JJ zXIi&FqBfBs1Lw>;7NMi0P746O;7&d`S~-@1;V>3p9JVesAhQNs%EP41xTj7y7o&5} z-;FxomA{<@QE;iwWsYe4jrCbac6N5Q&$;aMc+>^!p9_P80JO|(K%dYYVqv@NK|PqV z!D$r}9Zdsdliob^!Xg%G!ZJYXgb+{=uOFC;Bscf_exE4Sc>zt^;7&<&VdXzh0f&iG zB6I11LE2AOj96MbkQVfF+*C%&zl)MmmmOv6pE0<&t&)TU^(jUmw>Xd|Pm8yZ_9VLf z-U`7zILgS81zyU1_4Nc(FvMR+Is zk(ipQp1g8kzpYC{(@Vyud36$=iRhU?CI89q_gPh_LPjJ5$wMk5nKKkSbmF=7ySCC# zW4ns0MX%4373U@P^&^-^UZzOIr4l+2L7hSERy-ku;=DJFDi$YcZIcx>txsxNaI622 zob_~I(8y*>&U-4L_KL;*Dw}?FqXi`unmLftm)!;-UVE+YB~7SapQ^lyP0o!7Zrq9x zKTFNDGdC$Z&JAhZvZ$TL=qUeMw&;~s%5ck{Yw6{hR1)OeoNRxb=4aAL0|Ngv*>4yl z90q16mlMxPIXrji)r`}$Or(;XV3Vh|eK5+^bm!Ij@-vh;4w1?rnSJZhuJVnq8ytEU zMX$tUE(`PXxLJ?fYYdd!8j(k$Q4)eQ0t7^)qrK3nz3-^JKY8czeL6tNVrQvwJytHVkkZHpHP=UREj4EcztZ-Lku&Zu~2s2I_Emn(7FhQI9h#xAM>7 zEj}1gid!+4cgaY|G5$=zNX(O%SB^K_J4zu0-?0y-v|Et3R#xO$_PyzUH||S(s+E2P zwp^y0oYy3HjI|GQDV0x{*>#{gQ=LlhmA_nIL`>t@bLy^-XRDUjEDi*^7ZcO4O~DU* zvu4y?f*Wa<4;RwOqp$z9vkS!NYq9kk*#~cGAa&kbY2?@+&AUBiT3>I(jbz#W>|K&@ z+|6K89AF~NJ$OaWGIG|W1#)jplkR*j zsZl7#m>$nW_NH=ckcP76aa4eZhFPv2WCGK6K?jhAvX>y)DnyGoS6Rm~u3f?B+RYg0GyGR5|74ek$?i+RF z>=_%A+)4vu!S3H){O!loL#wP<62hNY_phvn{&W@kfe{hTMs)|2M{A={wFkxQ_qTNlNoDG3$4CA#2{c`T~42pp|)W z=YNK547lb>Ng3Ezz?#otsQ&PMy7E;+YOPv#|IKEdArF!I$Pb+EYTerx51qICM+U>I;^_DS6p9|xjVG@* z3_rMGf_?gZ)i=wyZ_;mvO0HDbf5Ty3VWf}i?Fneg^01$}^rH8t2_7t{Lmb+(JSm-H zc~a-T4LiQ`B0zNtB;qmPm4M&?Wf9>2)wr!9R6?wbX*7qX20&mzJwrl5LOiz}c!?_X zuR~4`6)+GvA?$}kFmb|p!%hqtI`~#f{sM+`SZx=K*K%@qbd32HLoCn~NhWd^P+>zP zHNY4H{v&uUh*7sc`>$;K(-FH+5W}!)emO`HkZMXF{u{^`p+~?VoKOf%;LU-uQD%hG z?|y!w9s%?NB=AhiU^s}3i$Tsykg$MEfH7dep8=onV|ci+s|%x`3U3AZdlQIl zKrBF0fmN8~XX@ZU1IFVLF-Zvt^Po7nKydB=?*s}!j&>0@Mge?6xq7drp`Zucz(mst z7+}CPv#kQ%2}VX(0YQA3ThAGM`tN3*+*L4lG{fv`{faqo#e#;Tkgx4^8Y>B9s6^%H z%&q6wp^*d>`@mTOZ32#5SxsX>I7U>|>dwycW}P*gNfP~Hqb$c zZ?;Lxd>93z8Yf~+5ImrkH*0@v0m?dqh&H8oWuj>Hux?iXf-F3M3?k~uM8yNLd^s$X zvqFavqP_=W(US)UM9yUu1}(F~B7$oM4pP!}2{<2+4`*O5Cr}Cv-~b|CG$^1w+=Ed_ z#EuP8(4GOHR>8tuBO~HdU?ho`-YK=yC-e;siGCX($-uh|nGc+WHwlcmB~IZ{yv#-*x-?PGAomWXnY_@N{$Kc628?et2CbzA}o;KTyExGC-kX0Gpmc-Q&(%B=IQ zXJSCWZ;<>a$=whh3T@%CX55iX`P&uB(3yAheQVJiic}1KGS>uAl&X~V z)cIL2TA^ssdYTiGLDVJDcJA#m8JY18H+V#@JO0^UaErfFz-b<9VM5P(w{9e*tTfAE{UHm83%7qdM= zE+piULxas_6Ju4ZeS@T9Vrhna7F(=au&$=CF_jzjtq$dQD(&_FaeegF3A7&JElp{L zpR=)9+^_O#6?_OmG{Z2MF1?&X>&Z@7-t-8AKy>WCgXG{R9KOPQM}3VnMrZD-eBe>_ zR}9SwwU7__B3RE7*LC247kj1q(&YAgOo;N)jUAhFr8CTj=PkPOK4AXH5H^$&--Nx6 z9o(&~ujF%VtiLr+IO}_FFl=yZ!k^aLW&FBpRF+;B7)x-Q? zys{JJSLblmQR(V)ypV{`yus%3&Z5Fn9YwK0y&8AwU*3NWZ~FZ8WOCeo{nra1bm_iV zOjKTNr5UEDJHmY#^ik zk*rH!F9&jNo#bXLEX?w7#YTI+VVR_`(by<5AZVVY;ke>njmxw9H>K@!tQcC&(F9Vb zXScHCVlQqcj$pUE*E-Bw6b!C`Kd7tin0lCZ6 zhoVe&&6}tA50>4ctNji)xvSo1OU5@iS&~lf$R4-lJUWni1{RKk-s9b4Vj}{Wr0h8z zdWuNcgZ%-zDUv}P9CzIAyRx4wB#-#?e7E8tn4%MkQ$#?ra)vsX4ezp{1!uhfIaUeI z6k{&0*SSIY^_Yf@8narf`=h*z`+3{<<_f)~kJi@CJ=J!*d(02ye>~Ici8&ma5n7<_>-$FWOdO{35>Mzq_%>CfZO9YXIsH6ba zBa%1(3gBvSUWt7GNEe_0#PJp(^|E`lTR(bz<3dN$N4ANMGeqvrCK#EC*Z`VI4cp73 z2@nDy@rREE@s1eQpkx~0;858EtHPD3sX(3{u#G{1G+0g)6Rp9>tiU0U*5ii(Ll8+H zA0GetG#qQ*=6<{zU2`e9lsuUG(&lio53yQk;jp1TGekexNeqO*XV z@PNlF{@b<60}Q}|J)V^!aq%4_dY12dPLm=2gMXmjZeHQ_*W7h~VnD5*f?gshgzt9k z)S(1NT*T)>W~7WQqnEbA|Rb2EiDZa(kX&;qqHEQk`f{U0)li&OG)?l z?sLEYS$CavmwJYoJ=^_0zo*{z&C}k^8Ka9mqwP;kC!Y}7X7Jtu8x>~tNwJ~N(RZT` zNLV8YceroR;j~>32L*1Q_xARh0+j^U9ANI@>5_O1Sk^%*MA$B(5Svmu{oLvZCwgc) z2a`8zW}g-HW$VxB06U@43>L2>Y9J5`xT#npC*{kUd%03zSJs<w<)1i5wfEDzs&$L)j?&M@6J6x z3RrjC4x$$>F7DP&<^??fRQE@H@(Z~}jeC9UAo-r2zK2ZO`oJ@9r(Zq8NIuT%X}UE1$%s0mQ<^igq|A5(*-Do~r!;=523t#K zncx^z;0JQIgdWwt?f#pTT)7gAliS1uJ>-d!*0*KGyGU2Ee_L2e>f)kt6ck!sBnXP| z8f4lRMA;9>rMmoFVayu0V^thmb{SuG(_5~dJYieOdF%3Xz53^RgZ#ic^NO4CKw{7g zW&e=yB5#d05BgingUpVXv(-eDi|Y4O>=tc5zIBOXV{l0zj$C2c{+O0$Kw@>>H}1a0 z+k)V0AqLo@E4HKE(r-eG?SMtttBoAy&GmU*@LC+*+g6E+S*mx^lzBj-<6x`}+0-X$VVD#;*;t0Q=<={pe} zaUZPn$vmIljD8-*LbCq!g@;5Z`45FyI$i6F<{TVJO8fyfr#|aI_*e-pu{Smf>J!(6 zB)k+?DPIl@9aXYDq%SeoAYslE`-N`d9oY1cc$KurvdMZ{xkCS3oml$dKmgW{oE3S|AAfT<$*o?WAF8LTJwH73soheUuczlx@F? zKdWh_hy)8J+b(k{^^Cm#SM&Z<>VW%y6;Kh=c#>#3#~9;>(@YGP!B4oYXU5<86i2i}E&t)!#Q?81*;k7; z*p6|Khwk8IR9?KVGZ~pxjh$9SO^t2WT3G+`PUEyIw$=>^{?)hGr(;^phSsRhw8}Zm zY_x|gI^B9N6U$!Vqpla$6LkmONK&JUO1ZmZK=8HSA<$v(tT&9WMXiat89N_+vktwQ zvQ}Ji{?5z(#*C-I#Cw?sX3?nSyklkthnUt>Z%Z5z3foX0hCOM%8zO#JS$pfnHaeU~ znTdnP&4yifC`x*yDay`*e8-Q~8v-bIeuXpt+{FF;>2Umh>JFDjUF10#(siwT=N zA&1d!gsGnX0Ec#I^?ki~=zJDma>u;`A$OaNLD7^;q-g`bOcB$aUFgA zuU6tGy5Jc!YJr#u5)-=E7C$%oyf^$70>?`pgh#=j@G}Nd3G)kwlP3Uk{1zu`_G7s)~`jwN!K;DO%xaAOe0p2FAZwcJrYNgtM`TXI`2%J0;qkCW0FOrS@D(6VXlZGiXJ(i|=zw|| z4==^|is#+XEdtyII5&`r6d)B^S|nxEUuI`tL-AA?pecbw0>34=bs=CR^kWq1&H}2h zlAmw}^E;%^9%Y%|=S(7C^!m$(bZeeK77myq@Fl|=g?9jL(1RcQHu zR|3ibF={n^TX>Fe6p0$h+k$#*`0RC)UKsvvpQ6|lb@ z!NuTwg%%xL=<&0COaZ>Zi-YwUWK5z61VsTxglN&= z%ySu1 zyd)g!kxDe6M!>@iZxp=gFTq(%L`-Z7BnoIcP;c|*%^PDKq#@N`BisjH(j?FO65^IZ z+Bdbp((mkw)2D7B+SK^fW~F?n_eFG6;6U7OqCY5qHLz%K!mAkv8jDowAn zl{N_Oc9oQR$mh@d04s~2APCz5Q-P3!(6XXugD@?lw)`&2^JBnI!j}t*UC$2Il}+}& zbs$hw(V-zB5b4TJL~3mQ*E!^eo8`^Ywf5fqdNvV)y{lnx++qYr1~68Ei`aW=`At!@014E+n3x14F|%L) zDB9T>!?aYLDqsmWAAm9}5T1!hGDSVflW!TpO7p|v+QwkhN{=G@nC{L`r#s&-BH31? zif#RqO&FB&xxL^M1fAmQwi05M`(jb1O_drQ9 zuY-K%rnV_x9(E8a*3%+Oq4Sh^=Gp-9pDNnppNwP9pe&9zv^9sy59XoD*pa0aafLPzb z#4OzQa!VuIUj-!A;&ysm~Pct;Eaq`Q$GQVd{w7*kG zle<$yrL=`cXDConj*3fV23EKi#lA=$55wg1)@zr#9&kCuLogsWJmwYUx3oDuK_2{d z^C3f)?Z0bz_4cjDFPQmMX04<+nktx?C^04-PEQgWDFQd>G~-%4DzmsBhW9n-5NS;n zyeO3-V{2cE?B$f;NDN0|{`0wi{qRBYyFV?0+M5*b%uAFl94(Z|3Z{PnGo9j{PW&6m5`0X}XPJSIXegk>u28|E*Ow0XQX&Ema595xQI~@f? zHs+@;)=Jv*!k}GQ|q#$|sGep5I>!>vv}g z6>L`a89HP!zws}1GHT=R(5Dh+SRG@G)@V*XM>+ZTE5t?qsvF>K+?BEreW}Aq*}F_1 zEJU^EO8n!*6Wil7-wIPD-!Ca(Xv)gu>iy2eES8_0rE1`qCwgags{2eg>2C$gTSx2D z)}tFXi50q3MC0OCEnG>(A~NN%tcC>%9y&xrhNSaJ-hJE(ANp-Yf*aod-M`&Qd5pFb zX{ItI`XRAC+F-t2+dgZqKQqjmC4z>1!Uh{$1=$&#z%Td{%9mw#)qfEkVE2 zOS5a^Yj^T{e!p_`Y3(CGC*y55ogK(`oBKa8I^F=y8w8D>A3u=Qp71vnk=fz769N(1 z>hbgpG23fP7)>P#mwxCaREnVfCI>RD_)HvaPjD)`-MhXU!G#_uCnh2Mz0FI>UX6~9j&}LJ_M1^h{veI8f<|J|>+DAQmw=7X^|Wty9$*eyZwwKNqVjlc zk32lzJ;P`)$rjh&l1!W#6z?*%s|do=_6V1`msh`6c2c$SspO!|xXu3I_+-zYV8?oo&JcpQ-QdvCIgg#T$QR{dVN zX2JyrPp7}bYA0CwBxU7$SJyWGc*S%FaSISPPLpGq{OezFp`Bx~D4&w*)=W}bxPP+? zo=B)>_5%o==-w%Y{H>!SukwC%2gnmp3sX{)f?5X;0Nx$;JrfXo;1oCF3LTLsezl*# zI-q#9q%dZ{Wr!*Xlf`(UbRx?1gLL8+^IQeDHzMm%_t-@Qdv2RM_kb`0B%+okzjRo zgd?^au@ZY33HuwMm>g4iZMe(y>jMEFXos=jyn|T{+!xAtkC)(SImBWZ)Sjq2(mPgM zqf%;7V8@e}lS6_?wbQ;L&e1?=bZ|WTlK<k zLZo{A#0L972XGmJ7(f?<`3j=eEUeC8a;srX@8Uy= zRxHc-ivnMp$k_`fSlc8Y!`NQ$yu>Rcgl`6W5_U4p935jjx2N#8;Df>aal5gM=@Ll5 z-$Jp|?KgIidiWUSZ1^t`yN6jx5mD-HONE zW<7@uZpU?>e+_Ti9e9+2 zs*mk{g(XdNk3NLDl`mK#Z&OLx$|Y?I|u%F+lwLAwlK@_*5#PwMSDS?yseMbSrQ9UuI@-_t~cRmb{_M zi$zGpM{wx|A-<=_Be4iA2l9s4XFQ>2=u_XkNec}8e@5oFCI}NxSp3Sg9Cmiobf?Qt zZ9+KPnp$h=p6(bwG>ZKydBghIeaE@Pw~-1FONnkXCw!=RW`gV? z@1A%4<=udM!&WQ z6Bda;u9f~a9;aP^KysQ<<$W`jQ=$FgYl-=RrWq!gs>}wcZVlW{4a_g6tj*@wCHbEX z&|@+FzeI^F<1iJ-G(=A*+r+-qo=g;etH^9QBOYTni8M4Y&POMdN-Zkmk;4c-d#L`7p7f zSA{E)h&k3%jp1w!6+!kg)b^@klhs4iLL^y5-hvOU9a$xLTJ3`*;ZKp8e92n9(WSVi zORQ;Lq&xh672a6>A4s3B*5+_ORo=RdebJ`;V7smLuyUgLx@yS9*U5XvGg`Q5{3+#O zZtDxSdLIfO{jpjQP~U#qo>@FKpRLCk*w(JYCG56!Ura*zF7s(^1&^=Y?TdsR{N@+= zkMadHaJBOM#QW9Zrvwxo@*~3GK{&GdP;@%}$9f)_M|Uoboot2go_)!jT)NNaLF28~C5Drc zJgNFdvcpok{=nCzcJK4!r!&b8gGLw;jncs=6aV3+wuVem;`%A6^__3CN>$8sRHHH0 zQw#hbT|628jHxS6czDg;Ziv1>zc!2&EgFwgdiKW7k2H8h&|_UL+KQ>**1A!N>j-}P z9IDz)>cLkBbBuDl$9O{aO$P^z`V3-*3oS9p?i&9Q4z&+H2?z>yHETP-PA#aR7Q|kf zuz!-r;|A-k(fNYRD#ev3nzXW!H5dhHsjo0Iz~>1@5pYgOf=vX7b1(zI9OZ?+Qy6PN zG^kw2WBi7?bpl54BEX-7XEDq!poP7iWC*Lk5(2+~$m-C0*1pOPM=@kDgGm@MUf9>x zHzLN3ZUP-FEG%ePGo~#VT$xF+%4h*W156;*!_dy!{NUD?uN0}Ek|P>C#B`AC40Mo* z?WFV>Lzycak-q|dK~CT>X1$LGGv#0|!JvYX41@?AgAwBaFd*=5b!?Df70!l~*$!8O zF$JLHSEoowdVx_APMu()M1nx@Hetqr#S$z-9;e%#h>il>I~>EIS=9uLB5+Qu7@kAk zDEwrI!sMXm=5GYQflC7QFAy5Tf?Nt@ic6yT;X=XH3BUJ+KOHWL$4Y*(BV1~*i~{rZ z1hUxLxYhCbS{x>TFJQ@~6ufh|IIx%v!LzUh#K-))L}?9@V*wNeR|G=M2wMYY6f=Ns z!+Kzd)vNeKsV0~ipXG2XCz9;`2L{lU~B==PTu_!^j)l(Mu}ueQNJ z&+wSThZ>O_Ftxxwvcst9!^?=!gS7X8fS{5l81Oy$mU9z}f(;bgCxxhFib2clWgwQ| zZOtN9VkpLi$QnDFVjvW{kU4zWqmE|0-@V6`{2j8x3;3&e1dWov(9Lz7d`Nu!DrR4e;%BK3o6c( z$NXhlGXM~;knJOzpLbNIccjce*H8oVL1ZkZ468bUMIl4Mm(J8;&h+y+m@?pJ=0Fz_ z{3y69;j(}_h1|=Kod%s`t60^C04^6GA20|Z3<$h6K+59+#ait7f@gL-$@2p3aIYZ0 ztEVRgj-UA$@o2aQvSCk;KF@7*MgcpgY$Noy!_6x}--#%12s4DNsf2hq^4|bPgX@5- z#sO!QU^Hlb&Bb@1Ws$6t4=H8>01NCTEO{j=83o&xh{*R&We%gf(>nlNcm+@@ot!3C z9N2Bz97&DN^nqn7f+y@@dz^nrz?I^=;&7Z#hKE_9%KmZXje-d=N_x?W-VDek@Pi}p z5476$ZcDf$;BO`nKL|Ml$S(5}n6|Xj_2HI+696!I2xSI0koaMccvlfD70HbJ*LUlJ zwLuY&{%aL(Ru(%Ey{#pg##wQehTOKm0;axRz^?$o(l|HkXqJ>kbdJDl-|gW-=Y%v$ zEd^aN%w#cR{0l<~-7NDg?*F_1 z=?2EbM_Gv)ODS1%a|4(IxoZQ2Hw^exa|9yA9%hB+=s)Gp^N9F-g)YCv+26J&%a&5M zq`9E0L)4!Z^JmURfqYAcPFX}HCUIBM>u)>PZQC-@_`_&A&xJ1A<}%`&w2!=nt;t>o z)ww8xZ?H0S+ML=zxw)I`o}@p<(~EbVQ(Z&cBbrBM+F85WEpn9JW_V9n6oP*h=4{b% zMta`488_U={U>y&LaBZ_7?n%Dmxt!Pk6A=H{O^*7GoEdUU-R=!fr$eQOcv|7BuOfr z5Ru=$my6d%m8Y*O5HkueJ0?c!7Soo@Nv$_q54?Q$fKBuMK$M#~iPq!5>tFckg3Lx6 z7qntureDQ+TaaRwZH9xh$#v*@x8jzqe9`9aJE0=!Tg{EHPTVNBJ@H=lX-v&|lH&KL zmPB~p$d^_sPYWM%cgYxFbY&r>HJ$Vf%b~CC6|&%8(4dhQ?#vu?E^*%QOIzjdT-g*{ zXUM<5c%IwebTzcknooGp@$@QYNvo?R?T6TH%@7O@%y(aDt#GQp_6>=9&qV$u{IhMI zKEYaKrf6Jg#bxfCv#lFEzvV_rzJoiBKH;W0*8C-{yi$QY?He5u$5C2b^TL8Ssv&~2<{g4bwlTuA`E0K_ z^oRoKlswrb_%mC(N57~o{u{Rl<|onlHsh?uOtGXENjKcRvy@grE_vpArsGS^)ilzP z^!wxZb8Yn><|y?9J(BQ((+rb_9*3&t^mRLmpHtbGJ{p1)G9kPj>V9f;VI2NCyDG%L z!h=e~mrSZ;6DROyGJR$u2UNm^u@yvjRdLM6Qho9d#}7{Xm(CW0T%tXv=qQcZ?>N2j zI=+g*qCu6ryDe}l?C{17ZPvvRJ{PtD6M4zF*8`zY4;Xwmd2dns(d+~^3B{rdU3ugxg>#?4m4|*i=U2+~J!u}78_MSXG#-yP8=1tu;CEEL(QoJU zyU={S!6`Xj){$^f zX0(6*1nqNT_pMLyDAeBL`Miw|A=@3-gHK-1{6Fy!TN3VAuryP2)de40<`8dhYKdMX!mBR6BRFnD! z;i`L{jMAAH;Ro}x?>-;CpXhXnPhL1*InGZr+wps}bq~AF@>l(fPPBQ(q&s8d{;9?F zlF*lH>fOGqA36nVL}t#TRNXc19dIqllGspiE*SHN2T{aGx*g2eNsn0^?rufllUQSk zY02*Gy8Bb-Z|;jutyw?L*Lc-u3}#Gt+#-4cN<={5tE8n8PJKf|_f=@e4b&ijk(?GD zn<%)r^k1k2hRZ~QYeZ09D2Wt9LtR~hh#|WC*npuz12ONx(;nCoKb02SKxdRAMMn`-F$@ni3i zL-DU?$Yg@FIidF3oayiTuh+{H{}U9D-C#z?1Ib%KOs6R8R8wEy^N+mI6HLWZ{S250 zNP;T?SZ%ADvwUJ-bP)RpL=OljW6V%mLk?s&OXu!$6b-I);WJ8sU$M(X!_8Y#!@1BZq0^zw9DsT`Chz?Vxr8I`eFs%*A8w@6%5C z98C7yMbW=70_}k#2{AfS$Q@0>F&wN7&|L`H4YOi=&t2qG?<^vG2xQpjfyArxJrf2w z2?Q2|b^&N(bxO7uWR>BG3y7%opz+{77Z;bK(r-{Qv}tmN8j!LUFgK(YAmg@izotAJ z45KI07h-^q0Fw}><5|Z*mKOHqfm}6lc7OID8>kjUdc>G9u5$2Md&2ZQiZSUx^Zehf z3vzfhfJlc>yLS<=@x&$y3?Rt(1`Y=4UKw|2x(pf_;F>cxU}oSt0g9^wz6bCtGBx2( zBUtWu^}Y8`X=hB1KTj_46bwOOGEyn?U+x>W!%Lf~H4TXLlF`0q!;jg)euTlZ$HwlH zq;wsMe zKJMiH+vdFJyx3{V9esW;j8q}6fZs0Ls9H@s?^SL)TU$hFhsPZ%Oe%@wkZ>&Z)aEL5 zUcQ+u{~_f~VSV(rsa2mWIzXhlZaz_ErjCa=Q1)69qaXUEyUN#O{l+E4JE4s7YT0R~5tY5lx{9;LEqN7xpn4v2)tW|eKr-GXwqT=v&^i~48Y>@vJ{()F z2CoK5tP4KR8q11XYyp0J9^v4gV@WL;jpJoCawZzi1ZyTomri-LAgs$(E8Q9iEQ+5L zBHvq$j1-T%?x_wC$LB@Zk8QiH55&f?M7<1tacg)b<*&N@74?!2S>}JV9eBmcn4x3$sBK7jKct@0@54!&I#+`UegTR938w;AY z39(ik(@4qq0)+$~K!(=w@K@O}T2xxaNwqS_sy+xjKJ+{jSfw?Vf+0%N__n zcFbH#+l-k{^ZP^A309H(h%i$P<)L1OR zhsas#^hh@_GyNi5!w*xn>7q=(W@q(PO+U|hN^EE2Gdn)!@wzmh8u`Fr$bnkwHtlNL zfP_bvCF=F5{nmP7#vPO`2EFrL#-R?bFSW&}rUsQbuIp$nNe-5bHn+XA# zk8dB_Jou5_U==;OA83Z@OX)*`is?(tP?sm06a05Jj`L=cm4*>pSY1i(x~5P_Wz>=d zN1k0DE@6H-TcMJY`)gr5wq;`6oTv(JOvRNuQDll+C!fExjl{NOVsYf=-smt0OZ=hN zV{I+9F{`U2$)LV!)RbTHu9!)h%|-PrFhZf!Wf|L%Q_%jNfEot1BH?b2Y^zaQHZ zc<$hLQ4ygWBfp;1x1df>>#wo3qV?(YBD997F>`?M@07j4(HCD;Cu#p-lZm~s8%f$2 zy1_OI_uQk-?v!hEPct)=iIa@~=q#Mv{9M$yeyuNI;Vs3)!BLX_CWXUtM`DGq>%r1l z8_yTDyibdYq_TWU`54snjw!<%Mps5-G_PG{KIBo+9>0ffVefsF_`*Du8aV$B!YvS|Dx$&^w~!uwX2Ce+Iz_M1CV!(g4(V z08|k-A@%wYO@X`wL~6lo@iSK*@~hBKj~EBo6nS}ho2|Ll_JrS;#^xwOf*a~ZAQ=j{ zr|<-HaqqGWzjM#0r9%BaK&^vhf#?>|JCTY*HbqA`#HWe4mu>nN*2qD1F<_c#29XZte&G8Z-oD<-)hSw!XlEH; z{C=ycM+KVlNx%_}tjdK-MDT;CMzd2{!@DDlhR+M_yzp;`5km(IVsb!gV_>Fo#^hUv zKd&b$z2m$0*bmvy)&fg)5}yyefpa=i#sj-@veo=G2;h|=B?A{5{y~zhz#>4Hl@q-8 z$UZ>uj0CRxz_-ySe(_%m9`HUZ6LW$cz}$c$2gFkpAUq&XVAT!MK8Ez7AVd!^Bfx4v z&=#pEF@n&oUpSx&S~LD)K7f&c42&GPd3ff4%JDec8=>n)$RNN7z@CAclcD%s>EpwE zy;95OsL*2YV<0glASYm>F9(@@d<7}#N`ZT;tJp``ki4t9k4Wa^py+WBAt^!wX=AcdU+buu5D$Mk~0@j!_!acJqo8aN;)14Dsh<^IhZ)fM5C^IQIdc&SdWT=7r$<6qeVz(QU;~1tH}5k1Db{JYz5N}$ z=dZ>jeiI8=$h>IUymrlkpQ+-x33KukM#UDNDM`~MS-z0Q)?o3%8gm>*l3y|y#H_Jg zdG)(VCSjdM{`*`Rb=7)Rmzw4JNj7pKF!j7?M>j(sO6=+Xjwjds-836z?srQ|uVjxy zGF0;?4ooWTxy%$i<$%>vPf30K?&zs74dlWFBdY z4zP>Pejzk>6I#BR6iaKk-Qt2nqQPEhP9|GPI3!o8i5}#WM#uSg(>KT7zd=mFS=^cs z+=FRrSykLg>rEu-Om~WxC-quTT?yOZs5RqC<2_UFLy?KcF3Y#nIK1qa7oT5m=6)$_ zQrgO3Jx3}v!<0QWOtAL4^Vf+Ft^^8~<+h`eg7ZQ~zVIuO0xMru2?}f~{&e+i@^JI} z-B$EN!`B2eE8SPG4!ovfxc$Sqq(as`OD@fQHB;_4R;f_e^ym=hiAQo#U8%mrWV%^# zWBy5Xx|Zc2U0Bz)bN9);Su5`?QN?sj@?tJsie|w;G2P1V@7+=ar~+Ix8VJ@UZd~bY zm?KH_AQroM=<)1;h%Io-2QNjYL?;0w?T~E0?F`G*B;h2(#tf5)){Xj|lVo<7F(oE> zs}N@KGT$N12Nu&j=P*_cMnaS#jjoqSMrT56Q< zA{@22;(aBb#!_UDz%`F{rSm4%%7_%|r`=6L(rw?Fp>8Qz61>~3n^BL?S+hnm3zffc zpHSOeXQ6Opd|phhLon`Nl#KOpc{Z^za5WG6hYnv)yoOHTkZ?P%28UUH#}(g)q;F0{ zXXR7fOl~Wgvpd|ANLBP$w8Nf}92ysXN2b`k_-lc=3m&k zipyhTf+~V$PLJ4j*;lvL8hz@llw-vL?XX6D-Z*A_>(H@?q#B7-GyWi%A9*4ii1}8{ z!K|)_T!xZaxPn3CiCL!npy;UIw{oE~typ2Y3zGYNrW2-39Nu}mHqV)!v&D@|tG?CE zUL5${9>LAVFyU5Xf6U09aP)kA_0cJ06}eGMM$l^8#z9^X z*XRDkT}<&daO}u76mZjc>n9^|WH{j-I^lG?{rvqg3Z-hYm>e;^r~D z=0J==?CR*mbx>FPX)L;CcskEmbT>z0JBftCC2vir`!A(2nWsUVL2}%_BuOa)my%7R zz~lN_v+l9Uwh8x@;|TwDfjhq3ZN;CbETwkixLrOAJf5kkIZ#)iiurieyJvko(v$)Q zBkZslnN+N39r=g#A#O z+TpaJ;I7Gm2$S~g0%he#S(=lkp6CrDhSsB8*ZT1v7)CSdQ272Sx$ zfCvSX#$`^}i8I88Y9EVLi7EOsUL0lNHdlNg@DRqm(B%bqgciziB`F~?dW{}^EIf!o z&0okW&{~8R38KsDN*#jH@OZ!7d0SMJD4!A;0i@rgrt@cxA?LS+Oii!~0HX^t7`j(F zx92-60S-V*DoW+ocfAN;>5&5|(zAQ7ar-hXjWL6v3$qo@kTM@e&HM8p`UwwUFrR9^ z)OgVhTUFQrUIu5~eSRD)6=0GMzyk3$f|3T@H*yL-KW}{Udk9%t3tQn3fB;hyBzxF? z01m^i(e93pq|kRpbdYbIsu<_GHp~s@ZCIer9L`cwRyG$*W7rH-b0Pcv=YK9Cn{rlM z;C~1$VGRCMFg1c*p<>w7+nXNpy^=DecfdWVn{5Y^6nu$@Tm*0gd>kW>`J%c3Prxh% zO$S_m+r1*2-X$o06u66J=sUp(WJPNZM#!eUCr!byo%i&l=|UvDeJ=YI62AnKCb(%4 z^aO$g1ZM=Jk#Y<0m>|wdUYl51-_ z-2Stz=d@(T0PVNL4)$8*(U(@7Bs$*2AIJ=inBC?cV^!C7mTNtQldZ9oF zZ#F^Qs4=aJpI;_MRZ>z?PyMRfClGbil=z+=^Cm&;cNPi7qKvJrSJdBqk8!jHmt{Cc z7uPdVw4!?<#*98dfFu8kdcN- z+E#>Y3x@v#10TVXolJi8z(Tfz?sj0Uf%$#mIg#)a8(q3BXy82r$kM%P1vePnQI9BL zPdru!NGcOz{#ey$*&@*nfHRDJn>BD#05-N)#eb{O9OwT5%)meiRrtZ3(*`e#;x(3^ z&P~h{zy(4DR3_XG)KU|OLdK=-(7Fd@$euhBD878+{38(vo$Ue&syARv>^aH( z=Sb7O!gc0lk)4P^nN{<|yNbG^TheSSh{T`pIbE)?Ew&vI-kDGlEA@A}yAjoRgXk@l zpQ6mhw|phrLxQQs-CH=YyN;%-9deCb4;hV3qOhKnd^Fr`-xT>_pO9RqL2x8=hn#6{ zpCsZEu9Ao=r_#uhFPY@E04+QG-ywtp))pwLBi6z5-`psYVVwrAK}@=^-dmXFjHAH; z<0S##3Q3LEJassS^jWbo890^ zeY+ElIc3CaJARlhF|y>uL`F*)be(W7G6)n zyG;AGuF)>thhu#3BlQ#>`aILdvW>tQRb_{5-asY5tT_af1!sW5U&gZJ;SL=AMK(HW*$(r=&^h9~n(uik< z<-ul4KS_W^#X#Rr+P}8bt%V6apH+-!e|=vby>ier|?A{6it zqiZ_UIa!^WSMq21Nc7Q{TC+BG^taxH&9o?yCnT9W?q3f+-2WXmvVXT+7R)1hviHu} zgENfp1R8CoIBe0%;^r@ZJFz1~=kW?RV`KR5cG~|Dq!!Cvx6A&FkTDXf$?&Ggw#Vp0tc`DXKKNd+pZ%5XIT`hO)iaH zj9y97nC`1w7rnQl=`e*&wfVWD?d7G*jw)$kfryU}Tbe290PP}Vx$>g0iOlbfuWH$ex3d1G5BIF)$c(rm zJ)RoRPA49HTLcF05Nia{=lFLz^qusmI~~SuZu@E+`Cy+9QA4Bj-v2_*Y;d>)I)Hxy z!#}AVh8-Nm9APXr*zPrfObLN7dTg7=b{*#xseUM!wp0BV2*`Q2PheUuHHZz7CJ;> zz`_|HDUAU$0?cK^N(BH2kuV^M0(J6`sR?JgIP4U3U8Rg>bPW##z$BU{C+9jbHWtW- z3(c}5rNSv%38G;7?M)Nfxi-A0UOytmd=I6aRyF*v2zaszhjIs3#>I6UK>K6|8;Ys(k6dFC;lI!&mM79 z_i~=19{!&fAQMVSp%Zluc8uYJ&6Uyb)CmY4DAGr+H`p*rT=tRL5@a3Ye~Stsh(_n; z<_26Em@wWO4Fo@hyA^mcSW5NVfvlQ4;-#+Qqf#1y&Bt&7M{B!THpg)Ej~!C6z7g7@ zh?>6%YsNWV{kH00XSY2W+Cd9nuQmnN#Du?b1AtBt6bTjMw-}6pECLWjG?Q?FJ2Bw^ z3%r(YVv~!33ss6h6cwx^)y+_UH;+n&K*@2-h#kj*iz@&{d5Fo+8E$fogvWrK+YMb= zbUjd9*MR2js5YAX#{4D5nKqw}_Vhm^CP~3cth5Z&(Iwik8-ama-X^7}ylS+if0w+! zNtP{<4N+paLHCXK7TKc<-#s8^`_Nwz9=NS?*78lg-t1?$aBG*GnDIK++hLqd z4DQzn`ss%}>Q2{se>^B}cS!8MYkl`e{G~CkB>uMzp_-yBIQ$yc+jnL9mBI#F1DrRi z`!SOT40oh4ucj?(oa{P@kro^HT#m$YpwyWRrtz1?PP1djPQmZ4WVT4p8oP$IvP&8z z6~WtqlWL;xsv(Pq{%CU9_)hhm3cZ&2&u^;Kcx_L58zV!x1u`jXnHSxkqEV_CZUki~ z&hrPh16jQ?)`O83(V7m|V!5h=6|rPGS4>vQR}4IeB$xZ?l}=d%eB1&OP~s#puLL|) z;@I*+^0Zzg#^3d~2=|j-MN6)KAJG&#jow#jP7uMRDH#x!GG`aeXvRpxway99Y0<&C zYORBoi6iWPJA{{z_&hdq%OHEu_y7i4wR$SXNRKQstJa~1^`3*A!8?{e26x_wrb?>E)Va$iv zVdizn_sFM7AxY1wTfIR6O~kMIT*0Q z*8P^)7Cx|#pZT>oGFJipH@2HNpJBhT%OB&h4ZU3Iv02a~qU3&s?`Pk`KHmLPcmO)Wc8G!Z?_%hu zw}_sS>hhRkwDG^uJv0WdIm-dZpnH8eM|&IlsHK`X{)#%~iSOvoM@6?z%+#3{P6+pK zQm5iBSH0647Ngg>dF{3d=Zzv2rRI`aom#J@TX~H(=K5z}2Z=ZK z!pu!BPx7lmD^$<_%`MI+aX%hL z?E3p0n+7k+Lu=gV(yND`)|AAM_&ToBEqWq?!(#W(JG~+hro4b{abe|tXKP6F7}!R(^Kbd! z!%7shUrC_0K!Oq^4dCUC!EC8#0}W5$Co}~z1vG#tx%t>*GD!ijg3;wr*e(f1J00&@r-}Jo>7YIB^gG3aH#++9I0@MISy=A} z_!cR{)xEqvUvUXCwd!2d+rhWIF~A{7jBI3qeSV}Y`R-33DD}R)F&q>cICsy~FJ-j7 zb!dDAcL8iJ1|$Y^AA}ZSWDo-ffWRI|ihSN3cz}3t!7qvcwhte$Y`8(n$*Spq^bF7$ z5KYlF_)d%XXmJT*K$xMBKb{1^18AN)Kg8kzTtBpu;>~1*g9QZXfJ1UYoZD)>i$GH` z%D{^vhECv6z`%Mf+6*vW2(J+oe?cnNnLrh@|I$m=>lsjG2loY#2l|cPbg;+K5*EPQrg*+@`0ropz@-qclrPhA3b>Vw5AG|6gZ~z53ry8O{HBRroeRw)nes%@P z`+{Bam+e)D&n^CZ zQ3nEzNM&wkGy~H4c2WQpwASv$z9^5LIG?x<#P=;(oVuAe!DHdPDJs>=4Uul3z;17e zu;*)>6@mGsqI(gDumAP!2NQXPvndMZFM#2rPjf(^9YR_jVv;m#*cXGRPaPa$T4wBP zzpu-`i-Ftza9;d;K2m8c_un`4#SY%IWao6cVnAAt&B6xxqOpkhAoawBkPp+uoF$uv zPJ=&%RJU-c=$nEGOyV}7=i4%9V`gkwi}KguxGq0!Z+AV&M9KV?z0tqmPas?tYbuY) zNy&N{EfI$OL}8}WT)g&fUeElcH=K2BaVc0L}?r&dh(Lm$#ogVtqHCrts7>_$ooigF}rQ?yfD%ym_yfT|+Jr zFbwP^aa~$$mc)yc9Sbs3kJMShj+C}8V+nblgYIN6XVECg-IU?EPL1ThRcpRI@fx#X*-qs#&B{H6 z$*zhoSK{Ud4z)@{m{loIbVtl@BE1y^EzNDCPZ=L4^?eZUoNdxIYAcZFXFg(GFfkc% zs6nCVNU4^>_80VX$j`_I(uFSK^;9;kBDZ}zvEt3A4Wqj%xYW1A^yI@R^K}SUM&{6+ zVhRQIk!Ixzi$MGs^b;oqZ{1DGxg{VsDCE>mC?0Istk6JaCcDVUS9<@+>^R%-3 zd+CYDZo|D;iE?%wGmi;^v#>PPCZ`A=ignK04Ee%J`I4EvkG~&m+*Xn=qic>jyJARN zTN8~VxZ(EzL-NY4;@Pk*Y1LJ24D07Fo+aG3OtpC+j;2~)=KY>8>All*VdSAzWzDns zrE9HmN`Bc4_1oU!^9-+A>=)|4G+gfEm|as2G@L*7KZ)GpSK!9V#x9Jl@=a~1tRH`v zmH6Fq=X58t1K5AWa4&lF2PyFD7#@E8xaQu(J*+IRB@$14EheFh%hsiTwx{jXQ_Ox8 z-1iY5cizj{`_4s_Ttm`yB2sSM_vZTeoPDj+3Bm7i?{njbzv9nJ>OV|}I1x|P?2pM+ zw4FR|3N0oLqyIZHnFj?8aPs4KD{@WTme&*a?sP7co#LH%TXkq3flbcNN`2&jpP zJNb(_lqoRMV1`Ll>hw&k%kM2;CZHh*j;x|)Sb{+X57k1~o`vTnyL$r(K1E0ffCKQP{a+?>LbAlQm>*V) z6q2zm)WFMhYq-$oeU){+xkq7>{#+kg4nT@{p9u~Sn3%*{n%&JnP(ZW<{^%D zv}XTxGBq8x-#WfhFpPAh!pR)@-FUVZBp-?NHhfMH4U6wv0;?zOUtL4P4j|D@A|>nf zLu#nu&jYZ5GzCa0$R54Ti}TI@pC^DG1RI-(L9QE$Kqo{a`3og>;Pa7I`BAIPcHkSp z?1HSBcJSSK>v6P@4Ehz~cmPubOTy}NxJKZmKnNE2aoeMPzOOYi;sd7uLjdGK*>FqS z=1J88iv*V%Km&+qkZuWGlj~LlngaSqN&KXVbckhBhn zd(ev7B)=k7SWw_N+lm8;6aW;k;}1eTV7CEt4YMM-=)r_DkWir-1n>a?NzOE87O*3% z2lSFa>sH_=Fm)a|-uz#m`~Cm!!{a{gt#r=$oa6I)y`K~ENfF14|Do*80r+`p zvo9p-@oG{e~af!b=4$;mm`GHUM=5rjNJetO>co1NijOGhjN z=)7{NEd&`)4R3WXMzk+n02^N9R*cgC-YYiT$X zYs_QVHvwFO1r>e~oL5aikeqkoP<+A&>nyxpKxV{S5cUkNs%0|l9UMCX{QUomcFB)e z&WtvCHPP!$URhje`d;GUMc9R4=U9EOXM3~2^l^h`yqwDg&_F-7l7_4lH;q>70#jCR zzTNbM`nf}6F7IfYTWkmO8AxmhG;UwFn3kQ9W5}zJZn2L_Tzu9S(Es^G^}ZqF6}U>f zIm-JvSH*_~iVk}?eaW;do@4p0tOi~)eEpP(?4IlvM^L*{*Nx{ScMG(VGDMC4oCu;Q ztcG$4msJ%G{laWAFoGkA;qjCstq(#J7z1S|SFb!I-*ku#7nvgppq5#@{vAaf`jlWL zlgRCB!_GL_V?=+KD#Gq|+)I3=)MXEry8#bt&V8&Bve%jYR?|%^b0(BuN?&cFV_<@; zQ|iuz<g=gyu}m3-FTN9;VZMN1aTmk`%anN4k)afvm%`PZPmgdfv-<5Z5?%yq{=`VSnr zETtysUg~EYuJN|PHn@zvuaqQbCTL#ZPpi>c6UdG){Yuf8D8iuTh|X<_P6gH%3o4j2 z-SOBABQ9mw+aX?`6YLgNo@dc%#qvomsY)IDC3w6mb+UHl?AAZ(8q7HQxbteLL&%2l^`zvI`0gPhyq@1rGP{$nMHf0YpA8Tbp1KZi)kxpGsuSwe z=$WhNaYLZ$&;IVlymE}oUd64B1x3$wfz)X#nXY#)o({H)F#c=h{UV#^!~##;JrGIs zHcm-AHB`VnEYjP``{q+To5F7`EbcegCu%LGf8;xc@-HNNvPj8t)u;CoKK*LMEdPoX zluC1Gp)hXvq*YU=e`TakL%~>iB5%_l^IE0wE3?{x8sW@usl(5d6Ff1UjnC&u}IXbN;|I0NJUsD7{nP{Jd;jRP1O^OV|}Nmi8sfjqkG?;tD=6B zm%5!7y5`}IhKPvBek1RcEC1q(C&Yh8C+;d7y!3sH%1>CK>aJrkoyn0195}-@&Y+?h z$hRZE5b~C4|8uvGV)js-eC59asCqP&{lVqISbfVE&cB9p(ezYD!zVrJxOJ|?#t%0p z6*d*mwkVB6r-()}`G&j`Lx?qEQ)WlDxppr5XdvddQ)iC@kP zZdEgn4DNow9&GOx!x%)WCw z$2Dxgf_F^B_5LNUAH5vIJ&pP(14*S_;?dciQ0x8!G6%1kV{s|klHrxDHvxG{4=S^& zv%ZdB!A)Fy^~GV~s5s=~_{8c)yT~wKa^p#Dbond$HOp(18@C_z|eC{GKhhU!R;uRsAHtFb$tt* zf53l3Fa=a$;8uz63-dEF=FP&*8?bqZdJvCMt>5rf3Lx*p&guCZWE;bmhp5hMY8-VfaaC=e_=puh#Wa* zt3iGV*|7i9DG1{~JYlH62oYVNWo&?qC&0N^w@2?ygX^>6;#b&10N0?Vp?L*v3`jRm z#U5NOL+a)KQ-~l)$J$BHc>2ZmN0x&P=QlFgzWn>;{VXd@b~>>t9iz%~th1otSIG;y zN$jt7TtXWMX-xq|3puGjI^(|+yhI+b9o+coZRpA~-gx>m#I8{I`0AU7*OrO8SJxxS zy3o!VDZ@vB@vmNS@)@EVZ@S!hWCq6!v6Ko?l-9{_ezeY8FLQvmvILg+xa zX=_AMJWVIwsBrO2@rQYc&`8aU{;DV=(?Tu#J^3Ca+`{UhCA8Lc&!6E0EFwYhzX0-Y zkAi`i@%feIgYVtECFW4gTy8)f2)_no1A_V^DNyf!*qK{mtWHr=XBQSm=iP$pxQpzDd!w)E_< zjf>5ADK>oIFkJlo&%MxZvRA3E`a4uIWU19V98-w=&pkeh3EyR zf;Ry_H*rui(FlM?=>Yu9P|wh-VH0&=%Z*}H;#7PR0>Q9QI0H^+AlXR2qaEX}434^$ z(gwcOe$&T!TX5OfZ+9m6%6vE~kJ0qTjXj?@#-%b&i5Lu+sb;R0@9pl&0%nAp*mJ#e zbaW(=sDd3ae%D0!1gl#7KyIa$Yp$Q4pOFrveyy{wcw7EdrDSPPsJTOL{q=nAnZ4DxIR35+*U2xO38BU&#J-pAq?$;vrFfZ#MH8HKm`kgkkwgV|rCluWWhSv9CfxqA*VHSWLLEbYXY1W6|WPx#c0$ zdT!@wZHUl<=T!cZN2ExFtbV+5b2TJ+@`hDhV#~)iw1{BGhv}F850}Jh$89~YeH@=t z4P1RD++C`Y zLiMYwLhfH$2s?U7uu8h6=dFh`=Kty6phc=v6`cL!u3x|}OJju5{3{dK%;?#$= zcot8>0wp9xbkV$wyt#2Pfq0V!oZELME%il{b95f5<`4T1Ie1I*k9z!%yldSC`zbol z`*LQRv3YEZT8D2j-QI6A6*W*x**9hpB7+z!Wrfv1O+ zY`$YJ5SkXE(>}HuKG(iu+^;+N}$n$jE`;S*lX$!V#b&>&kVc7=?X&O-H$)PPnVwV;M`n@akF z;VIn$E!@or*_j6lCnm&0-s$hAvu5{ir)r@C}T=dWOpW4F)JGhGT$Z0PPk|+=a z4!^jsCy`3e;O(hJar{ztqc5HmnaJJb4~`p*@n?;a?Itq)DYODY0q=u9QkIk4H4hSy4# z3H5G0N;WrRT26Ql=vX?><{V;eXYDn=JlhvR2fRI={J{`8T(o8TzJcs){XynTaIp`Y z{x3p^Edx!bmvL1kSN(_E7ASd1`WD_s4X3+gnBYWp(!uaBo0&&Ono~D1Mw0(>#O;Jm_ z7wul7q=T>;P(@NTrdl<&KJzxKkV1@Ixz;AECw;NhbzOx-Rw+5huHP7*T`YK+0k!vM(7leeT^@ZsCO;>*`mM^p{rx*TlJoMh2G4KdrGUtXSFmZlp~LQT(j!@{_&rT(%qn`T6DlgabAsVDmeT6 zr)TR-`b2VKg!ctq@>bCin#qGtBBcBa59P0#>7aNjG(KsM;l(j-Mt1Qjm2!IVc$dpOm6UDU)!3E`UzSZqzMh;O#pImhVrkWWcPIc@PrpY{y3Cy z08oO1tORJ`y$bw4081(DBAEsyFL2Ol3IYc>$}UgTMZ=|q?IHlPGXovt01=uyfCM?-ksD zZBWl5kBQDW7r7*LNO9-QN2f28{a@tC}P`HW8U_yGiq0Gb0+9NOcc>IJT@xM3&> z3}FPf7+`}WSDbd9u__poL9Gy64c8gM_kpBhaqR~^?XOTycvnkumqE<|Z#!aPF-EdS z5zYrH{{D-s_gSf7CdvmuWD+p~RsNvTz*L&;x=+T6HGtFtL=obki3PR=M5Z{;Px-y% z5C0enlMCwOUejj08Pc1G&FV9QmwSe)iU)KoUEADL{{uddL|t3n=CRbOJso zvI+`K@H~_bSJjgqBW*a~#rbGeL;2+25(vJJ;8yTn#Yblv@xokB7Bk7U5*=C8ArJ?;3$TFhBBNzJ!MEsnbm9{>5jjd zg2fqU=jQt}Qm{-HkT%5rytA|S1R5maL}d0Q1qJG0Kg;|vtV*3Ite4Ot%$28LEQ2!q z*|k>eC&y$~F2U(aj3UK4#zzLBm^>xEioPXx4z#y$Z;(ow3)1gIXH>7(b32};5mIo( z41G^reQB1vQGYJ^8|8h9i`^LS*$O#d+L)G!v|MGzgakU_pr8;sHq2K%M+gaTJzm*W zCy<$)1a(25URSWBh7L2Lb4(F;b?PhurKU0Cby|h0#74-ziNXuLVMR$Hlz_IUxJDXZ zU9qlGUYjQ~n@yadZA|{}6>&<^RqY3pac#?q6FzY{QDvPMN%#`;63BCjAL6m%H0Maf zQL@fx%Ld1m@aCvLGZ@EXiVybe0tIoRmNh^Fu!|}16S#DPl@A>1~)vE-Sx1V$r^bR3QoZRB869M z7YO(Mv7mdz?0DLQO(xK_aA5yzGpP>$WmCykjfMvSYT`pJhaB876jbbbX4?{WmnrB- zNiF$viFQ=z(x2O;itJPsx!o<)a&qd$d`9zYU!Wlb9X20z+ICAM4PUXF|Cfuy>!&~I z!Rue4Y@|*`w{FHT^XTDbhydtSVCyu)G?t+cBkBtn4$1Um%2^E&FK~%OXyfc26 ziaM>e-aLpf3rg58tdco6E`Cg!9(bmuBE)ZHkmg>yo=-Q~)1$2NE$+l&?N&+(6LxBGfiHsSh{-Pbhm8wb0U}2ac3(Ek-x&dD7$l7EfRupzCt4EsgWLEd2JK7&_tUQs8^N& zLE^ahQ;XH++*4~B>cUU4c(jib4XYp(DUW!ni&LCx?iYK_1}r`foohm#Yp0S*ABg6o zB3jK|TNPXg^Bim^Xc4X3l`9>*JTYO{(p=I0Vw|%y?qbLLd{>dE?Te~|@F`vo5v{b2 z`Tex@k#sxBNcGZ!-;;~atU0wb-N$Z^uKV7MjgDEoxaFfVB$KR`+HYpcPvSO9E92O# z^AVfpiQ~28^u!TedY)PMd5hCyJm)CmR4H8yM@*#ZHAYPeDgG+dsG7QN+NCe<1Vt5FOifZllMCOkX%rgm zJRNwh`3vQ2aGMDJdwDXE;FCwX$7&NkTZ>r?BbnNG-}Za7CzsNm_huxrTxM6f{$$eP zmqa{CgGAi7U9lxg7P_c1Lss$k^rz)5ENp5XSE^&z?_3%7%e&!NKSFZ^1!ucy8bh)_Om8XeB>iuQ{ONy9a)cT6j}IL$@vm|xb`&*0pzt4;gCw*NlbD4I~J=pSz!pts#^x8q$| zYG(X<@O3<(m(7U%Mc&J|wdX@LxPNK6Bj+%2%i(rT^04FGw}-hO<99GI=SGYD&N$)? zJa2Upr5R69Vz_au2lNt-7}*Ebo0soCq{6MZ%mrRm7GsYmJ&6Tl?Tm)!2LgIq3HeLxWcCK#oIv3^&`25YmI1Skm@AKzQQ4~U20`GV}yCZ-Y2 zw%~_(a+^_0{!*fR#R%ABA7Q31pu$R0$8B7c9 z^7p5jD8R0RY%0hm0^v*utpo4lYm0&@&=dd*1L+}MXg5Lm$OC408puh!*=-S`+g-DeMw6Lket_N%c)WSj1R(6@DwKXR^No1)4572{m z@XkQy8FGz3_drA`u_}Jh%7=#2f0ql)!(jGV1w+k$8KLLSk=RTPg8~D2XQ6ZqUg9By zqh3VPTVZDe0n8L4>(GS^qG)e-^W-Rr|;qn&)aR-`Y5Ko9_3nzC#Ne>Dx8loT)O~z5^#m)a1 z5x3!|rvS+`cd8!JX9Rl}A_79f^#4~{h-h&kJqrXScJIaj=YfwQcc#IP{b`;7Rf4uR zhE$;jGQ9vCaw_n_%(sXA^Q|z)YVuLU1VA{QGjqW|eCKu9CJyCd?tK>pTQ)3u5_B$5 zl>OOq=17aaWY`sXSK&G#u;j|hZItsR^4J+fo=ZKV4;5`735xdL%z3HOfICGuv)nT9sf?go>e2TiH&SGXq-lK$Jvte~o1wDJ(5@sEq)#q+ zGwGAFRb1Y5(`W6lAci-a=~=%@C)7WG;F5a&kngjcdx4y)R+dl>mnDDVj$Fh3RQt_4 z`#d^sUra6Ndb?>WMe~X#CFWDwMBaww{?-~XwoqYhXJT8W`|&C9lASo-$Ii_8yx-Lq zlAXf+zk2usSUhmPsAU-j`8GlPR;N1 z3_F*u_-#){AaR<)KEPJ9xRlxQa?`PNjd$zQd9sH~uy1HSakxlei*{&=f6MDk5ZA&| z$CckA3Q=v#Qa_KoGa?_Zk)lG!t6!yCb!&1YD^H)bk_Q(TRK43#Ov>(+vh_R=qKUYi z6BLchs-AEr;T1{nvO;2^knAl6!Ccwttovv)I}Y?~N-N{C-*Hiy7OF*U8XFrM8}P zG5Q{YUbRcDdPQ019T}xpa-!xJ{<&&?C!lEY9FdZAwUWkq64P#*WKs)RV{h96KmBpm zkD28}*#n`ac~W8)|Ndj^RYLOBR+G`BX*eO7Max6w|F&;5QA?`3lr5$_cw zQ|DZ19pXH4tl-gBC9`^Uvy+GYYfD2>T6@@ zS?(rYYtLs%k;=Y$ zWnV&1;kf5<;YF&r=_f@7^Z)AmTw|lsDe6n=lzB^7xo)4gT0P<1$rG+1RXTdKxS}-K z#<}CPJZGI;y543&W*lLrD2M&~?X!x)sV|kx@9EhuVyc^G!XwP8G75z*-}~)tNRTw_ zW-86xo^kxScc|vQK{b(IJwZOFOv|+#o+q%9WcadE4C94qHaB z;v%N@mR0ham7}VAf>O`R=KgUeS!=4V<_5>x&aCrty__*!+tUFjg}7AR$&SR=B~ zT15V;vuQ>xm58JL4!5Jln48~VW5^qc`{o&;c+2=5Pr|5Nbmx@DlF^~j^#!2HD7VX_rEjwirhsHRsxU!OTmaQQ*8pZKg~d@ zbTBwCWfpT1@ML55qY`$hB=F3a(bf<3SHfPOioVvDrOpW}L)6Uj*w~T0-#x3ba_Y9< zj~n_s($rn}iWW>YKCU|Jjcl<9>?{{!vRHncimAHA3VjlF3%qt4&C*5j*^N_Ez`o3tfcP7esgQ#2{I{bM`n zJJzNbTL|{N9#;l3CpXQN;bd15wWs{@9jV8#_Xx9^n=P?S{&wD_>`~VxAEa6@Z_fV*q{d2Kw07Q?_V+o@d z&dR&LXamAvPXH4Dm^_d`ZKxXu>YfD1f4JbFC_w6Em5Uv@;DtGX=>p$C<}(t;mfuT3>Jcm&Zn9B76q6#AyVu=TP!( zTdMf{xqWMarx!*J9L9mL@zHs9I_8DS72pC|z$5E_v|v3A=*RM#F)1NFSVxe43)m`v zv6zO512T)1&qw_>yq{$xB+!^&V3v{6rPZ(W)xN%d$&P-5^_cwUeQ)nDDD*@Ta}n2W zWUgex9t6A%_=aPQ?ZBb|W03lx9)CO-MzBSuz*&K81DZ16p%6(Y$SHo-1!Valu2^PK zO9HGLMqpxv2vpZ6c=QE21`F<38@X=KpMXX4e?25HlVCt+rJ~_&firSt0Q96HDXU=3 z{j&(10$i*FW2D_4GRZ*9D78dq1iKl8m*CvoBF)?0>H)Q7tb?RnKp#DbQ<0o%|7zm_J+K$243sm>QtGl%#>^?a z+lGc-jQFA(aB%B4EYolYyr!bb?puGaqe%5M7kw>Ul05laKEa;uvmZO&?`2T>0}LM{$MzTmm3 z(uw1%{)?%=ABeUSmLc&JR3Sz>|Mk)WxB_xmcr4hXpyf8&<>60XB~Bu)*^S4d?>Sx2 zt=Qd4_pXXo^eZ28mS^x9uSU)HWI0{V``)TE-pB3eW%=0hF?=I@>OlWx1(>mGbvzkw4xz0|ChIicq&r9_&G0o9x%~H2*L?y?_=Pjm9pn<;qS z0|srX{Yf(#<$9fVb-UPCpBPkn%Fux=9LbE!Rw@c<;!#9Shfn9t;;iJ~RWJMT9mH>( zpUvqmoshON{{Bjuo&1*stIPQJ9>rAOm^B}R-y_F1lsNPC!yDdxi48$tbI}Q`EyYk2 zQR21`+(jSG+kkCX;TRF4W{9aSq_vDcW#VW(e~=UIJLK(vW8OL+7f`yW`ZM{%xw1#ptCBddVqJ z3=NG@ZT>mPA-eS7@QjTz_Qc*(e&U`F>g$&SJkdb&&)7^!QY?=qYe8gb1~-8*P=}f) z_3y5VvY5U5MQ^u;_2XvNUZ7~I{^i?4NO8i0xO z8*ZOAf5ZFblu^(a(Gvar8*;r=fwxMHjmq^|KQy>4@sl>3y*ynw{^)^T1zwcYz>~c< zZvWZck{5XcZcaY}jd>rjnh)z{g@3@Iy_r(p_|m01@b(j{Z3lYzXUcB}d8<6iCN2PK z&kDyJ_JW{rysfmWcm7_0;oqT&p34PZckfZZT2kbf4H$2h5)$e?XNX(t(0yZkpeW7QySCKL5&m;`-J7tnK|QBKMZ*pedF~ zgC*<7713=x8+Te2<~pvWuPKwOtu``^)pf+69oX;XkqN4|Z9IsZ+B$$EmUQz5{Xf*g zrazU-9w<$rJio_I%B5{7I&nyrq~gR`Q_=B93{zg_oI5+R2fXbf=X}KYTqk4*+^CxA z=K)M!L~Q2`dt_&hG?h4#%RK!D29sOh%m+#;2}Q*&;S1B#44`h8%TPQ}K+>p@1Vh9{ z-yvq*u(u&*NnF>+BngA68Y700j6r>x8EaTkQPID+)G(lVS>gq4`?{^;2J*VwD z9l)?qYxU)1JHE0mob_?X#G;x1O(W|!+eyZscxQ{xjn2CHayp`)AMcc&T27~RI(lGc zJ;#ATNjHeU_*3mnvlE||)w5No{uO1*(p0`T6!+Nu=?u>@*B9^3$9?;SbfgMbAIBTy z)8w6*L#qgNDHv>I#O`bkIAl0S_RyVFZ%J5PK9nZgQ~0~Nfl5^{ck^*I{KA@rv-!v@ zaCk6_6CZ9(eO|-Q-#jgf2Q?)31%40KXIwyI1C9*kkSv=T?PHdrts-Y(LUmSZd=NyX zoPLVGhL3Gss}TNn;b*>(m|3n=66P>*ac>|}lU*j*?( z-`v`Q#3`QiF3=<3SqJwI4j{iF)wTfWb%sBxbVV9apcrF#uF`&~RfOM6iBIw_R)b9m8m2(owv8A^I0+dTM0EFNMMJRMb zDIW~?z=59b85cMql#C7Hc%^;h|6#EMW&=58JC?xghsoopN7-Ki#tURcv9W=2_cH)E zg|{au>1)0{1_}bjzg7ox93Bxs17J!(hCqsm`F*EqOtZ}5DP0h2#o_T489?Jf0RYs` zb_F~=fY6~f1^!0Fc+t8vTCrA7#)+sjuh0>9c0;`{m|9PuQ5c(PFpZc%fV&uOy>#gk ze1?&jP6P&ncKH5z_|URUs6QN~v>d=OYPN;f8Lkk-gV?pz$X=^Fj1JZ>kkXS z7+%%Yal-OKd`8lc()gar67Fz=eP$tCK%0Sv28=xBaldxZj`RDaJlis5NJr2m3;b-H&dYJoT(&=3((lV@(t+jmg6y#jq zop~hwX=Jf`9}3@@P(s;z$Id_aPnM#g(Epy9nfa3XJ@1je2dfYtXfOcIfV>rNf3@Ny zGkuDOSM_3=D6hIbajgsHXVemg(`2cie=OnD>QUosDtK2!QsTok%sfH%Xk5@!<~45J)~1$^hdP$O<)uJkwP z!gK`BH{eiAl=vbxZDW>H3H`QHVv){xIZ8E+UU|GJWl@}+8Yx{vP`3tNMOZN8P1LLG zry<`1+Z(uSG2XR#Om+#6y60ZAV>X$KGA2bp^*J6vF zXNIw8Wn&}R6G%&qx zCx7*t&UO;T{LH*{fK_nK07Xrfft@6=i65(;{B=F4pidUHxF!VA%9II`M_QCSR#c-4 zypO{xJd&-cs3?k=ZPAy%#tW8G$?B+UcUa_~dHDTNrJ0f;ihI>!V&%N)8=Vw4auX)< zxI$_ct(Nx3b|MsNr0aB4=LE78v!i1Imo~;R;UrSBN%9qwzs+8RB~qaO@99vAcW54pcdFF-7O6KdI}KlBv^zN7C5o>{%w^8ycndoPW=zL1ckk&C zhf;H9t4T0#-ihCkB#ql(plp!bGYQ{O^3?k|l|0quhe;c@acy zg5A#j6vWZeL4mZyPU5a|9OROvonES_)3Uv<=i+J^4+TG_lU$^ z_W3a5rf3|d`H9}M6TXsNl<*FkN|eNvp?;*2{Vs98fnw@)^3@+&`^UIUU6uQjk^xRJ z5;Kr_#9JdN*%_pgWpT6p_8@Oyx~vK|D9%wYjyv15g1%+5CrBu@CZ1p)bw#{I^3A!` zJ~B&TXbLXJ^=}gF+?gaX38%BAz-Kyhw zXu5HJi$e8*f6-{=OS@=>mC6RrON*ksE(K*p`q~ohrSBiBW!(13F8-!`?S_Ass9kH1 zKFJ^5_5D1w@12jr98?!vSOaAf5(^wAqNY9=Pr7vl+SR$w-zx5`ZhKGeHpSL@{-e*O zfz+?`o>REMBN!X53-&_spKhT zC$y^nX%6P`*SWAHM_v(riOJ0R5kccicdKuY-_LfNv=kTB+kL3E?7Z06au0JXs@L6( z@Zj1T#Ztv&qWX~oMlJGl1U;wfPqC%NOr2rOL{4$a4fpDBL@HeS*H$*oIWQ|_(Xm-2 z8|P_DdlmDSMRA8ETUNFlX;Kmz?wr|Vl#SwmBVQ36q~&6N6=Zu#igviGvvZR6c#;+g zGXQ@(_$I~Nw--H-EJBHk7fHCNSA`OF%%An43QXezqbyvyi4OM%>sn5Z>P|SV0hd)P zdoq;hv$t6*NW673E&iL>$mq<*hI?G@zJAnv#k*1u^_||{+Z*|~%jJf++5-;T#SOKn z=jt<|Vk4K{DZA+Na#7?OYs27!Blzfvl4AA?J7J+ ztn62b`ON&E|4$1rP^EwFiv;2L>jb*{(p>Gk!AHJHtFt}H(Yvvi40HBm(F2xM3KVDl z&Kw!u&G3BWo6+q}-?{f`rEzRha^sxeN$&o@4F~DMr-@{P<9?erZdyx-vr4?6JIlh# zr$HgDI&p@Q1Qmw1dBS(4is2JJHkf;oja9-Kji?|{jiv*-1AWSdmpXLb|Cq{kDK`7P zfwp1&04T*Zv~3s|Pz_3zyjM{uyU90*jq_JyXvW(b_i0kds6uk7Adv}bVL@vbO3R5s z0dpRKw2N|rc(e!-9l&G?9#Ni50}o6cY)KK^O0*JY-yT6KM$=bS75V*|^ex`_b`>31 z9J*&g@(M^fz~on1o`GVYdVs4%pspJ|30hBtc8L1Eb9ERYS^&sKdcokCM3clq`x(-} z31mJvFpwl|S=lg}NyB&&RlIJp=r3SY0H!HEhFl0rsKx|A-vJc60Qgi*T*LyP3*b17~J{N`Qw!%0FRN!$V3;_dpaCS00kA0ly6^LdiZ| zdM`AWKaP`y>?ybe$le4Z3;+uxJR1PLLFk_|eHKV>Di}bZWk$qnr$6gBLG?LILj>q~ zRpzM72~}p0wFW~KcmZHA+;^650Z9cklvBZHUyzG}z(OV^trn~*?n@(OFKuY;sz7Ul za0I}Uz|kD&E#%4r^pAv@0f~_5HIBBKY8DIF)BRcHMGNudL39|f*m%!odc}bLqstK* zr<$(J)v0X7EUU=Inv zgVC3ive#X#57yWs97f`(8FG|QnSMW-vx`r z8nBiBEpk9m!T-7+Y`c-ZIq*3BMe~d8vLiZY!q4a&-|XC%s)9i;;>9;O2pw@$+3MnC zPBaE-343xI`EQ+-jz5yH3&9FPv{e=PF|{S>PT5x#Il`_=et&qgklkb6s(=&!#T3J3 znyF&HSVtAyX*(>hLH9TP2^>@Gg|l=8RqW;gr-?nY83nT%+z8=X^%U+0oYiFyZu@%u zJz^P+qOXwLzN#(Un!zBBODYOLtMNSN$B>`q&Yp06pp;~WD@y9BbuqY^l2MQ?VD(OK z=DOs4G4VyUK2&ZbBCUPL%59C9_64a(aZnieMn%Z)9IAl^xTLTn^nr{ z-+48~UVINO<))3KF_pL~>X6fk3(y6&pZy!-5%%>ivuc_KmjM3EugjfGGT&Id*TXei zj4Wbewk`=}m#O6vhe#4g$g$s>hHy34&W8jNVM2uQ#%OK_l%9wOD=~Qvo%{=t_t*79&yE5ryR-o0@LC)@(@0*2N3irA2zoGIa$cxshUO zH^rYbkq$Kk;K>(P=&8l8sbR?%;5m&H@xJKV8G*X#N6tL9-Hh|dU; z2E?2QQV<7zK2{;u%IjKnW<|e!15ZpvOk=HQr2QXxBUbHO`=czZddMbcQV0Zsif{WDl?ZM_s>t5L@yn(;uTS&cn(du_PeQ-!Vxgk*Cf|icpQVVVW zyndB2XRiCzYxhV?AF62n@H>@O<6OBhn)SHT2FtqTkuHLdKisxXxe(o|c2i6#W|3Sf z)zMLn(^Zpd4nN%5EU=U{(9A_;$>=G`lZ|$6@ovo3qFR?3pcA|?gUx6;TPveVD{nTS`TS(|vztiH5_?-<^INf)y4ZvZd)cjOZ$wbn;ukNW4IUj5 zkNk+ATUXvm*R^aqsvLa3#YTFT${(xl?QtKI>md?LI!;s2DVvw~&U)UCDMT9Ob90OT z<7lXoNM+{i)-Bh7YzYmDp1}_*|8PcB?H2pBGc8n5o6UW87@W=7$yS086VgTGE;q07 z)|B>K$t%gfqI-uZq~gLCpzfJdBFOlEZN*+oUP?jImC4&ZgtX#ak!QB|Rge3bi9- zm*=YujW3_w800;C;<&X!hpvXt6rF1~?Ne5AhzZd*62oeIQ<>sF^U|>vXMm8d z>Gw7w7}Oqz;n$yU$cg4bBmJ2r88F*`dw_I5D~VUZvokZhDKMro?n7%Rq$+Db;t(K5 z^x+|oDX$B`Q2JjH*P0v*D}Wn7*-H3Bibqbf#zF?%hK7b4aUYS|#M1 z4rBlvCsBHRTYzOFnh7Xb{m+4kge;W2hwuYLO0c`yNGkzz6u!xKr)r`ZITiy>fJ9#q z!2Dp&Ef%XaiFBF4u&lc$&4y?fp(qRxjo^fVfdNDk2oDJi0n*@+)x!fPSrAx&`|%2( z`fzXsk=+`=^O9PHkSlt5V(%2#F77Y?ltWJDfSOkZoG5W9c(0oACjb@{Z7;YH`EqFf zp}aTvA3%EG6Jky!j;{e$WNLH1A4<_H{SIV0D3u-)^|p=zhcfQFp$`ZD!Uw8vxdqaXKkgPJK;oendEi_;^w9;os6bY9Akth-<0x}Hb;Q$Lm!cHNzqZNrH zM?%d7BUY~lY+ePIM+>rd!Kzoc|GsWY^6Eb!8?!w)=r9Bo2W)Dvh!BwWlkW?UNL6Yf zh{IBO*p;cUdYux94M$>2@wRirpdvxyL*eKTivlQn)r61^I`~LcLoFFX9s;ulE5&~` zFNih=&`N+ER~tEx>5%AAsAPr65ZLI=!PW(Eov1hOgdhU`>C5d>?N zNVBf1MXDaDD&1eV30w8j|S|WsTa2Z!%~+?Zw6x%h+2w}ST`%5NQX2u z8Pi6V+Ij)Act_p0MLxgb_W?VY?AXKE=@&06$vS0qJg@8++=h%B7PAx4&cTkNBvLOj5R)K8MNaG4Moc z=zWZ~-`7A<*j;_FND+Adfxn~&WDWTR&|g0=*;b@p!Oqq^^P=htod)8N;=NbxV^}B>y~beF9$lDUHv+p>~M~T z)1OlXOkSp8G|$hc2A0Sx8l4NYSLM$Hv~B*Vq~6dmr+!56^o~ zC|3hJwzACP&beK5x%d9cd@GL zP>N^JzQHyxeBPEdH-=p6SS&Imk&3#2F*}yHw2n+@<7Pwkx~FQ;AL8KNtunldlgMK> zd7Ct96=SysD$K|La|lkvBd*w;Ns6G`a+46TzAwPHn9A34)#4w;joV~Jfz~@Fl676g zH9V}6t)*TjccnfVr}Hk{R$|a))E(US<48M7{QA42_>-9K>4QkW@g4QkD?VzZio8}1 zH%{i`yvx=kYuorT)II7-t@lu;&tlGK|8aH;b7CxBHlw2|#_yqMBeeTaPigLVV%XHD z8*Lkkegn+5ZO(Hqb<$0%TT;}``S6-q`8h|M61TI@*Y4YhO>j=TEtOxtzy2?!(r!4* zr`H?@t+;bPvL&D&-E&1{4H1_WcN_VAmYMrAP z9;--@P|*dGgqnZWNh+M>iA{p0>V^wuaZ8xDt zU16U8nc9K_DMT9J(qg(W9!h800quQzNyX&CAVZRT2S}R>$v!B z&o?l6DhoM^7k$tr?f+qT>21$${&{9^|E5|sl*h@)k$Ziix~#L_6C0IY_M4t)!iVbe z$rSxR>-_qb2BWhkULt=TX-yV+Oq7k%LVdeV*>%TvZGymJ?<5#U1pfF{Fjhoo^?y^+ z4!YT@w1v6oo3`Rxey-pmjDW(bYm%vP8{q0kdYO=M(V6wKwdpr8(1Ng9KqvuPhy+3j zg9oh+`~bq1)II+7i);2P913B&xvz{Xiij#T0GFMV#PJKrdT4EI08HF{w)-3mPzZT= zD1k{;=K84~9bHw9BRXWgJ7~W?6tzTEDmFOiTh751LXxSuY0Q~f(6<}EJ5;%2ca@=%s#7nn%aJQ2){xg+B<;nG z_ty>5K*I)e`F?{OwR%#oyn@1Sw2{zLIEEYA^twCyWSJwan0M|(uwEv=Z(2AAw|+1` zaORr`uYHC)EvQXls!m87$$^9cE=Uk|5@#$&@ghl&ZNC?K92(U(Hot<7ACB_CRs-t| zV!pL}=xp7E42Nes<36-NmIFfohiOQyMDElui(wx?E*>Iq8L#m{e5uDE4m=}Py98Q8X6vSQa9S_T z!!AL6iaUlA1#jXxbfO=7j7X}U9i)RI`~(bh#IXWC56)pjop6A`5m*I?0gy@{8%2q( zqCWPMz2rQTuT9(`F*f3LSfITs9q=6D-l{HL*^=w$3B^mj2XNR2RtRPx;28ikz|OSo zF24d`K!P!-Qb2myqqxJ4BsMSytT7{H@4#!|;c_4CAPr35D*^@kQu!3+M)|k zWeb-NPWnW$Ahtxbg&<7?90**uFxi1}nuZq!iU+V8gHoa)l+!;9r~$|TL8{2JD_UriQ0Ey~=Z-fB}TW5nf=sza?&k&{- z7%7qML~0p6DcN;(S!f@a$>fc6KsKqu4hIT|;D6wqWhK__#6gw`EPwG6 zK|+=?0s7JWAO>X;B%pPWD%xQD24EqH>r9TYQyHt}`zT!H?7* z$>4U-kRYO4Ds$pz{MpRK7T>&)Ef(aaYtQT`zd7`$Xl0=r?KCMKDjPsR`s;p(M&xdR zpzq#2#NZ2{*8_GF9i$QlRJc%7j~fA32YgTgBx=n;BEw*Hg(Xa37GxH(AT^MmSK}WthFs7`1H~BY*v)*R?hCQG< zQ$wnLV}|srDIE5nmZLEXj&B9JY+LkYm{;7WqpGxJV`gq<5sA++B7{Wr` zK?V(<9^^8Czvh2gtTTJxU{!%FGdsbKt}+2BXWgxWG#*Ev%jFa24tlH)c`TOrZTKiC zRwsj>m(F3%O3>j^%vWbU9lw38SuuFX;oyZq*`@?46lpEKsXPBq8-?T_dJ6tnjd>-z zo3HJYv>&ogG8Fgnir`y<+A)S0eSYf7@Z8;8{iNc}m->`cXh+ZfF+ScmqBLZE5k#h8 zN?heMmS3%XSS2ENYjB53eY&^2{;c6B?7azfLn}-JZz%3h2Y*Val3C(=rAl!R?U>Fz zFEuZ90uLY(uA!wONi|iZLQ_9_vt2H|GfC3_!WwOw^}9tSRMb~jm9zWg*qOIt7DntP zS7NET`4UK^ZjeaOu|@4mUexgNX%=mmXd>gQ{1U~NSHoNS`J-rZP7*I?j$7%ob^3PV zJ6LRL?7PxJr5F({Y>YNh14Wz`F)_O?yvwZO<_*=fjS0j2sszb{G_5ry+Xh!0US5cF zf!#KmTP2lO<@Ov(@B8@oV^fZvL%CIQBGW_vIc~Bk6{%6$%tkyKTP(9xPtMU6ggVDg z+a`diDC*FUC56yIrSr59;=g*1e)LpPdVU-^xYYsXejbbj3 z$;fn*(@v@#>|u?51t(3pR8c?ZU9}$$A$wS)bT@Uv_de}Yea^Q;v?306#sn3c#@Dxx zyaF9V^T^@*ez%9F&s`IKbhC$AAIVdA0fKS@=Up;?7d52w_A-A4_n|Ra)N5DF!`cz z^$d3CbdA^a>zNyvxJO@(M|#Hy5x!bqN8Ohx%R!cT>&!QULoCyO>sR_MvzWx+_+nX!S{6Mc>`*GggOj-3z~%$j zo`t`0cSfIZx2kh$Iku`5cJnF9(xtCFz92AlLHoF%=Ceh$;gf7#BVUhfPy`W+Ui;qa zOL#-8G=8MNl zv_mguV!y7ZE4w~({iZHbg{kZFcSVdkv}C;UMzKx#Xnm5h70XkKUZ)~ zC@(b(ujkUWpoD}6&iCiPD$}ePCybAaE|1rQZf#v8=R(eZkYy~An}DnYmshHTVY^VHsW(5g?oSaWv}Ha0ML=6U3ZkZ&%nrSE2-k8Hp_LX@53uW zpC!7F_69Pq$&>yD`G$ivzmuj*#lPy)iS47Fb{mpj);nvh4;Rihj9PQfOJ)6*39 zb@aWj^EcnxD@~!psA6#*Qt>4>=r9?Lb0bvNKT_68n{IsViYdHYuDt4fSZdh;x{&xg zT=ji?#2+o1R|T4-g|XcN#H#J zk*&RCd#9W|Oxdj`V|`XNTwnNMWRnI*HgCU7OYR?A*RJzg**@jE`ly7LlanPrW5#2klqa#A%IoD5@7|| zn20eIBqW{Qpx@!omdr7ZjqE0K+SsjLCgJf#VcV9MD++ zMldzzHE~5L>o!3Pgd~!w_A_~)K_PWQV!wfCfhEUS2Y`=w0Yk`tBC&9RtzmL>;#g+< z$-)H)3PIKmL^z53M8F7^XcGf!1aKy3vuDyp#VOKY+d+VmA^(UH1%w7I0Q(Vmek5%&P`1R`ZZhfcqNw+C&CWdIPaSoVHnT_?QiLTH zAQW+ke8Y>SeTdK41a=MJjMiu1{Dw6NP%s?inn!aeHst9h-#(g^T{#Wf zA0)pO*s|)A;{$jX>YJZ4LtsYm6%eah zSjENn`|#Wt%L37D-y#M+tg7(?;_{-|{)e|TaUJ{>YCFPen)J$`^Gof_b-C>Irs#!3PBG@5>Jt8cG<|nGmH+$yv562e zN*sHHtc)@aEvtwUlASFy>~U zCd?Y$B^8a+`qig)jgo79R>Jl*}ap)6ctTYxJJ7VMrVHuzMjT8*r08yM+im#j-1Bxn*>Sv5vV zYZV;rUF{+D3_E6%aJ!3NOgdIn9QcR`^4se?Y1J@fq|>zL)+{W%A6Qdlb6v0dLHw!# zm#8|^JDl=XMsu~*Bt5jVYrVstI_q-&oX5|4u@AMaQ|EMLne#>S^_BG~+Y}xjB^}i_ zZDrW?6q+0^-ZHDmPkdf37NOa*iCxBvo$y$Y_$4vh{E=wR`jA;{e2`^2q%vTp6Yxb{ z?EdYnOKmPc=#t}D{!Zc_P|{N7##5ZF6L?!&q%)v*2gR}ZZ}&`Awu{Mq>#|R8o|b-~ zXXfsFg)>E2+?1-KPp+f0W zKi(J7uPrQhf(>czxh6Si(8omJEgFPonq(~5Hy1Og&ygv32fFv36Rw`m`!f_g6X-NOt%EKf-MR+Lf^St}#r-1f=2Vizso!y!2!>@X*16Ef-J41>ng7&HW`#+u z+j}Y*t)G;cI{$wz!0hP_qpx?bdY;XFB>!;hvC2!DSNoP0V`QfY&v3>(|Kffr(4VlS z@Z!apl@3MO`MbVv$!%Lr2HGWw6H=px#ri}~^?vY1bN5NrdFLteEMKO$I_Q_$Z$rrE zVcu5aJ+tl3{o)g8oBk`Z4_8ZwO9^y|QCPJZ6yU2c*?#l+1_R%ULs=)=jZ?rX+-=eH z@rSn;yo$kK*~t728NI8E3zWyx0=UReF9}%7x5uAURI%PuNNy+9czqOk>7=4ZA<=lC zWQG~-WUra?Q*IzaJ?b!EGPuf^pgBTQd~d-=6z?~n*yYz1k)LJezT}D7@eY_6{%0<6 zGfSzUV>FkG{mjUANr+U`)Ucz;bKktErFB3so)yzNnFyjYGdnt1YJ#n+~wSucZ)#rGMsnbuKwVyuMP)t>C&Q(=RY_yu*XzRC@L_$3=AAq0; zt^vJoBdP9j#$u|C<}4IYpvD0Hni;SKp@c$o*lyR!q2@P8mE1)F?gLFjM@JvQdcz1k zJ~U*;E1(ubbjKjP^>$|d_l4Oh(0al|xBJ(%rme>c22I!tko%)aH#}bF&hUML{sE*7 zFx3G%gUBJ|XKoXiz;Fg(qEJE*Y9$CDZi&B_3q!h%xeQP06F?wHa121ji$*bx>f}F> zy1q5?q(Yxl!|uXxzZD@Tm*S;FHCkm+=E&`wXOPQ1;QrvjgEKeI02Yn(FM^2>I0ow} z#8n)=DKvsPkf;GrJxqtS24I}|KiAB;r@+eqV~tn>6X0?Jnv4iXp>{*zhO)Ol=DErd zD_V+fkR)Rc`vso^5DS3pncl_lVNhyUT+YLV`k$ypOU)D%6`8v)-;e_b5((;H4yO7H z85tnrR4&jp$2)M%b^b%FLcV&EpHm7uo^yZ>3{qru+y;h)G5BvnsUV^bA zbYG+e7tGH^nk&S}k`uB8EZisev+FN3b#jWC$%6JWwbt3ukp?U+rohCi9*`wue1`1} zNM#X`Fl=E!gi{nBG0Bo1{)GR~UG);`xkz$&M=YvgQ4yG_CMIYX)@%9~2t~z*Awld` zl=^JfBlyax@?g6v_Eo=VPc#3XGVn9s_Lfk-Lww2+ZZHs-#-fI7!6rQHIw9f%3JI`a z(82yN&-`Fi40mN#)fdlGOVA+kI$9!4mw~rs>XHjf(o433Q+Uy}A32H?SQ85o)1}f% zAMtT7Ufwe#nI)tK*B(y9Yoq2?>}CIyBog>}ulluKuTx76GT|j9q`>n~ohcINesdvF zypz_{{JneDp~r~PUDI2k`s6S831Xa%*%Ey%8@py>#euWJ#r z1{60l@t!Fn|CRTZapPMnqv6HvOqbC>@wH+KYBd#4%8v=Gx>BhYbm<}jmvF^9-eY1d zLHr9;JC9!LUmwV=wsaSr;ko;W?$O$f*nbJ8k4iPX>eS*}X|;KU>ziCDp4OFFZH4|MCMCEH-VXwoECP)c3su5^^3H*{&IOvU4U+sR< zYQxR_h)UFXjF+-}uIHZP+DrDO3qy6c=O36ENq9&4nXxg43~3AOD;H~ae;0E>FZi9B zZ%nn|_QY>1T|0WszYpB71IA+KXW%If>c#1rhH%yvI zBQ%?m_$jB9@Jfk|`vhN-(iVn~ns{1uLJynf7i9f}@^+#<&eWkCi}p&*Ld``r9?yBI z3f*;F>_zonR$lQa4)#B_yvG@dA?r3!w&mk#-@=%PU#B7sAmi2fLUdcmV#u$BNeRZUT85^^Fp}kr$8R4?Z8LxydR>^EoLv;;$3)6P;|QG@$+J z$@K+aFHwZYis4y?yGYOpk}nEYVmPl$`}_ReB08Hr)g1P`z2e=i$=+pz>npv>wr^dy(8CP+Kzg1M$0?i$>$As}8jve-b6! zTGfBvFLx7*e{}3x*Vzjb27)FR6cFYz=nm!qxBgU78Dcf4onQRr78v{nAKi*(BS2jo zrgdw#lFKgLHamE0=VJdjIxXbFFyE)CjKk@)arT8;pGEfEQd5-VXu$CUb2S^v#n|mK zZ^<7^bAK~7q{)I@R@tNZuxZiW8(+dYI=*93?BPF$9tEU%68d~Q7H>-7`{@zsdOhZv zd*ZG^{J+Dc`4ZMPMwHhXbZySuzh)W7GgFjT=N!$3#zGpEBJc3Dd+k^x9YJNcDM81o z9J0rKRl{i`6nsd{*lUIrG0fR{^E_7}#feB4z-T~hArl;;1%OGWLq&wx3ZaMu7nYW; z!EngJZ|q_Vb^`$Hzm`*kRW{(cz)esndp-gPD$xi`;^sYu*!a@cnWr$;B6$a38hGrx zJ+>knHGPHsQ2fJtM~rlLWdMpGZX*5KQ;}(Fp_bCiAByW<7IU$B#IHEn4~%7Q{flSy z86i`YIndZzSok@Uy=ZYx_+!jXJU66YeDSf9$&pC_k9Ij`Kz`Pu)z-TQ|e zU)edlVM~>@6Z4IGt`8nOew-nfnm+eowar4@un!5d1g?RQrW?2;02-SGJVDSfjvvlS zi$UBa^bP>N1I7=uzW?m2UB7Q$Kq6Cj*Q0$SB&<4tISHD`w&Y9Z-rniBi(wZm|K~5+ zrEnkw6?A+D&=1i6!4-tY0CAjVI7M$I0@WudundO(Hf_dXtBVI0l)z+ zazfY^Af@*xFy$v=vjklXbYF7o4fJk{`EOybfXvCjY%o5aF-9yz{ea@w1`=DuoC(=! zIQkw8BW)E7-$*Dvtn0z?GbzS`Z0lpGAe4((E zOd{BnVU<$EMjYBI0nstL;wu{a#FY@KvX_PovgE;_#qMG2(*XTwSIM7 zMI=1{VEx~k0MxsoaC>ijPuSm%G#SO9I{fk6`MBh10{ z8*=S$eI2#r73Uy^#*$@Ot;A5EF)ju`MOx*x_*czQvMd8&2+wsZ3h@t}xeTsn?q^P; zM2x>j9PF%KQ)@Z$g(R^VTv)cVmlrEQ7Ce94fVyF63OQ_Mm?Z$W5QY^3AHm~~NOU0^ z7|D(S?leMJMSeYVFkm;g08E3gi0IE?r?l`Kjcb4f8Z3>}y$A=m{MMe_6d%MNi~od; z%N%n<=(~i;r88e20`Z2Hm`V#8Wr6&=sBiCjR$SouPkD4-Eeyi;7!OnKz99l3vXlq zQ;B_#-dm=BJ8Hx-4Z&U9@kUCUMW)*~1SuAHYV4~*UkIG$E>jgDXHFuD@k1EQA}{X>y3U_U2Gn4_E*h6-m`I@e~-Oihku~ixiye@ zRn2!ut>V6|-^16T&nWKKdaiA+aNn{PA_VWDW=Yi;rK;^xsWTV!p9V)?m*V$oP%- zwA~q1BRbD?Zj+eD@%|N+g-Rc9>Gs9#pAXRS@Dm(TZ+K`DwUP2NYcNwox=fTcsq@ps z)!1z=K5uKYYpu;fp7aF2+dW@-3#UtNJ^X2B{ql6*YA$VtW-N`Tg5}bWbj{^;&G4YL z!kcsDCW3J<>Dek@c3#6@jg#4&;OvxX0ao{Xf&Uam1=%Mq!>i(YO`9YE<2mbn zziYw@s2gs^dC6I!UALwrciyj zk0~wO%kXws>=OGL>&34=v$rz4_dc^&wefCI4XuTE$DNz&!|HTZ)T=zv-;4%5pA2{P z1cXQ*|6|KImwf2l5zgXe%a?jl=b5zcl7OQJ|1*+2g$|(r5uYo({43M;JO7;bHQp}a zhc!ERciN-1?@#QZRXIIN2E@a(Pqqkfak(NZUYCkjN&Z!>sB^Qc(bbIbW^KD}-e;G4 zTRGk>$D?FM5E&+3sw=3v?9;>Lxu9OUj}afvv@Yxmr+TBdnEt)j&R8UYdd|Hdt*G}f zbh2=-9c!LybFXqgJ`S@WHS1EWGhewkWh*ov-73oQ#~K`-HO1r3oM)%D*^=)} zrq40#E^N5_uY=g$Q0vk9tg1>WulK7bg-u@K(rw zwS%3HW>C9lTWK-iR!{wv!+Qq%rfePqQp&vMDeq5Tjdu^Vt?@Z&NeQm$<8bRB7;v0j z|7m#X0@FzdIxo%@x&K8#Xq>(Y@O{k^J$0yuxYZ zW*sl+tsbui)12Zyu-+Q~nzUsjSupCzBz=6P+X~HdQYg8KI*Bk0CVGHHh@M_@HnCXpsn5{~z5>akrMH80PE`4~iy>ju(rz zZyRPp*@O+jZ2w&bNV`G=mB5*V%8sP0mzXy@9qn()N2o;isElobAtmCG2`GEKV45SW zD4=W5lv^i8=(1qn?Q5Cx!ym8p$alrgxE^?fF=oTrpNXl$L4!(N!%Iu8dRJRfmb^h) zPOd#J>HA*4%n$NIsBp3G`$2dCFzu07xm@J2{PU!HE*CBZ835T7H!B0mCC zwlgcTn1GsnD~c7|9cYk`MdTa+3V|Eb2=BkZR_G-Wu{5GcZGcS$BO~MPIa6jN4IX|N z!ai!x9`~B&O8gCYs44|g3woq+0xO9C!8iOvM5H-i&`$G?C)e1>FJ z=!hiKZo@tb`aW0|WozeS1cDIbeIWZbX!`E!Aj8A(irMq$|GeAO_jmqW^4Vo1CV1^rwV$HyYMohrRC}_onEmtPv%2KCoMV5#5I#<+>FFYR#of4rVv=lYJZT7g6?qd9cdJ9jUv0I?xy<35lXwjHpGOB-Z>%=~0 zTCZ-8(VtICAXLJ%@S9362!{@ScrQtmNpw}KZ|HJPu#2iLE^>%o)lhIT+K;3;FjSfH zT-okahNMa>P^gX)n#OV$B53p&%U zv894;t@fMMP_P%r-8}F3+yEJyhe>Zl)W=zh!w43*RhzN*?-3?8^wF42sgF{}4fvN$ z5j(#|FYv0EJzf<4sbUtyEhWaMnsB6!zmaxmIdNKpJv+tZ3SqPSvj~#UVku3mbLyRf zlnFYF-b%-28OzC1dxT|<#=T-qT(Bnp+x95z>`6sKG%x!V+Z+GRu(eM+J;)tUeEL|%%wnC_!@4f_^m z7%kPwX%_kX8#Yq>t+;{am! zKgaDBK2FjKT*8>;;jsR8T?{Ihp!o`^r9@1xmDQ$H1NQIJYU?(&o8FIN zf8nA|uSF?YCk+adG)Q>g=4-n2iL*tkKP1eio8WHwQvdQvM%ULc0wquTZ&F7CnpAhk zbGdbFGXkHVwL3kmODHLNDu!FMQd4VBg^>ABwj+Kb^1O?erpoN#w!E8n?5#7yo!euc zsUoi>-<^+6=+g?5z9S&5*-Mew*f~hID7{_XK(zK#_AFC#Cy_kn{lSk^GG4Ae^;hv~ zH0|e!d$yllRS3!^iYD>f8|l=XXJ)Bff7#@~A&)M}J)RU3qvO)IeTrH6%Qxta64bOD zl^@;<3i~a86x*!QAN|f!j{o+T(r-1>idgCBWXW4Gj05Qzj@m+00iovR%r`^pBEnO% z-7_c4(Uv9;1$(!NU+1`6+D}^1afN+_e-D$D0Z-mW-gz4Y|9?^uR5^T8dSO7;s6S%d z*}loC?aDhF>V^qk$}#HquH!pBA>WcSy>`FwDQ1b^ zrT*8;=4f*v&9}ysXRTd&M=3^Ip; zHd5S0TMhgc0m`3%Y766L<+C|zq#D6`2HxmUo&keD4Nej&al~NT0J+r226^4CX4?*; znGixFP|@5v*;QeoTq!XBf z7!#ZXaoS-l&jV@O&p{pxtg{bnAs!14Qd^DNY=|dxQU946!KtR;CjmM^;Lw8-0ji1_ zX^kjVsslL+2q6jD%l$A6SGsTVB1Z&wM&LPuWB}%JBGHKkSW6+G3F7TsW>BE476zLN zU|S$o9KUVBClh2Z2sg22FRdmFzzb6VN8n&E!~)k62>Wo0tg;Ni{s8a|1X=)2Anb<_ ztA@hD$qJvP3Pi#RSD0HB0x3d~z|{XDzqpdypcz6!;6Zf?$8JBqp=J_DUW7I;{IN+pah1COvrZ_gut z0xBk;RKGFH3BoFe%quUlOyV|2yTFWOUzjo6(DC?n zNb8Wjlq{Rhg@b3W(Bz=7isJ^;NlRKU=xO4($vXXhknd7Y;GJv0@j^NDUiwejFpkrr z_ExYy(^4x*xb!I`Doyyx!XH2nykq`a&Eoy znPoV-h^X65JeMwXgUkWzoot`8>ii})j_CEw+1FZpNka9nF%hx^XhK@`)Cun7(YKKU zKZMBJte!h($=J~U&0wX;4waj}AZ%gXi8>fG+ss5=n0xSCv)UuE;{kn?fbywKv1=Zg zdm6lK>Ze()$E3|7oF_ydxKt?2D@NNA_#3|UGfylv;W675iwn&*$DQILt)U>r?`rPW z^9Im3N#3cuVr(Wwb1Q687)5l?qw~tM$o;T~4`|xgIC(;aZlg~RabQ?7jlX<(p}{W_ zn{G=_W5Me&Ec{#K;NL~dv+EK|{(}k$m!9Pl6a?Mwq)+idQ%@*i@d;iy-Q~B3-$`@?(owGtf9 z&=$9|$8SG*;MS`k|F@-~jja*! z1KIvCW2^G|zY87cq_CO)&jmQ|AXE~Em&}~lqdzE|=#tr9fBRR#<7Go($20Uxzil?} zwH$6<4Z=^J8xPwJ8N0>AU)(8i^xB#$KW6>xT1ZJ6M0YKf=*r$y^yFSdyy>Uqw3pnD z!UuV)ZTC)=pB>zbVJG_5{fF(8^E35Vt34zAR`X{CbW0_j?w>Lvl3KZaMqGZUVyBj_ zykW$$_NcWuHopPY$WRtP7;^reS#5ZOMqckmentb%lYRbD!dgg;?+*=9T8Y6Owx5IB zWX!B?{|;n!15kz3q_5qdZO~MD>#6(hWIgpRw>z91u6?ojZfK#Kt*Gid-=BbmjsPVJ ziFkqqT(ss;!eeP^n(d!%`Bm*$qCg*p&6=(kJf7YM^+xqaB75&1dn#t$J=k0C^WHX^ zC^x>Y9v$N2X>>g3M8-!5sc43Y4|ey6QxL%OCU$m|+G>Ds zgL&^$Sr8_GaR7qF0}c)TS%7sS6FG3wf|!i3edq2n$R}mV14|#U=p>eEmz8tyNjn8! z!Cr}U9!Lsio}LHS+G2bRc>@s@0n{13zKV*9oyUy?SeRAC!^0h?0~)ByVWW+bOXVKt z9EY|8ka$zI*2t)bj~$h4m=tO7#chC+@Z*?&Do9I{6n!SlthhsMJWA!5u=1Qast~s*(fL8Rl(e@}#JT zdU_LG4+|J4Wp3iM{b>D_1R)VqbJUzSzV?44%vf#;;1|5%Hw(^&s|Q29iU7#xXq&|{ z!!h8F4TTXQDgfgjc>NPyUq?lt1At4AO3+fY17JKk2SSyEGl`=^hT^eh+}8{sQbJN~ zB1V*I9kI{OJYL8gtKm}MU5e~jZ3c#Y%DOYq5}^u5XIq49zw6M5d9nCnRpAK7{CB7N zsIy{xJU}SQ9PT05LxF??31`@%p<9Mo+@3 zuCx!8uXL95Rxea!ZQQXeR9nHs){NC}{WPmb+-HA)^<|+@GTiO2XPeo%LKM8KoOHV-y_d(@G~O0M zqdadr)wL)6!5*PCJeGTi+=Il{?H&OJ$uY6a{dq4HP88XUmgb|9g9Tb+f_T!*KmvgQm@m8J7oP<5H{{a981kmP96J> z*zXRlAPJ6>Tgg6mg^ox|TU%*JIHtrK6F6P{;{nmqKHbgfj<3F_=lbu>pO{2^1~SgjgEHKG*WH1@r(&#{0;z&Deom$AKfOEIlhE zguhAoOhEWutrz~|t@^3UFKK^$KKS=&DTb<(ZkGD`qRg`SuTG;w27mKU645xJquWvP zRR019lAL8|8R&1f-}8STV9IZlPRXP!*B!(;d#&)CV5X}BEh=%EFa6sSJgTu<{7mY& zbM`17ulTmU=1`B7wE3RVf?s@UZRAi`tBF~0pno4hIZ3t6nQNz}WZ%3MPQSFP?Lw_W z+BR=_c=^x1*o<v)m?U8Mx_WbhU<9nT38+8z?{DURTlq3cu6m0M&!bQi8Kjk?-gg?KLbj# zpHZUT9oz1Lc`H`4J4q9J5o^so_tN&(hY0SRwo6X?pvA6!y2z=2I>7#Z715*2$rRy{ z%IiY$4Jy1r>BHEuiaBoDNGXN)xX2uXs;733^Awz(F|a3FG~Ic6zty%jNO0*PVcoWK z%ZrOa*ir>_U~t0cCxKxflx_G;KVy1QZqTr%nB-S4**-`!vi~Zn0^kg0y5o+xVwT=k=Aj-yGv_AG^(b-E5X9in}~YIa*fw z;!afjxe58M=RSg%iIRITHXiIgd>NNG6|H?vnO`M4`#K>GLW;4p6oD#e9=~$ovNx#Q z?r!q!*U%g#C&TgSgWTdH|DoOZMIxV?=g&wziiP7_uvo>>CmyW(18P6akI6nYKe)NS zw@^5}*iBw#$V@sfbe2SA zHd0R=)W#?jOod>?3vedZ)ZtWpOsz2Y0Uz!3t#A=chS{%bw5{TU%R`!W^41+PdNj1P!m%27Uls0(*O*tx+%{j??~afSBmQKsabG z^+G7!4hA}yL*eC*?$#Gct_LYwc^?E65Sbi$!f*vpFJw5tR|IK6Py!uHrLYHXzsVJ7 zdY$WpH~1^y>y~R@U@V8CC1O~KAi7|&2oS4SjG9^)|I2|LxE=rp0ALR{B!$8nP-o-a zIwoL@`$JWQMK|~r0o0D@>8!0oQ++c$76tOSGQfiY$YJ1?46y+|NBzDRV5m+lQqeAf zjmB@=KmUuN2z?XEH;+uvlIP%5%y5|@DXa1|)^y;EvI)c;f$R~!8vKVS=AaluRfRhM zditLL7{kez|7Rr$OL-C$>s1#jxWR8VGm%hIhEs6oZh*eQ9O{uo3&Pn)L;;|lM21`> z9s=|VNMG~*_u_XkK61h+bN1vdwRhjyH*4Pjm0&hUs54t$d5NT)E++Ql=#$M9896yB zR6DJjxh^yYaFL@^2kn!(;5f`!iWKL|X&oDKu%!S{g=)yedV2fC_nv1H{{+(k4IwD~)q7^U1r{$L)nQ4;yJ&|=Vm80($hRrNERw7R5P z!7-d>gBq5de{v14#9EdbL?tQ-TvWup9*Nd|)YeM-P?vN_dX-)#m_p7ov?w<+VlsSnlE5}l}rFbRzgzJ z@bLy6 z)S+X9-p*hI#ZU8Z8cVD-kO}W9tW?iA(lTD+V7=L5XQgmSc*E0#hcs}2iFhbh02}GR zRb_nsCb=?KGz&5DKp0wIq}|@1`Nv_06(1#GD3-gT$Nq(C%o|vZP!U{a4emXR6P} z7-@fY&HFR?nu&b}PhCD=%}F)+Q~Y7AdHZIH4QqV*iZSQ3j7ocyk8iw!-RUifzpmR~ zi2Y0GybWYoqzVlGco)AXa=!bp<=%+sdQ-T7Zj=~AF6F1tcURvX&Qr2jL-7T#w``u# zH0vekW<__1?GBuyEeyFz6*jIXPvte#a#{Rq2Jae)ACGy|QM(8!jhCOiKDs~XaB28S z?uw_}-|gZP(PwemT484BFmq-uo58}^{c>OP-k;+YM-WE)mY6LHwmi9Us4?;3X9d=5qe3@ zCYeVrM@~sbWV?o`uEVY7(_UWKl;`rRt{0AP+eAyF#U+ko8(uKncwNymL|_|;zEK#h z+iHaU$7lZUp>1Z#38t57f4g?_e6Pf$~Bx)VSb>!W%Qc+ zLBR43!Kg2}#1TFrvd_duEv%D3 z90Tqb158{q4HJHf6XC4y&w%x)@9ZTv#A?vR>ezDyQBrbRb160eQ zN@r0v$PiO(1gSJd5|mUXUNDHo_yt0}hBJ8{rs0WHAAr+Vl5JVAx+75W#|D^>WBni%nL`kfRNDV3*deb7;OIsT zD@2+O&d#(qH#Uudyq~K2QTGFERZSqY5(dv0?MYm+5pw-dL{Z^y$N><&0bDuIvcnP` zp}fw`!U${^6uSyIFSXZGCrYief~esBz^wA0D4H}o|ou+#>t9cXQuAoVGVT`>x{ zSD?%{tno>oIaWz3(*5vfdu13F-Aa~4)!XL~YFfpZ2PF-=0^(JOnDdRF9E~@3q)D%X z`=I2EM1#gZ8&bWv-%DH9^4q$w!a_pGfe{(pY3K#m_`_B35-+EWk2jL<7U+VUpoI#{ zAi*CD_Q}u06ZA;D7oXr8lwV#oIB(PJ@-_Y3ML4}Xq2_WBz~KLJ6X9?m(u3{?F&T#I zKxNBwvjLC;=k5w1EW)J)k7$_p*W7;Degc%8u;B6&h_eQBXfPJKCJ+Qq25CXFb31k$ z=6-HffACbcR00KFu=XPU3T_vOU{1>eVwT&SIqW0E%!R-~WM!2MUsUx6g9Gn&X~Ok= zMXH_iIs#Gql$6zCAt(3VcMgH&}OSBW&ioo9m3?@b`dtr*rE0tMzl^<2C*M{Y#BStJz;6`qp6uEnU7m^Xbm z{>0SaMfd4pHSMuTqCl^bTR%?^M^F5|@Ga=(Y1a#sd1zEbms2C2dsTkzv9~B`(RQt| zX!k!|!4?(t89qBz@n=F}x9|n%i5i=j2R}?WxSVa`8i-&2VVb`8xjObenc1C^gH}Jb zN1XT9#ageJdEC9d+j)yga*MjYloLn7M6$5|g2FYGP;^~ckf(TIEYL(&nd~JYd$Xz| zrKmI8#6GIzQ{}PJQ7v!P(dW(mbko5z2fN_}LnMBeY*?JWk{EscIcI8(4Y->iW^Zw~ zAr7Y$Blgr^AS;R}tp%+?V8;r%wPapQ3^pW6ZCZJ%QnV#RJ@{mb=jijKsGjZ1qaJ7M_HJX0x)n$*_UBJK!)|7hUA&uKfhtQ*!(l(s1shD1OVP}rr?#V!y3 zy0yArh!kbMJ!M7Xyz{t|L-+?i`ErgpF;&C{4_e@_+RNC8z>>MaGG^89cH1qE6bTv; zYUrAZJChPIVyHkreyPqtHn;ZutoYB*(fy*WdNtG$uP-*|#T<|}3sI_EMwQ|}M{b^Z zxnrQ^yM?MIw)~fSsTW;R{tsvRTdiyfm%Cc7R3@6$)<@qgG!&t3NiWcHb1Jga z_1otSLMy=@y&4YQYpTbognv;DUzlcZU9W%Sd*ErM2TtBPQ`>+xjVbCoR)GPb@#@z`T( zH^ZzpO6jl-IqH1g?E{59rJ{vPj4$n})72R% z4MuBkO(Yw<^<~2SZT?DQcb+TMq1V$18$0FGetl@JdU2BJd8PVs z-tZmtDA~Kx1!mRtbnjQ^xsJY~w*Q>Hk)=l#cp0xrn8_=}JMblRG=M>Mvf7coNwhTi zr7t}{PPT!TU%z+cA%VB|jl&8>xr8cW?7`05dcW_Hd{MRH`wO&=3O`s5-8Za8=3P}v z2BN*bo8UTn-t)Mu24w8TCazC?9@{E6zPI!^W7FGUi70s1Sag%!f@@fUY(I3C$gbUP z=j-__GVNa(ODol%_g<&`upWt=O8M=qO*g2mkSDb)zmT)Kl)smDa-Mco@$cWOnK!-& zD-37#-!dgEe}Y@SR_f{flXY{<-0I5{zoTK3)$O~hN}e^F3X4?=cQy~MR3DFAojwpZ zXnuQ{50#(dVV&tn3DXjk!|fx{QI;Z2L= z(SVUEqV@t8IE0A2d%RN<4U=c-@(fh8|67?NBxR7abs?r7!2N-AxJdw<@lb%^&0E*w zfsO5l$_g=wwVr*WA)kPKk7(AwlMbp*(f9pDHXGqmn7S?Bef2)rHW%*C5j7)5o52VGEp43>rjRN)11R{6ESRNsU)qWz(}P*asbZ=49#tl2#0U@vgW+7u&^nN z$FY?xA&d}+XGv+0!1V;W5a2OW&4YXmFcl<=AwU9_zDg6)W0WN2?ZC4MVv`ChVD}Yo?*m)0bG(m zz`i*GJal`hv{%wlz1cocbM@*~xlVEpaQ1F^Aq^*m{sERM&;cS^M1=2PU|`1k1$Ot`s&3TRsnTF=Gjj{{ z@Yw10Y;QK95-Kx7slmE%lGl%v1rvXS*=}aW2X1oPEu4Q{jB`y)&Se~P-xm9WxqfrD zN2Gkf;{9g|(MJ5`6+b#jUy;Duq;Ct=?d7-SGxe|2XBCF{HSk95QSTiek(efzPzD|e zTiktSV294W{w4W$FZT0};Jax9JqivkKJLIkT~ZV=MJTNZsfSVy zwxis7d&fKpeKB`*!XJh*ec_0dyg-~Qxsk4>^>8-|_0Xk4uk$h&|H2a{ZtV#U_Sb|c zU7v8xiyXMbu-;Pygx2|ItWOJf)D@p%D33znVu;W9qd#NfXiaHTrya6l`Ge4*8iPa_ z3co-CbZ2(HaAKm7j$kmYNidVnor~sb6XX}oadIsZ2AY>CFA-nziw)R{JE>bbzg#bh z()d#(EY2Sh_hw>Br_w*c_e+Cxy1I_P-ox&@r-n3q_&XKBDLpF{uPrnl7lV&T-9}M^;QdcT>V>rJtF1r^5?eP3j*bHXg><^a^ z84P6@i!@{EqIdXcl5KsZ`xQg6c=GIZ)|2I!H;EVcf{4by9#1yD{dJq&emTTw9L{5Y z_C=O>J+s9mmdIdu%9~V8kiNovNGNHbMYzXpN_hGq+p0}cwY=B z*54C-&7c^qYAOCsqp|(zO^s>~8okb=!ufQyP4A!h4;QYobk)Qx5!SY5OEUAtA`=Dwo{z)oQBBQiZmsG|-)k$rK08-Nn@3(x zk78-dsnyM2r|MiRV*Pi}R`3GX)OpJ`TAGoya$0?}F8cW%O;_MnxYd(_7&cPL?}J?V ze|;vtH}5GNf0=RP^)T|~{aEoa6IbeMn6&@cWb6##U1pBf>mSSMn<p7R+NG~KT4rGw17nasn#Xr1ZZZFVF2Jb9AuZj)hr2n(rV z+$W92(W3z7XXqrLk|MrAphQ0)edjfDGmDsTlhzs~ssL6j)EvYCoIjf16{wPy4X+^i zN8qa)--5*Gfn%+{3;F!nX3JU&MPp8OUR5y;s)tkrj8Hwbz(xnA<8h9x-%u^p6?s+b z@EYSx{e68-8`G+=a5V??8$f2zk%K25=0EjwEy8dDU$qG^uQx@{gU2s?t^a9%Dpw(7 z7rvdDxp{z}6EOo9uawy!XI>`25r|?6w10qVfOrcqfc$-$dfLdF0jtkIgM~QK0d)zu zZ%ED{u*V>}Cu!_8WFSwlmk|7{yYL^_4L{XRbxY$W@WK$08G;ob&KMu_01lA#sR^cV zQANeBb34eo8(A}(z|rBaBI(03W*fE|3 z7(HY?L&M{?J!rLF0Wm+(^^J-#iNL@HmKlH$Ldl*nXGEDqwUa|kN;Nb0@WLjmm2+kH zf=qv4Ky@cJ^5q3(a}*2S9H(un-v{-USP74EFzyq5$@#Y#wC6aM9DZeJFe|4Y0xF-I z0H6nu^g$Tej36+^HBmqiOd4JRADq@!wfBxRP&J_$fdnAvCZS_ytjc+#7$u#5B(sNW34l1=x&Q=K19RhGv;(~WVxFt1u*Z!g z9d&ecxLycAg!40z8ETaNSo2(3#C%3e4L2>;VtowsGFUMI6`)zgtPZdexmC1f&;OzW zlK%ZWSQ#2R2U{aR9av;4;CF#99;729_a3@Y=&^vaH}`h=ojgIkAi(pqH)3&x3Wt7c z?vjKld30k5+!mhF<4zN0)tW=Kv)>FSBk5zv_8!_gjPmxES6K6L7d=1ItsxNps=Jjt zFeo_gTpjNaMQ%c;ynBRQT``YJK{f-r;Cf>DqqheO;yAlxXE+*xO4l00~|7de!6TJ7a#SU`{=$FijZ=o#Ptkp z#_;|>%72ljWnJcU(BsGvEz!=F*U(9-zN5?;3vHK1kBnH@?Da-1imdWLZ965di)(93PRt5sANZbY<&q^LD#~W8RnF?XEh)bQCw^4GE2b_Lq$;AVCR&6i7hG{2Kcv2;=FV#lX8ThSLNmzCeo>nHH>UWt3l z{h6cwCgY~@O7)$xGx}%>xiAcES^S-TuKx2!nqkg=P6-lZ+nYVAe{PYD#t~(oa`34T zpbX~fCaE;af5AZhoTohOv~umphqe8fQD=KO2J=6S`ZX&wD&@Hfw-2&PCs>l7b4(bm z4$2v$?-6^T7|FjWXyEAxIL-#D$rVRdMbVx!P>J$w%6#ths`sh-91aey?#HX#VN}ztW58X5ugGehi`Q zgy{M2I#}@n9qry%wamPC%F5qUaa=d+Y@@^z#=KP0$yeyC9Z3urOQvO1d936+Caglx z#g|_=|NLCBd8VmO=?XhJ`Q!a?0e`8Z6h8~GfX4PDy$Lq-zm!3I7 zvr^@||Lnm+VeV%wAH!$sYPp66Dr9JL7TYA;ZFL7y0~Tg$)w`)DCM>f!Z+BbYFo(9T;M1oe;U9$--L2*|nbq-?*AAG4MhmO4yiOmb zs9tA=m`wYq*ZMAPWpo{VpJmqE>64ATQQr4$PD$_!y+X*t zoqY{cyN^{>xDOSssjO^6A(Agorb8OosP}o?m@{cs=%tL3HwaS`=nn1~79@FPJiM7xs}YKZjlsarau8cXB%bnbaKA%^z%!eY zP92y4;68$+>$%i-JK5@}g5|3aCh4~%j3_A_e$*4iJT&)J4M@6uoC;;94Ht`Yvs=Gn zgeC!qz)t|%4MAIq=0&d^A4|m1i-$pNhQ`Oq2SL2)y8vnL0Ow**=7YAWb59q-eSt#< zL^mLyK|3%9nyVgNXdI$|`rZ3>U?~SANYI*~^iAW_8=ppkiVKElr0alM50fFNw3Ys6 zr4C_<0Ir8G1H=#9GDI#7QfmY<2R;H6c0e`I$VTJr*i#ZYo8U4B-U09>o|bW?u2{+n%(qXTjcA5(LFQ@P@dnf(tnG@kqd!2-PAAl&>HOCd>3S#~=v;3+SI8mV0L)_+@OqHaw!LuImlZAlaRMqQ! z9{~aZ)i$8vs73&qC^$9D0|GMVs6%f@AH{Z7pIuiWpKK1K1KfuP`k&3AilECdV1ujA zf1a1%v+b9%`mT|h9qZzmw!(h-&;!NC`d_Uo2ac&$B6K*0b? zH_#!#!7hEuNv6`M*3c$e6|)l0hY@Ob`pc}&GDKsqu8!Cqz{(!lHn|}z0_mE*Z2N0h z-;z5Upoxh6lOD2*gic*!D!R@bE-geZ6~jH59Pw|mw!Y$%Rj+^X-D1ocwNuAm2Td#7 z1-+iBbzLvtUyWh+$Z7P`^A8-`Wbr8YjOgQHa*ypJk)jtsT2ck z*s}=zBzBye3goI+B4&4PWqjtlIvBmw!>{(UDSw{OUPiTrZ)#DHIfLt4w6Pg$jGQLp zzjgteOV^ammU-WQ82ipJ$y>+{&n=sDdjfhd;caZ z>Zk43-|&a?-+b?FLB@i|ij}t3qay0(q$u)p^*gs%Xx5La$M0_0_`l)3ntGo!;k_vS z%kRxX9zE#52qUr=J$S5Sqwlec4{m&oAJvaY-rSwIma5M=dzYC7L-hv*a~Eb(RSk6$ zA2S9%jZY52yKC#T`?fcPvT;Hch(_;p2wdT|<$J%KDiLKRs8an>tNmpNhX!rG&GCQ= zR#HVIE=I0jRmH*Jb8LR>Uya^vNnCQwzS(he2beQm{-WNz%_O03KTn@yve1jfqEu*4 zoJ4-KU3L6Qe9xS7UoYua9=01DCz)#x|JPeGS8znU#Awu6FbJiq1)}EfWDN?M+{!9- zQ@05!PiYmk&&f+JvZ>VX$Mo6_oUAJ}dlEF`In^I`%~jn(mBO8o0gcP5k}6F+l+!SD z9yrixMcl+k-`~T;Cn>Hqud*bNm%To=pVD4(+h@<#Mt$H_s>o$_K2;(Y7ECvt5b<}U zI8PHKvr@};uU<=zJEHSW{5-8cyvDrl)l_vuQQpY1wL|4ij-?POzdH@JYb7g_;Ogss zG|}gACkz%Wd843e{7dV;*_|lbk)`QyDbKlMTUxOjnMT@9)w67vv=6QvD+F`n`03>I zR2JnX^54$$?+Z=*N@!xX-5OV;)Jm)xBWV8Q6l?X`xCG-7XQ&ZF5rxzbN13%XOv{Vj zc>Wyzc9h0z9&nz_suF;b}gQaJap<) zpz|NPZmo&tZYzmz{5+P+JAZ0O^XJc9X7WCkKF;P|Ybosg$i?f^^>KqD-7ovFA5*vB z`9hxRQSkFsYxUr@$!a?9{^z$$W$JbYBSa<+?o(C8Tr$cq`eI}mV#953CTi3fd(a-(p6q*ndgb=X zhn^bYUQuH6@xMusEexa`>sj^=X;Q_r@w2xV%rpM=eFwO2_b^)h`syzX3txpEUU%Tu z)2UcBY!q0kei&!b`{}KiW9LLi`j&QYg>-hJCb>{ci*$bC_Q%_|YCvSYC$*BiR`*R< zhosNUO01@@9@~xnf;&_f@6PWQm--2Wv^6Y|dN?^XWph*r2q^e-)E)|(=hvUI3khT- z*5qVUuVG*R>FY;PZVeASpaNaztIbxwe0O+BsDbyYEjKqqmq5c5ubCP*qCrBninbgf z&glQAj7CyvU_-o_wGn`exV+!fl!{~mJ94qdfAJ7{5n>evKJ3A5i)V|$=XOA42KX2h zMToP>;cr0FO`UhXs;fpLiY(ZeZhYDyfnln5O%7@d)HlS-gc;8j0DNGKuZpiH-(JA+6>JwG&{S5eP;9&u^MBoOSfW0<(FhHcBhSpKFokP*9sX<8qcMRA+ zLm&)@yE5EXMysrPETQ-4S~ZsL?g6S5lQ&GjP?yQv?^fxn?@_ddV4X^D?G9*K+1NzN zX#uh71+R(aCaH=#d3pp+C`^Mek+wd8oh_UX*dDVI-7XJDHnv;ZsuobMQ6E|s9*e^w zeGbTK2$dcPUr1F1DY4EQ@tXPo$msZ>efec{8Zco)g*}R=vF$*5-*Ds4hqX%CK@rMQ6 z9?{gboK3U&cAECdFCMGO4_*v9LSduK-+Y0e;1up2!S*KbkCFnav4XEhNP-`pV^ zxq;hWE5kQ%aGD{trnnC;U%lrgA{T>nfyilSGyw5OsD;q2AjCbm0MN^TEgn)eFYy!I zMoe?T!BuVwg;*GNc}g%a3O$L6I+VCsoC$ut8zAWeXS`f!n1J003_b;5po72B`{X%y^H4C&k_!zht&~G9h_J|n~>?q*JAddqS0qLE< zV>%W|JVJttAy?k_4B@D_vfC>c*x;NMRGnas!`JX%=3(nL3n2XoH;8W|>f)PHn zu#js2zaXGacsdMn1)vGQ_1p+LXv7UWBweE#IbTq^pp#&jyB8$S|Kt_g6UT0=dE0x5GA`>~vNPGF$e`J$7QBpR-OjCD*afc}UfE+h2cjG68&4MN^nbq>B z&5xTx+WEgRmumG@XG5Z|d1&H{;Eo@@>J#aV?R?xahcAhv0j4VUyi|*Uo((l8YXtc# z8374n9}oTBmi;3461-nN_(p*1qk5~rQs9%MA6T^Ro@)3GNy58Sb^hFc?4^FTygt!l zyU&t|cX|KZ?|jcV_UYZCpa885v`mISfsSA*2};Ghsuhzc$|8dQ+4c1JR< zC7*wCb;Dh9`&fA63};spGDy=1MoEvFOlP^{(Lt&9ICt$W>F-!(e5L>TEdM&iL`7}PjfbU#srusT z6*BG^JxsV?=W3f|jQA><6*=%PHv3o@B2+ zO!8^I{gay0d%h6z4F5&d*+7Z-g`@P?dm*G>a~<<=l@*h3iXLoV?4#m7#kF=F%5}b? z+D~xUk~U8Nv*Ba6e>z?3$oEtaZ{qu}(9g!D1?f(sSHGEs%d+A*e=_$HlxhA+&Fz0W zg}zo`Gns;wADQU5a71$wX)QA-;n^`gIaYV?k=ddgw^X6mMx(>_;@z9V0#ESQNtcfE zEA+Dk@SYAzzV7@`WA9?hD;bX4+xQ(fxDDM-sbb_{)3p}CF!-=CHAHJ zKKMyTINdA#tzi{=H$ZPp!1Vf3%RW&T(P|Lo+z;$7m_3#pwTXTD0xO)CtVvbFUK zhAauQji5)qryGqk23QS#qGaQCy{8hMt)JrAGy)l&THd+ODqS3?Y%D(6=UQdXS;}2| zR6J9`zf7pgU1NBcqjSrOZD=F6J1FP|P?LiR%(I!IHk?0yR^W&L6xm|`k_4xK^~17z zL~0@E&-Coo_~|ORRYiYyeA!jnE4Y8(U9|##5;uCb7$OEUAcO&NONSs*J~UaNc@IRx z6KmVan5x_mhiCgJ`VAi9ua%$j&#Mt0hKS%Ad7fSzS6n~}+ozCXpl!sL=tdkL|GJvO%RjOi@zI8@%mkp4(J_H;ILLXrou=PbsmWqXl;u{3S z!9y6)U(<=Y1URIB{b~ll1K_JUDee3FUIemN6fV^a!)Jkc9lYRp-~|w`m3Rfz|1_h! zNmwAe1_T^1U1Q!nc1v~o} z1;)jbSpQhES3M-aL+z9evUq1<5(mk+99g9`dn!oVV2p=xaTZCbhphsVObbu`_mhsW zmMIl(7=q!y zP|JYRj)d;QVZwyU!NGy7rB4sLWIC(+q+@|303QaW>bGdnoapEi&?UoUYqc?lOB2eK z$0b3Q;13*0pacN zJ{OCFa|N7xnB)n$uZG_b+^0)gy_*y<$Nhz-;mY$VxHG}P->?ipx&dW8T|%Rd(vTi!z^cyr5YucWm7)gwmYWM$g2wcm@{x zwo3Uxu>=SOtl+@2&VM|!lR?nTB~#YHgW=-VXLkH_0Vm*mAZiF$gV^d746>xJx;xBV zv|M0hX-r&Y`<)aJ^oziMdWKLiFZ`5V>}-$f-SirLam3ZoFFK19nbdPw^c(jC%uF`yy$Odc*7O7VJ zCOeA2@f*hW8yC8N(!B8pExKPA%6gj9T3&iAn7S0fOPwRzbr5D8K$d!|R@tO?eXQBdC&ypCI)Z}j#`m%$HBzvx|lj~+|C?Q6aAR4fUJR{7QD^bZQ( zUhwD99AVXpv+>|9%L+URvBrPI@iUY8=N0O=MBS$Hr5q{~{50I%w)vTorb(X}6MC)| zrq+qm~}&zYHS5;oUq6lwUkn(IVOj`Ys- zuN%##B%F?fcJ-uF`8cWTD0kGb4=}f1WH*TtCe3|V54te8-=uM%-q&n?#T;eHKZ>Ul z#-*Cir7gmp_`c(cO~!-Ycv51Ylu1ccNSco1a$)c3Br`f=Cv*7wWPOjA?{Pp{2T6Ad zgCRA+J$41HS;*W7Yc;p!4>#~PE8*F=y&#@3CWJarc#&*g?fTic?>F={*KjCq`sat#_PYa!AXp*dp<9rp{-$^%^FguOq24t1T?6Yz;#B(>X?}sL!j7!UL`|Aeb7Y^o4k`M;S4gwww0S;yb?fdp;ls!M zo_&5VvTM)E3K;FLIltRTjlb`Z5c=vkO?UAoy=`IhRbgqvuF;^JfV%#=8R6I^oI!i> z6Eb0Kp&h4z?cv6K@zQ3S@d+-aaiN^`yxDBe%R-CQEq^~Y1{(jWNvAnz4IGzpnQG2= zQEU}MEpbUCUBr$mkvq{TvAogeCVdxFA>-)ttZRpBxZA2)rZM>QLi*A(_m8Hh(;Me< z-Zr23y8W>^s$=`5x2b4YG56CQqt|U7ndGjk3E;C}-B$CL6RPKZq{%<6u2M!b%jbHs ze&6XsG-I>fOy0z2)5SBb>3<)`na9>09bO*1^kjJ2L%Xu-uRB#|$M<056iptD^5FA3 zNIzQWTgkfNVzzK1=alR+Wf3pkVCHgvH&bKsyPekz#kjNX$==y8rF)CYS*@9A(`Zma zxhgyX8>fc1#8*NE>h57CH{F^W6{; zNJ|AP5ZL!Z*cLM__D_5=mahc>OV`&^fkij`GvMX}&kI0nsKlg_o2b|R>*ATxfwb{5 z=VH>}RED^xeOM`PtOU9qEQ}@hN3DGR*5ZVoRh(kOL2#;M}=zMQ9fI9fw zml4?k1E~*eMBP=@2>iSy7+_wnyI-s;w)YRTV1;h5h5fg(V$}+iEwC#`y?XUZxo`j( zPj#(Pqr=KuoLL$hI^MLjw0~rS!I=Y4T)b#=;V?R=+ejLK>cqH1t-i&zRMoZ}NochI zIso_qQKliDVo;6)W)?mD{QR_dQkf%=WOzJ!mBIlqkEf=gX`|4TM9&-`v98Fr8Q|~# zt=8pWl?{uEfEgu91!Uzb(l`GYS%o;)PelQxVtU#Xn2hw2K4i!M3SR=Id#K?Ezb`<# z&t4#p%koPtC=B2{gPyLaut|y(9vKW?H&KMFxxo+2FfD)>8Qjyfxema0!6q{<}Z-HrTF!?hZn1 z|4Peyc_7ZFO@5cLIw4@NT9u_(oERvV;M)Vu+u>-Jbd=25fDG(J5YxQ+mNRD!ko?p$ zL>78C(8~nTH*d^=X&!(youomVn0ieoKm&|LxE?>1n7#lRVG|KeZc09q8Jg$Q&y^pAY%3zt$*( z{S?i@n{%2j0VJvtY-nFwh`lr>XGTCHSQxqc^|{Ex5j|cWIXd!1EN+0j=l_oQ?STF3 zJhGfxV4T|XqJ@j=26}bIomx@fu-d(E7v@`fmB`Qia6}@IkQ_z8YmhyWeaO-%H@1*m z$I1NJgE##0)QUJ`qH0q;%$Nt)ZLd)6Nl@)NBpaaJ+D{Zov> zWe!`k=Wl=T4&RiX?FvV6e(1N!*(`#PjGSxvI(uZSQIt9((eE@_uq0wQe)7pG;veeB zA5(r#-n77Qew%tVe~^q}7Ux^maP4$i)D;uQ)$`Jhg2uYBS`|S|iy+LRSB=Y^QDH0} zrUGgiv19H_>Y<-n->z$Tx_E>qNzAa+YEA7$rWI2wCQE<c&3=F`j>y>rjIv)NSP2yA_tQnj@i3)>1+eY2vmU%%G*D?pbuu zDSC_edZ7+K!Gd)PO))7}xCiE?5M2>v7R&brhVmg#DL2`fv1L~9Bm^i#I6t)I=RYgZ zVT=8f5K6u`T{TV2&rzoP!madvueCLH%T=YW;tFw`fB9W+JR=FymhOojOkfd-{cBGN z2*1lFgCgodl`wcZ2*sm>eO%_+4>7|^KlDao+iv=fhJ;B_$!#W+Eg#kzY&t)(_|dBy zz2%10H9nhIHvZ+i^=oZ^-PZ8!Dy+QEZbX`g4vmSjpY3n3Y0-Y5z9fmx%I^zTJ>uN0 z@;+c8{IlYqvHz{~sa;BB!~N}l^KaQ|s)QT3?>37qe2>Q``Ll%=lFFa%FHM)_5jP%n z1)nTWKs~fyBA4q%6z(OZ5Kd+*i+}`9PqPP?WoOf~ybK=zgWhEs`LCg>3uSlE-o?$8#x+pS=Zte0{+})=aE|H zMq6Iy8%FzLfrXHDBc4@4`AH#n;ycB=tgA;iw%x0?PpY(@TuQd&VtR7i@mZ*dv54f5 zu*Bv1hWU}dzj2xA&5N z$v^Wct=!+p%zE#y(wuUfzBwCB?Q-9vS7h&SUZ97|YtNImn_7^9gIFN+k34lkCi=eK z65H2={ffYfl&AT)hw@TbEGX{$jB7fy#wvBWoyrf>4NN*G{-xhqxXtBH(cn@%JvfQw zmpS6a&Th%#G4sq*rrxRdo#T5>+Ny`9%jJ1}!#m72L@WVyY??R;&9AQw$k24eS{()v z@rihH**r_X&(|xafD-7iaf^7$Y^;%ZEi0v5H?{GHQoTaGW6rRkUA5WtnPp$-QbT8R zGy1@Y&goQvdp}&Ca#AGQ?82)d)k~pV-D|R@8nNIcU*$ zJ~kx4H~4%U6c%!aOLx+y;=`nW_2}C1!uY@EbyX%0UN3s~##(lt4@rbAJoJ0U?=H1B z8`>3~FV0Jc!Ad5Sh}XXqVVJ5^o9A9usFY-e6)FC6=*3bST9{Kb8;sk6t` zvd_q}P1em_JsU&MdNmTODkyYAept!l(PBaS#(XDog-f{M+?7)hE!Ol7;A-%8L*!pT z(gU09t<4TnciBKt9aHg{Mr@oQRSj@)R8fdvsQAjt3ZfE2(%WCZW<+ec5PuQ`uduB0 z8Q68N=K(5KoV>bs#>w?h?hDJDD6xT2%@ zCdJ5tTJW>7DnHf%8NEU=nPV+&H-D1+Gh#_d_1!%jARE*^c~*sU->e0RK5CDPsJ5vVe^ch>BD$@yqNt@0 z5P`6OPD-v7dkAla`kyYDa{*ui0<#X-1AuB5T3%08MU;vq<%txg1_r;Q_o2tgPl3rE zF~)-*045K3F>E(rFQ1@MNJDF2Xow&KKtL$Go9E$~zb*_eJFqGMzjoJ`zW|MZeg*gi zn~#7hpj|NnT66?#7K;-XHUc96HNK_@z&3zapv>*I^+#cMcXt-NUZ5Q@Pk0ZaMQ~9C z|262@pz+)Dn?m1{>_Y%}WFvuC+Q8CeVCHhHf?i{ZUI}y?qtnxnOQ-+<3cwFwxB&PD ztoMPRPyg`m6wm(;g(H{snizw00OCrUeQ~IS@^;gGWVfXE zdR#5z*=bx#(tt!VU*T3{j`sHb{2*mWiYu-ZwB&tZMNNciNsdRU8$P66fkZjjFTj;R z$~Sx`6oJ?H_;}c&@4vM*&^F4FVP)DT>h|U9E(NLxlp6DbC%>uU328^dB3?e1L*ZLq zN&;AXD6^A~PEP&}Vd*8t8-Jsl1BYEYtYCk$7+Gcjy$~7;1RR*0^yvKg>iJZ~RbdZJ z&3HDq3y0-Mkoyk_0tDhcu4)b3n1BGtx5@N#2Lb@t6o6&}(x}X_)!)gyEIDgqI&Etf z96PBzZMirdc_=~`Fn3Q-U4if4Y;IiWmti$rM;}8TbRPLz`FsA{ZrYn%X|5r}1W~F4 zF|^BA{cWagWMSwlJ$40Lf7+hlCi^|Vti(nAuz0>-Wbiqo&TD}fE27uhm6=~@TUFg{ zn4Vz2TvD~jk)QcGrz<(Ez&{dQ@V3$@tLHlA+BYFG!WK;PJx=_U1&bc%FIA>gkCwu; zOMNmcmrcnY{`q*~DecI0S6_~0vo9+);KY_Qi|WP;lNG$i8$`dYYcJirZC+Sflk)AR zxnl9PNImoIue_4eiB*?%Y*-t&{wc=xCp?+Dq@1Cej3wW$`~0KDU9`KjhsDa1$$Vve zy}#AV`0ek-N-UiZf8{T-kLF*SFC^Kg-MeB|Y*l6W>QS3G$659gr{2Y-%7{7k5%k3k zbX1r5ZEK#X%LPrAHUeV;mH2YD5?`(s)ZP59xl5-L7(-u6Zgu#&_}8ch!L}LJy?%+o z3i0`?Ct@d2{Bof;1Df z<@i$IV*3>i&s^=Lff)Co7w;GfME1x_$LH`1h!hDzm5M9tY~V$u>*ll+_<|%>jBy7gVyY|K-r086&gHy6fN#JMy3^eV@!dEMNPRccCXSO>SJTntw82A zBW}6249o_1@#^bdaeb@VG|KPYR|@wt$$sfFc+CF5=@@+=p=#}y!Drrit9Ft!rNJ`i z-ftWUVP0;E<1|uhPeBZaqv|q^Yc-_RIk)WV!|Ld`OLwXlCh~0`8jfLne-?jNBCs(JkMW&Bfx zsJQ*+Xy@i8G71E_6{K$L6ljXkm=@t1ijznd#D*F@f z-H?e!wAQCB%bD0qan3rqTaQ~lrLi8q><`KFJNHs+bgh^lN*cjES$|!No4^PQ8w2n~G2bh666wyN#@0~+puA!P++Go7ISjC%*8{4%IdIhBY1f*2 z`w6xDyO9;dbQPF?K)gbv$$-NK9Ce#@B5Z!(`;!LDVuHp^2_|DW#;pgzdk=t?)fo() zFu&ciPv{x_R|O`$X9AHi8DfHwxOZf8du!$h2`23y7zoE@3Lx{Ibi;-E2om@JG^x}s z8A!#uT?uo-cHnUx_x&qy%|_}?z((LTg?Qi2W+-U@3YU~;s1O|ES7}BWVPFSi85sJX zQ)!CV#&Vl&4Fz4j>dK>cTbg+IY zLI~|2+%REPp;Mfr%Ok!y311JC^w=n4CT+?phwe~JTttip^gI-S7*tFc&WVE2v)&jJ zMfBp2v4H#sX?38?`wT!rp&uPJwQEQ{wj!YNH&Q9jvGJG&xwgx zpy@-59BP&_4gNjkt$=4fvblx=jO=Nk82}PShZrQ=AiIDr25<0XojpI1bf&yYo9cCbMnjRmQ>=KxHQ$((P+BkmEBXS)Oc zk!WYt%#O(!{r<6>E?1oMAT0+Z&zw%poG~=-*H*a6pi{n+XB`Cj9&{smOm06uAi4mj zgVWg=)*cs9;^O!yqE|^~Y-IKh4l(y$Mp--sH$;HA0Ge?#G*KN>ewPbbF?KeUu(1Iu z1!Q4^F92{u0+#P(BMYj+ViVwPzy$=`CD`*o=Yw!lvmpZs+MO>=2h*`|JbFV8^%H;Ci5QD0#T=+p;Fk`gVb6QQtRSmsw^vmlWC00PmrG%8L$qsFM0bzdzu` z2n`%Uf(5q7z7^mlk}_!IHb8E4BO@bNRDL*^_W$StVO=Cl(yLsxI^*BrMu6`iFgQZ& zhb9oqtBOsz21XTdaP3`bU={2n;s##?w+M$aUr99$<>d?(xY>&&``*x;LyH6u<%&O0 zYv7v87g5&3RY9mJz00lul-xVdzSw!-aBdZ9mBd`3Pwf+#>c`b;U-&A&h%59;80M@? zrA~z{wm*@2fgH)1KMC1wS?*dc;men=ud7-Wr{0&uqE~*f#8b9=KmTRk4Dr*2F!LYX z4b+|(na_;JL|LY0#zp_$C5w}NuV2`dB0*ge-cU8TSB}~8$;AoVmHU@dalXJ`>ttdc zb3#?Kg7}O$dXIoQ_QZl;!%fdd7MTl*vrT@hRQYF|@%~fxDpO+dxK-p_<~Y?8(jFay{-NgI>fQfD1M<{9*s-mO zEFb@HQr(lQlain&^vb2{3^-3Yj=gtdIYhkhFrPB@U7Y$$RpJ-{u`%MUjJn+9$04)? zB0Dl+U93@E*7Ocv#Lm`Hq7u#p8a6Zv1R~L_c{-gf?y`cI#Z_-q)EjPl{KfGq;7C4Y z4YrxpL${sxjTSNlJZSR}xnz^cEBp45$Gg&K#(EiaOnFRPF{H(2IBR-~T`n+0*Hc?q9w0Rxm_R?6#cN?p9iT7%}VMsC4JfX+g9S$jH%1C3Tr#C7i1FGl2u2psi zQ?<8vEqMWpwJkxsxZamFBzatCd`~Ut2d(2M<&DjFv^c}pnx{N@leWWEL=7d~h zSp<)jo=^`=YV3@U>I8$&Qwgut4y@Y3q9{p~7m13H5g2 zU7J}xA=7H?ZF=D}0ri(^4r<*bz8{y^YHrr;<2shhh8kcdDl}{;Ih_#AN~{>{ESvCW z*r;KAo%i2rY^f$qMsK*hRGY}2zRqR8u!CXA*K#DyyN`*|6>VNzS-m09zB$C?QBxNs zs@HY0W=VA*ale+dHx_j=zTHH>x$ZLXD*Vx-F7Z*%xmN4?(H1F@m$(6+d6}yHnf84g znpZsJ^%!?b9Z?5uuMQkeisg3*JSROW)GYaCr;zAhSY9t)-3XS7jH`gUC6AY{^ItAohB_-GuNs!E zk1HLB|D1WfXaTV&NK^{KO*H-VHDMI~0F(v=P}~1!7zEOV{{)JON{oo>4v4yt6f}S& zU^xKDJrD(fWC7mo=CGeeVqL&5sDo7I8A!NcB&C<|z(YKWs`LZyc_u2eL;N`+Yd{wN zuv93uwt4|?L=TfOJof;p7#H#!xn+QdmkIlS>L`FeASphAEG*Sp*^N+ZQKeX!dyT!o zG;d?A?rQCODAv$gKn0%>^wby3xC4TD1V9(0PeX!Yl`RSfmMUKkK+|`dE=4}InbWhX ziJ+h=^Hx~OQ7CC63w|;#fW&X!J|ifP_B>Yi$|U1gG)l$7IuAg zy$4OfTppZ_TwVKBuorz93prDD1pmoX5$P%+CIXX_cVMdpM*BNf%X0q{#} zO0rBf#i5Zi^;;@`@>g z#M)d$foTLV4cUlp1BV0YLy=fO_&Y&h$9_S~bP?q1*o~MF%>lO(c0Y&l7l)+l721?* zV^rKXc-u;*2n?aB-Mh0Eu2Q zQi89g5)%{uMl6lM`uF^s_TOcV5#>4G>aoA)E>!*}(RaeaL!lcll~b&I3}L!4J`&C*&?TT>$m~YSe4ju9dQnHT9ZB=x|Z$yCn`zr)2tL0IGvH7qqsv zHU_4j%ro$|oCasf7U&Hxvly0jH{09dmfU2K6IJbP?3cUlFI5|Os|a(|Q($8~JVjxU zB6)bgKMf;R`*I$kB5{KF^EBsi5G@N9!(i`hdkPv zTrS}bYhpw;a{&Xx?1*_*C|*zFB4-WH-BxCt!fH1E%9L@e2^6-@l)puf0iMMTJ1I^& zw_N?gYR16A=SsM=-2JKvk?&q9&M3K{pjp){C%o~z+ji+D3#M-|e z^Zr`ta`tGyB9V3FO(iBiwuEfBr9gq!ouU@POWh=Iik>IvRI~i*Vnj>ucbg{;;Fg-# z@E3EaqsFo8xtRIb151XEBSLwoEo)lQ>o!?o`5|4VUfX*b0G0MNgWUsIZ zG0a2cLP-YeQqs5tixnR3Cd2an%+d5Z1T9g@I234g-zQ|FIDFG7QmXsn z-L4C|(1)$EUBiCqM8f&ae)4NOW`^wn)X&@gcd?h@`)*gYSdJ%6YIWIhVwhHta7~~?ht9$YErW39<8`ZR`A{^jLmBQ zLZ>@yJVw8h7psI*yqH%?vn0OQEkurok%_zPEe+?|U_rYN8;-8Jz(c$e3s#(hSuED) z&+nXKOngFrd!u~xQ$PHTF|MI!0{T|j&4&wgwy#;m6mmaCulnEQXk;cU{YZSF2(`(`-#_adHTlCtxs{p$xFBd)OTWUq(7ha?GX4lYoNZd zoZfTHQBWjR{%dj&G_=Bkbo@KvC^^>t1L|aDj=@uv&?k%s=$ZToF;$M zW51x2a~@IL6|ZoO4UJ%bD99A9@iRg7E&eM6#O$9M{vQ{hw|EX(ld%?>l?Is-vDa%t z4U45U@#|g!CvQG{AWrhEf3fI0*)<)j(5u3VYs)UHF_gMuw{|?r=VHN?CDYNvUHiP~ zW0rPCfdq$9o};r)6WdIa*>r$_vt_G;yYpnzx_@;`vv;idD;%t_R=bnC1xd<Zr``v8n*S1C{}} z$tG+)Ab90Bm>kh397vKP{Q+yDEYwaw+kvwv-fIG=%oFKdmKwtwNN)fScZ6->I{*DL zq{SdU2MCEDRw#)64?Kck;{Pv17TA}~CsP~i7?ayar;g>I1!RN?9kH$BYdIAJC*Mj! zYoIG2Tm?WXV0Ynqv^_6%xo>(s2~?x5nlS<(h8%FMn{Yu8C`BNJ z8wy16n=1Ec>dLBZ4e**##;ojFJdo0E~`YEr9)j0&-g-3t`IC zW+DVlO--=GccmTqzl6N#2tU@Nx(OF6Ek|%e2Cjik?IHjeKxTo$4-QKVfEP$fNqty+ z?T>^c03?It7SzJp1`db}3(jBYqAwDi>pF`XF@PfkNJaW=NplWXDbO=v=lqf&r-w!d z02%1_5>yM|1*;KYzkG3sdA*1TRe`er`vQcFyH+OJ;qQLXH46 zfE_`TCcT{)k7Ng#T^x@9i4~Ba^KHHha#(VSf!YLd+W-^-*dGRh69T|(`5?1a*buOh z0*K1R!XN|yoC?Ct4nKfz;X|askqnB9-#UBjmJz_FHHTyzXlZm*^>o-+k<+=qDgDECtp>pW!P)x{=0#TJtVq;B|H|6Auar z)UsvTsXj;Y?^tjS+u(Ym6{3nksm?m7{BWK> zKI~7vY-dGl{=aSGz02nl2ftT#P1;Eu1SD;BbO~-14PB;>sJtAEm2F6c{iWNfRb$g@ zvNiLW33Z4FvjuisvCH8OqdhPFzc;etg`WoLD5t1?4Ig>dmYqG$9;zb~;m+BG|B) zB?-wxVxAEeHn5M>TmsVEfv4Za0)=($Z}AU_^?gd|Wiv;qv__Yexm8r$QoO3!Nf7r8&x?Np>od>ZjqRN(8?y+>CHIAtw3N8M z{F0m8T$g8QuvE(U)2#b7ies)CSUel*zV0(F>vvq=94fndyes9m_isYqE!GMo*r*WQ#15?A}rFI$$^^*^Ii8SNbg^|Lf_d+fYnD^fB zWwh+;vk%@k4wD{`q|h_8=z8>RYM;unKjT+^ce+Jglf1CVQ$@R_9?#qblJ!r+wADAn zj2!syDPH>X^;{!<&#gx~W$>HR=rBHqft4BWi zziMc<7iBGw@6r9ONV1tqx=9ffh85RWCtNurSV0V0h+@@JDSMU7 z*Yl)Y`96(PTm$fd^pEwx{%x)puTVW0%>V*`XADUDk(oSbzd9QsWP;uicFLeFLv(=P z;P4EJ5(!L@h`kTOw*=lNqMU5>B8DyjS=GQ+9U|ADR>7O3y?6mxbqHw^2oR7h_Xi{q zKx70F0bmV}Q%V~8=4@@CJ?M&KxD6~lFcijJEQUotbDR}K!U(a~fBJMc<@3JY-o5TC>WvLUX;6SU+LWO4 z3v3uh!`v8N2P5{}^Ae){;;5x=@!awoZ zY{NCUx{j>Lkk|%fp8}adUn~<(?i3EVot^;W6vrIMmj1<(J3Y|(8UoJ*h@SAnHX!G| z?0uWpaJAsC$H&1DINjIQF69^K8tED?!y!dEf0KFi=n-2Ct46j8cltLMz-r(uoq$%R z%|00TJ|{n**#yz5wT_8?;>CH{%<&Dxqyp|+_!tC7f-8oazs)6TZ+MImp~oaxNvjDt8$OCJaD7S%;~tkyif^M zJmF{!f3)k@-XP;3r%eAa-+lh;ReiTE0@Y3L;Te)r_EKlVgk*yS{S=CYI`56^i<&jB z`Q`M=T_u=SM31jEELqHyQdMG~A|eazc24e-8iPN6NtkMu9JH#Q*%WN$)p*E1 z#HZAE{!ZLxS31qzuTB<$(PddSczf9({|;sKOQWyM)PWpVIk@rp2a0)XS!qHa3dW`Q zCFU7gmrxlLW0Zx6(BNY}&TOw=QK+L_$+=b7Hh5*^GP7m+9UeMa<)${O5u0pU8hF`4s?EL8PoTHPPzXn5X5Kj*W+rrl?-=EQlpeck6-T3Z;s zNhEuo!)L3o)P2#o$z9vs`eaotRjWm(mS!}oFjr@PGIolu#Pe%ycA1@V_k@z(yy)7@ z92w%fn>$yz9Jewedk;%SS;Lv;{hQPp9pmvRuA5IgHcE+>jP}ZZQ^}Yoj2{5oMJ_2< z;Ff1W1zISZS?D+}n2z~3C$aJs_T3IcX^a-aA9)_3jG?}anJHm^F~?q8l{4ji$e*zy zWFF|8eBSPJ8r)a(bX-fk!woB8X(K@B0a<>|;?izfyQ(L504n8s+N?TZJ}Vy|@$SPD zhJ?o)cJBsExbS!DeLKwEcfKLGzv<|} z0yOaTai326&<^&#qs!Wk;LDAl_+qZlDg!I*Z`+IHO=z85)_aDPP4S#*SFLf%w=`KL3!P{GLQm{0d~jrRZlZW- z+lSt*jq=;rRdLbz{|O@9a+;I+mYHw`*<$zr(V^L ztca8N|4=yix}O^&YUE|sF|+z*p8`m(0<=}D`lNhJ)8-{!^;+stg$j8_<3@I|Y?0&?l4@F4t zYPW4Q(O~~Ej4H72gcno~psGUc7!M#dP#l z31Po?`N7Ho*(8HYLDxt3#Z7?2e}mEw;pKUMdR1_zrW;vu0H49QIe-SFqA{4?z&{W6 z_i#WYJZ2wUEncvGpD+N%Vu|}y@Wq+FzCKhZ+lK`Z+|$xBQA_gjD7H=FZJ<0nDWNdN&rjXE?{*O*0Q@gRd}(@KJ@WPzgNj9=86L5iEQIk z)W!)25tP9E2@VBecEE-N)FLpvgH*8E1mU;*&%PMWzA-N*YW>rWMtKPwsfPDQ_}ieq z+(FhHz=r|V>lR(h7M%~0&;U}y$)J<9e@jbkh({7gRsJJpK%}tih>16n4GSEM&(J0W zZ5#xVYD#V)X;WZCpd@pwZT!I%&2;up33?f1YS%-tVt+!&9sl!71o`HFqy@0Kw)FCX zxM7AujjVQ{BDle4LN&!@^g+qMb#?_8!#TKMVgZNz2lGIcL6#o56eV&1{vJ&D$F$dgw4E(>S93w9zvnn5fh;huOA`pI#m{P#%E+6bZ&o%9?r z0qEuM4^_+4jld0mWJfYv4jI0PZUYpVtck5qV+&6MA=i;#K%h-}13E}VCmeJV2M;jBcLD6CVDH5jv=xhLC7T54L!lcOG9Hfg1$D;UgF6^{)WZeQmT1KM z06|aA|HYr^pf57cx#iPIr1^VzWANudnR`~5 z9i^K6_F}{4Z$xB6p!5Nt2}(E;K?O`%H!zPvq@nQp1$xg?LvgUM5Q|IHC>)yx>|_h_ zAa_Rn|Mj!zC1VX@{{*ZlKLz$Xod|&fP#2)xuz+;<-_QTtt$|nrzgVvWwpEZwE)W~z zb@Yd-;!je_BMT|GUeJjHg_N3(Zccg#Ze6&WftZpB$x_fMmhudPViwpg;EC=&1s)Ji zB8_$oKgI5Re+#e}*j*vLI$RxSac=u#O^DJGBiIw*SbqjzVEy{#n=n&%pfq>$xjX9c zP4$$^t(M#wVOruS4Es{`!U1>+5PkgR1+EwQDMTE}W&L)v!MM1%(1ao;*Kn)ZNun!B zlbbZVFV2TA%;`K`SiP`Wy;~?Bwz<)cidI=Pu@_dvHnQ+UiE~ja#aLr;V#OUlRcR~? z6;z6T_N(lY@fFwBQH>$na8eO=bd(#4p(*6AY*hL6m@a&Dn<)F^(9Xc7$YQMTBg!i;yT}uVk;v4*9?5`+NT1r>Eze za-Dn5x#xY~&-)n!mL}oUp_XLfU$t?89)z$7&1n|SCM?R(_;blPJN{wJ)IH`BQa{h; zq|PC}U)dJ|`G^hpF;2?dQ;{0l=*-Qj&73t>T_st%WO z7?WbBA}!>saL-7V8!9KRxy-m*ijpj&3C&V5`94zlJ3e7Ia&OR|< z`62Oxt;Y5A%v`|I3amQo0^wNSN9z$V^5yOdrlYz5p^rFuuoH~2)>YurdzUu&NI zP=3!$;pmbW&tJJ|gVi5w*+Z3@4pr$mT$uUPvg5$K08T>JR zZ$l10(KizpOm#J||Mf3Tr4GBKjjwKV+3p2f;nNhMa(ORb8>&0`M29pesd}>HzqvE~ zjmuELSUzrmjUHGRTKx_kapDDCWM4;ZF5^i(Pkga}e~m#e&7p4oeUZ!bIDqN(r&PPS5dV|6U#zZvi67D<0aYXYMWW2iXbJ2e;;}NZ{_#w zYsV#&Q`>kT7fm6lk+yTWikE05dXi@4nw2d&^P81rg!b_M{NPYyAlDwR46kIo-Kp3% zO(hGtL{I6;;lr+BP1VbBH^is6gEn---%6j4+1_!!Q7vvGHIXz$(f(P}%=Pn&OH$jS z40?T+!>cG_6iv6kI{&(3#s5r-pTu}{`g((L3tOHnkdcRr*W9O z&sfiFCYe@mFv|1Xy|5_r>DJ=Ws2FV#HGK9Go z24)x+i-(J;QThEziy$LFoDKhHQ4kRA)zbk8JfaY-^V<~w-y@dbV>h{f2lIe{Uur(! zXg)pJnupLOWc)TNEX)dGfbIym2R^f*#I7sfxOMC6pfn>T;tDuD!QhM7M{`m2V`gWm8XfO`N`LPgM2Pg=?{qiWl2TUq(c6V(A zj}KKk&jR36xD9Cu2eN-gtKO5{4x+;)t0J9cXM8MB|f$}WZ z)upR@uoH3vE+@h=p;SB;&J5hUso(P*emX$uK(9q;ie$e_OG?VW^}$(sGlW1wK=gqA z3621Hw_q;`Iv6P@hup80%T@pkAjm#+2Kr?q6;)N?2s@MQ6MM3jGNw(y@_!V9$snkp zK48)f=7+%iz!lLzy#am;Fg_7Uh%sHyok~QdQo9ARmH*`{KnEy2%$wf}AbLBw$Q zP(~4#5x{<4ikI-}zH9{oBODC8Z1Yb3B`auy;7FlghU1LKJ!ok6kcojM&s-=mODiaa zTKTU*sx-op08nez<=>(UvU{6HegFcVKszCK`19F8SMaeqa%ixanmaq82Ui0Wd^7t9 z4HAS-#n8AoAgDb>qu8^q#v3LoX=>qT% zrUu|$mzS5fwvGb_8%V83LokaNtK=D`G7XHJ$ijUFz07(Uw8=ilh_ZRRUoj4DxWPg_ zF>#$BCVgsq+3E%8eBitbL#SzyCndD>;9m_p8x8)kT41W=fV(*mhk+svRF@<17@NIR zE&k+Oz6Xm&5EKnv;_YCZ7V^##G>{z;@KK;o0^=95+2Gwb7E}L2SWf0o^?Pi;O=1hu zubI{6DU&v~J)LS(aTj6jI=^E{=%d5-l|U+a^%3EbPoCNxrFTjXZJV<~mUz!D_bbmf zUsoE-n-|qj!`HcK85hc5l6@(oiri0%gxW#yoXmC!BQ4Ew`3T&U@#-d|!!308{=5MJIJJ_VUGo7Ms`6gEy(d3x<1^B`e-& z+}UFNw%UR#4-9eA%YS#Bf0FAd&&R*6V=f|UIYAflGxm)4O;Z_@LL7n}?&Df>Bs>h$ z;U3G( zNVn1bmEb)SHctk1^amQHf~6|ISeu7-T8R4{Byk|%GFO|9td0T|Kw8~i&*6+xV^t-KE z)6J@5N)@#>@G{z|!~fL%dU;9X+PBv+{7~KT4>X_EJVS};m3FM!HWT%zp=$)vc&V_$ zJ+?#*?3b*M+4`LvP2%xxt%TUxQddOx5tZugk*=#RD?B5gZ1t;GN~z~sW-xLZ=#Bj8 zL$F6DEQWnCMwC|9WWjjxDR;x(-M@uyQ8EK}4ll@1_%kejkFIWgAt{yRb4=xEDmOij zN)x-|f9K*JhO2VWxBRjH`J$t?{ zyvMVtc`Bm3GdVTq=f`S3Zw;%X**9jqBp|Whb=iaGbu+93v z(xO(=P})08!Iei;WU_e0=1xBMTHZISY|92o=}dkuOS`}9Y;h)JORx@=G`<()YqM}i zqRE@FNj~V;iQ&45?S9~}x3jMGX64srCnNts;(f-WQlX$6{R1L;C7`D7_!0!=C}b_6d|+^e9RXAyzK^Vg_vHKMX8`;_D3|ci^V#{TjuZqiv{Y<`Ng3P?qro5H zgIhE_ArVCZ=(-*fcOd1pPKWd??~niVB7sU!x};+kx}WhPse7`ry&-*p z`%_)Q*8rP<^k(l+D=&IR#txX8kqQHy0pdh3LkRXFh&JOPF(s08Ja#v0q3W)SH$M%@ zFF8t(3IZJy_5#o|f%hdMUIeFzm6b6&$)w^W^bE9J*Ll!NK(hetD0EP7EWkLCVgSq% zp@cyF*{*39w#D#}se4*WvZZ0KwWi;9NM%u zHH4}FgD2E;sOtC$Rpvlr0P6qTkwVAq5Y2r}E!cmdqoJ4jA+^{502XY|1H`-mq=%sw zaT5Uq2-fR>lehsZ1&|)3=etp6eg$3z78xL%`I3DmVF%o$*}p&mn}l-&9i9^WExaU* z;q;qYJkJoY2Cfw-NWt0}P#esb?Lby2`k)B`WCWRxp_74E8?A+T-rWMID^Nh7j7S9? zOF_$tc$mS}lijRC=#Q{uh`h1TasPx1u>f&<3v*((Y2lz8PWdDg0z4EL^^HShQAH}A`%9GIHG*b|m{0KI`K z380aRiVD2`Z8{Y9@~21_82EwB0jKk@5$;~y7+JX7d`}P*;!foXpBdHc!jS^>ZP0cg zn?t@QbU&_fQIQofgV_kc4_Fl`B?hObi}*W?TAY&;6TPdJZcH89a+?n`mqg;Ptb`Y_ zCd$}yBv_s*%E^5e7Rs-6s=oEI=UEazf5avJ#sod>d>ouUU9Dc&5W#7~u=}JFTuAA) z(_PT9yrk^r#h}H{UFb{^hC*(GGH6v*a$0R9@P>e8G%UeS&Xey*(Gh>-3$|ZwPuD}n zeLX#gEBJ9AcLG_vZE+W<=&w{G&U8n@h-kJf_&{4;af>ASH#3E{9okv{o3C`Q<7^vY z;UiLgca`zXb5gV+j*|&e|qU?Zl+x_ za`_^uyz*?!g=H;$v@(qfO64INQ^k>>bj?JWNwA`0m2=3`hZ&#F^YlAK zWMkJ)qV|od)J97s*^o5?Un{{}o69r40rAC|c}6Qd%Pztsj1Tm+t6w}J9C-aLxjFXw z_($wtX2+w1eA4ir~QGk$nQ)7BYx>tE8y`W#d6^c%uoQrP^^U^IoXuUW*^15K`4jotSP#h7*e0uP4`3Lh=Gm*)^!?RR{riMl5 z&+z2#hggYTV9q3r8*^pC$Eql);3e!xUY3Zn8@J@r98KsOH2LaD;YPzjqDtNup{u3$ zPH}EDrRMtm+u{O`#U*Y%v3)+CTG*wod$dlCUHr#<@Vq!}`niGVV9Oaa{vGLJ7Xtgn zo|qCGkGNsMNs2)X$Ly_)xLaL$nS1gvzebCSq?@XBtpw48@xJH9msX@hpm*f<{bKnh z`OusyQ=?oI@QVQwI|ktth9vK!?BBolq?pB+?#0YJcS$s6P5Le|Ox#xSAhMk+f7s)w zB~3E)1l3^FOE-;U`8r)tiY7g2$`*fqr<^0ocGql;&asaCuM1071Uh&RRcM%18*p>d zh_}YS;mTPv)^OAjZoua*f7E!7o#R8YKMVsY%I}<0qyI7;5@%QsbGFotyu2xEQ%ovm z{-QzTvZ_toPq&cR5tcW2bPJdDjySvfoEm?d4SE*~WnR&&4NPhoXZ~c^QdnO?`b64Y z4RfDG1#Va{0q;(;cyTC^ceytnSJ+q`DtiA*FJ&GbH-TRr$M;_4z$+tf@Y*s4VZT}O zXS2<=r#VBqF?&sWeq;|nRPxfR3I1lgi8XVfy<@W1HLFCZqHFh@udY;VY?+r1;4@e0 z;bS-OXVpbxz#{g6!kUe z5Iyih-%C$uBS~*Z5=HUS>vXEg47ap0T@a{?5aF^;53?X7qVk0?6dPFUL#F^P&0r^R zr2wMs+x`OjoLH*}Cdq)!%k2(bC!0k!AyJg9$jSkbeMF_&!TK-$+;xS$ia7QR-I=N{ zAg+Wor8t<1z|u&zNU;bB@dG3pU~X`7s^?DKGkzWy@RJjJ#jDHClM>DfKNGL&<=B z0LAVUkwS+B-vD(9x(H~Cl$8kcoAEJi6o?)<_v@@oJ*>A7G(m$4 z@k$2h0LT??QTKPS@gTM6m&qFMPjVXLj*wzv7Hv*db6^<^d)x5ofQa8AxHEy+PdPCL|We+W}m7Fo{bg|`bu3Z z*wE9UclPl)VBThjz2G^AI9NRZs=yAf0;4|SFQ%B>ZHp|Jpr(OZ_xEo%Sm?Y0{s5UO zSc-}!`NK#Kct2=SVUcBQkaq%&-+n(76G8q6B}1IH(AdFZdo1vpZ~R;U<2+eqha+ zlsfT#NZ};A=TUBX=p#`K`1V*7dlwBB;}K}79kblj^WxG=akHH&!@D=Jd~NeZRZF!Ku3TPgPWcI4^9XY}_7NMKTC~)8IbGn+(=sM= zT>67`XeE%*XSkveK+h42ul5fA(jHcu(tr!A%JziNmgeE$Z4UGd!IEXY3%WY&ON*>M zY3$NO^*~dsgL{rtX;ZOdT)J(TLyVQ^5$T{Fxs95Bw63(aevE#6bl4?p4SFRF!pO5y z1+CJ5Cy24i?Znt+lrriJ{&OW&Stcy)i`0-6S_4OX+ayu3A1HC+CV4y!%FLvY9kz(@ z!2a7~V!Q4aLYOb4qC`+Rx;MVEFB~zl>&*7poI<%D?N&g$S#K zR2tRNv8lDNSsh9C_$(a@mU=Dx9e#2TXR=fjt3^V$z`~9_v*14W@mKypc}v(`xuO$x zaVdO@37r!4SWL0qwQ(gWwwx+9CQ=4Vx-PW+Bacxd!3JhQ`_|*kRx!rogh%pc;!bOZ z{|r@N*xBUsH+g1NuZHYI5YZ1we;A@8Gkx7)`zv;w_c;;YQ@%d#P>;?L&Vn30`+^U2 zrK|1=N7q)xR6;^22)pS&MTgS$qi&(mx=-|spL6o{UAHOL-y->(EB>|l+=ptXz>X6_dlXvtGZ5826YH#w5sK&a8U8VF1&2}<3V_8H50 zs<=0Ov9n?xK=1F;lifV&P4P|rI{iC3_r-Gq={1dietPi!1KQe0ljRSV(d|#-Y}`-w zxX}410^#_mNygg*w81mCxpd!BvxUUG9~EJeb)zw@u#FKv8kZMqdPkdh?cLaI-QmF3 ze@}`j8r8px{)x_et4!J5(c$iJVwACc^m6OcPOQRNjXNX8PbMOJi`TtM50+!E-#0co z5YGwNan5}e(U7-7*?6Agi;GWPWa7v7QXS4#SL{bvTyys=?=W*!z01I|gnwJJqx@E) zymKqQy2?#BU+&F!K3F7j@~GR;IqS$=Y4+gH zPhIDAliiZl?Ak_)Ggc!bUJAP?t3^XX^ElP7ejQGdBjzH?~%1-dP}NrZE>kw za>mtGUprqjyl;wsw@>|kg+J||07dSJ+WqE~cUhaazoAmh8)wLsh7~4D6bDs#HusNK znza8dFE8JC9LvnY(#)x43}IF}lmA}P#9URys&P>v+K&tPc;g9XWg{Xm`ok6kPzX?q zLL~7kFxxb_2*1w(gbMIHluBUA!7K$6aa0l&kmhaA<;TR38(-mA$bt9?WM^UV?@vkv zK)Q2{knYf}C5%+NaO}YcUWHI_w3r1=0m5BaQrMS_fzJ(%)Gu&wWe zO*2c-ftB2^R($wLh;SR@o@Z?k9p$ZTQei@dxPHR4`5W@Meta)A zMchMxA_#c#Xpw@1L?n{61Ob++&dnJgPh~YBWdwzw>5zpyw6=@=OlWUu2hI!tT+AWK zOu+0{%l&H|He`x8lHB74$Xid3GecMGGjF~coF*7iqpYE^0jo}gn6K8qv<FEeA z;86VplsZnA#l;aq0^lCdoRxFvi8COG0JL66u*hat-as|zJHTdhRT_*>0clbe7ciA$ zS&EN^lKY>(B~*9BY6QdwEO7|Vk3bLB6?D#14TLlM((B`JQjtvz1Y15G?o`-L>qmT0 zkmL%W(;|fy=`lV)F;AFcnR%mDuY zFd>ApasXCe_mO+@;l3DHWyVJydtv3ad=vP+j&IpicK`C8SaP7H@EGy{;q!~ zm3ITtkZQ4A66KAEa!G)ffI19mM``u9Q<1?=l+HVKZInbh zHlsiG0r9eT730a04Ar&u>hg}E%#MGYc9=I>og^1abkEPZ8s)ufFN^(45+S!edQ&$$ zt&rL6=WDFQ5&^rbj{vc*s}*rzSG#kR8yB_G2k+qsce0{$_t0Yz>t5{mr8rdwxm%vy zk%5D{D%k~lim&bgf0>+B3wvcwQdO=;3_lY0u(TWVj*=%Ic|(i4Y!!j+ zm(n`ZE~d+3Mbk_0CIDv6I(vq)i#Ksvlc878LOJG3Y1Jx6<&w(nPD!7dntR!S? zubr~0LP}SCU4|IH=4uh8R?M&bE>gW9(-V62UbIn_6j`C=z^7Q*`;;izz3P#kFZW9d za{Wlu1JhTZuZ;_o8>D&oXm@SOg8SM(OlufVlB5)SmOQU*`bUf~ElB&sHbDFcp zOYeGY{G5l1ZCUsO550nRInPqW(f{U@DXC%=VHe_mdB>$rJMLU}!1a;ldz7UZyJSIm z%-g%AI(LRuW9B_%mLO=CB2!WHk-}4a^J*!Yj zqnx`pYm}NkZ}s*Oig>v4Eqk?rQ-6DTQYi6MkaDi}?@+6A9bVp-B4^0SJ7(JE+zwu6 z8Z$ghn;Dz+c~6`*akE#X?#@4{=t~dx1&({x*j)LP1DVoq2(gUu6LvX|ZTOFK)H+Z8 zd7QbwSh*BEHt>G+%P{=krh1M6ljjvu6TdrCs7dgKfe&S zPLRzfCoX6g{zmCe`qhccx3W53))xNoTTGoQdA!l$Iv#T5RTi^QP3-sG!mICt&G*_h zUda#c2g7gMKIxiDeg4wTQYwqLDCm2|{%@H+3C#l|sbcT%;@5+pdHH$wq;%WvCwJ>K zq+1DHuCiAqZtR=-H|IqXS;pu%^*+Ndr#d6^bS3nS8EIRl`x7&#`5;z>nlHIWY?MXG z@iLBFKXNC?_jaiF(BVQpi{^KmE4lU#jx2d->Bbuy{FY)|U(I|S|1vfGX27%XStNxG zn{qrG+i-e$O!i>Z(dP`k8lmLs>zNx%Ew6>P@_+6{?Q3UleXL3m47%{R%pf9nc4&Jd z@L=If{&aD`*6Lnqzo37q=X8J3ezUOCkzHnsWVnmV^yfnV&x=#n(|o(Sw>)GlxTEYZ zX-EK%4w@J+y8yC-ZRJ>P-fiV8G(5MF(gH>N6r_#q#V$z1GpHZ& zdEuc7?qy1qW3~}V;Co(}=|=+U&a#$&GP3EEOj4+seQ2sefI|T`Rg~b9=CeC|12mOh z@(XUfC}nm6jsy(oPk$jUQh@4&ZXJP|?MXEghzUB!+6B3c%J}-x} zkh)w~_bG?xj2i3>N}|Q!tijPm7D6w2l9vR<9|*vphdF1j(Nv5pg5VI5PghS|K^p>0 z4M0tfU-T|upMFG4J3+G(5>hqoXQWjzes1@MLoN7pJ4%qk5jQu-0x=;+9LNoD5U_}% zyUICg1?LKMn6Gjq3WI=H+(+UG2XwRv%}10+eta^`UMcW8VWD+^fFfXa%>u>!KW63< z;(4YjK;!Vda{{=pptS%F0Wd5OeC9v=<%4Gzg9e=jVz2_B3PNFl5)A}ZpOf7Y5rF5QD*}!tl5KM5;1Bdqs1R^K`Cu&qi!d;V zefP}*kRKqY@U1(6a0js|gA3!7-fb&&T#ydU29Q(W;yl79rkDjc7o^+GNkY_8EP*>n zcIST%Uq60JA%8?%&o4FYP?-lE+5tlc{+O(~byiA6>t0A?%w&8!^vKZ8!G+XxW2ha< zO2$39nu~bYA-3id;9zwyz26)K_}VYJF-lKgZ|XJ#SwR5BQe)NHiI32^!VTT?#2>QT zkj)j21kNQSsUhtZEaVVA6W23Mid>Bx_UlD7Nw`N{^Nue3B|iaj1LOzMK?!7lbOs>@ zqe9w-fy4Y#$_))%7$9HpDjuG}*CG&ShI0yENzfoboKu9Wr7+4?hK1TkQ5ufLYGnzkwI8B#LTu-fS9MGWQ&T4|ZEyn^{QZ zktxnB_W>xRe!p;F5s}UasuGQxV zPUR^!=;H3-5fO9Ppdz)^=lc&82pE)P-)GZNk%qnfCnkIoJF0J=Cv`PvHZQl6%dXXu zKB`e%b%tDiDe^3dG=9ZV`%L?FdF;*Q&Zc_bRhc8dcEMXx7uT0Z2k}&P1z+Bn;C%fs zHPT>?50|4zTDJa|`Q+t9ZCAIBool;rs0)?s7ivEj)VYSoWHOn&*&Vo*_qWOlJ(xP4 z^fsi3@qu1;iHtKrRetEMrdj9jhHY7~#ZSr`D6+-?z4m`E-rYCf*c+$|C#9q3Z5ZFs@$MB0Ukk7GYK?fSk~P=L zh8vgpd40g|#h>}{@TTooDp`W@g`uP$TR`{tHYsB%-|%YRK;+}Kzz8(!l9w=j`5Re- zjxmt^x>rub+L0!1P*7han2l6g^lin{%QN^%LifTmM}SypKECz*_xy@GUD+(@&09B3 zU9t%yd*pH_uh>j+zUG(v*Shd-VQJM$mSiHhh*CD&ZCREibUCt)3{5a4)Q@NA9L8cV zk#}i+}jn;+NcO!njFX_A}aj#Jkzz~MyFI2ce1o~yO|%sxUa!m z-u@AGCGSw%_V9Kd%mwin+3Z3wXHCy&)!T`s^KQ()>PVGeE!L6!-ibE)OLng-_RY_H z3qkP?E#^(zA`Hod%^zDk%G|eCZN8TrjT%dPVo6-Om$+L$r*}N%hFS|N= zi|FmfF(se89^*vk%waoTe}<=F|3h?uoQY@uK-d#Mj(x?|hv&)inw{?QoQ#djj<7_G zgk&~Sa5ZX6JkK%5fBx0Sn+82KFr`qcY_*p|Os50p6@ObR65 zUN&wYH92Ws8XuU9;;DGdHhLl~hCg^GGcVpK=~6%6ljh2RO*iJ%pZgD!cl=Tvr>E^E z&EjgL?LYg%LI|ExSoEZG9@pm)eQ%k4m4|pc<#KrXO|w5Q^-9#$d@@%hY5oy->cQ?U z|EIZoNB-q>5OZSS;MVZljiZeROM~fc1KyhljZ5d7O|#o=botS_O=j-1N0*y!o;2?V z$^;zmH#BYOP~|9mOE1Z&+h3w>DJ$E0Q#A^}fjo7ASI^a4ga1^Yao{frC7lfeTzC}+ zLlq1c)tN}fa4ghUrU!4PoVQ)Vu}sDM7&Ls{SV)tL>U~Bm_(9Q;LD?$!A8HSUqh((% zZX5DIVA=$-D-_zZkJaD>kJwov~#J6t{##knJumcSP7F!h3ANW0JrJHB2aY#juA49^&9RvP@QK;-M z%itUUI|3A_PVZq;0gqt##fCw^0bpYC<*RBN3!DSrM!bR6B-|7BhrpbKUr>8`ZU7sD ziwZBBw)Ug72n~l0CKL`dk^~NZEGJoc$r=+O8%kSrN$4TV`@(j1yn`7a4-~$28MB}YX3GYb_Rf6sax1_lHRE$lM#tS z)J?U{Q$Gm30Dutz?q!$2eaKBa*OZq8+b0CJ3C99%0Gl4T+GLvWb77i?x{n0nQJn!? z4JK^lWPw=*{QE25{V^BR*aMOb)61 ze|Oj5yi0j3W8rOr*=kSDEPx<&EN_MdqI%(*C)GjE{C&fVe)R$k$>btb?f(LAU^chX zgQXGVq9GU`cz3`$5CAs_esdd@>mSssp(PlDZV~nNe2gR_(m+}w z#B3Gr0N((8|GT2}8vF>31JDnsu@Kk~`V7{i(Js0=uIeV2;G+pt2)w*nt^u;sxqtuZ z5oh&b`j`uYJM0hFqS|*MQ4I{>tw5XtjT2(@0-`2&Km`E)64v=MY7^IVf$?3|v~Mv8 z$`_JvpzKXt0X_n{%Mv@TUEusvrbQoj_h(1@2#$!j-&vbD0+0v&!_pskXJ86y{#k;7 z+@sM9UK6-RaQ-u&@rzr-)djzGafU06Q=OowL6r);(8@PScvn^ym(0^RB~->4#-?=f zJVJ}=uK=J6S|^~5Zd?~iaH1z!ZA@&<2T8*rh36b1J;0IC3t!kbWr;3HVt z!Y^<`tGHfjEX^d^C!2JGmaU-v$ztN2$}{;iuq(Z(Tq$`8u8bVQPjzcXk^6sbZr<8{ zuQES;O$GCXazlOfQPm~9BWH6L;>54V>H_6MlmK?Y=Q50KG^$%6ZzVW*`&8}C6#lb{ z_ONUzYc>N}RaN=pWp*G*k zl)zg(p`QqnDU;YG3wgHAQ`zVx|1KsGN+*prvEzEsy*lo?$E_5Zd=CJI4kDQVraaqt z6?_hcY<6x&iW6?`EbaIov1{+WGvak)9Rur>(g@GruEva8)Fy507^ z_ZLq(BA-9&45Ri*hv)h0-~C8bvI&QuV}@TeX?iv?RJK%kb_8bp(VMAXswKbEyU3y% z?wv3E8WnT4=kZj*%l^g=3avs`VpLSsS||u2QlwY)bbR9l(gY=!j4+jP%-ik1e?A*$ zkHo@6PAucE)@g(vu+wNbyQRG3z2<(|l#%)XPoI_ble^f-dJ6~()X_|Fsm zkSu6Mjkqg|_Rub)3xc)g7=F;|Z(_@S6$|i}!QzmgENR%#4VBgis2*z2E zqMQCDD-$bcs}{Q-XxmLhcGj|aaOTDS+?HDw(>Qloz{)_4Lu8xw%1~TeTzqkAkms;$ z?%P$95AWkfZ6b&I0!Y)rp=D^AZgcO9MzNVt(p9}b#ccbO6z{A9nwmmH9+@4&Fj@Q<2$xztiRYtK@yr0solS70!RI z$Sz(zbYBt@c=@1r6{TaiS01=lN^_q@^*+8VjjC*v)j+veTlz?LUQxeg zzH=b(nevBU@ADmV$E%-I263tTjha*G-0iApRH&kq**QMUG+?UoTpP#hznMF}f1cO9 zOxAuSpNo*)LBw6xUZ+#6_KrkZ)-(X8TuBl~>uu#EXQ;R-x%`3m@ z<&eOT(B`fRR-D?}?p7kr5}PX)EzvY#w|yD0&GFNEM=Kk=@BEKe zPEwpDYeyl~@^B!m`EAUf7Ez8=1j}<0P9+rH%2`wP_q%1qm~26e?QRT`o5z zAJ-l2Y|enBPJ`=LKS23Xemi_nA1a`p!aQ42Qj!f()ll!@iOz0Rg;YrwD4_ zAtQb1k_q7b)W1~mznC<{mZH%N!)`M5aa#^%+ZdxBzOU^LKuFZ$2cNEuu##z~KXR0? z8~~a`iTSW|?U;x>!0-+{F3&ON@mo<@Z(gWLQZ1*tT=`8gfVu`xT(F4XdFHEbx9;SP zn_;&vyDcP^odmE1AvrvR+bF?hf_<1*GT{}g^zO<_f;-sgnj6z#L8(!?MVp)trtJXE z0A>QS8%_(n#-N}=WdWx%sHup`6&y;LzQtN1+0}>|7YYTy+Mt!ZBaFCA0*nGrXsk;3 zY$KR=8Viy-=b`F$qTEaS`p5jb?XE`Fv*WD$efl+^55obFmc;%(es8#YGjs@a9FU<>)1RyrG4ZHVwrvWrWrN-WsH~`2IC%g7!9qmJ_Yc>@7AVJH z%dK8H2CO4hAiY91S@MM&`frA@kJZ@1m4KEck^T|9KH&aAx$-%n-+Fs_A&n=PiX1+p z;$MM+w4SJOkezHK z^99rVO&XHhAB>W%k5yxr8^u0XspLS%tE@$>3};}bR3>70M^AQ$DMPAgwTUDKnuU3j z;+G9LsGD=Y{D@*&cQqv0X>+6#?CLG(=UM;wJ|t|1D_r~!1l;q4hj<)&G$;wRW@{I% zX^H&I8BPh{Tj;oWve~C7fdMU3+!Zz>R1P}OnZKHrj>V+AxHd0`gXDUx{DKFu z$)~X`!$igzPpIM=KuCXCZ&9mI9{^Q*SU!l|!kjukMeCmZT#hAbu6 zOi51owQ&+-^_w=-V^f65u3qNNt5NKkWW%+yv9b{U7PTaa;Wa^Zv|Gz7k#^Xg@5y#` zPt1AdsyK4Tpo14@??3B{#`$80P+G0e(BG&#l`kC>6egm3)~c^i;m%;VJ%dviK7P&7 zmA4TjPbwkEdtiBS<+V5e(Osh!M@6jgFT&kV13oz?%RVZs6Y|Y&;Wv*KQ!n5tVKg+G zwD)CKG?xpb@cH_qR0uLX+7tem@I)1Eq@%;;i0CzHe$y=Cx}9GOdWMq4tHc_KjTp$D z-O*+vdPv*6^g8bFcr`NJJ)?p>q_@)jQbfq&Kw`-Uwd{&e4WABSy@oH zWc1%xFQU}XCLUHI-karHgjp8**U;YUSrG$x>@TJJ(n>}%rS~-JYcy}AtDjqVeog6@ z*9$6|rX@;4p>f;q$+i1A?&%o5LS3`+m_-)56zaJj+vCG;tu}&aB5`837Mm)vyfp6# zyd2g!XPNC`{^kWl5aLVH6jVscsZxLFT=PO7INqysV*1o$+#t3;c$oY}Om6VYag$M@ z?V~Sz3H3S4QsJ-Fts*mAYbai-OT@4WgrWpLc(VRx)cW&Imd7;341)YQia zRDPer_jnZ;sMvlqD1Y_jB*R@NnC`D0Rzod-H8WR#?|UN2*azdr2;Ev6mJlQP4d10_ z&5LJ7iA+8j?2N8XH(uKcw2uF5CPg3BLbN|~Eojo8*FSK-ZL{p?o?;-Ds!wq4azWFN zf$f)fH=lOvW9BHe#)&^o>#kO;Ij+t)D%8~`DvFB!8Fs#*$gWw;{aayz9$ZnKe`;70W888Kq!~Vy=@|5y1;QLBZQ@1TFmRzl> z%90XuP&l<$%~vcb0}BFS(eA^*=Q(&1QWQ0)0$ zP9QlXu+@Ma3Psv;SX5}`O9kA4cv(Hl3m>!1n#_sMegxNSE4FyU3chPV#YoU7N0T!@ zYbEi^Z(fPa%oWapAq-)Nz+k?0bR1-F|47wd7sPz$pIX7t*+t0z=4?1XA&6B6fa#Vn z)Phdpb_xm!0Re!X;&c?;wG-k32w*qB6cpRufV0=t0y7GAFx&z`fzdmYi=ElP+w=hz z0X-EIa-a2zF2J3!aa|Sg5+)ZT0oR8ix}pyjCeTFCJSa01UJzx2M$bK zI6kQDh=gNUn4cTDK1dAe|MFhdpeQ$)cY%uqv=3gP<*>Mc>GA+9Rv3?eMJWQpqXc%S za5Z4)^=>&bLoCynswyfFxWxDir|h*rk!RiIRLn7&4XwE~o=5Xt3VR|KFJ80+g2UbZ z%#W~m*iQlaaUk`;>^I2uK#`AacG!CJR^Jjd=DDs_p~4d3r~r;12;XP!TpWabfTPzu z=#-hLM)v~|Z~)!_kXFuh0QnYtWlavnfT0R(9bggNZ5#r41kJM!S$k>&GYgcQT=L91FmdjVfF6ivMmk1dG!NkjrCbm zYI->hYfS*k!5yKn2nlLYVke5Hzk+k7R+g1SW3}iaqG-q*=+)nq#}5B$8jFuosLI+K zdnRVOJb)Yc!n0xfO@J?xR>Z1UBQTt4!65h1kI1Pf3|E9sx^h^U?F83mYY!>d#hz&6 zp$R8l1K!d;L7}}?&#bA{&g~CvD(1AL2!yPAnPfzFWDuHFHdi}H;Jn&;BzwYB;?3|i z>6RKRxbw*7q;=)J4t!&;_eq7y8^3o80#cVR&0a!A=a;R~$2vfs2g9Wjd}FELSjEIO z*L}O~>FH+4#uDSke$H{ojbhlpp&iyP$iz32QvRhtztyRpcnRCI+GfSvMbZpbj?&%LcLK68{!6D8% zJ-@fioD0;{RL|pRiuJ?UgfwR#-y>e6r&B90r+u^O+7wwqMZ`BLVfal2|CpAj3ytHR zFMlrT5yVF;MEa1bhO+*y=W1N180yUq(VJMCVsXdoI|td*mn?f%BS~veC81$x+}bw@ zL01)}KX*yC8VgnOs<~PCEk)?KO`5uRXS zWov?!7w-s}Pk5btw8yF)lFs{GCwsMA|Gn4)XL6UsiT<%#%nOs~j+<9GMbvWL)N(80 zRc?NG$`B!{-uC%*!c9WaT#dy|+7%-{F$eohR*FE)0s1(8+&lN-$Lr*GCb}H$m1r+k z^ypnJ`Xo8W8zYd`zngu^k@M?$h5jc!_NuTnW9j_rD@o_N!|{vm4~*EzX6M!PNmO~X zx-#|+Y7t>*`lie%lm+`H$%r43J$yC!G(*H;gEH+wSc#*CTi54wxz+vl!_v#^Pw*Ic zxuluZ8SRXS8|O-@GYdPUP?Wz)WRSz)s+3oYDs9KSp6TByQ0TrJ}H^yKSWervmK#Ij_~Re@v^bB z&}_z!M|;oBFrhwjq4wfL>~bEB%mktJ&4DQ-Cg%y>)%5rE60`FYHt*#~Uz#LxrfM9Q zo#ff{Y&of1b8MWR4xF6Y@N1MQkTbQ^d9ilYziFCr(~xz$FYd@33@dRj-gtf?#x}PG zt#z9f?y$_Cywa`A+8d0z9N`q-6y&y%e>BTACWmfR$WFd>)oq0(c@aeS18M3A5H1y9=95JXXm`4wSKn01XMEP)tp&6C@zC z$MB@|Hm!*GtKN@|j?M=0DqV+j?Nb;lfr1C5FHVrCvcv)35r(gaZCQ}*1iXk%+)1`; z08}FoR>GVK5{;5qG>_G=1bB#hmgKY#J~F*R;Q=XSEa1xUC3=Rq(~0-2&|tuw@Ui_u-RS^=@Eskw5bO0_@Y#1y-@c=bSiywZ(e`4RE zA)02$ikoeZAoT$|E5tn2x&i|;KafuV_CNw=k$hG-Ige)!GiKV5<_+;9fffNFNFcPy zlSL$g_Ty7p5x6Lb&jf5{{!@HvrwAd72f#o+fr zAO%hbkSCBTjyRq${yJ(oJwl?|fLdFp0QobIOfC}TSG5}emJU*wAi2wzKeAte4FhiFghJhSgS2yK5snuu{&7F3XWDEz4KhB-RoD_Z#$(XP75Qc_ z4%@Fov9_!oU+^A*-r=Bc=J?u6S#OHpK1@iQ$ncvRpyPonLASFWp+^jITfqJ!oPoeO zr3pX^v^s>@$-lw3h3@CuVF%>gv*oJ+5CV-aToWYr6`=#C^jZO^1iT%Ir!H5G$$HK_7}(#~`_T zz)V0s0)V{0XB9Cm1Lg#LzM^b{pxM+1(u^U`s1#UXAe}lw+i-#G7lgurfJ*_B|M8nSuKRs&s zy5SMS*(dODOxP5iM{w0#^v{Yu3HvRI4|9>qoR2#0s@Hev{=i80p70%GA}WR^llm?=hEFQ>tyfYq#?CuauRmI1EN>_GKI1G#{_AVZt-{ib znQt+-Yp4BGEgdeOp*`;!a(ST7;K8-@hDC~3CGC$Y1$Q>Dy;N$Np<_MR+#2g%SF!CJ zTane0YbN|8H!mDXJ*~&uQ~WT#;|4u%35EY%)oIOhCe_@M1TXMMmldwmR~ynEZV0l? z%EVqf^$b`GAR8GG@*0W%Qc3zKq9wwe<-yf0vn7Hr_XOGqyZNYZX|@}gKged|n| zBz-Q@gyOyZGW0XqaO>Ej0#P03B%1IzgYc6HUc@;pITt2ZLPPTJtW-ga`>l6kFG?f% z#j4YsOjndBtz18=(6iU+oUK!tjZiSQd^wBbCkQ3K$Dfbanbx3=v~Z%RU1x=}a_(;y`&h?Ib+h;%oCbcjkw ztCXaYQvUbjdB1h1 zHUjUSM9u__wtQW<@z~IUHPwOXy+u6xi(_d=GV!ZrS3P4{rNor31j}rSyKPcP91vx3 zg)#lTN=7HSm~mZ_@!QlNj`{xJURGa>^03(c`w;8>T4v{bp9nSq!vpaJJ}hZ65eJ5WQv)N z*cKIOId@2qHvU5|lNz;}t0rgMQ7MjcNm7AbD_7hBd)(4LsiyVC1`V|%06-$3YbICXa}+@|}oAMB8`bqrWE_h^D%toud; ze&F2HwZXuKdv_*k)*|D|AD%UjC$q#Ux2m!DT7-d466P0gDdrGT5RCzI3mW$8=HcXx zHMfaEFsUAZg}_fFm@a3+{_na}P739J+C~1*OxVp?j%r=*1Q|ZS6_7CjFHj8H0wz7& zDFD!6uO6xj+lwkpw$6H00Ts@ktxHmJAEsX*Bb+CWLg9-ofXqlAqM z1jN0hfFhyUJg--){we(O;FmM{>e|NnM3pe=NAM<*=J{RH)rx>X;6$V9uIL>0!odSU z9*`(NkApY@{s!I$A}kGSK8e4*^#Kng9?Jwro`@WH0*|(}XBOkjJG}fDPcN z!MlP&7jdD^i$lWJf2JG|v*f;q!30hTSc@Uj4bd3%KfMB9+5)QH=8k6%=&Eq9ihILM z3FHmvDUirksKx`f04N`AwaBv1VlM(fUg64OXkdWEg2L_{g1|tI2z_g~AV~#9VxKaM zI)ysX8`$#hAoHNp4%vRS1&L%(@d87!6}*v-8aRaDL*oB>C2&3(7fDF@U+F8LG+?VB zIi-*ih7l0Z8!#o|PrcgmY&2n>vZgIe0d>ao6_~*YhIbI}4uaAl$z$=%(vK1Q6KFvZ zC&zZQmOnO(*@rzhWkO&8NAe?(&=$bn&cF&W<^i&da0|wYIjTpga_7g#D09WZ^Q2cC4imU#`62NJ+&Pu64NHVIYJk~8 zjw1}-3~@-jjJVqpNrK5wGPqii83C;0a1RKWwG1p=QZJ;O_5Mx@tl>ON5KnZzfrMEq zXr{?0`O6SYY*V&GmyP*p=u_}^Pl{6X+M&rF%+PWmmA=~!${qMJunT}c?h=E7^x^dZ zPzUg9&^Zvf3>V70rG{Ed$Jf9_HZ5jvqEHjM6b4ZyaN*S;_YF)XFl^4dG{RK_r?Y96 zRj$q}kXh=)HfvIXEai8;BQm_&z>11|Fa&@czP$2ve);6o^RH zLzW32z0)hM4euci$8IHqrvc^67NK@bmnC9dBgckIQ=WXg!5*~8Fn1m1%O2(bXFxd) zI+|PY#KG~o!PrHyq3iZuooFZHy)0ithO#MtyQblS_?92jh(#(kcDMi9bo`U=U&U)U z0w>xXO{IrD#2XjtrCKD%*VdJJ`GddrhNG_UDxk35-l6V@h|?Jww5Kb|6P%9_oYV1^ zE77JFe`C#rYeJfgXQER}m`h^EdOwodnG=g7_^!i?HSUW!;dx;te#337A=EriWqG5%ibeJ|gCaiKW4-nd#^jwHOy1)Stk;Yzi|qt#&Q4|DnmB0I(lhEJ zrwu71&k~$VB%=3uNPXSYq^A#Mjhj-QpUx(H?|wfXC13Yag!?cl9<77iu%EoxjGvPr zZ&8c!4C(!Id08KaL?bd%PK&D4r@B~tA7-FXvt|+~>Pth~^d;|~&%S^40xhqm!5@Hw zJv=>}_N>f0d|5(7!Et@BsrK|s#ONanVMo6axAz~gDe+OP-XVEJZ$7)s)X&pn-G8h7 zAwcf>GWzdrI$5T(M2rwl0v@Hj9BZ1-@WKVJ;zWwDyusAwGcUR@a#n6!xtF6Q#J=hQ z0@kvmD(&PMQ#o`E6>L8AX~dkRsUZUL)+Ty<9F59?&|@E#w0b@zh@n4(>aCr|`Sp1} zdR7c}BK9QZB5JN)erUv93X<{HTs ztk_X&*8N3W98*`{xw4|VCH+8=p|&Ob1^wp7hm;nk_R{mWXP#U%;H1IsrDJy6Kak2- zQ|`;8;viG*joEljj7OmThWJ9mr&pI79^W4gu_ihvH~a7ox&eD#lr~Bzr*~a7qB*SQ zvbD003c8y+8X9UO47M&AdFvUvZ{$ixCb>8mB%CItXfd_ujC$MdDM@ODt*3C(W!SLW zI^B)`TJW%vYA~T{Fl&mCXwB6#W;SzY?1O#d^2v}`z~o(%Ro4?V!4R!N26;@?=573% z!k;`*u}hRzwRsDI_`N+t+O4h~#$Wf6j3}HQJwIs5Ckhz8dHeB!$5ZkbwgTJF>)S*g zN}mx2d)1h#-XGyP?tgezrjXI7X^R;+AZ_}|!CrMrDDD33O$s4ao)ntPVUKqu_?x>i z_0J#+zs+yf$ATHR#FmzSLGr<-d4<>336Y`z?xXdOzvlF^`Oykx=Yy59-AIaeJcb1yvJ=DNAqPoOVpE6^oi_|(2Y51(U{N?Es}*`?9aN8-Dgtu^`oip> zGaqDI`_JrI`2Z=9kL4!U7(&4ZSAYB_^wgp*Q2gFfskE&l;fS}LA zFJ`BAo6e5b)^}S0qG^~BK$_4wplr6a)yz!$COe4P5Fahb2VnE*@P3asQJYzn+Zb~=D+3JFrE%>kZOM<< zRsKYGydq*ND=(*b;CC-ifFTYWRoo7&2?SV|h0s>F0zv>8SKzf21fOl5_WbvR_;_K~ z8y|9hXZ0`EIl)d{Az;XnmZ%%tlMyheT;#|Sql_;5NsU7Ei@YjoVATY6ByYQ1p4=Q{ zfFLJf6?_Qn1sp^8Z+K-XZctactc_g;eF!9ZBA5$=aUwQWBpn^{MiyF*Hx>D5tPUXt z9AF?Mb^{;*&`BW9lL!E7AU6upUjl0ZI1s4j9}T)#6i)!pkyLy#ceY=P%vdl6qRh9I&x}AYx`TXh~~@K<4QD$D1sOYbK!;-USIXMLza+hWWihDw*TS z;crHBM>H_=0Y*a}r%ZqGWefO=>SV_rT!Uc;$wdVZy7xx)I5Y)B!=QnPXh27dx@vyo zXCkfyG7Yu(XY>O&2Qu+rp)4mTPz(W)2J#;eAV=ste$RPc>So(r5WOG}&w~q$jL2ji z*&nOK4rz8sbuKV|_p5KR1W+L{{i2x&sRoqO@)r}Fy_W#eu%ai<;6~*w)UQriB9tqB z0kte}37Z36h){g``sQWD`uvt29@NOxo~Iaz(2gLFeJ&Hg0H)k8X5f$sBZom6?k)@O zREIlTQd&D#xeBRZ{0FrbFvLh}(H!KzMf{rn^ZB$XN9H-7CF7`hcSEz>xq35&HIFs) zy)oKh6y><0P7Ixr{_?Sc~*L zEv`grW|COaESQi|DZBfeT9UqrUVFmY~5q-ocAHYv{!ihN9#kDgk6veewX|9h(0sNrDtGq?L?i>6ow zIl9Pdym!9wH{~LCSyMu^u~N2k!vtHrzMrEZlHugU_D0XYMsqeWJkoZG8YolC*2Ooc zkde|-P`jW>svs|JalT}HVvxlL<8=??@%xgIOyN4+RWatOPo{Fk#Tkjqj5mL6;m)fD zXtrnIhS>^KO;w;g{=JQpJkpf#?2{v8=6`0x zHQo-FBbwte??ahU+{;UDbJmKih}B089PqDq-DMx(eKe%Fb=mknmb8vt!M^pB+ILK! z`u?32SDW`k!OrjeP*Pa9OUpV$(y|%X^?Y0KWauiAZB7_a#od9IxWsc9e}28qZY|gE zc>a?BRmeSsXB$V5UxKw2*tqaLLgBu3)Xz@5hkk$G4yI8KU1CXJ#y-AScP_3WIO*aTN@J!5@ zO!vx|0J(#$1OC)GoeLEPBXT)Al9jCi+pJA82XQ*QtjW(H2mz_Mv1tr)auMDYwgU&H(Fb)1bOzKnZIo;_s4r+3#*iT zk@`IUP@Izd!yomvDX(!!r+b@?8z+q>^|QqHsZ2_bBn)#xhpd=Z_3ln_|L)iJ74xuR znJptTzQKOG)6y_2=fq+wPB<2w@x#pXTSK$s-fQU{S36N77-Xd%m^WTxW^DD#&^_t3mZt7F*@$By4X;sc<+z$Z*zwY?z8(w^F&X*?r z?uD?3(hQxv=vN55cZ`~Clq!D6lZrOE5Vm0c)$`bD@{dpH&cp$3U-K&7??7Mm=%07h z!c{nlhCi{=mtS?iqB1AK);24JE>6HSO3Ny%EM9`LHUAWyx0*Pt1t&O|+JlJTM~Y_H z4Lj#ZNWygQ^em_j-PJMvdCMuCM<<;9KL4ZK{fPd8@4SWLpSc2@L^Jb-ca82fb7W|| zfFccZa}-K}Z3lERmuwRybO8DWgDoUdppb?Y6sif5!2sw+I3y?#2_!{r*9INe9`2d_ z^*~}yLEYF1(i22B142*eFGWJy5qSj*OE+|c0GosGRuHxTN{KBUPFF?QhG?`ttrWZd z1MnGE8^&31eJz3|PL1y!aYz%oj)R)EFVx5uvq_+%7LlM5+;uv8OKtVZ>jKf6=XSvi z3)-B3@ZYMfJlC$*osfX;y(+VIT0I}ECkdXp8#87DE_z!2O^sYL&Uq5@`sD*O3V$M7^Ra2#ZqT`@ny zb*)u;x1i-UPuqs-#X4-`-#)tW*biFdgF;%58(XcqszKNy2NKWsFy#RaQWum1l2as4 zwnv%BvS94y#w3KYLO$o>;(dTZ&}`u3j73^$0p;2NRZlwv%-08L-MUpyWB^PDfGh|v zGXH&F;}|_ z3Ai;fdJlml!`;?f0Aa${0l5>M#HME>qGNgUDeRObAl zC=8m9>Pgse5yLuwF!*+SZ?B*t43Nk@t$?3*V3&g=+QT`4Zw2z+!)X|$;SgGeE1}-@ zsO{W=vIh7x!(Iis=_;IbfoA&p^ZsP#&MEMPgG3p-I#q{+WvhtHc9gB+>$=NWHuob= zVP(scryp)>I_b7>%unNz>-EZ&eR}4<#LY<&D)pjXa_7g2yH6A--izyGxERu~=U<>y@cSap`8)|X$_HPC0#)Eyb|;GKHIs{4Qp01s z9_+m4v$460xnTsa!>}}@j8 z7F*4MpzM+DJ z)3(rCnvdKmY{UZl+K+Rtv@$HPugn!8l3nXRfELx^tt!%61M(M6|3W$vV4Lg(wn*Wef>T)e|*& zd;$HJ3Pj2zNxTFR+WvN*#`jxhy2YetuogOq`cUy5my7X93Msc^Ez<)-gv&(F3ySGf zH&cbICl|$)B;j|CVoFH(d)|EMQE?P1tBIv*KUBTtrqSa1&^eGuQBnKur?Y~?C83mJ zdG;x1JXUPS-_m*Vlo7Aq4kl;&^u$^Set&LLrt&D@=S3l$tX!klbRXEdu9a-7YVx^h z4qMfQP<5z;$98B}B&BEUI85}RoogQ?)o8j?Px@A(vPlg{2w3w4-FyYAhkTq|e_qfg z*GULm;NxAS2pT;7I`o&pDNVtyY>Y7S&BTIMH=b5En_Is7@aW$CRF!Jd-*l|37jCeU zCYb4u=*4)ekPF)SWk_e3`~@x6wCv(%oZvePE>CV`Io5 z-u_V$>2kB1xCjlN=O2j~zKC@-J58eHa0jw4Rx4jp)DOJEbU#mvl1wdT^KFT$hQ^D& z7pUs|>FH$m04wkn=IGk#kf!t1Zt`!18#Mwk__letVM%D++#P;u+)~m#{~v?|47Syh zpRCZlI|E$EqrtB8>T>MPt!hCPgjB%_6UyO|HZCa2Y$9T)$PKc>*4vxBY%R zTP$HeeDv=2ns8)Zu05S;+)#9CBnY-m7qAD?!!*|*Uo zt&{mquMt+?3PbLB_d%&*#qLJd#lWvxEW1>edA{ps%~fgMlB%-l&YK-7UF_T_xw6wN zHGx-S51ozE17&CYqQ`hUC$y^sA5Wt(^1|^NtknKy;bHunp1(s`4=-LW;KgNZN2q_; z(1BDVFJ2Zl!r&s!-Uk0%sC)rNA^Le1Z2aNTem5Lxj42)W3V#p_pfDtQ!ow_*v%qR- zU;u~!=#e3Tg?{HLw8?4~AuYNe!dwJTX@KUhC4tuSKmRMB7$8k`l|%$TXl$^jo-1BtPW}pC3JO(z zSd-%dIFIbwzwk;Rl2VXuK)%{!V!%H$Fa==jFfT#eNpd?*Z7XU%hD;~H2MS^#k3I6` zTfJgL?xI#m35OeSrGgYBh786Qq%`lG2Ltqs&;qFjnqBa?!rQ#{-3J+(=3C>Z(0ZCMtY@l(@i$0xU3o z_!m+G02rZF-HT7FxiCV2wH7hZKuiop+)ti#Bs~quBT)wY<7`*!FI5ioxBP;FA_NOF zJN`Pp{iQUJdhTef7BP|Sl?E{d?cECshin%(>X~e02QT&pxeuU$09?Yr;<%v0vtyO> z51|7l8ZIqJ_pj9X1ZlZojrtn|;gKrw-z6@bR=n}u%HA~a^(3iTK;e+H%3-Lu47vFp zTc*FH_kH5F&)aF@H4_dRsMc;47&oB>F|Cl&t)3AcA{iUMtyqrfIs}!VXaM5t zKpqZ{436Bc#;q1a2F0p65BL|PBm#GgD3;-HTDigF0A3JJ?%3sj?F3uR2gr?Zx{i#s zaNiZA054~I>kkmc_sjyQK}-g*C4kH#F?W!k2%;V&T;*4a+>9 z{A)taiZRX}h)#eP;US8Ukny1D1~m^tH+Jh5|?P$ zt!M437oWA>dO+nw^JSYwToU5T zGv};ky)~NE#`ie+FTa?wxnvIKtc3NPis*npi}K^1`@Za~6g zDVo%{!tN)79hvLQN-|!5UC(#=IYv1xp&Ns~3*VwJN-yGbTcJL3p86_L`S8vlK2@Rn z6fc+j-wn%Tj(s+LDsmi2wE4p4(!jkzqRd-rQ=a9c6-O>k*mE{7Oh&@-Y(@gR=CH8R zc|R(iIT{Y*UB)CVw_PN$%-vZ%>q&n4;uDWXBe6vMpQq!qse=#PPSew|lcV;rZG<`X z6fH!D6Dtc&`IBpH*D3ukr|9Y?>9?bQ@cl{Uyr3F!JHwN!*C5T!T2IK{z~{N=ydKY! z7=;4HXVC*#Z&Zp*>zR6o^JluVLyyW#>K>zF?Q)hw@ECIwonEcT;4@KJb_rNlB)DeG z4EDMA30@trcHF7G&sB*M>0LMJ`+O;ia3BoNX7=0RX8V1v$MIsfCnfO9(6q5DNAfAu zNhb!ix27syQFsehVZ~nH5)Qez)BC5G;7L8t(LYnaSS0r+@2!bAdD9H& zsy*s+-*{HYTNW_wwuEik-PG2jpX9)!YNX6{dFD(@sH5{Pwr$3f{3)KR8;qft){>g zJI!9;*~&VaCb#ypgwzYkU!9++yUyb2tgUGIcj&qVc$f{W<=y=&?oZ|GuSDI`RsL>7 z)o-vgD$aP!r5=zezS^VP!SUL-y*sKR(?D76nT$(2qrEzpol~xyhP4_!p+oisx_aF( zUjf@C_s18K3vQ=oiH%AnaFehb-fS$hJedt)nK_~vnof<-r`7EfPTPHup6QRn_z5G( z5;)&}5ROCc*0St1ut)0szRw8%WcI-Srka?|_b0R>tRknTXi`BA^J3ehQpswU09{o) z6lL9BDf7gPn=Bfr3$6L=TdySKt?@^{-B^Yhvo?(&FszlZEvsE>p zUkofYJ|3Qupnu6eKVgKXDkJo~zm)b&`d(Yt5FM z#!;Jv)sx40Vj>J)d+%FaIg<%HLoizh`;K$_8>d!RBgYQxDLHdWgeX0w=V$n08fz3U zqNz$f=WHkEHuQ)%-Np~SOKxnxm}zNttR&mFdwUB_x6PId-~i|o0PZ=j_|eu$vYGaS zt}IQ=Y44!Sx^)VBuefCg8^;nyl8Sp=`Y`V=)d8{20tMyud$=pW)VOE+rh+>Mo@Ux= zzy1)ee0HjZg%kGa0K?FED@A+yLK;_{2zgnbv@Dh?nv*B&pK=qHaPYu@Ko^;oI(&ga z0SW|p^n#8DfES)I$Z7veXF>O3(%~BbEF>X2Qe?2;k}Ig|b0w=Hb!+g`e``I6FJY}m zitp01vI3?^8DhH97Yd7uVy3%?5S-@oi#-BtxHb+_3K40bJ&i`^z za$f_N0~~?Gxiy9;&_K^6_qdqFpS7!V;6gD%3@3)hA?1hXiw z`Yu(!A4N)@`{+Ej2e^{Jk_0>$q|CxZ4Spn`H$Yu(Fbi}Aq`ARa303@;R)ZjC2(1L6 zt^gWAk}cSI&}={-mH|ID`k<4}9S#C$iqifx0j2=zUFfo8FFdh zZAhYkt@D?$G=$&}$kv4!4~{yrAcKGkpgDDQCuq#oy(nb&c>mr-YMZ|=TE04nB5}h) z>T11jC0n)>)q2-$TDGi!z=H)70y<1gOrW7hfgBgnn)f872W=AsVL;ms!62Y;LR2om zm_h9!LI6Q38;Ew>bH|#G$g^Z~hHujSHRi~@96TG9xG_;~g-o+B+%_~cAkEasV2+8a zes_hkGE?XAR8%^y3AZYC?rmevxmg%C9BXIr<+}d_yzciJM+hg4nwFNKwolMHfIaf7 z4lqo>c#y{BUne`mz|W->CKsk4nq#D^0p)|_y^Z)X|0!E5p6(IP`>w93CMkZ3o>4lL2fu~^KfYesQs|u3T&wZrxhiSKmeW*zG z)E>xC1vMnNH*L3|ju9+vKtJu^jwAAVe<06b)JAzvmw*%+G(0{h8PK^r2}O#%R@|xz zI_p!#W~1r&7_KanersXmG80u@Hv_2hzx4i_a9I_9vGf^)OBZtZqNqWku<+=}zDa#kZr99meQ}{!DYSVo`+McXXrssA!HrFqWiHQi>=|_@}UCHCrkYN8!z$kw&Mf*S|xw`1X5Z1oP(t~k9I*^;oHXb zxPC9J>nyrhg+vMq1qxs6r(h~Z^Dq9c{c(dUz+243Sq|0tQjyY8@R8#-E0y%33Mp2{k1t88IC+_E$B z8&V+r61gvlLq&mm_1A)r5L$jdkri8TC(I(+iq!yRc6jbEN=T_}!16H{jlI7viRY*} zg?JnL8ywZ&&bZ?F2b%{}k_Mf$bpZog1qFC2r*Bk#>Ri{j`R*$7pJehxQR*REDxT@O z4Z=%`8W@b7SumFEM1}8keO6U8PLdmz0sjFXmx4W|pHBbL15srhUXgWcwsOvAq9Y!* zR(TgnJr1fdc*7Vb3CPHOH5P9mIG_9~ND@s0H{ z(*hh$t2v?Xc^2%%DzlSJk)i2{<+0Zvr3rPCOz_hrh(yKycoWJhh`Ne1hW5wd2VTTjiR_g3@;2c6`Ng+pn0rFQ-pekR>^Xe7|%``qK}WQ^YC;UragKchbR$MZ;!23zfX;-!_<>BzuKJ zJBIuySi!K!Ueu^8DNvK;h<{MH2QA@E?zsw&&fw*HMCVGlF^!(%C} z&Yj$7O};D{1WdqO%77ZKhd}mXm5}Hg~5#PXMc$_@f_aM70UKb{iY;njkC!Qt*P*{j6+kAWwC`*^v-&6~12( z#!UygsE4O>e*=(iw#>N`ZUlZf+O<#1e^@(JxAv|PHkhuEZi!@R&Yf<0VXgddF7mf4 zLi$esGwmQH#yqcHGff}aUu6KA0m}?ztB7(1mQsG2?=`;ySS;v-%Lq_MM@Mvr)VNp# zPk`zHo&aTT@D6|q&^#kM!p26)jvj?H70&dJ5pNqCFF=lHVUNn}lcCh%WmvXBfQ+S2 zI0oG`DCQ)tDUdbD8G=>?wzS7&Lfe2X?dR|9?WqLd$zx!pQlTfLqe1O|5-h&987T!aMS$QzHjjSF#cs#}VpA8N`J~ztpZ{RXRJjOu%Ap7x*@y$&q#2N*G zVZpJTke*l$uLeXA#Dc-B0#_1j_z@UTWLPQ`eibCnFC!q0p8xiRn6ATK5lb(QvU&Il z#}~3>LDLM%5rHo*U`O`y5<@xUXTL}#2=u8u6sZ4BH8~)E-WMug{E1R(?MD?5M2m{hw1|jOj=9H z_!@#rfCL<*?x1yn&v_x*3X@h3r9LF@7{J*+sUa7dZfj#RL7U_IlMjxCaL@k#a)3MA z_)sJ?P+;-lKdP||qKoCW;Q+%m1~n2uZoMciy@DN>rt<>6!}mMnxQs^jZwv1IB*;p( zeui^9;9BM_nD%6}KoJi2=s`dQXz<6)f|y_g0SQ$%@MZ$q(_j#Tfz;)Aqt?pDCnMN< z)m=hZl#tDH&jZ`mEB;TG@}jY+>Fl0C@s|)J25?ha==w~p*IZILXNOV`@qLQiX!dB? zE{)62!g)Sd2q~XEaeiizd`d&5q{@$@i7J#X(I6K(=i1S$>Mp|DSH`BFMkU6E)_g~3 zo6lK78$7U5Rnh+eccmbmlG$G(cX_p-^m-)0dtOVq8~C4aXyfw})QDdjGN0=cVWsbi z7Rd7VOo}7f&-=lNRmwjhum0$|*l8cP8i$4ug|-USk8V{Z)9x`F9D_@Kwa;4R3GOma76)h=IQV=E*`@><{ZOMA(=RXIdPxVA~d&&`oZJeowp zzP9b=dquaP)}CH&*@RPc<@|Z_wh%3iwe`{PFOF9VBMj8+h}dVAqc;+Nc2vsI+-EPL z9Ox*xFVK!+q;D91h~@WgptOZyMvI@7e%t>6?Nj*}IcJ;T&!SStZ|Ct$&&Pygv_+SG zZpruO64B19n9C=1J&MoM?Hs>K_jy;jaMIm<*6E zfO&bk#U|&H0EgQuKckz8c9X~2himvn=pu)Y6R!!yRu|M)%G>j;UzBD3!r}snn=hNx z>Z&NMqsl_1^W?j=PP#iZ(h(Qq9Yi};vV2ZXP3-(xy^gqs#-CkPc17L4YWoPwK4K>JfVix)IohWs!^@w%A^vU#Z15C3x%4?U^_)K#OtGW30o(;)-`cP7>*{l96 zXqL!Lev?6*B~@}yngu;SQ0jaubIW5olWSd;_qtDj;}Ns!xU>75WRT2o{H*L#HUHyW z72*!7A-*{QHbs=Bs9eJ?GIeWiL>*iZ2_1)vw9h+?| zWc`Zq1lRbvp9+MTR}>jJvz+{)`{F3YEJoI`TAnv)mpf^P`HA^D5-`8ojQxYy*g(Cl zkF|cx?rLs|r8Wf?YtQt7K%F`tAO)SQA_vA$QmjMh9xF(~(Zc)Kj)^9a; zSwP^omn6M0{7b3fsp_1sDRkeA$F87AG=IX#1Y}yJC;W=?$rI~#-c?N!Az+puPZmjF zH+U%oIJ>zyCYY+zmm3K!i$l%#XxXs@e_D}v72n$$y%7B~O3ns@&jD-sukw{=FyW~e z-)@9fd#4x(iJK2Wcn>fFL6p8cT?ClV-*Y5Lg#;Z&2FZb#8rDo$#wwE?A=?yE^ z;?UtoEypuk!isb#o8>n^K*Ek4@^L{=0@E8kZZ!;rf6uo5F3AvLPMOOz?!n9{EiH|h zgVbv%%Bld=NKZnkbr#&*lV`n-9RTa!3!T?(J5v7z(E;;_19~GrOWhW}tW z0Tt&lYJp23)~^OFdjOaL_D9uJrCh_aPE&14Gf3rfuy1h{Rur zco)`-ogCFKM$Dz zAkXeg2Yu-#+ND<}o3 z|8g#!`}EurjvX@b?C$QqE1x+CXgc~?j3nkkXEB1{Y&~=4D|9lHserj3LWLIzLr@tS zHp8yZV)f_kPT&cU!$qlD^tbTKf#edToo}(Z%ZJrM zNQ_xu@?WxAET2xpO1xoxfe>XuV-u&7Czy_h?V%l#=rqme^^(_MjS%M#CBsPpTDQPC z`@Kqt(JyWYnv)}3;J19VM3z$aos$`*f~6XL!w4aREs)<&}_Vp(GAZc`9r^L~j)!BUtU zdz%{^DfeK`vw_m#3b9Z5%}@rk#+%c}IcgqF!xdJmkJPv*7%=aWh}dw7dGRI3m12?- zMQcksHrAeNjW?T=-5*1r73C8MZ?>gqjix>%&nUXeL59_1{`HPX2E8Et$0HTe^^at$ z3@<~TP=?-o@PAr>>~9+=TfXt4l**BH?B-nydZm7yhw+~acf_zR^yH+hZt9kz4qFn} zv@zd9@O3B}BLvOsMpTt9av0ekXS8^}mgn+K5#p(yCnok3Y9ku%B%ezR_|a-IrdpYh z&Kq!({p-O30fWEthP)#qUfRdCOguxLzzfyK8s~*Jv2Zyz7zcQ<6mQ7|B!7sI zmJ7Yg!fsxF8nL7H)`*d%Xa7vHLQI(FF-=|N;ikc#&wc{{bsVjDtS*Fb`}rosmErp< z=O|_@j30>&elO4=zleJs|4%|lSgAj$D2K9=_qOgUtGM5+Yz{db+8H;O!(Y2p@`bB> z`F*I$kLnm8-I$L4`940uW$E(JNt^LYy!XXDUeSC#dfCD|>XJ@toCI6~jBVxQX@p4_ zo4)vs?3)g0?)(I~ON>)WmdDvvu^Cf4#yvP;Aykyv@->(8=84H3(eC_mqOl&4`k?ue zJ^s*Cwa1@);FeCy_|Md_YbqrX%(?OLLC&QEVpc}JViUEqIZMiGMh`!B23&o8g~RHV zpw&XjrB6=yRjcrmcv*jqiuO6pbOoKvo+qLn(-%t{s=7IgBgnKE+h zJ}`7R5u7r0%(F9H8lpJZpqbEmW8^hHL1(kUOJKZ0Jhau}4>?%=0yef-KlaOU+=cwMpS zYR~isgC=@@!!*nQHx<9uN#16BwrfKzSTU!J|FMYBjkxsLV)YG0*j=*2T z3xR8tA#i~<5Xl&aJwGg!h!B zJ?R&);Sf&x-e)Zgi|@%CIC5Yf`pcc60ll>;g#x`RJ8)27!A6ocfHC2JNEg#ZS9J}- zGPa;i7)TzT$}Nz%079Ru&o7L5rSn?w&JcKi8X6msvK$D)1Ey%&XE_TQ3qXh5e?^X@2KEIa%OEoZHTVjMD_HK~1A*2BN&J8#3F8fb z3`y;>h-q04Q8_{1O!L8PjPAuQIf3CF#7hGZ3?kofp9EZ@vKPEIuu+EL!xF?c5S)fc zPdO>!xDVjgLNG3fset2waRSaSa$1Z95Kl3Pd`(Ls)Ac*pn+Kwh-vett#Ngz^XaWop zSbGsQ1@H>n^}_+@{s~Lq`T@}na!!DzLEOl|?;$QAc7SRA(+mTD0ZJjnWd!5i>Zc;t z!!jG@#=mFBLO?MgWrtTl3(gq2lBgBqn(hvqz2rwKFYDf>If309h zjzf}pVA}X6cj>!SI*;f!z@-o7IHW8AEW}Q0AlHU}2Zs(h3xM#!`y;OhzXduABsLH# zC0R2xz9E%)plkwp5eyZ-5E&D^Fbru3)CZ6VTVW@R902Me>Ljz1E;D3s5`w@##9ovG zZI}p(@*P5e5rIykX3?*itw35N{O_GfW5jU4rrY7qd##U=DHQpU1Kk7+U z3U{~owmKhtmQJBsh%N?oHq78~iw_8@VkY#8@u2hov?NeW3C97#01&M`0{aPslY?Gn z>xBupthm@g`eIl@gEUUTSO1+Z4Z5nv%?4tKDhAETAu(LVCri#}+z6y8b$0mAx0T+$ zjcA(?QyN>U+QLJ#V}^e{pTLWfa3k^@xSOC~fWFfQl=r|DBG(4I9+J2SMmqqL5EUNu z1qRcR|Ccjl8SyNYGhjGNG7{R*LB@q#iBJ3UK*ds26q&IN_Fn~a$byF4KLQkjtby+i zg#pYFwAm1Gja>6TxP$%Sn*h9626rDkwGiPmJYe{J0wC4upDTcq5=qJgd7D$?hA61t zfHq{5@+JpsCUX0M%q%ZO0jk4AQWH6C;NF4*-aiQ22si)`d>D2Adg^GBCRorQlM$Xh zh;%IOf*69{g69zK|dY22VRK6CTlC`f?9i@Ln8kRj)%P!?kSDeS{IcP zk4vMteP29^@ol|AvX-8>YpF+_^u^u!LWyp?IR?|8B8Lg)y>##D?JiZa2R0;G-lApMRtxu3TT^FHlo{QJug#|h>A|XX%iHq<_8TW@S_Ais8r&?Iy0}rDS6@n4Q6G?Y zVZbSQ*U{T%{3)&Go9DUjnhB$-2+%pR& z$A$=gWUme|d?MuY$hnW3cv*n%Mn?^3Fh#y_;L`vx5WLU_@<@?9tocVM2Bj|!q8TPX zZItKvE*^kamxhK0yQYn+121dtvpr!f;^CPY;8|1{RC- ztj8MY%aILFha1l5=w^oT}#9n5@gx z`{aYA5dLvVNlAGSrCf-$CmD;(fQI5bTqpKK%+@h~fbYr(8`ArudvPJg?1UXwVF=v^ zau5DK^gY{m{!0UbSs3I>oA&`BF`rv?IEKVH6bc3)ukzJI>VJLV$gE{!6LGM-|mw`$vSJ20P%Q;)kL1q&O3xZ^W964akAb2vpeP~B2rGGI> zsdDQW5hB6fqC>DV%WF0oVR&F=g+Gv>lhFzTHO{?Zm>6Nm1Jw(Rx`_7=3Kn!5)35@y3zT@y$LePLKY1x1;6@g^jgnVHN62pD4 zrdQmx9uCJz9>V7xfii@qBl@P^0_I!U#9&)@7LUSP91jWQ6K^xO- zAH?IbuO-5>R)xsXcXv+)x+iN7o}SJHowQ!dWbGGM&Gb){_;c~@D>JTU9fhodE2QZk z(#e(6Mr$ckCF*fU6y(D)22xjkOUPlLYg3{#xHkMr)%$7hzzz<6$0TkYo+MTT{Y^E^ z8iNRI>W_#Qa#2qoUC4m@%mvjlObc-0{}E4!QHp zFIHd9PLEJbB_#8Y^-9cPh%J}yI?MBaASBC-C3Bd0*4a#(ESr#cs6V;XC`y?lYR$ZuvLvm z>-H4d{X;;l)SA79JC}V%3+$Wkc+MTR}bH0Ft zlsuM(yh@4p@{+brdh#p$6)H7CzLFrybS`Y)7lsSgEwlN@cJ3A*0xre{hf|oxV=;-d zQW9IbwPOj8ccrfFkj&q%jQ07Vh08!_>F@lWM4jJFeJ+j-{q3vRpx*C z3aN~YY|1Ws9xFt4RtX`gWUpk4L}q12RQBGh{;$vT{r#V-%jNPIpYs{#eZTM5Jy4g6 zzOGhZD4|}xL`LEgsD}qZrOZrO`0f_od^YOi%yCWJ z0y>oAVe>Ff@_jEyl)IdGPS{c}n*P$4uZaX5E)PCjt8>Sa8*rk8yLcZ=mWiqalboF@ z^qW;#sq(vLBeL-7bK@c(E%ESOV^jf;lsIjts)GI98k5YAwa$kR=C}VDBwPEwnN+L4 zb+w{kwtjM|f1}}+^sI8SwZFi)9=VuH8$sNY=;74K*xC1qfkbBUH~OlVG9A+%fdcN) zOyiP!QnD1AecixWcCny)vMJ8~Bt0)v9;x>)`q<6+(fzx~n2J|e-OEFbj*W%4~6V<0G%<*hQa6zH#hT|ozv+;qJ%_W31{PoRU5Ve%ntUkVg0?!p6b?lsoP1!FT zHlAq~V$inx@_a7r+e7I$A8H;vUKM}QbYoSTTra#(St*xrEk98-X|2D_&PC%b;b!B? z_))jO+-ef}hcgyW&(_@H`O|3flBsz|7H|V2YnS4ytt@G?LbcU=I;t3=#Pm5ujS{uya(_ zj0V~QPzrzv*aRYy1(^RMxohCz1!t~1RPP)wmi#>jTm)?05!VBx+~P1rz+50@vJ;Si zisY{#L`l}$ckh7op|fP1d2{FF+-m)r;)HwW*=Osz5U>hCJeiqRrPsiG1%P6mI_LKX z^`PZ1v3MI0i9jA6p@l@ouS0eg7Hb1KP5m1$#)*<_C79mTgRv%t0yG;iv`E|nK!uXc zV1osz`*(Ul?-Oe7X?8RF|HAyO+|Fp2Kg>;K04)&=rzGE3D8g1eT@We|VO?IYLNoU~ zQRnF&ACFPVZFaIItexL>{m%*o5=&@UWGm9zy!;wtMV0sT%j)WCloIB)l{l6_g#Um` zcPAVw51u>3PBfyR3bw_ ze~f5j6bM(5^MshDapeg>7Jk>g(rLwUr4-Z}h+YZCL4fln>_N~BQmOq+?6eo44|uT% zXh3vNh^2@F%ed^lJR;us65Lu~hlkQ_Al5+hgTuB=)5`vZ1r*Q$G**fO@c>sA5hhz% zg%+GEGWYlMgDNW!m<&u!#RKnX$EL}b40=;U5e0a~9sU?7MogiF+x5c+F%o?w`Sb>4 zCY>+&(7GIvB~H`tWR0W+gT)IFkoN)LQn(_l>4t`eU}Fn~I|<09-NLoNHGhPGgy|sY zN1&vUtbh*2Wth5GuGf`#h;fTy?>ti@tR&HrQ$3(}u0f;h9uhPsWgYFVjsYA11$pP` zdwXFdlrxY$fZT%cVnBcU2>1yIV7_x$aHkb`LB#bAUx^0`A(Gh)S62*ry5ZinbJ&)r zL}suze*U?C2~H0{8eq2`1doAaN^k;xuSArGn_EJl2&kApKku9KjRTuMqAiBs4kt7Y zG6k7oVoIsF&tdNS8yx<~N$dXYBlKWa`U{bRi1KVunGr-ELvNQd6`_1D;1Ua9f{^D0 z*v5FzcAf)+*w6olm_KfVtO$~zrls@? zy8x=E=+yrlDb`#A4l7`4>f4p0YS#@Tf(@fk+A-PdXWgvEq+{7D4_YNo8A+kh*-FD* ze0TQOBZvcu%<<{$s?(j+r)Hvv{se>s_08Gfn9gSZ5*O4cZsACI`()5X^L8@}`e*Yr zssZ<#bnF>VMoGzlG^#2+gXANDRTL@JDUZP)fn%fgrL4S@QB~SZR1YhEUv{XL${9O! z9U!J6P;pfmX+l?!7D*>Nh3maP{u3ZVtz{!wo;@az=n!wIEZzRH;PTX4mQ}gcHIL`5vTFk`tUqELlP4x7O(o!|Q%bv*m>#q2jqSfD%`M0% zlVezMr<=$ROK`H-xjj``_AFJv&^t#NCERY1LMn<^n>T)g=b$% zq(vtXwY_EskM|Yb1G8G&Vk&#a%w4POb~sq-pk%mg=+m1ir{B;6A|H+(Qm9Md7hi? z_9;6{>YQI)n#xvbH~wL#p9OY>&KEhZeUV)f^NX5aJFW8hx!C>9xIOwL+eI~r9Meo+ zzAEW2zCyESzFf+qv{0K7LzB%bk+@wUZ(w$^&3{T7PBeAgI=i9fVH)mcF2|mO_gBoU z7^+jS*M3|YLbhz@^I$H8-ecmR&VJ;Fd|y^}rlHZ5JCt^DJu*r})Rw=V96x8G%<7vg zE8c3b+wy!mQY5;_z@Go%U*pQ%3z2o6ord!E4|sQjHYvT2rbxcAPx?RfUVGO5E_Y6e zF1f2!@5LkqwJ&O!J|nJM=w(bDN&WT z6LNpmUC@wh8nRP9oKOGv!P9M`k09TF yY8`pC)Mvg7rC)4A_!LY45D`q@!(AkV0rb8B=Ha|I1h^b%eR z#YWSO3pQVK+j(;LqtApruLXJm+I(O#vs~*hZXa&>sW}g}Z9+QlD!e{7c?SJ}66In8 zZd6fkyI=!&f=Cs3 zYGjdxcUe#ZKw3IZGa3nZ2c0VW!KbU>h(W^DAr>8p zXsM)$0(Gp}oChioBuO7ET1eS1BhEmG-k5I(X*mGZ$X;ZcxgY7y`=CsIa#iB4TW@ZG z$@K+*4peDnWw>7h1ymzIy>3zz@(9X|Baf&{<$@sg%5T}m zexe%yLk)wO5>uDR>Uh1QXu~!Q+#ZZFo&aa${~d1`nVWaOfGVN;_xhM)3CNQvA@mLc z?V6#l>3^XxNRI>(IZdwazgSd=n1|g($W;+nT0rCT=WLLl2h)wz`JF&^aHQKxmB4fk zx-~iBG>M8<#Cz^y2vm<6!9xTf0iF?PYK#CZ4L<@b3QSYv*PAhjI2eV@ie~vy#P8A5 zWud*0BIMJv0JqTbu{`SZ6_={p@a!QuHW2UgU&R)#K;N=!Scm&hF90hrD2YN^4e_@K z%P1%qo7&^PUo9;(Ro@PtGg0xy#bHx;Dp#coT()jv7(MDU|x03+gYF3?A$ zZ9$|CyZvy4h>6O^CcK0lmoIwbB%#Lv9=QMYKN)-uJaW4&pNf;SL!V|-3CD6$ajBgm z;1nQz=bx{UKw97~gikFHKlNL7^cPA}UNcsXoTha7a_e5~vnSW?huElU4<=MRDiz~M zw!BDs3tgas4ZB0#Z`)raQ|}{4nDeUNCS{rSeV>me&QIz(v1WiT9vh;E4prvVv>#U$_RF);rO_ zVzG-wbFcIlyl(2d9mXvRO;qi^iC;TUR1jd4nt{Tn{xWElj8;P@eNJwrI|D}NM`IP% zW%{MVCxqkH8{(S~!?m{mPQwq|7nT48gE~HbZ1TUACAw2BJ!vWMJt%a<@WXWiEa%T? zDl!^<0UtKr(;k5WMSTk`VbF`IKfx~3;wbSVWuAZZLV*g(xpzv7yYO{5M4r{~psNHj z@`TbM$!_=U74%QRz#u`?9h}eYzaf#DZKl7cV{3^bWmq z&`?MzGr4gbG+ExZYDSB<$_N?L6I&nE&Fno=CezHwuOdPEzxb*Q%`&-y2z$#VGJcAxnkqDP=9 zKr5;KQa}A)mXll?wd^5i!u<+qbqR(4%3TW7Q0PUOIs^lOX3PH|kh>gz_eG|dqHT;b z>QrdKis^UOFZjHZWISJhFrJCwLaipQ)0vZw!!xA<$9&3wZ~d`YKQTI2St=JD>6s!+ zu#6A2KP(8x^FQ0=DLsQ}4IobOtw-5xFJ8@$3FKbVuzu!W{D`IhF8877y6tF`R`2Bu zHf4p8>c~@+gN9c-Yph>S*K$3}drCt}OG$|G(RnIIL?_ku>-n{e(4m3+SF$t(otDY)XAsI0!3)UK9lyI>3RutRN@u@!h(C}k*?&@A31UPK`$3cvgeJZ zC6|6b_M_j~iyN4VzTvMCZ_=Osx7;oM?w@=9Prgicy0`4t-`8?rRu#;|jQXtl+67!t z))2URh5o1Mt0K3|B^9>}d18e@2b}#yQlHtHb)I~>-o2Cs&B0>dq0^q1JU(2oej;|1 zRVRwBq?6wz(M`|xc^=5v`t`x~883l9;!)2A+BI`)PgcAqtXq4;wT*k)PPa}zOV2d} z2KyC}Yf|79*K_*pPFa>$R?1wb6!Bh5%!ZwTUCW1+9a9;SqxCn>&c2om4hkM$?RqE| z87Mt^EsE&Ps8h?{mq!ty=7zX^5l??=-+@29E6&DBj9w3@7=AP7-RZYp9B&b+jlIN^ zckM{wr+cH0Akoy8>tF#_#mkxi^RX9!69h-ja*Zdm!D3&EDea$g3w-y*Z{~)R#PHnc zKY1WJy)S29Ns;s5TxAfda;$w@#Q2f_luOp=MPiG+N%YE**j{dp3tiH@qF($(`lmSk zKG%pR%X12fW#>YsW=N`cJXeBh-KK)1xD8x5w=vrrKF`<_e9r&rv?^1|#ekdUGM*Ts zD-d-ItlWqXSBU;nh~^ay%>ud#U059dp3dR_p7M#jjjGrn#+G)$A4IXRFALEpgY6zf zf4k-U~nm`Hgm37lY8KZ3ufYREYHL{OtR?+?O8h1a=?D zkptn&|GE~T84}PFl7s1_)Z_7Zm;L?SuFkLI6_<`Y&!5BlcZTDt9Xj-2s{tG%t;7h%5x=K4JQgl2-{6UL5jpuUmt} z09XXLRA7gKOGB9Cpv^;rh-x4b84>XS5r(XPfU^+y5#-t;ng&oD!_Wv0TTK1SmOQi~ zAlf0wg+ZeDkQoyqfq`Sx)BFh^AumxVUZ4OOKJ~lQxI;hyMXNp zZo%w-$8$)h6I_4b(q{75PXs_r>wd6l3uGv$GZ5T}T;p?3R3tKNqPyXO0-T)%rmf@u z)Lk$T97rTnY3NA$_YfFDWaKFNZ&P#wem@p@a3&^xDJp@I z4ou|pv3SUT30pg=U8x?2-2zOd5O)=b=aBj_ zA4pnq-=4n?>5v$B6hJ)3+6|qrFs~am1Ue3RW`PF+@`vl`m-3VgT_n0XIub+1FzRG{ z2of$t{{>y4K-7UwOiL4zmEkmF`eR54Upxb)I*@7sQ}!<_;hBL6TU-Q$X@h(Q$ufow z0N_t}vYECghlbi7#BpHzVUq*HM&ycs){T`t+VcV2#-sc|lNswD^vbQZBi$$Pq%**s z4wTWhNCMB!MS_8(x|qoA1CuAI9>25i_Hgt&=M6N&9|p$tjwlLwB27iC!A}QQYJdK! z(xdxzJ+pMzcHuntC7a?#fLsC@_W?6p9k_12o-+hHuL6*2sUSY$>OlYCv48R>mCw6R zO-XPwR*T2m>}eA`+g;$vCSh+k`qLJc*eXtAo*5zZu-0;aFv;x7yI!$GBIQ`7Zi1w{ z9ykXBl|&c6sN$Z_YjwK+-m_E``R*?8b(5ow=sD+(;?x*XI?oqOb2J{Yh%pFkT!|Ld zyho-PE-0o-D;Z*RS9|@9EhT3MY(d$H zr`n|BG!!+zxALfF5#16=e$vU6L-tMhnPK|W`+n)bpxXg)d=U#)d*;s~o+=Rjb}<`w zEXsW_WnQOtc~sW{l`L`OP-av_MU!c(E;&WrkHdV3`Vu}8FT>%;cO^=xFpL#q=*QQOqkzJ4LeDpzYM9`jw-{olml9K`l zPrd6Va#@jq;XETkSfS0DtM_Z!I9~l@(NIy=Rtu@1R!>qY+-O9}s?FY7t1%34n{g)Pti}4CC56me ztWk8gf|30zN*W(k4<{*Nz2znKGZSxzjE756l6w#KWd4}myz*#`?W1#2&9?l0h+V?A z^;sda#?D#%94Y_q)shUFJD~z+l^d^}3=>2OIVPv3bAP{R7kh(__F3cQlkB6qm47@( zegiar0G0^h9ZOx-mCQ zy{v1;#b3-mr!wzUJdu9C+n5x9`>JzMqY( z$etUKw;N<-GOZEv@1lhE@a6|@W+W~w;~S>ymz>NN4yk10e07dr?z)}y%9kqNPuu-g zYWcap-Ig|QJoQ>!{%_;kbP$^kVwlx`qi?<`c}P7tkwtdL|31WQNM^`2PR&T7OM7fQ zRwn~>(mDw`USxZ+4L!cKCVix_^Vfy9AP>)NsACd&t{`f3ytDY6KHYw-de7t%#m)(l zK)tb?+};I`wKq4z2j19z*X=U=L6Jc2HvXM0d+vK{bzO?S61hjRqMfvT*4(w;yPa2E z85rI6%08NGo_|05e&@UKcWJpIpHox5=fC^1e#w0IR3SW+gi{i~NZiWCu^dKr#A!o8 zChou&)W>FNI5iq3ejxmmsL1zuYW=tSwWMeJ#)UC_VZIh!i6PP@+fzpu4Vs2yhtF^w z{kW|(CheR!?y-8o@43pxsVE7dRYl@2hBtqm$lXvJzY{blf32I#ae}IN4OOc#aU%9~ zKV$4uR`$K-8uL5%=c-m~8`BP8#R^v8DAwsro87J=Q5(iZ$kYLuoNxeTk4 z(VaUa7NhR)J_sU)iZp6%|*OnsD>Y zx6+1&FTZtoXvnQHva=)g$&kLAc7DYWNah$e_di`T>BRz?Va0AwZ`(jaP7Q`~|4T+0^_7;A zf=Nf8G#Z>`fYrclkAT*WbifCYbY^#vRz<8^2QY9cJag8#T~Ra2(l-8K>GuygNytE$eDp;fC~U17PvV09FlRsZv~bt0I~4b z@F_IFf-oq+)vAG|zS*#G^9+ztV1rf{ECXE$;A({OL68QVEG9bKvIpo!0R92aK;*9L zk6i;W09cniKWuccfHM9+F-!1qXE5lKTD%*#&VmZ{`Ld|6FmejuKR5&*Aawv60-par zRr1hKSW%H6nE2HWw}D=SV*$wtSJ_XX7~#+%edYfII*1?%W}7ZkfL4I;L2~netOUpg zt(}N$2V~5UnvW9XMQ)OvB3-zSKM{pJV5Fdfv|uKrM5E+ntmG#mjcJ%VQV5u3nQG=& zI?#aQJtq18%KNE|`v&EQu43e@B$9+28V zVl&+JFjhpGEx~+fueiko009w115pU4872Obnkql}asoaF$yfja4e2F?OJ*w48DsUe z?-jXp%oH8_yh7Pq4MA@AvBya%6@?X&>Fu z*$Kgs5nvpEq$3hQSpVe!1|8TUBT(1`A%UF;2L<#P5M#68PX|WpKQlfAWP<89juNg1 zc`pysX8@Q;{pG0B3kcPdsR6hWbhBg_QWF5yjVRqUr+&x@e{A5}w~w=MWrz``GXx$C z4y=zn2ZvCZH-tGLmlxV&LK^;)UuAR_0%ZK38R7+Sl*kDJ+7GsYE))CzM*WjV)RUG1 zj$?Y>KDlN3=&jY6J-dq0$>q_nLwVH~^0IT8Vu@7g$yy2UP(TgG27alF8$F|@SZ`e%?Q=GI%QvhO{y|2StFqO=YAUfce% zEUkERZunCagDBT*;6dP1u!oF{k3&s+Gl=&#ASnQ-Ky%nHb~O0!Azu9hT^<^E7nt8W zg4h9=WL~bHw8KAuA-I$*oJ+v0P(=qwJs0*vrXrG2Ux~kGD+Xq^EW!EzU+~f8!XdZ^ zY<#<6learN*PCUHTZS1l>_DFfY-%*x6U6Z+Yrswd8vGz``@RXEosMQ?WF%~(tp8jk zV8W28vpwWQcBzY@11lK3&8KC8|jz;Sx}b8NB8&s(#*Qm5-~%Gj;#|3zVqI>Ze~He|@7cFB9UI9F`Z#ab{;fb?^SVfyB~d z(y!xa|IGbz6lW+-ipM`6e>Jxs=Dw+MO!> z%&a|?s>AZ5&8}t!#}oJUr;Ywyx7tt=M9<25&va~AGJ11akbdF7;&f+*cqB(dPYVtF z&QrGLaV%8y)O-F*Fg=UhX?9?Zr>I~ozZ7qiyG`AyE_BW!<3uAi=z2B1#MQfjgR-8% zvXnPbscY_UE#%Oh;otZo#J=AhJ4twOqdDt1{E1-2B;h44yh$e2+!1wv%PfD7!iK_C zyVOtS7as5#u2=6eSu@T@5)00fTTWaZmvQN;*Xs9x7D#>kI;P@Yw4Gj%;(MR=Mb7+3H zN~_RU?yY5>soZ`=r>pu3brE){{`7@BziBCl;pB6Lxkmim0ueitiHL` z9#E1d`)_jR62~R>=?`{sD#a5jH|sxXEcu;|VQ*Aw=3um#-V?_jGLj#zlLV348nY|IOaknB+Pf+Wqo`^DdxrAKJ8DOVv$*p8 zbfQo{AA%V*V?pB%BTZtZ`|O3ba!fwls=GU;Or6@wnXeW86n<4u>u{#`=^;+Md`w$o zuXU~`I_~Ie5RR26M!l|-_v$mAqq?ojhT4ab^H7x{K8^vk=dl=d#%RVMN(5 z?s0~&T-8c?$AW46`#3WZIp#={S)9KU(P=O8D%J~OodKtXP8lm^@Qz?6&BFw6j56rt z(S@|L+IB|8U0y+cA)VGi-!~iF?QV`6CVMdNT)Qx}S&EvjN1FtVCYjkaMLCZ9=BUkT z`e$ckmn`7-QHa4^@#bzyeiOUrx3D=* zm@X6nPr9Stk0Lg@1oeh(2d(>qjd=7e^5k09=jQL)qJT!>hSc@Nd?1#L~LFeUMH6|Cf) z?GOf1LAs;#CEkSfL3N(w^*~-%QEIM4x9Rs@a`f*RSJKRXTy=kzZ{4+@l)OEp?$xAf zP0elp@5j;1e2`KW8O`_oPsCB9dJ3G0Qse+YT zf2{eiO@QM178xISN7%w6Ek9XsBt_43lTjalND9`Q&k}ySK_9IWB`a%cI_Fr~*{=dE z0&k-08qoPnMU!w^3yIow~ z(g*G1iC5WL7@GDkA48wUMOe63r31y_%`F}{ z@kUTZ5kELhj3Fn+z>taR##y3jZ!a(K&+OO~bvk*{jp+QR?Qyyaq@N{Yxf!4=fDrJU zIyu6u78JO)+8U`}Jk5a0a-#}_jG>dD>=qn&*%AH`*fSta08dj;P^4Raac50E{RNVy zd%0geZLvTCo6SoY%3PnyCguNv)1{RNLK_%%rP62>=z~D(7;pSP^);5Wf5i*&fJ@do z14UV=lhrzP{AFr-b+R7TE;loVqoX5)Jpx*DcMmBbjfGVn*faBzNaPFw9)s%xOZ%ApIY85tLF*WRW#Tt}fJ=?)AtzFpZrb4Y1Wg7iDgbhT(m+0rMj>D0 zy@Q6iw-vn1E*lz84bgNnze-2Qja^*bW%{hNKcB!Yq;Bh2(_CX z9UWDMS@3MUQXDXbfGz=E!(t4H#1u$|AQB#p7~a97uLLYEr20H;I(*aA3Y;mNK_uB~ z`zUY%8bU*20XX(txw@k%NrUsh4k*7$4j+nYm6 zO$}Fl6aG6|Z*@{wJC#d@k>+&pNFiH|W)^~+-&?*x>WTX0lz9&Z_{C9h4XRbA_Bg|* ztsTx*J@E;0IDrNelt97);IfB@3GfhVNu|GqMteYS5MT&wF(Oxky#)YZK(N4Z!`;Kw zu7={b`YS6h{|jvj4-kG(H)xY~Hy3~}+%|w47+F}_z-0jU1}M;xJa;HX3%87d86{w9 zxEW!`L!d{wa`oy};G#j(hcAB$y}rOlB8iSj>ch#=9>QdTGj`ig0Z1~*H;ki#U5+|B zIxnWyX4lsfj)G0>?mIcfD!(V(=W$~~5f47Jj8fxjxnB#7CroT%9H1P8*5J#)99N9~ z`WyBmDkmrz*A0zy6T_!CYkTg>53cQHH1urAv-QDtsF8t_ZoO{O1+18*l?XC|y9YSw zKAcn1Pd0L5^80K6x`6om`&SV#6C|yJUJyz>j2aItHLyhQs?o*p1OfYO$@p9>IZ%6O zNhtu6pn|^0rSC60!c8|6YDqfOV@nZIMZQEp^jTgs7jI2k!E;g4xK-=k%QGL-L|g(+Cog1Ou?Q;2Ut=%Txj?^!jhAOVV5{bfcM2j=v-8~8-MLvo=zr717} zzZPKT@G%`pl|i%1jjvur6)_7Rj9z~F8_}Gd!@>RAIM_So!z*hHzYJ9gW>>s}ZTxD6 z)N56uc0TLTe`R(ryLDIW^1D!{^{M(%4=qnqklQ5ayRkX^EE4Q}^SdN{ppzhp+W&M3 zt($zLExVa3c6ubK&ck$(A-o9ln#4#d@3stwaJ4wW6XVD2`_2Rjx9_(S(j?IkiwQR4 zsYdXQX-DdPH*y?B6Q`#hWhJBd*)Tfcjv=4IZB^gT5Rz=gu4oYNYt(0Q?Kp=z{E@%; zl=@%5GH$H%wdMHpa7!A=xf|Jb4d^$C@%?Hs?{#m!H71j{(=yWBZObLUxMh@+(fL)v zLT?0xInBmGzCE)i#&M#CX4PxR;Veh>=-kk3 zC5-*SDekc?w!5;-!{U0~x7VURDV*x&Z#|c${xs^~Qfb2#`yX|6Cc)p)9kDC!>D)as z$u<<1l`xd$S zH2hM5@$&S|9=5JpqPfq%T9RH~oW1(_DB-ZO=7EwG<|pa8y0#6yBon&ZLyU*RK;lkC zN<_QN-Ng&iNu7p&=LxlmkMDK@Q8Y0ccXN7LJ{d`} zE0}(k$bj=ch1^5Sn!>%L7uMeeFviCbZS(GbWYuz%#VIo*t2%FakQc}dO(r~RD14t{ z8O1^Fc|f7`M|HG4A?DxCdB9Bzc&efVze)cHk8#cq^Or6x;Z3idw<74Aw(X#j0^J` z)0tXPCM$dG^PI#=yR1*S$+=Diddu}IAjS_oJFoyC4VgeemDSWl%6YFg?*$@iqe&M@ z+LT!tglAbONLz8rOTNXmC1wFJi(_l*f@u6$_`n@eUh4``)sG~1@?nef8a)fQ;+QUht0+va1 z$A~8oJW7nocZHa%3eDZ4KoG#gA;pB;Cj9hLu_ZOSa-6FyFsYA_YC&>V$YLWr+N7l<4^Y#l5u(Qq69R1*UL>d^vTU=T4yrokBtDd}I972S*$cl>%h)G<3g zPn9&-n^H7wISazXu+wsirk!og8`F=_1XGu%@7YmwUZ#4FC141dy@I=#o9g!>nkCZa z!?qT?W_9;aGrX1LYiM$-78#`DdjGeX7TDNyZX&OLd)F#EA|zSG1}v?b$YL}*r^iO#PL!TL!%dh zBTJ$2;U$dT&=9=2u8qpoJ2*we5q^qk%+)WG!|GLxYB&YSxijYtu$(F~^c)oWtpgTZ z*rL@t^A;DsN)a`S|5W2Px8Qqr);}&exz1$FE8t$xK5fO>lK8jmH1>h}?M0qD*2?!| zBGfQc1+%SBM5cK-%+5acdO~(mN^O~0v%AcJ06egSt zkG+)@PBAT`Kdgo7yuOq3%fPJrPkuF~EtWQmDqc709(l&iW#jf4B2Evv1TyR&#+(qF zN=6S8Y+ay+@{SNLDG_^Xl$a|VpUJ~Fem!4jkf43RqKdBUkpAVnqVFDhy`Spt9({LK ze^O2mt4xd~mA4aZSGm%;=*7!Q8kenCCp+zz5C>JL1>*VTy8MK!X->B`)h@&|YZR5M zH);((L2(p>MH1khhN?mnN?+e3Lt}=@RF7LPs3=BcSj<)PE$3-JQ*K{uAq!y+W=7Mi zv9OI+oh^N#afB7%qiG(Tv#yrl7VXrgZGE3f@jSuxX1O52XUP!fCo3`X#j%(!6}h?3 zS+rRG%9@ZhgBrgT@3Yw4>~FQE)+bMh9`Y1@{-jnK7pzW(b)R~*8jW|1g9B?a23tO=?Bc}^oR5gykBwE30qgK zvA25THd*wWqJ;~7kE1zN&l<(tRQYhz(vQg5>^-@*6K=d7-@<4dgd45+wWiO4C7Jc< zvFuPveDlEe#(3@VHS1){E77jn_24mAGRlM}vB-_{r3;yBf!wDN1pN`kv(DiDg`~ zXH?J&{hm+Gx+!tt^{`l`SBg4E!i%olr<~^^Iuc*svBQm)%{m;jWPTW9>#m;LV-mZh z!G5CF=Y9Q3Oyv6!%8akIej{~{U1>ALNvZjSXeZ8OexzHr&aYnk=SXhL{&;)Kacehy zmm%Bg9k8eFbf4nXtyU5fvfDkS zmm*CNm}yT(YZ%znvg-}KU_aQsM6!H@EbgeF+|UaIgF{maC{B(56z1e4YjO94ZzVp0 zPz@!ycpuG!vO&iZqz~#kjN`S@FPzW1p6+-UXU~@U_9Xwy^6Nib`6=sdR5;2I?rE9V zKg@>9oK!;1UlTPeKF#jb8Pt%~Sj+t6+Hta|;a8%eaKuleu_JF=Hu+kd@5$29g05n~ z)GXCH2};snU@bsV2}!=O55=J*Biohj_0Qc^Cn!cW!(xIuS-Q&x2$_(P(Za8|L5lQUV?Mx-!fsU+q`rvYq9pia33?M?Jp~wn z_^*MvK&-~HvSgfuFu{UDf{*6GCx~JeaX%v^6@M~d2i@HJ`LiY=xuld-hmb2zkvjTN zjC^3h14^^F(2h8byC99SOJrhax1R>4z{-N^8-w^G^rIHAoFOwcQ3!CcTPF}NRTmTo zTQg8NU|WL44@eFWae<=a31+(5W8vpdPH0FHlahJ}0(tljn4$osg5^veZ0lTnX?DAKK3;j+~8_C(ngfQ(aHaOp^H@x7%xV#I&$X3w%05cv4q1s&; zhijn>=mgLdl0*bBf{u&`934ESt@}io*e!baVL(qIfS0MtfN<)JJuokP~(M9oWpWyC6;RBftu$y7k z;cN{bv%lEYnX-0TzO38W*idJipKxv1p)cWH|E+O2%FBX7H1>!;|8OW9DZB$|(!knY zqGkaSRRH!%#Q6X(49Uyn zIY1+yzXyn~&)v-p4{m`(-bX_V7YY zdet(JBMBiB98bT@z@G*n)nhILjH;KGw$oRok3$eG1)6pc(G{^Do7$X8>A8 z&dMxL3EaVN>LRBGao5330Xp;t+1f>uF0)9Y0Hi$ta7t9?af7Xbx**f`m9E}B~fiB5U!)LegP_pP6bQ7!n*#tJn!(r-7X#7U~h%bX?7X?A*#(G2?W&vIj21; z*yo+D#0pqriF$cRR0625IDTV-6KDUKPQA^&o#iR zwvP+o3x_2QFvLO@x~B(aZ(Ydr?9LI95g?~Z|3o%6zV+yXQ42G*S-4DNoL7a?!h7Op z>Yit;dubkBYxk75`*q{3F{w?Mu@LXp2Tmf+L>s(rz<0%I#?*)C{{ar2CA97E2 z%i=NRM|a*1*BiE@m;9-6jV}31kuH%CMl`pobi&vnWUW>i9N4)`{l!DUAUpIZ9y@$^t89i6b?J zq;H|NTN8iY?%Fjg(70iL6%`0QSv=25;--KezGWe4C>dMl;^EFp631Y&=8*9t7k7@E zh@V5~K<*yJ%zo=~Tx!5GBKb$CjJJFaxVq`UZ=S-{D)$^qn_uQ~_k`G~gN zm~ul6xqG}^X9~LSMd`-)>Qrm&R=qbY4XD~UDw9(2`n-X2T*#$jhru5lubd0`ed`xSUXUS_9;f1?f&Zg z@+IkC)#+)T^qpYNftWd1U>eN(Pz}N7)XRU)m39)jcW_y`aD7V^BmepSU23VVMON0KJ~@y&d>1(rZ*-B*ZXKM#0_gCO|nc~Vx_c@H5nQn zrKxNkTT`9L%F*V$pFQBHmYmYxPIXSi8{Yg{a{6Y^ROwdszVJNAEq}YYqSh(3XdZN1 z$};{H`rRou+FHD}K(j#tCRCh*mB@yE^~q)J0N~%X)kbjMS+5L`TKPF}=CnB1Mm8z4N~NhsW9Z$=la8 z*q?Alq-YiZlquVs=wdu>;OBbt*`^$}r*5o~-x33q`cF2Gv^wvc3kvQMPV2r?pu7%) z0-&9vM)`XkRH9MFDe9|_M&jALSaW_Yph|laydoi=v_^t3VbCaL#aT`5uPNC`L4{D@WsQu<(Z2X-IvN9z=ZfusOf z3RqtOUJyT_GKre={ZI4+>;;skVOXz5VF=Fln2b85Dp)5WWd^u zg!3V}i~wPfIZaRc75x~%1CXJ7Bm0o9@n~`l`ja}@{1M$Yh^l`}e1O;*M3D^#0V_C6 zqu}+}?ZM~`00WF-V4bByLGmLc9J={>)j&Jd8OgT>IDW_o^VjNCpRu zWYaPfP;CzD8whj&7BD5KI!U$5s&=ldtROF1nX1&o3Pu+R<{*#(un5R%m|Z-y7?P5( z2q60{9(afWEfcS|q8a}RwPA%T0Vld6!4 z4YFfBI8H*whn!mdMapZaxLFI}3;?jgj0)Ht>fI8M%OkM~5M>R6Ng&gZv>p@JhL0=q z1&0|B$yPzoD9x464nEU z589BR(q1SznVhuUt%rmk7}>x{Aby{iG6AH}@F<)lL@WI+U@CIX7l{}OnCe8(7E+Xn zs~P_-0SOcPzyn!-0E!Q>SU~h=uz1)I@PQlidGSDvMXXG?v#$2c#0Ip{bm{v&k3H2)xL-2yH*jHO^=2ccC~3v)1n0!|V+ ziaOI?j#ptweOPoxZ_vlA)0{Q$|RJ*`zB-Dz}$DrC5bfSZ=tL0JdpKalq^ zO+aV;$W_RCnyB|)Ga5}O;q5P<^M&Vdq8b1hNX3ma58>fOlDbRJA4m{*_4f9HXsN=q zdXingzH*!hZ63`$X->lG8t(C7&m*-Jfsy$h{)VbY2*c8kZfH8wOesi3;vm5w`BU&f>HI4;&6$DgO9yXA z|GJlED;0zPZfm@QobjwGsvkv{2{If?yzov@3k!AWb6%x$FYuJMO2qQ57NqDOFI`$u z*SSt<`)0-tSz*?#Vj{Bq=I9h6PcuoP?K5Rw;&{-DDt7###93-=9d)&&?eq6EjGS+X z?P`0?8R0JQ-Yv8damI0di|$IixKJEcuT9k9Z9)FX=@D9(ReN|`*#fH|S#nB$(Z6hk zl29{mXgydZgpbol|2v+Y?k$!o@rZv^vYdh6&h_(i)657P>sI8;F z3fY`nU*4h#R}9rdUungoxS4S@Mowx%$pyw1ST_ceRwCwbI_3k_E}B%nk)POH8++l5 z%gthU2Yyu_(p_1VAQme_3vL|z`{ZTDOYA{?=dA@X)rp6;zm2bKdbRW7@ZVx(Yx@4! z@k(AvCmef6qyUo)|BRvOX%T7)^tIUbf;rz#ywF#}I;o*Fm!Gl1(Z7bZUtdmlby`nz zQN1}umd{7HN%9yeiQnj%B=b1l4e^iS6w+&^qm)Oacmudz(+XxZhF^Om8LW2jn#W>m@m+YIjCRzabF3QWq(+SBId;OV)vPa z1y;N3SR_3ihbvb9##K2Uv3i`H4W0>cW*PCBV4LY;a~%15o~E{7?Q8JZEVm`jp&*#fU*K8ie zJaoJH;$>_~XJU23I7(!MKP`3glyyw(2^W=YRegU_*=Y~2zVXM*k8z;!mQuAz+Lpz!bGEB#I^E+*`J*Rv&; zQ(o(mzg@FbGdoYF=k3$9mo^`?Q=)D>C|mJYroT7#yrSETjvPfJjUKL?hsusFO6VEN zh75<238cczix>4!KB23ZWRB?~)WJvf% z&LvrE;0xs2E^t)fS+CpTc^ni!mL5jpcRskJ<)%Ec9Pwn8{3Gig%)gMvbMoTo-Xm3- z{e`TPMG_Y8lRG+J4N(uzOxp2dateHd-=8eh^GYYG2R!*T=#-FMLi) zRpv?v9<*6w?26!Kb!vyczf8HnvV1|reAZohPM6Jab zftNs5Yh;lr8Mf{>0aO8!ODaM)RuWKf1M80j`iQ|w46q7m2Ag!b%0ovdlU~+Q4Ln{v{6pdy;+6i&nES6>1OYEhm9FHqIP-(=5GF4O0Kx(r1e_D_W`M>3 zKWt35U{VQr`_;}pv1+~zi!=}yQNAyMC~$UuykZMWamyJbL1<@b_~5VlZn1fZH8gu) zjB~7F&QCGThU*uw1~VFfo)C0B>LgJ?F{$cZWj#;wX_07)>kDy#LF>;Qrimgy{-vXNyw zpv}zdx;&Vts8PEXcl>doq@e4u@ooR{kln_CPGM#mgzlPhwzDIf_ZodTr^b}|3?2XwBPe~qkHDP(=%>&MRtgGlH!s49F|zPtZ_~EkJz-^-IC;2Ul2Bj98jkD@c>^c^j3U?Twa$myc;m+uKHkvcl{q(*8UKK(I+>WjmKCE3N{%OsiZISA=X;5BJeZ? z*ATHXoGRHZU3%otlz$%0i)#dWEY|8sDE5~zA(K(@)jOh8)EIZ+6c=Tmm#F`_UAkM( zmi;}$&C4*`$Ih|VpHkFQbiMkoI`ahHmG;iNUa3wkj}FrLaAw9OUKJ3U|T((9!0~OLRI7 z%Y%=p{`{5sCzD-;n0BQD@3e9qkG${j_aM!HyQH9mQaDB1S1;ExdqxOfpgsPSR*-X3 zs_N?*E`vwzgG1N#(Px`kHbbu&lP!I?+o)tq0=3Ls1m!I69u{Y?b0=EVUc+*itdtz; z(tb8Az1u=Ev0dpTox5ep_Gsc5fkbKcsgK?`$yKh|2z{ERWUvKouV%NY(r<>bmtD)c zCyrZjvZZ`NlQiv3P{Lz$3)2`3lg6EmWr;FR&*QwP1@t(nZu zGIE_@99CsIo?z8EIHfb%8!5SY%OHqWeMRpmJ9>HV5=8CVJ7V8Z$NW9~^+uS1xQ$1c zp;Zm`!I;>+MBzsa8Ki7}DpRlc{y~c3*SvO=E#YeoRQExU&S8*aOa)iX>2k$h&5a=AMJ;;wF{wLSp(cvtFN*W~-d@CBGhxBe zCZ@MLlu~V~esn*E{VWIT@hl2*h4}d_YrKFdZu0RdpCG&sr+l-NfF%b7t?oRvDuyb1 z+quqzy&I?NJo??VE+hTRoHX0bb%wcjXx zwUS#W%R4@#7Ih}MplZ{++F1MgM9RHiTHys-TF~POjcZG|%)~KFtthTL`k* z8?5OzO2ev!^ek)h;(wJGDu4ftM-|G?gkSV%m85jF^_F9I-(~CX@0tBl9iFDag~R0-9+c-~0fL30*x_L9Ujd74aK zXI(ySaJx4;Xe~1m)o`>Z2v2;}V&CYo^=+rtW5)}V8F`dKf0gti0|HR)sU7_DOgZo% zb+4QwYFRH`By!Z92&i=-Gw=)+W&8>wUdge>m3OkfSO&M`QpP>*>p5veR|70jv8rkMfZwzWfTE*!3X z8slz_vv#{fFWtCi-taKf%+aOw%_}+o%l%=nRjP~%T@%aBr4u9cU6UHYr+swfWxP)O zd!AI8MCHvZC-B~ires4V^BF4q0*dy0pW{PDh46MZLJj(TB%=!M{fu;UP~6WSO@H=f z1jg8>&Y`~vGA5wx^fM??6ibZ{%$_dt{}w;~M?8&Wp%C!7b z>`NIU$xX5w1CJQgXHRc0WGM&O^YM(zg?XI*eJY5Di%aTQ!tBH}%kedD6I=Plb1-5B z>%L@$!|NyhjnQ*G*5`=ynB4cXVY2Tya}rRt4f?)?Dk_1Ubk z?(coty%IPKxLv7YnFf>AQ+wyw-F2FkFda+}CqOsBCB24}8}NLp?X{`3BgR(;fKY&j zz*y6Xlutq1`twdn-paRsJ?iQq<43@kQ!R2y@SgsI$)Da0Uz$RAVYCbkz$VAUKGc4_ zLkGTNWI7*yHRxBF-|qgnOA7$@jWvX99B}(UUsnqG1n@2biOQ{0y%605O)1T{u0ZS(LTA7diWj9yn{{}8NfT~W$R`9Ai?Mb_ z0q^@Lz#RAtbxGAzBv z3-(6Arwox_Ak0z?YnRK1KyqQO`35)N*5oDGuEyHa~8* zo+?4npADiACQ+dItX}20jCL`{;Ns%#=iW2uVj{oMou3j7J)^fj70#%kuOK+inxjxX zH;mt4l1_CaWY1(fC^YM-t57;ixk}T2pf%0X^e>ifMhRlfJ zBVZVNIp031n z7+bwg;>5!7f>znOGX)QhKKXj^%We!lsiyb7u$-gK*Bz&65#6rngUH5?GTyM6g62_5ZHk!xzp+0KZ4t-Vm*`LT?#b9G|H zftqpgLdI(cO__f2CdDI$Z!}NcXw>_Y_$JCMxXXYc+N^*%b6HAgP4-Z^-+Ho7XdslrxY zSfiwT)Igq&NE`m9C0S*B_so@W`dInb$r`&nmHYldOTLoDi~l4BI<}4b7#yV@y*o1- z{BWyFUi$#|M!dR-{qw$emKNv3>dli5ra{-Nq@LW&RKH}B<*IfrC|}CjW=@S_4~02| zp&%V6XyJ6W9P&6@GaA2+tCx%%AAI`bGB*vA?u5tFV2dE>W-Dq;0!ky?laf%-!DMT5 zrun>^#L*I}(hjC4FH^%34yXDKMj!AT9Zj}6mi+VTiaI4d@yWH*o=mhfOm957X~ZV#KkDvkp8IgZyU@k^ld9>Y&P=5Od#@rbZ_&h_+=sQ-;eUNwwuLt} zt{o?h`jZ+P&W07eX67>xPiX$7&L|;rC*gc>6uXm^f8JAa@zNRG?&qJ}R(5}u_i~mr zC1Sai(Ou%K0;9^LLq+cDk#z;HkNqik-hKORAWbcobtzcQbSAT_bdlq;{)+F{{&(Su z)^~_W)Q&Xz`c>31hX^@$YIz9MwwL4^U)*UtJp6~1McU}gSHvwNkjzlz#UsQ=F@sIZ z_lnA&a>zH`ep@Ua!i17hdaV&%W-