From 22ca70398f7785af65446ee6a363b476c0fe72bd Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 15:57:04 +0900 Subject: [PATCH 01/59] feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fies localization/autoware_ekf_localizer (#9860) Signed-off-by: vish0012 Co-authored-by: SakodaShintaro --- localization/autoware_ekf_localizer/README.md | 22 +++++++++---------- .../autoware/ekf_localizer/ekf_localizer.hpp | 9 ++++---- .../autoware_ekf_localizer/package.xml | 2 +- .../src/ekf_localizer.cpp | 16 ++++++++------ 4 files changed, 26 insertions(+), 23 deletions(-) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md index 802bf7dbb16c3..a46ea7181315f 100644 --- a/localization/autoware_ekf_localizer/README.md +++ b/localization/autoware_ekf_localizer/README.md @@ -44,17 +44,17 @@ This package includes the following features: ### Published Topics -| Name | Type | Description | -| --------------------------------- | ------------------------------------------------ | ----------------------------------------------------- | -| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | -| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | -| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | -| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | -| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | -| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | -| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | -| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | -| `debug/processing_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | +| Name | Type | Description | +| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- | +| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | +| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | +| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | +| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | +| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | +| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | +| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | +| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | +| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | ### Published TF diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp index 0561e250298ac..84018c043cc14 100644 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp @@ -25,6 +25,8 @@ #include #include +#include +#include #include #include #include @@ -34,8 +36,6 @@ #include #include #include -#include -#include #include #include @@ -78,7 +78,7 @@ class EKFLocalizer : public rclcpp::Node //!< @brief ekf estimated twist with covariance publisher rclcpp::Publisher::SharedPtr pub_twist_cov_; //!< @brief ekf estimated yaw bias publisher - rclcpp::Publisher::SharedPtr pub_yaw_bias_; + rclcpp::Publisher::SharedPtr pub_yaw_bias_; //!< @brief ekf estimated yaw bias publisher rclcpp::Publisher::SharedPtr pub_biased_pose_; //!< @brief ekf estimated yaw bias publisher @@ -86,7 +86,8 @@ class EKFLocalizer : public rclcpp::Node //!< @brief diagnostics publisher rclcpp::Publisher::SharedPtr pub_diag_; //!< @brief processing_time publisher - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; //!< @brief initial pose subscriber rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief measurement pose with covariance subscriber diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml index 8dc3cc9844c50..e0e37f59d1acb 100644 --- a/localization/autoware_ekf_localizer/package.xml +++ b/localization/autoware_ekf_localizer/package.xml @@ -22,6 +22,7 @@ eigen + autoware_internal_debug_msgs autoware_kalman_filter autoware_localization_util autoware_universe_utils @@ -34,7 +35,6 @@ std_srvs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp index 11d7788adfade..5638a5416e6ab 100644 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -70,13 +70,14 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) pub_twist_ = create_publisher("ekf_twist", 1); pub_twist_cov_ = create_publisher( "ekf_twist_with_covariance", 1); - pub_yaw_bias_ = create_publisher("estimated_yaw_bias", 1); + pub_yaw_bias_ = + create_publisher("estimated_yaw_bias", 1); pub_biased_pose_ = create_publisher("ekf_biased_pose", 1); pub_biased_pose_cov_ = create_publisher( "ekf_biased_pose_with_covariance", 1); pub_diag_ = this->create_publisher("/diagnostics", 10); - pub_processing_time_ = - create_publisher("debug/processing_time_ms", 1); + pub_processing_time_ = create_publisher( + "debug/processing_time_ms", 1); sub_initialpose_ = create_subscription( "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); sub_pose_with_cov_ = create_subscription( @@ -235,9 +236,10 @@ void EKFLocalizer::timer_callback() /* publish processing time */ const double elapsed_time = stop_watch_timer_cb_.toc(); - pub_processing_time_->publish(tier4_debug_msgs::build() - .stamp(current_time) - .data(elapsed_time)); + pub_processing_time_->publish( + autoware_internal_debug_msgs::build() + .stamp(current_time) + .data(elapsed_time)); } /* @@ -343,7 +345,7 @@ void EKFLocalizer::publish_estimate_result( pub_twist_cov_->publish(twist_cov); /* publish yaw bias */ - tier4_debug_msgs::msg::Float64Stamped yawb; + autoware_internal_debug_msgs::msg::Float64Stamped yawb; yawb.stamp = current_ekf_twist.header.stamp; yawb.data = ekf_module_->get_yaw_bias(); pub_yaw_bias_->publish(yawb); From bb66275f29f829dd02a729de0df7fda8deb0884b Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 9 Jan 2025 16:27:44 +0900 Subject: [PATCH 02/59] ci(cppcheck): ignore benchmarks directories for cppcheck (#9842) Signed-off-by: veqcc --- .cppcheck_suppressions | 1 + 1 file changed, 1 insertion(+) diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions index ab267ec3ac007..4119e69ed72e1 100644 --- a/.cppcheck_suppressions +++ b/.cppcheck_suppressions @@ -1,5 +1,6 @@ *:*/test/* *:*/examples/* +*:*/benchmarks/* checkersReport missingInclude From c8ee48bd6828ba0b7352250541425e66aa96f2b3 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 20:38:17 +0900 Subject: [PATCH 03/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9880)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_detection_by_tracker Signed-off-by: vish0012 Co-authored-by: Taekjin LEE --- .../autoware_detection_by_tracker/src/debugger/debugger.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp index 39dd3db10cfa9..8bd1deba35ccb 100644 --- a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp +++ b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp @@ -89,9 +89,9 @@ class Debugger void startMeasureProcessingTime() { stop_watch_ptr_->tic("processing_time"); } void publishProcessingTime() { - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } From 56ff9b8de27e050787f9b2fe610f5df1348c4a03 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:49:20 +0900 Subject: [PATCH 04/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9858)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_control_evaluator Signed-off-by: vish0012 --- .../autoware/control_evaluator/control_evaluator_node.hpp | 5 +++-- .../src/control_evaluator_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index c510b2ea46779..9606dea577bd0 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -25,9 +25,9 @@ #include #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" +#include #include #include -#include #include #include @@ -85,7 +85,8 @@ class ControlEvaluatorNode : public rclcpp::Node LaneletMapBin, autoware::universe_utils::polling_policy::Newest> vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; // update Route Handler diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index b0db41b0fdc73..79e89423af6dd 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -34,8 +34,8 @@ ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_opti using std::placeholders::_1; // Publisher - processing_time_pub_ = - this->create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = this->create_publisher( + "~/debug/processing_time_ms", 1); metrics_pub_ = create_publisher("~/metrics", 1); // Parameters @@ -288,7 +288,7 @@ void ControlEvaluatorNode::onTimer() metrics_msg_ = MetricArrayMsg{}; // Publish processing time - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); From 6fe89228f731af6f97541de0f3b163752a5baefc Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:49:37 +0900 Subject: [PATCH 05/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9857)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/control_performance_analysis Signed-off-by: vish0012 --- control/control_performance_analysis/package.xml | 2 +- .../scripts/control_performance_plot.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index 9c2ef69e0137b..f2630a7d47f62 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -25,6 +25,7 @@ builtin_interfaces autoware_control_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_planning_msgs autoware_signal_processing @@ -41,7 +42,6 @@ tf2 tf2_eigen tf2_ros - tier4_debug_msgs autoware_global_parameter_loader builtin_interfaces rosidl_default_runtime diff --git a/control/control_performance_analysis/scripts/control_performance_plot.py b/control/control_performance_analysis/scripts/control_performance_plot.py index c5e5cabd5b059..d4a6038465e12 100644 --- a/control/control_performance_analysis/scripts/control_performance_plot.py +++ b/control/control_performance_analysis/scripts/control_performance_plot.py @@ -17,13 +17,13 @@ import argparse import math +from autoware_internal_debug_msgs.msg import BoolStamped from control_performance_analysis.msg import DrivingMonitorStamped from control_performance_analysis.msg import ErrorStamped import matplotlib.pyplot as plt from nav_msgs.msg import Odometry import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import BoolStamped parser = argparse.ArgumentParser() parser.add_argument("-i", "--interval", help="interval distance to plot") From 4d0a86f10df9462696a1955511f882042914db5d Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:50:28 +0900 Subject: [PATCH 06/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fmsgs=20in=20files=20con=E2=80=A6=20(?= =?UTF-8?q?#9852)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_msgs in files control/autoware_trajectory_follower_base Signed-off-by: vish0012 --- control/autoware_trajectory_follower_base/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control/autoware_trajectory_follower_base/package.xml b/control/autoware_trajectory_follower_base/package.xml index e7b00e4b19cdc..195c077835910 100644 --- a/control/autoware_trajectory_follower_base/package.xml +++ b/control/autoware_trajectory_follower_base/package.xml @@ -21,6 +21,7 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface @@ -37,7 +38,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto From 926ad7f3d6d1e0a6c689ce6e2a1a104d850913e3 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:52:15 +0900 Subject: [PATCH 07/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9848)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pid_longitudinal_controller Signed-off-by: vish0012 --- .../pid_longitudinal_controller.hpp | 8 +++++--- control/autoware_pid_longitudinal_controller/package.xml | 2 +- .../src/pid_longitudinal_controller.cpp | 8 ++++---- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 1d03d1b339af6..db5fa09b5eeee 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -34,11 +34,11 @@ #include "autoware_adapi_v1_msgs/msg/operation_mode_state.hpp" #include "autoware_control_msgs/msg/longitudinal.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include "tf2_msgs/msg/tf_message.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "visualization_msgs/msg/marker.hpp" #include @@ -98,8 +98,10 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro rclcpp::Clock::SharedPtr clock_; rclcpp::Logger logger_; // ros variables - rclcpp::Publisher::SharedPtr m_pub_slope; - rclcpp::Publisher::SharedPtr m_pub_debug; + rclcpp::Publisher::SharedPtr + m_pub_slope; + rclcpp::Publisher::SharedPtr + m_pub_debug; rclcpp::Publisher::SharedPtr m_pub_virtual_wall_marker; rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res; diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 67e95a9d4c0ac..127ce8e76d69d 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -21,6 +21,7 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_planning_msgs @@ -37,7 +38,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index ec95ce656fa6f..c87e936de3e40 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -214,9 +214,9 @@ PidLongitudinalController::PidLongitudinalController( : node.declare_parameter("ego_nearest_yaw_threshold"); // [rad] // subscriber, publisher - m_pub_slope = node.create_publisher( + m_pub_slope = node.create_publisher( "~/output/slope_angle", rclcpp::QoS{1}); - m_pub_debug = node.create_publisher( + m_pub_debug = node.create_publisher( "~/output/longitudinal_diagnostic", rclcpp::QoS{1}); m_pub_virtual_wall_marker = node.create_publisher("~/virtual_wall", 1); @@ -931,7 +931,7 @@ void PidLongitudinalController::publishDebugData( m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_PUBLISHED, ctrl_cmd.acc); // publish debug values - tier4_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; debug_msg.stamp = clock_->now(); for (const auto & v : m_debug_values.getValues()) { debug_msg.data.push_back(static_cast(v)); @@ -939,7 +939,7 @@ void PidLongitudinalController::publishDebugData( m_pub_debug->publish(debug_msg); // slope angle - tier4_debug_msgs::msg::Float32MultiArrayStamped slope_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped slope_msg{}; slope_msg.stamp = clock_->now(); slope_msg.data.push_back( static_cast(control_data.slope_angle)); From 0b73c13206e4185b0182a8ec11710e7c17959006 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:52:55 +0900 Subject: [PATCH 08/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9846)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files ontrol/autoware_mpc_lateral_controller Signed-off-by: vish0012 * style(pre-commit): autofix --------- Signed-off-by: vish0012 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../lane_departure_checker_node.hpp | 5 +++-- control/autoware_lane_departure_checker/package.xml | 2 +- .../lane_departure_checker_node.cpp | 12 +++++++----- .../include/autoware/mpc_lateral_controller/mpc.hpp | 4 ++-- .../mpc_lateral_controller.hpp | 8 ++++---- control/autoware_mpc_lateral_controller/package.xml | 2 +- .../test/test_mpc.cpp | 4 ++-- 7 files changed, 20 insertions(+), 17 deletions(-) diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index 7e2229d7b5754..4d99b1a134b3a 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -24,6 +24,7 @@ #include #include +#include #include #include #include @@ -31,7 +32,6 @@ #include #include #include -#include #include #include @@ -115,7 +115,8 @@ class LaneDepartureCheckerNode : public rclcpp::Node autoware::universe_utils::DebugPublisher debug_publisher_{this, "~/debug"}; autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ this, "~/debug/processing_time_ms_diag"}; - rclcpp::Publisher::SharedPtr processing_time_publisher_; + rclcpp::Publisher::SharedPtr + processing_time_publisher_; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_lane_departure_checker/package.xml b/control/autoware_lane_departure_checker/package.xml index 2689b4a4dbcb7..97ad5eaf82e00 100644 --- a/control/autoware_lane_departure_checker/package.xml +++ b/control/autoware_lane_departure_checker/package.xml @@ -14,6 +14,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_map_msgs autoware_motion_utils @@ -32,7 +33,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 366b84a1f6131..d9775415d3ed3 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -171,7 +171,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o // Publisher processing_time_publisher_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher( + "~/debug/processing_time_ms", 1); // Nothing // Diagnostic Updater @@ -342,10 +343,11 @@ void LaneDepartureCheckerNode::onTimer() { const auto & deviation = output_.trajectory_deviation; - debug_publisher_.publish( + debug_publisher_.publish( "deviation/lateral", deviation.lateral); - debug_publisher_.publish("deviation/yaw", deviation.yaw); - debug_publisher_.publish( + debug_publisher_.publish( + "deviation/yaw", deviation.yaw); + debug_publisher_.publish( "deviation/yaw_deg", rad2deg(deviation.yaw)); } processing_time_map["Node: publishTrajectoryDeviation"] = stop_watch.toc(true); @@ -361,7 +363,7 @@ void LaneDepartureCheckerNode::onTimer() processing_time_map["Total"] = stop_watch.toc("Total"); processing_diag_publisher_.publish(processing_time_map); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_time_map["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index 4c8d5df2c22a7..166dfa1814562 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -24,11 +24,11 @@ #include "rclcpp/rclcpp.hpp" #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include #include @@ -41,11 +41,11 @@ namespace autoware::motion::control::mpc_lateral_controller using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; using Eigen::MatrixXd; using Eigen::VectorXd; diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index d7442f64b028a..0f3004775e5bd 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -26,13 +26,13 @@ #include #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" #include #include @@ -45,11 +45,11 @@ namespace autoware::motion::control::mpc_lateral_controller namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Float32Stamped; using trajectory_follower::LateralHorizon; class MpcLateralController : public trajectory_follower::LateralControllerBase diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index b450af05ea0e1..719d11ef7948b 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -19,6 +19,7 @@ autoware_cmake autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface @@ -36,7 +37,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp index 9c30369305f6e..0a34302f8f60c 100644 --- a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -24,11 +24,11 @@ #include #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #ifdef ROS_DISTRO_GALACTIC #include "tf2_geometry_msgs/tf2_geometry_msgs.h" @@ -45,12 +45,12 @@ namespace autoware::motion::control::mpc_lateral_controller using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using autoware_vehicle_msgs::msg::SteeringReport; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; TrajectoryPoint makePoint(const double x, const double y, const float vx) { From 4dc720114dab3d07989b365bdd64be84bf5f4b60 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 10 Jan 2025 10:20:00 +0900 Subject: [PATCH 09/59] refactor(lane_change): refactor transit failure function (#9835) * refactor(lane_change): refactor transit failure function Signed-off-by: Zulfaqar Azmi * fixed failed scenario Signed-off-by: Zulfaqar Azmi * remove is abort from debug Signed-off-by: Zulfaqar Azmi * set is abort state Signed-off-by: Zulfaqar Azmi * add comments for clarity Signed-off-by: Zulfaqar Azmi * include what you use. Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../interface.hpp | 5 + .../structs/data.hpp | 1 + .../structs/debug.hpp | 8 +- .../utils/markers.hpp | 8 +- .../src/interface.cpp | 154 ++++++++---------- .../src/scene.cpp | 19 +-- .../src/utils/markers.cpp | 41 +++-- 7 files changed, 111 insertions(+), 125 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index a69ae0d92647a..4b97fb0d069a0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -35,6 +35,7 @@ #include #include #include +#include namespace autoware::behavior_path_planner { @@ -120,6 +121,8 @@ class LaneChangeInterface : public SceneModuleInterface } } + std::pair check_transit_failure(); + void updateDebugMarker() const; void updateSteeringFactorPtr(const BehaviorModuleOutput & output); @@ -134,6 +137,8 @@ class LaneChangeInterface : public SceneModuleInterface bool is_abort_path_approved_{false}; bool is_abort_approval_requested_{false}; + + lane_change::InterfaceDebug interface_debug_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index d5bbfe25fe1e9..9e6b9d229d2f2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -48,6 +48,7 @@ enum class States { Cancel, Abort, Stop, + Warning, }; struct PhaseInfo diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 90b13f86976b2..1541846841f20 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -58,7 +58,6 @@ struct Debug double distance_to_abort_finished{std::numeric_limits::max()}; bool is_able_to_return_to_current_lane{true}; bool is_stuck{false}; - bool is_abort{false}; void reset() { @@ -83,9 +82,14 @@ struct Debug distance_to_abort_finished = std::numeric_limits::max(); is_able_to_return_to_current_lane = true; is_stuck = false; - is_abort = false; } }; + +struct InterfaceDebug +{ + std::string_view failing_reason; + LaneChangeStates lc_state; +}; } // namespace autoware::behavior_path_planner::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index 059db8e38300f..a9ea35cb9b83e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -32,6 +32,7 @@ namespace marker_utils::lane_change_markers using autoware::behavior_path_planner::FilteredLanesObjects; using autoware::behavior_path_planner::LaneChangePath; using autoware::behavior_path_planner::lane_change::Debug; +using autoware::behavior_path_planner::lane_change::InterfaceDebug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; using visualization_msgs::msg::MarkerArray; MarkerArray showAllValidLaneChangePath( @@ -42,9 +43,12 @@ MarkerArray createLaneChangingVirtualWallMarker( MarkerArray showFilteredObjects( const FilteredLanesObjects & filtered_objects, const std::string & ns); MarkerArray createExecutionArea(const geometry_msgs::msg::Polygon & execution_area); -MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); +MarkerArray showExecutionInfo( + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose); MarkerArray createDebugMarkerArray( - const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose); } // namespace marker_utils::lane_change_markers #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 9f3c6c9ef48bf..ebcd4eb4809fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -139,9 +139,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() const auto force_activated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); - const bool safe = force_activated ? false : true; updateRTCStatus( - path.start_distance_to_path_change, path.finish_distance_to_path_change, safe, + path.start_distance_to_path_change, path.finish_distance_to_path_change, !force_activated, State::RUNNING); } } @@ -220,9 +219,7 @@ bool LaneChangeInterface::canTransitSuccessState() if (module_type_->specialExpiredCheck() && isWaitingApproval()) { log_debug_throttled("Run specialExpiredCheck."); - if (isWaitingApproval()) { - return true; - } + return true; } if (module_type_->hasFinishedLaneChange()) { @@ -237,13 +234,6 @@ bool LaneChangeInterface::canTransitSuccessState() bool LaneChangeInterface::canTransitFailureState() { - auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_DEBUG(getLogger(), "%s", message.data()); - }; - - updateDebugMarker(); - log_debug_throttled(__func__); - const auto force_activated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); @@ -253,121 +243,106 @@ bool LaneChangeInterface::canTransitFailureState() return false; } - if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) { - log_debug_throttled("Abort process has on going."); - return false; - } + const auto [state, reason] = check_transit_failure(); - if (isWaitingApproval()) { - if (module_type_->is_near_regulatory_element()) { - log_debug_throttled("Ego is close to regulatory element. Cancel lane change"); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; - } - log_debug_throttled("Can't transit to failure state. Module is WAITING_FOR_APPROVAL"); - return false; - } + interface_debug_.failing_reason = reason; + interface_debug_.lc_state = state; - if (!module_type_->isValidPath()) { - log_debug_throttled("Transit to failure state due not to find valid path"); + updateDebugMarker(); + + if (state == LaneChangeStates::Cancel) { updateRTCStatus( std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, State::FAILED); + module_type_->toCancelState(); return true; } - if (module_type_->isAbortState() && module_type_->hasFinishedAbort()) { - log_debug_throttled("Abort process has completed."); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (state == LaneChangeStates::Abort) { + module_type_->toAbortState(); + return false; } - if (module_type_->is_near_terminal()) { - log_debug_throttled("Unsafe, but ego is approaching terminal. Continue lane change"); + // Note: Ideally, if it is unsafe, but for some reason, we can't abort or cancel, then we should + // stop. Note: This feature is not working properly for now. + const auto [is_safe, unsafe_trailing_obj] = post_process_safety_status_; + if (!is_safe && module_type_->isRequiredStop(unsafe_trailing_obj)) { + module_type_->toStopState(); + return false; + } + + module_type_->toNormalState(); + return false; +} - if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { - log_debug_throttled("Module require stopping"); +std::pair LaneChangeInterface::check_transit_failure() +{ + if (module_type_->isAbortState()) { + if (module_type_->hasFinishedAbort()) { + return {LaneChangeStates::Cancel, "Aborted"}; } - return false; + return {LaneChangeStates::Abort, "Aborting"}; } - if (module_type_->isCancelEnabled() && module_type_->isEgoOnPreparePhase()) { - if (module_type_->isStoppedAtRedTrafficLight()) { - log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change"); - module_type_->toCancelState(); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (isWaitingApproval()) { + if (module_type_->is_near_regulatory_element()) { + return {LaneChangeStates::Cancel, "CloseToRegElement"}; } + return {LaneChangeStates::Normal, "WaitingForApproval"}; + } + if (!module_type_->isValidPath()) { + return {LaneChangeStates::Cancel, "InvalidPath"}; + } + + const auto is_preparing = module_type_->isEgoOnPreparePhase(); + const auto can_return_to_current = module_type_->isAbleToReturnCurrentLane(); + + // regardless of safe and unsafe, we want to cancel lane change. + if (is_preparing) { const auto force_deactivated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceDeactivated(uuid_map_.at(rtc.first)); }); - if (force_deactivated && module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("Cancel lane change due to force deactivation"); - module_type_->toCancelState(); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; - } - - if (post_process_safety_status_.is_safe) { - log_debug_throttled("Can't transit to failure state. Ego is on prepare, and it's safe."); - return false; - } - - if (module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("It's possible to return to current lane. Cancel lane change."); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (force_deactivated && can_return_to_current) { + return {LaneChangeStates::Cancel, "ForceDeactivation"}; } } if (post_process_safety_status_.is_safe) { - log_debug_throttled("Can't transit to failure state. Ego is lane changing, and it's safe."); - return false; + return {LaneChangeStates::Normal, "SafeToLaneChange"}; } - if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { - log_debug_throttled("Module require stopping"); + if (!module_type_->isCancelEnabled()) { + return {LaneChangeStates::Warning, "CancelDisabled"}; } - if (!module_type_->isCancelEnabled()) { - log_debug_throttled( - "Lane change path is unsafe but cancel was not enabled. Continue lane change."); - return false; + // We also check if the ego can return to the current lane, as prepare segment might be out of the + // lane, for example, during an evasive maneuver around a static object. + if (is_preparing && can_return_to_current) { + return {LaneChangeStates::Cancel, "SafeToCancel"}; + } + + if (module_type_->is_near_terminal()) { + return {LaneChangeStates::Warning, "TooNearTerminal"}; } if (!module_type_->isAbortEnabled()) { - log_debug_throttled( - "Lane change path is unsafe but abort was not enabled. Continue lane change."); - return false; + return {LaneChangeStates::Warning, "AbortDisabled"}; } - if (!module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("It's is not possible to return to original lane. Continue lane change."); - return false; + // To prevent the lane module from having to check rear objects in the current lane, we limit the + // abort maneuver to cases where the ego vehicle is still in the current lane. + if (!can_return_to_current) { + return {LaneChangeStates::Warning, "TooLateToAbort"}; } const auto found_abort_path = module_type_->calcAbortPath(); if (!found_abort_path) { - log_debug_throttled( - "Lane change path is unsafe but abort path not found. Continue lane change."); - return false; + return {LaneChangeStates::Warning, "AbortPathNotFound"}; } - log_debug_throttled("Lane change path is unsafe. Abort lane change."); - module_type_->toAbortState(); - return false; + return {LaneChangeStates::Abort, "SafeToAbort"}; } void LaneChangeInterface::updateDebugMarker() const @@ -377,7 +352,8 @@ void LaneChangeInterface::updateDebugMarker() const return; } using marker_utils::lane_change_markers::createDebugMarkerArray; - debug_marker_ = createDebugMarkerArray(module_type_->getDebugData(), module_type_->getEgoPose()); + debug_marker_ = createDebugMarkerArray( + interface_debug_, module_type_->getDebugData(), module_type_->getEgoPose()); } MarkerArray LaneChangeInterface::getModuleVirtualWall() diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 2719239baaed8..09a4216bf5857 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -892,7 +892,6 @@ bool NormalLaneChange::isAbleToStopSafely() const bool NormalLaneChange::hasFinishedAbort() const { if (!abort_path_) { - lane_change_debug_.is_abort = true; return true; } @@ -901,7 +900,6 @@ bool NormalLaneChange::hasFinishedAbort() const lane_change_debug_.distance_to_abort_finished = distance_to_finish; const auto has_finished_abort = distance_to_finish < 0.0; - lane_change_debug_.is_abort = has_finished_abort; return has_finished_abort; } @@ -916,12 +914,7 @@ bool NormalLaneChange::isAbortState() const return false; } - if (!abort_path_) { - return false; - } - - lane_change_debug_.is_abort = true; - return true; + return abort_path_ != nullptr; } int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) const @@ -1491,14 +1484,8 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const bool NormalLaneChange::isRequiredStop(const bool is_trailing_object) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if ( - common_data_ptr_->transient_data.is_ego_near_current_terminal_start && isAbleToStopSafely() && - is_trailing_object) { - current_lane_change_state_ = LaneChangeStates::Stop; - return true; - } - current_lane_change_state_ = LaneChangeStates::Normal; - return false; + return common_data_ptr_->transient_data.is_ego_near_current_terminal_start && + isAbleToStopSafely() && is_trailing_object; } bool NormalLaneChange::calcAbortPath() diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index da9ee52b038c6..eb120e006a229 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -164,7 +165,9 @@ MarkerArray showFilteredObjects( return marker_array; } -MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) +MarkerArray showExecutionInfo( + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose) { auto default_text_marker = [&]() { return createDefaultMarker( @@ -177,11 +180,15 @@ MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg auto safety_check_info_text = default_text_marker(); safety_check_info_text.pose = ego_pose; safety_check_info_text.pose.position.z += 4.0; + const auto lc_state = interface_debug_data.lc_state; + const auto & failing_reason = interface_debug_data.failing_reason; safety_check_info_text.text = fmt::format( - "{stuck} | {return_lane} | {abort}", fmt::arg("stuck", debug_data.is_stuck ? "is stuck" : ""), - fmt::arg("return_lane", debug_data.is_able_to_return_to_current_lane ? "" : "can't return"), - fmt::arg("abort", debug_data.is_abort ? "aborting" : "")); + "{stuck} | {return_lane} | {state} : {reason}", + fmt::arg("stuck", scene_debug_data.is_stuck ? "is stuck" : ""), + fmt::arg( + "return_lane", scene_debug_data.is_able_to_return_to_current_lane ? "" : "can't return"), + fmt::arg("state", magic_enum::enum_name(lc_state)), fmt::arg("reason", failing_reason)); marker_array.markers.push_back(safety_check_info_text); return marker_array; } @@ -227,7 +234,8 @@ MarkerArray ShowLaneChangeMetricsInfo( } MarkerArray createDebugMarkerArray( - const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose) { using lanelet::visualization::laneletsAsTriangleMarkerArray; using marker_utils::showPolygon; @@ -236,31 +244,32 @@ MarkerArray createDebugMarkerArray( using marker_utils::lane_change_markers::showAllValidLaneChangePath; using marker_utils::lane_change_markers::showFilteredObjects; - const auto & debug_collision_check_object = debug_data.collision_check_objects; + const auto & debug_collision_check_object = scene_debug_data.collision_check_objects; const auto & debug_collision_check_object_after_approval = - debug_data.collision_check_objects_after_approval; - const auto & debug_valid_paths = debug_data.valid_paths; - const auto & debug_filtered_objects = debug_data.filtered_objects; + scene_debug_data.collision_check_objects_after_approval; + const auto & debug_valid_paths = scene_debug_data.valid_paths; + const auto & debug_filtered_objects = scene_debug_data.filtered_objects; MarkerArray debug_marker; const auto add = [&debug_marker](const MarkerArray & added) { autoware::universe_utils::appendMarkerArray(added, &debug_marker); }; - if (!debug_data.execution_area.points.empty()) { + if (!scene_debug_data.execution_area.points.empty()) { add(createPolygonMarkerArray( - debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); + scene_debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); } - add(showExecutionInfo(debug_data, ego_pose)); - add(ShowLaneChangeMetricsInfo(debug_data, ego_pose)); + add(showExecutionInfo(interface_debug_data, scene_debug_data, ego_pose)); + add(ShowLaneChangeMetricsInfo(scene_debug_data, ego_pose)); // lanes add(laneletsAsTriangleMarkerArray( - "current_lanes", debug_data.current_lanes, colors::light_yellow(0.2))); - add(laneletsAsTriangleMarkerArray("target_lanes", debug_data.target_lanes, colors::aqua(0.2))); + "current_lanes", scene_debug_data.current_lanes, colors::light_yellow(0.2))); add(laneletsAsTriangleMarkerArray( - "target_backward_lanes", debug_data.target_backward_lanes, colors::blue(0.2))); + "target_lanes", scene_debug_data.target_lanes, colors::aqua(0.2))); + add(laneletsAsTriangleMarkerArray( + "target_backward_lanes", scene_debug_data.target_backward_lanes, colors::blue(0.2))); add(showAllValidLaneChangePath(debug_valid_paths, "lane_change_valid_paths")); add(showFilteredObjects(debug_filtered_objects, "object_filtered")); From 485ccc660cfacc0e939e3019b5cc13c0f25fd9ae Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:05:23 +0900 Subject: [PATCH 10/59] refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling (#9791) * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling Signed-off-by: kyoichi-sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../CMakeLists.txt | 1 + .../lane_departure_checker.hpp | 73 ++------- .../lane_departure_checker_node.hpp | 16 +- .../lane_departure_checker/parameters.hpp | 101 +++++++++++++ .../lane_departure_checker_node.cpp | 35 +---- .../parameters.cpp | 59 ++++++++ .../examples/plot_map_case1.cpp | 7 +- .../examples/plot_map_case2.cpp | 5 +- .../src/goal_planner_module.cpp | 4 +- .../src/start_planner_module.cpp | 6 +- .../test/test_geometric_pull_out.cpp | 138 ++++++------------ .../test/test_shift_pull_out.cpp | 8 +- 12 files changed, 230 insertions(+), 223 deletions(-) create mode 100644 control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp create mode 100644 control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp diff --git a/control/autoware_lane_departure_checker/CMakeLists.txt b/control/autoware_lane_departure_checker/CMakeLists.txt index 199195fc88b08..19046a09922f0 100644 --- a/control/autoware_lane_departure_checker/CMakeLists.txt +++ b/control/autoware_lane_departure_checker/CMakeLists.txt @@ -14,6 +14,7 @@ ament_auto_add_library(autoware_lane_departure_checker SHARED src/lane_departure_checker_node/lane_departure_checker.cpp src/lane_departure_checker_node/lane_departure_checker_node.cpp src/lane_departure_checker_node/utils.cpp + src/lane_departure_checker_node/parameters.cpp ) rclcpp_components_register_node(${PROJECT_NAME} diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index 1ac984394a25e..101338551cbf3 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -15,15 +15,12 @@ #ifndef AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ #define AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ -#include -#include +#include "autoware/lane_departure_checker/parameters.hpp" + #include #include #include -#include -#include -#include #include #include #include @@ -48,81 +45,33 @@ namespace autoware::lane_departure_checker { -using autoware::universe_utils::LinearRing2d; -using autoware::universe_utils::PoseDeviation; using autoware::universe_utils::Segment2d; -using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::Trajectory; -using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_planning_msgs::msg::PathWithLaneId; -using TrajectoryPoints = std::vector; typedef boost::geometry::index::rtree> SegmentRtree; -struct Param -{ - double footprint_margin_scale{0.0}; - double footprint_extra_margin{0.0}; - double resample_interval{0.0}; - double max_deceleration{0.0}; - double delay_time{0.0}; - double max_lateral_deviation{0.0}; - double max_longitudinal_deviation{0.0}; - double max_yaw_deviation_deg{0.0}; - double min_braking_distance{0.0}; - // nearest search to ego - double ego_nearest_dist_threshold{0.0}; - double ego_nearest_yaw_threshold{0.0}; -}; - -struct Input -{ - nav_msgs::msg::Odometry::ConstSharedPtr current_odom{}; - lanelet::LaneletMapPtr lanelet_map{}; - LaneletRoute::ConstSharedPtr route{}; - lanelet::ConstLanelets route_lanelets{}; - lanelet::ConstLanelets shoulder_lanelets{}; - Trajectory::ConstSharedPtr reference_trajectory{}; - Trajectory::ConstSharedPtr predicted_trajectory{}; - std::vector boundary_types_to_detect{}; -}; - -struct Output -{ - std::map processing_time_map{}; - bool will_leave_lane{}; - bool is_out_of_lane{}; - bool will_cross_boundary{}; - PoseDeviation trajectory_deviation{}; - lanelet::ConstLanelets candidate_lanelets{}; - TrajectoryPoints resampled_trajectory{}; - std::vector vehicle_footprints{}; - std::vector vehicle_passing_areas{}; -}; - class LaneDepartureChecker { public: - LaneDepartureChecker( + explicit LaneDepartureChecker( std::shared_ptr time_keeper = std::make_shared()) : time_keeper_(time_keeper) { } - Output update(const Input & input); - void setParam(const Param & param, const autoware::vehicle_info_utils::VehicleInfo vehicle_info) + LaneDepartureChecker( + const Param & param, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + std::shared_ptr time_keeper = + std::make_shared()) + : param_(param), + vehicle_info_ptr_(std::make_shared(vehicle_info)), + time_keeper_(time_keeper) { - param_ = param; - vehicle_info_ptr_ = std::make_shared(vehicle_info); } + Output update(const Input & input); void setParam(const Param & param) { param_ = param; } - void setVehicleInfo(const autoware::vehicle_info_utils::VehicleInfo vehicle_info) - { - vehicle_info_ptr_ = std::make_shared(vehicle_info); - } - bool checkPathWillLeaveLane( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path) const; diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index 4d99b1a134b3a..7aaf4816708bd 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ #include "autoware/lane_departure_checker/lane_departure_checker.hpp" +#include "autoware/lane_departure_checker/parameters.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include @@ -47,21 +48,6 @@ namespace autoware::lane_departure_checker { using autoware_map_msgs::msg::LaneletMapBin; -struct NodeParam -{ - bool will_out_of_lane_checker; - bool out_of_lane_checker; - bool boundary_departure_checker; - - double update_rate; - bool visualize_lanelet; - bool include_right_lanes; - bool include_left_lanes; - bool include_opposite_lanes; - bool include_conflicting_lanes; - std::vector boundary_types_to_detect; -}; - class LaneDepartureCheckerNode : public rclcpp::Node { public: diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp new file mode 100644 index 0000000000000..425b032af425f --- /dev/null +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp @@ -0,0 +1,101 @@ +// Copyright 2024 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__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ +#define AUTOWARE__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ + +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace autoware::lane_departure_checker +{ +using autoware::universe_utils::PoseDeviation; +using autoware_planning_msgs::msg::LaneletRoute; +using autoware_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::TrajectoryPoint; +using TrajectoryPoints = std::vector; +using autoware::universe_utils::LinearRing2d; + +struct Param +{ + static Param init(rclcpp::Node & node); + double footprint_margin_scale{}; + double footprint_extra_margin{}; + double resample_interval{}; + double max_deceleration{}; + double delay_time{}; + double max_lateral_deviation{}; + double max_longitudinal_deviation{}; + double max_yaw_deviation_deg{}; + double min_braking_distance{}; + // nearest search to ego + double ego_nearest_dist_threshold{}; + double ego_nearest_yaw_threshold{}; +}; + +struct NodeParam +{ + static NodeParam init(rclcpp::Node & node); + bool will_out_of_lane_checker{}; + bool out_of_lane_checker{}; + bool boundary_departure_checker{}; + + double update_rate{}; + bool visualize_lanelet{}; + bool include_right_lanes{}; + bool include_left_lanes{}; + bool include_opposite_lanes{}; + bool include_conflicting_lanes{}; + std::vector boundary_types_to_detect{}; +}; + +struct Input +{ + nav_msgs::msg::Odometry::ConstSharedPtr current_odom{}; + lanelet::LaneletMapPtr lanelet_map{}; + LaneletRoute::ConstSharedPtr route{}; + lanelet::ConstLanelets route_lanelets{}; + lanelet::ConstLanelets shoulder_lanelets{}; + Trajectory::ConstSharedPtr reference_trajectory{}; + Trajectory::ConstSharedPtr predicted_trajectory{}; + std::vector boundary_types_to_detect{}; +}; + +struct Output +{ + std::map processing_time_map{}; + bool will_leave_lane{}; + bool is_out_of_lane{}; + bool will_cross_boundary{}; + PoseDeviation trajectory_deviation{}; + lanelet::ConstLanelets candidate_lanelets{}; + TrajectoryPoints resampled_trajectory{}; + std::vector vehicle_footprints{}; + std::vector vehicle_passing_areas{}; +}; +} // namespace autoware::lane_departure_checker + +#endif // AUTOWARE__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index d9775415d3ed3..32384b7e6c7dd 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -126,48 +126,19 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o : Node("lane_departure_checker_node", options) { using std::placeholders::_1; - - // Enable feature - node_param_.will_out_of_lane_checker = declare_parameter("will_out_of_lane_checker"); - node_param_.out_of_lane_checker = declare_parameter("out_of_lane_checker"); - node_param_.boundary_departure_checker = declare_parameter("boundary_departure_checker"); - - // Node Parameter - node_param_.update_rate = declare_parameter("update_rate"); - node_param_.visualize_lanelet = declare_parameter("visualize_lanelet"); - node_param_.include_right_lanes = declare_parameter("include_right_lanes"); - 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"); - - // Boundary_departure_checker - node_param_.boundary_types_to_detect = - declare_parameter>("boundary_types_to_detect"); + node_param_ = NodeParam::init(*this); + param_ = Param::init(*this); // Vehicle Info const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); vehicle_length_m_ = vehicle_info.vehicle_length_m; - // Core Parameter - param_.footprint_margin_scale = declare_parameter("footprint_margin_scale"); - param_.footprint_extra_margin = declare_parameter("footprint_extra_margin"); - param_.resample_interval = declare_parameter("resample_interval"); - param_.max_deceleration = declare_parameter("max_deceleration"); - param_.delay_time = declare_parameter("delay_time"); - param_.max_lateral_deviation = declare_parameter("max_lateral_deviation"); - param_.max_longitudinal_deviation = declare_parameter("max_longitudinal_deviation"); - param_.max_yaw_deviation_deg = declare_parameter("max_yaw_deviation_deg"); - param_.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); - param_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - param_.min_braking_distance = declare_parameter("min_braking_distance"); - // Parameter Callback set_param_res_ = add_on_set_parameters_callback(std::bind(&LaneDepartureCheckerNode::onParameter, this, _1)); // Core - lane_departure_checker_ = std::make_unique(); - lane_departure_checker_->setParam(param_, vehicle_info); + lane_departure_checker_ = std::make_unique(param_, vehicle_info); // Publisher processing_time_publisher_ = diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp new file mode 100644 index 0000000000000..f3aa23275e35c --- /dev/null +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp @@ -0,0 +1,59 @@ +// Copyright 2024 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 "autoware/lane_departure_checker/parameters.hpp" + +#include +#include + +#include + +namespace autoware::lane_departure_checker +{ +using autoware::universe_utils::getOrDeclareParameter; + +Param Param::init(rclcpp::Node & node) +{ + Param p; + p.footprint_margin_scale = getOrDeclareParameter(node, "footprint_margin_scale"); + p.footprint_extra_margin = getOrDeclareParameter(node, "footprint_extra_margin"); + p.resample_interval = getOrDeclareParameter(node, "resample_interval"); + p.max_deceleration = getOrDeclareParameter(node, "max_deceleration"); + p.delay_time = getOrDeclareParameter(node, "delay_time"); + p.max_lateral_deviation = getOrDeclareParameter(node, "max_lateral_deviation"); + p.max_longitudinal_deviation = getOrDeclareParameter(node, "max_longitudinal_deviation"); + p.max_yaw_deviation_deg = getOrDeclareParameter(node, "max_yaw_deviation_deg"); + p.min_braking_distance = getOrDeclareParameter(node, "min_braking_distance"); + p.ego_nearest_dist_threshold = getOrDeclareParameter(node, "ego_nearest_dist_threshold"); + p.ego_nearest_yaw_threshold = getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); + return p; +} + +NodeParam NodeParam::init(rclcpp::Node & node) +{ + NodeParam p; + p.will_out_of_lane_checker = getOrDeclareParameter(node, "will_out_of_lane_checker"); + p.out_of_lane_checker = getOrDeclareParameter(node, "out_of_lane_checker"); + p.boundary_departure_checker = getOrDeclareParameter(node, "boundary_departure_checker"); + p.update_rate = getOrDeclareParameter(node, "update_rate"); + p.visualize_lanelet = getOrDeclareParameter(node, "visualize_lanelet"); + p.include_right_lanes = getOrDeclareParameter(node, "include_right_lanes"); + p.include_left_lanes = getOrDeclareParameter(node, "include_left_lanes"); + p.include_opposite_lanes = getOrDeclareParameter(node, "include_opposite_lanes"); + p.include_conflicting_lanes = getOrDeclareParameter(node, "include_conflicting_lanes"); + p.boundary_types_to_detect = + getOrDeclareParameter>(node, "boundary_types_to_detect"); + return p; +} +} // namespace autoware::lane_departure_checker diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp index 46d3b97b71e58..6172fb75978cd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp @@ -564,13 +564,12 @@ int main(int argc, char ** argv) node.get(), "goal_planner."); goal_planner_parameter.bus_stop_area.use_bus_stop_area = true; goal_planner_parameter.lane_departure_check_expansion_margin = 0.2; - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); - autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); autoware::lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = goal_planner_parameter.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker( + lane_departure_checker_params, vehicle_info); + const auto footprint = vehicle_info.createFootprint(); autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); auto goal_candidates = goal_searcher.search(planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp index 3518b5041be53..f7fefa8ba9dc0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp @@ -573,12 +573,11 @@ int main(int argc, char ** argv) autoware::behavior_path_planner::GoalPlannerModuleManager::initGoalPlannerParameters( node.get(), "goal_planner."); const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); - autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); autoware::lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = goal_planner_parameter.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker( + lane_departure_checker_params, vehicle_info); const auto footprint = vehicle_info.createFootprint(); autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); auto goal_candidates = goal_searcher.search(planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 8272ddde0189e..96aeb5f5e4da8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -290,12 +290,10 @@ LaneParkingPlanner::LaneParkingPlanner( logger_(logger) { const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); - LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = parameters.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + LaneDepartureChecker lane_departure_checker(lane_departure_checker_params, vehicle_info); for (const std::string & planner_type : parameters.efficient_path_order) { if (planner_type == "SHIFT" && parameters.enable_shift_parking) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index f45924b9542dc..83c1d55c7d022 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -68,13 +68,11 @@ StartPlannerModule::StartPlannerModule( vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} { - lane_departure_checker_ = std::make_shared(time_keeper_); - lane_departure_checker_->setVehicleInfo(vehicle_info_); autoware::lane_departure_checker::Param lane_departure_checker_params{}; lane_departure_checker_params.footprint_extra_margin = parameters->lane_departure_check_expansion_margin; - - lane_departure_checker_->setParam(lane_departure_checker_params); + lane_departure_checker_ = std::make_shared( + lane_departure_checker_params, vehicle_info_, time_keeper_); // set enabled planner if (parameters_->enable_shift_pull_out) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp index dd8bb02c97dea..726c9ccc4c5d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp @@ -24,9 +24,7 @@ #include -#include #include -#include #include #include @@ -44,7 +42,7 @@ namespace autoware::behavior_path_planner class TestGeometricPullOut : public ::testing::Test { public: - std::optional plan( + std::optional call_plan( const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) { return geometric_pull_out_->plan(start_pose, goal_pose, planner_debug_data); @@ -54,27 +52,51 @@ class TestGeometricPullOut : public ::testing::Test void SetUp() override { rclcpp::init(0, nullptr); - node_ = rclcpp::Node::make_shared("geometric_pull_out", get_node_options()); + node_ = rclcpp::Node::make_shared("geometric_pull_out", make_node_options()); - load_parameters(); - initialize_vehicle_info(); initialize_lane_departure_checker(); - initialize_routeHandler(); initialize_geometric_pull_out_planner(); - initialize_planner_data(); } void TearDown() override { rclcpp::shutdown(); } + + PlannerData make_planner_data( + const Pose & start_pose, const int route_start_lane_id, const int route_goal_lane_id) + { + PlannerData planner_data; + planner_data.init_parameters(*node_); + + // Load a sample lanelet map and create a route handler + const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + auto route_handler = std::make_shared(map_bin_msg); + + // Set up current odometry at start pose + auto odometry = std::make_shared(); + odometry->pose.pose = start_pose; + odometry->header.frame_id = "map"; + planner_data.self_odometry = odometry; + + // Setup route + const auto route = makeBehaviorRouteFromLaneId( + route_start_lane_id, route_goal_lane_id, "autoware_test_utils", + "road_shoulder/lanelet2_map.osm"); + route_handler->setRoute(route); + + // Update planner data with the route handler + planner_data.route_handler = route_handler; + + return planner_data; + } + // Member variables std::shared_ptr node_; - std::shared_ptr route_handler_; - autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::shared_ptr geometric_pull_out_; std::shared_ptr lane_departure_checker_; - PlannerData planner_data_; private: - rclcpp::NodeOptions get_node_options() const + rclcpp::NodeOptions make_node_options() const { // Load common configuration files auto node_options = rclcpp::NodeOptions{}; @@ -102,84 +124,22 @@ class TestGeometricPullOut : public ::testing::Test return node_options; } - void load_parameters() - { - const auto dp_double = [&](const std::string & s) { - return node_->declare_parameter(s); - }; - const auto dp_bool = [&](const std::string & s) { return node_->declare_parameter(s); }; - // Load parameters required for planning - const std::string ns = "start_planner."; - lane_departure_check_expansion_margin_ = - dp_double(ns + "lane_departure_check_expansion_margin"); - pull_out_max_steer_angle_ = dp_double(ns + "pull_out_max_steer_angle"); - pull_out_arc_path_interval_ = dp_double(ns + "arc_path_interval"); - center_line_path_interval_ = dp_double(ns + "center_line_path_interval"); - th_moving_object_velocity_ = dp_double(ns + "th_moving_object_velocity"); - divide_pull_out_path_ = dp_bool(ns + "divide_pull_out_path"); - backward_path_length_ = dp_double("backward_path_length"); - forward_path_length_ = dp_double("forward_path_length"); - } - - void initialize_vehicle_info() - { - vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - } - void initialize_lane_departure_checker() { - lane_departure_checker_ = std::make_shared(); - lane_departure_checker_->setVehicleInfo(vehicle_info_); - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - lane_departure_checker_params.footprint_extra_margin = lane_departure_check_expansion_margin_; - lane_departure_checker_->setParam(lane_departure_checker_params); - } - - void initialize_routeHandler() - { - // Load a sample lanelet map and create a route handler - const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( - "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); - - route_handler_ = std::make_shared(map_bin_msg); + const auto vehicle_info = + autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); + lane_departure_checker_ = + std::make_shared(lane_departure_checker_params, vehicle_info); } void initialize_geometric_pull_out_planner() { - auto parameters = std::make_shared(); - parameters->parallel_parking_parameters.pull_out_max_steer_angle = pull_out_max_steer_angle_; - parameters->parallel_parking_parameters.pull_out_arc_path_interval = - pull_out_arc_path_interval_; - parameters->parallel_parking_parameters.center_line_path_interval = center_line_path_interval_; - parameters->th_moving_object_velocity = th_moving_object_velocity_; - parameters->divide_pull_out_path = divide_pull_out_path_; + auto parameters = StartPlannerParameters::init(*node_); geometric_pull_out_ = - std::make_shared(*node_, *parameters, lane_departure_checker_); - } - - void initialize_planner_data() - { - planner_data_.parameters.backward_path_length = backward_path_length_; - planner_data_.parameters.forward_path_length = forward_path_length_; - planner_data_.parameters.wheel_base = vehicle_info_.wheel_base_m; - planner_data_.parameters.wheel_tread = vehicle_info_.wheel_tread_m; - planner_data_.parameters.front_overhang = vehicle_info_.front_overhang_m; - planner_data_.parameters.left_over_hang = vehicle_info_.left_overhang_m; - planner_data_.parameters.right_over_hang = vehicle_info_.right_overhang_m; + std::make_shared(*node_, parameters, lane_departure_checker_); } - - // Parameter variables - double lane_departure_check_expansion_margin_{0.0}; - double pull_out_max_steer_angle_{0.0}; - double pull_out_arc_path_interval_{0.0}; - double center_line_path_interval_{0.0}; - double th_moving_object_velocity_{0.0}; - double backward_path_length_{0.0}; - double forward_path_length_{0.0}; - bool divide_pull_out_path_{false}; }; TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) @@ -197,25 +157,13 @@ TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) .orientation( geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( 0.708314)); + const auto planner_data = make_planner_data(start_pose, 4619, 4635); - // Set up current odometry at start pose - auto odometry = std::make_shared(); - odometry->pose.pose = start_pose; - odometry->header.frame_id = "map"; - planner_data_.self_odometry = odometry; - - // Setup route - const auto route = makeBehaviorRouteFromLaneId( - 4619, 4635, "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - route_handler_->setRoute(route); - - // Update planner data with the route handler - planner_data_.route_handler = route_handler_; - geometric_pull_out_->setPlannerData(std::make_shared(planner_data_)); + geometric_pull_out_->setPlannerData(std::make_shared(planner_data)); // Plan the pull out path PlannerDebugData debug_data; - auto result = plan(start_pose, goal_pose, debug_data); + auto result = call_plan(start_pose, goal_pose, debug_data); // Assert that a valid geometric geometric pull out path is generated ASSERT_TRUE(result.has_value()) << "Geometric pull out path generation failed."; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp index 474da055b4de7..05a9201dad41d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp @@ -126,13 +126,11 @@ class TestShiftPullOut : public ::testing::Test void initialize_lane_departure_checker() { + autoware::lane_departure_checker::Param lane_departure_checker_params{}; const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - lane_departure_checker_ = std::make_shared(); - lane_departure_checker_->setVehicleInfo(vehicle_info); - - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - lane_departure_checker_->setParam(lane_departure_checker_params); + lane_departure_checker_ = + std::make_shared(lane_departure_checker_params, vehicle_info); } void initialize_shift_pull_out_planner() From 23a77640da41966fc9fc28355905dc4db6df6fe0 Mon Sep 17 00:00:00 2001 From: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:53:18 +0900 Subject: [PATCH 11/59] fix(planning): text revisions (#9886) * fix(planning): text revisions Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_behavior_path_planner/README.md | 126 +++++++++--------- 1 file changed, 62 insertions(+), 64 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md index ab8d02dc83f92..81cb945802595 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md @@ -4,11 +4,11 @@ The Behavior Path Planner's main objective is to significantly enhance the safet The module begins by thoroughly analyzing the ego vehicle's current situation, including its position, speed, and surrounding environment. This analysis leads to essential driving decisions about lane changes or stopping and subsequently generates a path that is both safe and efficient. It considers road geometry, traffic rules, and dynamic conditions while also incorporating obstacle avoidance to respond to static and dynamic obstacles such as other vehicles, pedestrians, or unexpected roadblocks, ensuring safe navigation. -Moreover, the planner actively interacts with other traffic participants, predicting their actions and accordingly adjusting the vehicle's path. This ensures not only the safety of the autonomous vehicle but also contributes to smooth traffic flow. Its adherence to traffic laws, including speed limits and traffic signals, further guarantees lawful and predictable driving behavior. The planner is also designed to minimize sudden or abrupt maneuvers, aiming for a comfortable and natural driving experience. +Moreover, the planner responds to the behavior of other traffic participants, predicting their actions and accordingly adjusting the vehicle's path. This ensures not only the safety of the autonomous vehicle but also contributes to smooth traffic flow. Its adherence to traffic laws, including speed limits and compliance with traffic signals, further guarantees lawful and predictable driving behavior. The planner is also designed to minimize sudden or abrupt maneuvers, aiming for a comfortable and natural driving experience. !!! note - The [Planning Component Design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/) Document outlines the foundational philosophy guiding the design and future development of the Behavior Path Planner module. We strongly encourage readers to consult this document to understand the rationale behind its current configuration and the direction of its ongoing development. + The [Planning Component Design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/) documentation outlines the foundational philosophy guiding the design and future development of the Behavior Path Planner module. We strongly encourage readers to consult this document to understand the rationale behind its current configuration and the direction of its ongoing development. ## Purpose / Use Cases @@ -22,23 +22,23 @@ Essentially, the module has three primary responsibilities: ### Supported Scene Modules -Behavior Path Planner has following scene modules +Behavior Path Planner has the following scene modules -| Name | Description | Details | -| :------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------------- | -| Lane Following | this module generates reference path from lanelet centerline. | LINK | -| Static Obstacle Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../autoware_behavior_path_static_obstacle_avoidance_module/README.md) | -| Dynamic Obstacle Avoidance | WIP | [LINK](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md) | -| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | -| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../autoware_behavior_path_lane_change_module/README.md) | -| External Lane Change | WIP | LINK | -| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../autoware_behavior_path_goal_planner_module/README.md) | -| Start Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../autoware_behavior_path_start_planner_module/README.md) | -| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../autoware_behavior_path_side_shift_module/README.md) | +| Name | Description | Details | +| :------------------------- | :--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------------- | +| Lane Following | This module generates a reference path from lanelet centerline. | LINK | +| Static Obstacle Avoidance | This module generates an avoidance path when there are objects that should be avoided. | [LINK](../autoware_behavior_path_static_obstacle_avoidance_module/README.md) | +| Dynamic Obstacle Avoidance | WIP | [LINK](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md) | +| Avoidance By Lane Change | This module generates a lane change path when there are objects that should be avoided. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | +| Lane Change | This module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../autoware_behavior_path_lane_change_module/README.md) | +| External Lane Change | WIP | LINK | +| Goal Planner | This module is performed when the ego vehicle is in a driving lane and the goal is in the shoulder lane. The ego vehicle will stop at the goal. | [LINK](../autoware_behavior_path_goal_planner_module/README.md) | +| Start Planner | This module is performed when the ego vehicle is stationary and the footprint of the ego vehicle is included in the shoulder lane. This module ends when the ego vehicle merges into the road. | [LINK](../autoware_behavior_path_start_planner_module/README.md) | +| Side Shift | This module shifts the path to the left or right based on external instructions, intended for remote control applications. | [LINK](../autoware_behavior_path_side_shift_module/README.md) | !!! Note - click on the following images to view the video of their execution + Click on the following images to view videos of their execution
@@ -59,13 +59,13 @@ Behavior Path Planner has following scene modules Users can refer to [Planning component design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/#supported-functions) for some additional behavior. -#### How to add or implement new module? +#### How to add or implement new module -All scene modules are implemented by inheriting base class `scene_module_interface.hpp`. +All scene modules are implemented by inheriting the base class `scene_module_interface.hpp`. !!! Warning - The remainder of this subsection is work in progress (WIP). + The remainder of this subsection is a work in progress (WIP). ### Planner Manager @@ -77,65 +77,65 @@ The Planner Manager's responsibilities include: !!! note - To check the scene module's transition, i.e.: registered, approved and candidate modules, set `verbose: true` in the [behavior path planner configuration file](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml#L3). + To check the scene module's transition – i.e., registered, approved and candidate modules – set `verbose: true` in the [Behavior Path Planner configuration file](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml#L3). ![Scene module's transition table](./image/checking_module_transition.png) !!! note - For more in-depth information, refer to [Manager design](./docs/behavior_path_planner_manager_design.md) document. + For more in-depth information, refer to the [Manager design](./docs/behavior_path_planner_manager_design.md) document. ## Inputs / Outputs / API ### Input -| Name | Required? | Type | Description | -| :---------------------------- | :-------: | :------------------------------------------------------ | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| ~/input/odometry | ○ | `nav_msgs::msg::Odometry` | for ego velocity. | -| ~/input/accel | ○ | `geometry_msgs::msg::AccelWithCovarianceStamped` | for ego acceleration. | -| ~/input/objects | ○ | `autoware_perception_msgs::msg::PredictedObjects` | dynamic objects from perception module. | -| ~/input/occupancy_grid_map | ○ | `nav_msgs::msg::OccupancyGrid` | occupancy grid map from perception module. This is used for only Goal Planner module. | -| ~/input/traffic_signals | ○ | `autoware_perception_msgs::msg::TrafficLightGroupArray` | traffic signals information from the perception module | -| ~/input/vector_map | ○ | `autoware_map_msgs::msg::LaneletMapBin` | vector map information. | -| ~/input/route | ○ | `autoware_planning_msgs::msg::LaneletRoute` | current route from start to goal. | -| ~/input/scenario | ○ | `tier4_planning_msgs::msg::Scenario` | Launches behavior path planner if current scenario == `Scenario:LaneDriving`. | -| ~/input/lateral_offset | △ | `tier4_planning_msgs::msg::LateralOffset` | lateral offset to trigger side shift | -| ~/system/operation_mode/state | ○ | `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows planning module to know if vehicle is in autonomous mode or can be controlled[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/operation-mode.md) | - -- ○ Mandatory: Planning Module would not work if anyone of this is not present. -- △ Optional: Some module would not work, but Planning Module can still be operated. +| Name | Required? | Type | Description | +| :---------------------------- | :-------: | :------------------------------------------------------ | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| ~/input/odometry | ○ | `nav_msgs::msg::Odometry` | For ego velocity | +| ~/input/accel | ○ | `geometry_msgs::msg::AccelWithCovarianceStamped` | For ego acceleration | +| ~/input/objects | ○ | `autoware_perception_msgs::msg::PredictedObjects` | Dynamic objects from the perception module | +| ~/input/occupancy_grid_map | ○ | `nav_msgs::msg::OccupancyGrid` | Occupancy grid map from the perception module. This is used for only the Goal Planner module | +| ~/input/traffic_signals | ○ | `autoware_perception_msgs::msg::TrafficLightGroupArray` | Traffic signal information from the perception module | +| ~/input/vector_map | ○ | `autoware_map_msgs::msg::LaneletMapBin` | Vector map information | +| ~/input/route | ○ | `autoware_planning_msgs::msg::LaneletRoute` | Current route from start to goal | +| ~/input/scenario | ○ | `tier4_planning_msgs::msg::Scenario` | Launches Behavior Path Planner if current scenario == `Scenario:LaneDriving` | +| ~/input/lateral_offset | △ | `tier4_planning_msgs::msg::LateralOffset` | Lateral offset to trigger side shift | +| ~/system/operation_mode/state | ○ | `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows the planning module to know if vehicle is in autonomous mode or if it can be controlled[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/operation-mode.md) | + +- ○ Mandatory: The planning module would not work if anyone of these were not present. +- △ Optional: Some modules would not work, but the planning module can still be operated. ### Output -| Name | Type | Description | QoS Durability | -| :---------------------------- | :-------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | -| ~/output/path | `tier4_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | -| ~/output/turn_indicators_cmd | `autoware_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | -| ~/output/hazard_lights_cmd | `autoware_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | -| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | -| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | +| Name | Type | Description | QoS Durability | +| :---------------------------- | :-------------------------------------------------- | :-------------------------------------------------------------------------------------------- | ----------------- | +| ~/output/path | `tier4_planning_msgs::msg::PathWithLaneId` | The path generated by modules | `volatile` | +| ~/output/turn_indicators_cmd | `autoware_vehicle_msgs::msg::TurnIndicatorsCommand` | Turn indicators command | `volatile` | +| ~/output/hazard_lights_cmd | `autoware_vehicle_msgs::msg::HazardLightsCommand` | Hazard lights command | `volatile` | +| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | Output modified goal commands | `transient_local` | +| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | The path the module is about to take. To be executed as soon as external approval is obtained | `volatile` | ### Debug -| Name | Type | Description | QoS Durability | -| :-------------------------------------- | :-------------------------------------------------- | :---------------------------------------------------------------------------------------- | -------------- | -| ~/debug/avoidance_debug_message_array | `tier4_planning_msgs::msg::AvoidanceDebugMsgArray` | debug message for avoidance. notify users reasons for avoidance path cannot be generated. | `volatile` | -| ~/debug/lane_change_debug_message_array | `tier4_planning_msgs::msg::LaneChangeDebugMsgArray` | debug message for lane change. notify users unsafe reason during lane changing process | `volatile` | -| ~/debug/maximum_drivable_area | `visualization_msgs::msg::MarkerArray` | shows maximum static drivable area. | `volatile` | -| ~/debug/turn_signal_info | `visualization_msgs::msg::MarkerArray` | TBA | `volatile` | -| ~/debug/bound | `visualization_msgs::msg::MarkerArray` | debug for static drivable area | `volatile` | -| ~/planning/path_candidate/\* | `autoware_planning_msgs::msg::Path` | the path before approval. | `volatile` | -| ~/planning/path_reference/\* | `autoware_planning_msgs::msg::Path` | reference path generated by each modules. | `volatile` | +| Name | Type | Description | QoS Durability | +| :-------------------------------------- | :-------------------------------------------------- | :---------------------------------------------------------------------------------------------- | -------------- | +| ~/debug/avoidance_debug_message_array | `tier4_planning_msgs::msg::AvoidanceDebugMsgArray` | Debug message for avoidance. Notifies users of reasons avoidance path cannot be generated | `volatile` | +| ~/debug/lane_change_debug_message_array | `tier4_planning_msgs::msg::LaneChangeDebugMsgArray` | Debug message for lane change. Notifies users of unsafe conditions during lane-changing process | `volatile` | +| ~/debug/maximum_drivable_area | `visualization_msgs::msg::MarkerArray` | Shows maximum static drivable area | `volatile` | +| ~/debug/turn_signal_info | `visualization_msgs::msg::MarkerArray` | TBA | `volatile` | +| ~/debug/bound | `visualization_msgs::msg::MarkerArray` | Debug for static drivable area | `volatile` | +| ~/planning/path_candidate/\* | `autoware_planning_msgs::msg::Path` | The path before approval | `volatile` | +| ~/planning/path_reference/\* | `autoware_planning_msgs::msg::Path` | Reference path generated by each module | `volatile` | !!! note - For specific information of which topics are being subscribed and published, refer to [behavior_path_planner.xml](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml#L36-L49). + For specific information about which topics are being subscribed to and published, refer to [behavior_path_planner.xml](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml#L36-L49). -## How to enable or disable the modules +## How to Enable or Disable Modules -Enabling and disabling the modules in the behavior path planner is primarily managed through two key files: `default_preset.yaml` and `behavior_path_planner.launch.xml`. +Enabling and disabling the modules in the Behavior Path Planner is primarily managed through two key files: `default_preset.yaml` and `behavior_path_planner.launch.xml`. -The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: +The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the Behavior Path Planner's modules or features. For example: - `launch_static_obstacle_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. @@ -143,14 +143,12 @@ The `default_preset.yaml` file acts as a configuration file for enabling or disa Click [here](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/preset/default_preset.yaml) to view the `default_preset.yaml`. -The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the behavior path planner's node is running. For instance, the parameter `static_obstacle_avoidance.enable_module` in +The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the Behavior Path Planner's node is running. For instance, the parameter `static_obstacle_avoidance.enable_module` in the following segment corresponds to launch_static_obstacle_avoidance_module from `default_preset.yaml`: ```xml ``` -corresponds to launch_static_obstacle_avoidance_module from `default_preset.yaml`. - Therefore, to enable or disable a module, simply set the corresponding module in `default_preset.yaml` to `true` or `false`. These changes will be applied upon the next launch of Autoware. ## Generating Path @@ -163,13 +161,13 @@ The `ShiftLine` struct (as seen [here](https://github.com/autowarefoundation/aut Furthermore, the design and its implementation incorporate various equations and mathematical models to calculate essential parameters for the path shift. These include the total distance of the lateral shift, the maximum allowable lateral acceleration and jerk, and the total time required for the shift. Practical considerations are also noted, such as simplifying assumptions in the absence of a specific time interval for most lane change and avoidance cases. -The shifted path generation logic enables the behavior path planner to dynamically generate safe and efficient paths, precisely controlling the vehicle’s lateral movements to ensure the smooth execution of lane changes and avoidance maneuvers. This careful planning and execution adhere to the vehicle's dynamic capabilities and safety constraints, maximizing efficiency and safety in autonomous vehicle navigation. +The shifted path generation logic enables the Behavior Path Planner to dynamically generate safe and efficient paths, precisely controlling the vehicle’s lateral movements to ensure the smooth execution of lane changes and avoidance maneuvers. This careful planning and execution adhere to the vehicle's dynamic capabilities and safety constraints, maximizing efficiency and safety in autonomous vehicle navigation. !!! note If you're a math lover, refer to [Path Generation Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) for the nitty-gritty. -## Collision Assessment / Safety check +## Collision Assessment / Safety Check The purpose of the collision assessment function in the Behavior Path Planner is to evaluate the potential for collisions with target objects across all modules. It is utilized in two scenarios: @@ -207,7 +205,7 @@ Static drivable area expansion operates under assumptions about the correct arra !!! note - Further details can is provided in [Drivable Area Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md). + Further details can be found in [Drivable Area Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md). ### Dynamic Drivable Area Logic @@ -233,7 +231,7 @@ The `TurnIndicatorsCommand` message structure has a command field that can take !!! warning - Rerouting is a feature that was still under progress. Further information will be included on a later date. + The rerouting feature is under development. Further information will be included at a later date. ## Parameters and Configuration @@ -278,5 +276,5 @@ preset ## Limitations & Future Work -1. Goal Planner module cannot be simultaneously executed together with other modules. -2. Module is not designed as plugin. Integrating custom module is not straightforward and user have to modify some part of the behavior path planner main code. +1. The Goal Planner module cannot be simultaneously executed together with other modules. +2. The module is not designed as a plugin. Integrating a custom module is not straightforward. Users have to modify part of the Behavior Path Planner's main code. From 00892a10702536fbcd071f9decc8953addddfd24 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Jan 2025 16:55:14 +0900 Subject: [PATCH 12/59] feat(goal_planner): cut stop path to goal (#9829) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 96aeb5f5e4da8..87a6e28ff0007 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1671,7 +1671,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath( const auto reference_path = std::invoke([&]() -> PathWithLaneId { const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); - const double s_end = s_current + common_parameters.forward_path_length; + const double s_end = std::clamp( + lanelet::utils::getArcCoordinates(current_lanes, route_handler->getGoalPose()).length, + s_current + std::numeric_limits::epsilon(), + s_current + common_parameters.forward_path_length); return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); }); From 594c099daf4413d6807f5dbe2f0d5d88a914afe9 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:55:44 +0900 Subject: [PATCH 13/59] feat(goal_planner): update lateral_deviation_thresh from `0.3` to `0.1` (#9850) * fix(goal_planner): Update lateral_deviation_thresh from 0.3 to 0.1 Signed-off-by: Kasunori-Nakajima * unified hasDeviatedFrom{Last|Current}PreviousModulePath Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix * hasDeviatedFromPath argument modification Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../goal_planner_module.hpp | 6 ++--- .../src/goal_planner_module.cpp | 26 +++++++------------ 2 files changed, 11 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 0765147cbeb80..cabbeb3435087 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -135,10 +135,8 @@ bool isOnModifiedGoal( bool hasPreviousModulePathShapeChanged( const BehaviorModuleOutput & upstream_module_output, const BehaviorModuleOutput & last_upstream_module_output); -bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output); -bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output); +bool hasDeviatedFromPath( + const Point & ego_position, const BehaviorModuleOutput & upstream_module_output); bool needPathUpdate( const Pose & current_pose, const double path_update_duration, const rclcpp::Time & now, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 87a6e28ff0007..d4f3953c557b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -155,7 +155,7 @@ bool hasPreviousModulePathShapeChanged( { // Calculate the lateral distance between each point of the current path and the nearest point of // the last path - constexpr double LATERAL_DEVIATION_THRESH = 0.3; + constexpr double LATERAL_DEVIATION_THRESH = 0.1; for (const auto & p : upstream_module_output.path.points) { const size_t nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( last_upstream_module_output.path.points, p.point.pose.position); @@ -184,21 +184,12 @@ bool hasPreviousModulePathShapeChanged( return false; } -bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output) +bool hasDeviatedFromPath( + const Point & ego_position, const BehaviorModuleOutput & upstream_module_output) { + constexpr double LATERAL_DEVIATION_THRESH = 0.1; return std::abs(autoware::motion_utils::calcLateralOffset( - last_upstream_module_output.path.points, - planner_data.self_odometry->pose.pose.position)) > 0.3; -} - -bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output) -{ - constexpr double LATERAL_DEVIATION_THRESH = 0.3; - return std::abs(autoware::motion_utils::calcLateralOffset( - upstream_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > - LATERAL_DEVIATION_THRESH; + upstream_module_output.path.points, ego_position)) > LATERAL_DEVIATION_THRESH; } bool needPathUpdate( @@ -371,7 +362,8 @@ void LaneParkingPlanner::onTimer() local_planner_data->self_odometry->pose.pose, modified_goal_opt, parameters_)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath(*local_planner_data, upstream_module_output)) { + if (hasDeviatedFromPath( + local_planner_data->self_odometry->pose.pose.position, upstream_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } @@ -381,8 +373,8 @@ void LaneParkingPlanner::onTimer() return true; } if ( - hasDeviatedFromLastPreviousModulePath( - *local_planner_data, original_upstream_module_output_) && + hasDeviatedFromPath( + local_planner_data->self_odometry->pose.pose.position, original_upstream_module_output_) && current_state != PathDecisionState::DecisionKind::DECIDED) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; From 2a94090ec5a5c658dd4108bf8c07862b4bbe59bd Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Fri, 10 Jan 2025 17:12:56 +0900 Subject: [PATCH 14/59] refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (#9762) * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * style(autoware_tensorrt_common): linting Signed-off-by: Amadeusz Szymko * style(autoware_lidar_centerpoint): typo Co-authored-by: Kenzo Lobos Tsunekawa * docs(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * fix(autoware_lidar_transfusion): reuse cast variable Signed-off-by: Amadeusz Szymko * fix(autoware_tensorrt_common): remove deprecated inference API Signed-off-by: Amadeusz Szymko * style(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * style(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * fix(autoware_tensorrt_common): const pointer Signed-off-by: Amadeusz Szymko * fix(autoware_tensorrt_common): remove unused method declaration Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * refactor(autoware_tensorrt_common): readability Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * fix(autoware_tensorrt_common): return if layer not registered Signed-off-by: Amadeusz Szymko * refactor(autoware_tensorrt_common): readability Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * fix(autoware_tensorrt_common): rename struct Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix --------- Signed-off-by: Amadeusz Szymko Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> --- .../pointpainting_trt.hpp | 5 +- .../src/pointpainting_fusion/node.cpp | 8 +- .../pointpainting_trt.cpp | 4 +- .../src/detector.cpp | 23 +- .../autoware_lidar_centerpoint/CMakeLists.txt | 2 - .../lidar_centerpoint/centerpoint_trt.hpp | 31 +- .../lidar_centerpoint/network/network_trt.hpp | 53 - .../network/tensorrt_wrapper.hpp | 67 -- .../lib/centerpoint_trt.cpp | 100 +- .../lib/network/network_trt.cpp | 85 -- .../lib/network/tensorrt_wrapper.cpp | 169 --- .../autoware_lidar_centerpoint/src/node.cpp | 4 +- .../autoware_lidar_transfusion/CMakeLists.txt | 1 - .../lidar_transfusion/network/network_trt.hpp | 87 -- .../lidar_transfusion/transfusion_config.hpp | 78 +- .../lidar_transfusion/transfusion_trt.hpp | 31 +- .../lib/network/network_trt.cpp | 357 ------- .../lib/transfusion_trt.cpp | 104 +- .../src/lidar_transfusion_node.cpp | 6 +- .../autoware_shape_estimation/CMakeLists.txt | 3 + .../tensorrt_shape_estimator.hpp | 6 +- .../lib/tensorrt_shape_estimator.cpp | 49 +- .../src/shape_estimation_node.cpp | 3 +- .../CMakeLists.txt | 3 + .../tensorrt_classifier.hpp | 21 +- .../src/tensorrt_classifier.cpp | 95 +- .../autoware_tensorrt_common/CMakeLists.txt | 9 +- perception/autoware_tensorrt_common/README.md | 70 +- .../tensorrt_common/conv_profiler.hpp | 108 ++ .../autoware/tensorrt_common/logger.hpp | 40 +- .../autoware/tensorrt_common/profiler.hpp | 96 ++ .../tensorrt_common/simple_profiler.hpp | 73 -- .../tensorrt_common/tensorrt_common.hpp | 449 +++++--- .../tensorrt_common/tensorrt_conv_calib.hpp | 241 +++++ .../autoware/tensorrt_common/utils.hpp | 408 +++++++ .../autoware_tensorrt_common/src/profiler.cpp | 113 ++ .../src/simple_profiler.cpp | 138 --- .../src/tensorrt_common.cpp | 992 +++++++++--------- .../autoware_tensorrt_yolox/CMakeLists.txt | 3 + .../tensorrt_yolox/tensorrt_yolox.hpp | 46 +- .../src/tensorrt_yolox.cpp | 184 ++-- .../src/tensorrt_yolox_node.cpp | 15 +- .../src/yolox_single_image_inference_node.cpp | 4 +- .../CMakeLists.txt | 1 - .../src/classifier/cnn_classifier.cpp | 7 +- .../CMakeLists.txt | 1 - .../src/traffic_light_fine_detector_node.cpp | 15 +- 47 files changed, 2345 insertions(+), 2063 deletions(-) delete mode 100644 perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp delete mode 100644 perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp delete mode 100644 perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp delete mode 100644 perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp delete mode 100644 perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp delete mode 100644 perception/autoware_lidar_transfusion/lib/network/network_trt.cpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp delete mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp create mode 100644 perception/autoware_tensorrt_common/src/profiler.cpp delete mode 100644 perception/autoware_tensorrt_common/src/simple_profiler.cpp diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp index a89ee3d02cd8b..a1d12bcb56384 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -29,8 +30,8 @@ class PointPaintingTRT : public autoware::lidar_centerpoint::CenterPointTRT using autoware::lidar_centerpoint::CenterPointTRT::CenterPointTRT; explicit PointPaintingTRT( - const autoware::lidar_centerpoint::NetworkParam & encoder_param, - const autoware::lidar_centerpoint::NetworkParam & head_param, + const autoware::tensorrt_common::TrtCommonConfig & encoder_param, + const autoware::tensorrt_common::TrtCommonConfig & head_param, const autoware::lidar_centerpoint::DensificationParam & densification_param, const autoware::lidar_centerpoint::CenterPointConfig & config); diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index bcd62383319c1..ef03cf6c3a7cf 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -176,10 +176,10 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt iou_bev_nms_.setParameters(p); } - autoware::lidar_centerpoint::NetworkParam encoder_param( - encoder_onnx_path, encoder_engine_path, trt_precision); - autoware::lidar_centerpoint::NetworkParam head_param( - head_onnx_path, head_engine_path, trt_precision); + autoware::tensorrt_common::TrtCommonConfig encoder_param( + encoder_onnx_path, trt_precision, encoder_engine_path); + autoware::tensorrt_common::TrtCommonConfig head_param( + head_onnx_path, trt_precision, head_engine_path); autoware::lidar_centerpoint::DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); autoware::lidar_centerpoint::CenterPointConfig config( diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp index cc3eb17cc32ab..1fe860e68a967 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp @@ -27,8 +27,8 @@ namespace autoware::image_projection_based_fusion { PointPaintingTRT::PointPaintingTRT( - const autoware::lidar_centerpoint::NetworkParam & encoder_param, - const autoware::lidar_centerpoint::NetworkParam & head_param, + const autoware::tensorrt_common::TrtCommonConfig & encoder_param, + const autoware::tensorrt_common::TrtCommonConfig & head_param, const autoware::lidar_centerpoint::DensificationParam & densification_param, const autoware::lidar_centerpoint::CenterPointConfig & config) : autoware::lidar_centerpoint::CenterPointTRT( diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp index 60aa09c8e16d7..2e3a7a2243399 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp @@ -18,7 +18,6 @@ #include -#include #include #include @@ -51,12 +50,9 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * const auto precision = node_->declare_parameter("precision", "fp32"); trt_common_ = std::make_unique( - onnx_file, precision, nullptr, autoware::tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30); - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - RCLCPP_ERROR_STREAM(node_->get_logger(), "failed to create tensorrt engine file."); - return; + tensorrt_common::TrtCommonConfig(onnx_file, precision)); + if (!trt_common_->setup()) { + throw std::runtime_error("Failed to setup TensorRT"); } if (node_->declare_parameter("build_only", false)) { @@ -65,11 +61,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); input_d_ = autoware::cuda_utils::make_unique(input_size); - const auto output_dims = trt_common_->getBindingDimensions(1); + const auto output_dims = trt_common_->getTensorShape(1); output_size_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); output_d_ = autoware::cuda_utils::make_unique(output_size_); @@ -127,10 +123,6 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects( const sensor_msgs::msg::PointCloud2 & input, tier4_perception_msgs::msg::DetectedObjectsWithFeature & output) { - if (!trt_common_->isInitialized()) { - return false; - } - // move up pointcloud z_offset in z axis sensor_msgs::msg::PointCloud2 transformed_cloud; transformCloud(input, transformed_cloud, z_offset_); @@ -169,7 +161,10 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects( std::vector buffers = {input_d_.get(), output_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( output_h_.get(), output_d_.get(), sizeof(float) * output_size_, cudaMemcpyDeviceToHost, diff --git a/perception/autoware_lidar_centerpoint/CMakeLists.txt b/perception/autoware_lidar_centerpoint/CMakeLists.txt index 88244b3153349..322907c67c6ae 100644 --- a/perception/autoware_lidar_centerpoint/CMakeLists.txt +++ b/perception/autoware_lidar_centerpoint/CMakeLists.txt @@ -84,8 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) lib/detection_class_remapper.cpp lib/utils.cpp lib/ros_utils.cpp - lib/network/network_trt.cpp - lib/network/tensorrt_wrapper.cpp lib/postprocess/non_maximum_suppression.cpp lib/preprocess/pointcloud_densification.cpp lib/preprocess/voxel_generator.cpp diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp index 671ff54f8ce0d..4b531e34877d6 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp @@ -16,12 +16,13 @@ #define AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_ #include "autoware/lidar_centerpoint/cuda_utils.hpp" -#include "autoware/lidar_centerpoint/network/network_trt.hpp" #include "autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp" #include "autoware/lidar_centerpoint/preprocess/voxel_generator.hpp" #include "pcl/point_cloud.h" #include "pcl/point_types.h" +#include + #include "sensor_msgs/msg/point_cloud2.hpp" #include @@ -31,31 +32,14 @@ namespace autoware::lidar_centerpoint { -class NetworkParam -{ -public: - NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision) - : onnx_path_(std::move(onnx_path)), - engine_path_(std::move(engine_path)), - trt_precision_(std::move(trt_precision)) - { - } - - std::string onnx_path() const { return onnx_path_; } - std::string engine_path() const { return engine_path_; } - std::string trt_precision() const { return trt_precision_; } - -private: - std::string onnx_path_; - std::string engine_path_; - std::string trt_precision_; -}; +using autoware::tensorrt_common::ProfileDims; +using autoware::tensorrt_common::TrtCommonConfig; class CenterPointTRT { public: explicit CenterPointTRT( - const NetworkParam & encoder_param, const NetworkParam & head_param, + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param, const DensificationParam & densification_param, const CenterPointConfig & config); virtual ~CenterPointTRT(); @@ -66,6 +50,7 @@ class CenterPointTRT protected: void initPtr(); + void initTrt(const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param); virtual bool preprocess( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); @@ -75,8 +60,8 @@ class CenterPointTRT void postProcess(std::vector & det_boxes3d); std::unique_ptr vg_ptr_{nullptr}; - std::unique_ptr encoder_trt_ptr_{nullptr}; - std::unique_ptr head_trt_ptr_{nullptr}; + std::unique_ptr encoder_trt_ptr_{nullptr}; + std::unique_ptr head_trt_ptr_{nullptr}; std::unique_ptr post_proc_ptr_{nullptr}; cudaStream_t stream_{nullptr}; diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp deleted file mode 100644 index 17778d77ed798..0000000000000 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp +++ /dev/null @@ -1,53 +0,0 @@ -// 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. - -#ifndef AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ -#define AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ - -#include "autoware/lidar_centerpoint/centerpoint_config.hpp" -#include "autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp" - -#include - -namespace autoware::lidar_centerpoint -{ -class VoxelEncoderTRT : public TensorRTWrapper -{ -public: - using TensorRTWrapper::TensorRTWrapper; - -protected: - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) override; -}; - -class HeadTRT : public TensorRTWrapper -{ -public: - using TensorRTWrapper::TensorRTWrapper; - - HeadTRT(const std::vector & out_channel_sizes, const CenterPointConfig & config); - -protected: - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) override; - - std::vector out_channel_sizes_; -}; - -} // namespace autoware::lidar_centerpoint - -#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp deleted file mode 100644 index d56ccc699add3..0000000000000 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// 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. - -#ifndef AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ -#define AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ - -#include "NvInfer.h" -#include "autoware/lidar_centerpoint/centerpoint_config.hpp" -#include "autoware/tensorrt_common/tensorrt_common.hpp" - -#include -#include -#include - -namespace autoware::lidar_centerpoint -{ - -class TensorRTWrapper -{ -public: - explicit TensorRTWrapper(const CenterPointConfig & config); - - virtual ~TensorRTWrapper(); - - bool init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision); - - autoware::tensorrt_common::TrtUniquePtr context_{nullptr}; - -protected: - virtual bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) = 0; - - CenterPointConfig config_; - autoware::tensorrt_common::Logger logger_; - -private: - bool parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - std::size_t workspace_size = (1ULL << 30)); - - bool saveEngine(const std::string & engine_path); - - bool loadEngine(const std::string & engine_path); - - bool createContext(); - - autoware::tensorrt_common::TrtUniquePtr runtime_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr plan_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr engine_{nullptr}; -}; - -} // namespace autoware::lidar_centerpoint - -#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ diff --git a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp index 530f59179d25b..c586eeb961716 100644 --- a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp @@ -28,39 +28,22 @@ #include #include #include +#include +#include #include namespace autoware::lidar_centerpoint { CenterPointTRT::CenterPointTRT( - const NetworkParam & encoder_param, const NetworkParam & head_param, + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param, const DensificationParam & densification_param, const CenterPointConfig & config) : config_(config) { vg_ptr_ = std::make_unique(densification_param, config_); post_proc_ptr_ = std::make_unique(config_); - // encoder - encoder_trt_ptr_ = std::make_unique(config_); - encoder_trt_ptr_->init( - encoder_param.onnx_path(), encoder_param.engine_path(), encoder_param.trt_precision()); - encoder_trt_ptr_->context_->setBindingDimensions( - 0, - nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, config_.encoder_in_feature_size_)); - - // head - std::vector out_channel_sizes = { - config_.class_size_, config_.head_out_offset_size_, config_.head_out_z_size_, - config_.head_out_dim_size_, config_.head_out_rot_size_, config_.head_out_vel_size_}; - head_trt_ptr_ = std::make_unique(out_channel_sizes, config_); - head_trt_ptr_->init(head_param.onnx_path(), head_param.engine_path(), head_param.trt_precision()); - head_trt_ptr_->context_->setBindingDimensions( - 0, nvinfer1::Dims4( - config_.batch_size_, config_.encoder_out_feature_size_, config_.grid_size_y_, - config_.grid_size_x_)); - initPtr(); + initTrt(encoder_param, head_param); cudaStreamCreate(&stream_); } @@ -126,6 +109,66 @@ void CenterPointTRT::initPtr() cudaMemcpyHostToDevice, stream_)); } +void CenterPointTRT::initTrt( + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param) +{ + // encoder input profile + auto enc_in_dims = nvinfer1::Dims{ + 3, + {static_cast(config_.max_voxel_size_), + static_cast(config_.max_point_in_voxel_size_), + static_cast(config_.encoder_in_feature_size_)}}; + std::vector encoder_profile_dims{ + tensorrt_common::ProfileDims(0, enc_in_dims, enc_in_dims, enc_in_dims)}; + auto encoder_profile_dims_ptr = + std::make_unique>(encoder_profile_dims); + + // head input profile + auto head_in_dims = nvinfer1::Dims{ + 4, + {static_cast(config_.batch_size_), + static_cast(config_.encoder_out_feature_size_), + static_cast(config_.grid_size_y_), static_cast(config_.grid_size_x_)}}; + std::vector head_profile_dims{ + tensorrt_common::ProfileDims(0, head_in_dims, head_in_dims, head_in_dims)}; + std::unordered_map out_channel_map = { + {1, static_cast(config_.class_size_)}, + {2, static_cast(config_.head_out_offset_size_)}, + {3, static_cast(config_.head_out_z_size_)}, + {4, static_cast(config_.head_out_dim_size_)}, + {5, static_cast(config_.head_out_rot_size_)}, + {6, static_cast(config_.head_out_vel_size_)}}; + for (const auto & [tensor_name, channel_size] : out_channel_map) { + auto dims = nvinfer1::Dims{ + 4, + {static_cast(config_.batch_size_), channel_size, + static_cast(config_.down_grid_size_y_), + static_cast(config_.down_grid_size_x_)}}; + head_profile_dims.emplace_back(tensor_name, dims, dims, dims); + } + auto head_profile_dims_ptr = + std::make_unique>(head_profile_dims); + + // initialize trt wrappers + encoder_trt_ptr_ = std::make_unique(encoder_param); + + head_trt_ptr_ = std::make_unique(head_param); + + // setup trt engines + if ( + !encoder_trt_ptr_->setup(std::move(encoder_profile_dims_ptr)) || + !head_trt_ptr_->setup(std::move(head_profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TRT engine."); + } + + // set input shapes + if ( + !encoder_trt_ptr_->setInputShape(0, enc_in_dims) || + !head_trt_ptr_->setInputShape(0, head_in_dims)) { + throw std::runtime_error("Failed to set input shape."); + } +} + bool CenterPointTRT::detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, std::vector & det_boxes3d, bool & is_num_pillars_within_range) @@ -210,13 +253,10 @@ bool CenterPointTRT::preprocess( void CenterPointTRT::inference() { - if (!encoder_trt_ptr_->context_ || !head_trt_ptr_->context_) { - throw std::runtime_error("Failed to create tensorrt context."); - } - // pillar encoder network - std::vector encoder_buffers{encoder_in_features_d_.get(), pillar_features_d_.get()}; - encoder_trt_ptr_->context_->enqueueV2(encoder_buffers.data(), stream_, nullptr); + std::vector encoder_tensors = {encoder_in_features_d_.get(), pillar_features_d_.get()}; + encoder_trt_ptr_->setTensorsAddresses(encoder_tensors); + encoder_trt_ptr_->enqueueV3(stream_); // scatter CHECK_CUDA_ERROR(scatterFeatures_launch( @@ -225,11 +265,13 @@ void CenterPointTRT::inference() spatial_features_d_.get(), stream_)); // head network - std::vector head_buffers = {spatial_features_d_.get(), head_out_heatmap_d_.get(), + std::vector head_tensors = {spatial_features_d_.get(), head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), head_out_rot_d_.get(), head_out_vel_d_.get()}; - head_trt_ptr_->context_->enqueueV2(head_buffers.data(), stream_, nullptr); + head_trt_ptr_->setTensorsAddresses(head_tensors); + + head_trt_ptr_->enqueueV3(stream_); } void CenterPointTRT::postProcess(std::vector & det_boxes3d) diff --git a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp b/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp deleted file mode 100644 index 7767c0b5cbb02..0000000000000 --- a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp +++ /dev/null @@ -1,85 +0,0 @@ -// 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 "autoware/lidar_centerpoint/network/network_trt.hpp" - -#include -#include - -namespace autoware::lidar_centerpoint -{ -bool VoxelEncoderTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - auto in_name = network.getInput(0)->getName(); - auto in_dims = nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, config_.encoder_in_feature_size_); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMIN, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kOPT, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMAX, in_dims); - - auto out_name = network.getOutput(0)->getName(); - auto out_dims = nvinfer1::Dims2(config_.max_voxel_size_, config_.encoder_out_feature_size_); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMIN, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kOPT, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMAX, out_dims); - config.addOptimizationProfile(profile); - - return true; -} - -HeadTRT::HeadTRT( - const std::vector & out_channel_sizes, const CenterPointConfig & config) -: TensorRTWrapper(config), out_channel_sizes_(out_channel_sizes) -{ -} - -bool HeadTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - auto in_name = network.getInput(0)->getName(); - auto in_dims = nvinfer1::Dims4( - config_.batch_size_, config_.encoder_out_feature_size_, config_.grid_size_y_, - config_.grid_size_x_); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMIN, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kOPT, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMAX, in_dims); - - for (std::size_t ci = 0; ci < out_channel_sizes_.size(); ci++) { - auto out_name = network.getOutput(ci)->getName(); - - if ( - out_name == std::string("heatmap") && - network.getOutput(ci)->getDimensions().d[1] != static_cast(out_channel_sizes_[ci])) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Expected and actual number of classes do not match" << std::endl; - return false; - } - auto out_dims = nvinfer1::Dims4( - config_.batch_size_, out_channel_sizes_[ci], config_.down_grid_size_y_, - config_.down_grid_size_x_); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMIN, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kOPT, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMAX, out_dims); - } - config.addOptimizationProfile(profile); - - return true; -} - -} // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp deleted file mode 100644 index 6d4c2e053b34f..0000000000000 --- a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ /dev/null @@ -1,169 +0,0 @@ -// 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 "autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp" - -#include "NvOnnxParser.h" - -#include -#include -#include - -namespace autoware::lidar_centerpoint -{ -TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config) : config_(config) -{ -} - -TensorRTWrapper::~TensorRTWrapper() -{ - context_.reset(); - runtime_.reset(); - plan_.reset(); - engine_.reset(); -} - -bool TensorRTWrapper::init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision) -{ - runtime_ = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferRuntime(logger_)); - if (!runtime_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; - return false; - } - - bool success; - std::ifstream engine_file(engine_path); - if (engine_file.is_open()) { - success = loadEngine(engine_path); - } else { - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); - success = parseONNX(onnx_path, engine_path, precision); - logger_.stop_throttle(log_thread); - } - success &= createContext(); - - return success; -} - -bool TensorRTWrapper::createContext() -{ - if (!engine_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create context: Engine was not created" << std::endl; - return false; - } - - context_ = autoware::tensorrt_common::TrtUniquePtr( - engine_->createExecutionContext()); - if (!context_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; - return false; - } - - return true; -} - -bool TensorRTWrapper::parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - const std::size_t workspace_size) -{ - auto builder = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferBuilder(logger_)); - if (!builder) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; - return false; - } - - auto config = autoware::tensorrt_common::TrtUniquePtr( - builder->createBuilderConfig()); - if (!config) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; - return false; - } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); -#else - config->setMaxWorkspaceSize(workspace_size); -#endif - if (precision == "fp16") { - if (builder->platformHasFastFp16()) { - autoware::tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; - config->setFlag(nvinfer1::BuilderFlag::kFP16); - } else { - autoware::tensorrt_common::LOG_INFO(logger_) - << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; - } - } - - const auto flag = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = autoware::tensorrt_common::TrtUniquePtr( - builder->createNetworkV2(flag)); - if (!network) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; - return false; - } - - auto parser = autoware::tensorrt_common::TrtUniquePtr( - nvonnxparser::createParser(*network, logger_)); - parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); - - if (!setProfile(*builder, *network, *config)) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; - return false; - } - - plan_ = autoware::tensorrt_common::TrtUniquePtr( - builder->buildSerializedNetwork(*network, *config)); - if (!plan_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create serialized network" << std::endl; - return false; - } - engine_ = autoware::tensorrt_common::TrtUniquePtr( - runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); - if (!engine_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; - return false; - } - - return saveEngine(engine_path); -} - -bool TensorRTWrapper::saveEngine(const std::string & engine_path) -{ - autoware::tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; - std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(plan_->data()), plan_->size()); - return true; -} - -bool TensorRTWrapper::loadEngine(const std::string & engine_path) -{ - std::ifstream engine_file(engine_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine_ = - autoware::tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - autoware::tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; - return true; -} - -} // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 825fc40234120..19d1475db9051 100644 --- a/perception/autoware_lidar_centerpoint/src/node.cpp +++ b/perception/autoware_lidar_centerpoint/src/node.cpp @@ -86,8 +86,8 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti iou_bev_nms_.setParameters(p); } - NetworkParam encoder_param(encoder_onnx_path, encoder_engine_path, trt_precision); - NetworkParam head_param(head_onnx_path, head_engine_path, trt_precision); + TrtCommonConfig encoder_param(encoder_onnx_path, trt_precision, encoder_engine_path); + TrtCommonConfig head_param(head_onnx_path, trt_precision, head_engine_path); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); diff --git a/perception/autoware_lidar_transfusion/CMakeLists.txt b/perception/autoware_lidar_transfusion/CMakeLists.txt index c3a56f883fbe5..fdb978c64946f 100644 --- a/perception/autoware_lidar_transfusion/CMakeLists.txt +++ b/perception/autoware_lidar_transfusion/CMakeLists.txt @@ -84,7 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) ament_auto_add_library(${PROJECT_NAME}_lib SHARED lib/detection_class_remapper.cpp - lib/network/network_trt.cpp lib/postprocess/non_maximum_suppression.cpp lib/preprocess/voxel_generator.cpp lib/preprocess/pointcloud_densification.cpp diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp deleted file mode 100644 index 71cd08acdb8c8..0000000000000 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp +++ /dev/null @@ -1,87 +0,0 @@ -// Copyright 2024 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__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ -#define AUTOWARE__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ - -#include "autoware/lidar_transfusion/transfusion_config.hpp" -#include "autoware/lidar_transfusion/utils.hpp" - -#include - -#include - -#include -#include -#include -#include -#include -#include - -namespace autoware::lidar_transfusion -{ - -struct ProfileDimension -{ - nvinfer1::Dims min; - nvinfer1::Dims opt; - nvinfer1::Dims max; - - bool operator!=(const ProfileDimension & rhs) const - { - return min.nbDims != rhs.min.nbDims || opt.nbDims != rhs.opt.nbDims || - max.nbDims != rhs.max.nbDims || !std::equal(min.d, min.d + min.nbDims, rhs.min.d) || - !std::equal(opt.d, opt.d + opt.nbDims, rhs.opt.d) || - !std::equal(max.d, max.d + max.nbDims, rhs.max.d); - } -}; - -class NetworkTRT -{ -public: - explicit NetworkTRT(const TransfusionConfig & config); - ~NetworkTRT(); - - bool init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision); - const char * getTensorName(NetworkIO name); - - autoware::tensorrt_common::TrtUniquePtr engine{nullptr}; - autoware::tensorrt_common::TrtUniquePtr context{nullptr}; - -private: - bool parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - std::size_t workspace_size = (1ULL << 30)); - bool saveEngine(const std::string & engine_path); - bool loadEngine(const std::string & engine_path); - bool createContext(); - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config); - bool validateNetworkIO(); - nvinfer1::Dims validateTensorShape(NetworkIO name, const std::vector shape); - - autoware::tensorrt_common::TrtUniquePtr runtime_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr plan_{nullptr}; - autoware::tensorrt_common::Logger logger_; - TransfusionConfig config_; - std::vector tensors_names_; - - std::array in_profile_dims_; -}; - -} // namespace autoware::lidar_transfusion - -#endif // AUTOWARE__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp index 363ee17a0d6e0..e60ee04150b5c 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp @@ -35,21 +35,21 @@ class TransfusionConfig if (voxels_num.size() == 3) { max_voxels_ = voxels_num[2]; - voxels_num_[0] = voxels_num[0]; - voxels_num_[1] = voxels_num[1]; - voxels_num_[2] = voxels_num[2]; + voxels_num_[0] = static_cast(voxels_num[0]); + voxels_num_[1] = static_cast(voxels_num[1]); + voxels_num_[2] = static_cast(voxels_num[2]); - min_voxel_size_ = voxels_num[0]; - opt_voxel_size_ = voxels_num[1]; - max_voxel_size_ = voxels_num[2]; + min_voxel_size_ = static_cast(voxels_num[0]); + opt_voxel_size_ = static_cast(voxels_num[1]); + max_voxel_size_ = static_cast(voxels_num[2]); - min_points_size_ = voxels_num[0]; - opt_points_size_ = voxels_num[1]; - max_points_size_ = voxels_num[2]; + min_points_size_ = static_cast(voxels_num[0]); + opt_points_size_ = static_cast(voxels_num[1]); + max_points_size_ = static_cast(voxels_num[2]); - min_coors_size_ = voxels_num[0]; - opt_coors_size_ = voxels_num[1]; - max_coors_size_ = voxels_num[2]; + min_coors_size_ = static_cast(voxels_num[0]); + opt_coors_size_ = static_cast(voxels_num[1]); + max_coors_size_ = static_cast(voxels_num[2]); } if (point_cloud_range.size() == 6) { min_x_range_ = static_cast(point_cloud_range[0]); @@ -91,7 +91,7 @@ class TransfusionConfig std::size_t cloud_capacity_{}; ///// KERNEL PARAMETERS ///// const std::size_t threads_for_voxel_{256}; // threads number for a block - const std::size_t points_per_voxel_{20}; + const int32_t points_per_voxel_{20}; const std::size_t warp_size_{32}; // one warp(32 threads) for one pillar const std::size_t pillars_per_block_{64}; // one thread deals with one pillar // and a block has pillars_per_block threads @@ -99,9 +99,9 @@ class TransfusionConfig std::size_t max_voxels_{60000}; ///// NETWORK PARAMETERS ///// - const std::size_t batch_size_{1}; - const std::size_t num_classes_{5}; - const std::size_t num_point_feature_size_{5}; // x, y, z, intensity, lag + const int32_t batch_size_{1}; + const int32_t num_classes_{5}; + const int32_t num_point_feature_size_{5}; // x, y, z, intensity, lag // the dimension of the input cloud float min_x_range_{-76.8}; float max_x_range_{76.8}; @@ -114,9 +114,9 @@ class TransfusionConfig float voxel_y_size_{0.3}; float voxel_z_size_{8.0}; const std::size_t out_size_factor_{4}; - const std::size_t max_num_points_per_pillar_{points_per_voxel_}; - const std::size_t num_point_values_{4}; - std::size_t num_proposals_{200}; + const int32_t max_num_points_per_pillar_{points_per_voxel_}; + const int32_t num_point_values_{4}; + int32_t num_proposals_{200}; // the number of feature maps for pillar scatter const std::size_t num_feature_scatter_{pillar_feature_size_}; // the score threshold for classification @@ -126,7 +126,7 @@ class TransfusionConfig std::size_t max_num_pillars_{max_voxels_}; const std::size_t pillar_points_bev_{max_num_points_per_pillar_ * max_num_pillars_}; // the detected boxes result decode by (x, y, z, w, l, h, yaw) - const std::size_t num_box_values_{8}; + const int32_t num_box_values_{8}; // the input size of the 2D backbone network std::size_t grid_x_size_{512}; std::size_t grid_y_size_{512}; @@ -136,33 +136,33 @@ class TransfusionConfig std::size_t feature_y_size_{grid_y_size_ / out_size_factor_}; ///// RUNTIME DIMENSIONS ///// - std::vector voxels_num_{5000, 30000, 60000}; + std::vector voxels_num_{5000, 30000, 60000}; // voxels - std::size_t min_voxel_size_{voxels_num_[0]}; - std::size_t opt_voxel_size_{voxels_num_[1]}; - std::size_t max_voxel_size_{voxels_num_[2]}; + int32_t min_voxel_size_{voxels_num_[0]}; + int32_t opt_voxel_size_{voxels_num_[1]}; + int32_t max_voxel_size_{voxels_num_[2]}; - std::size_t min_point_in_voxel_size_{points_per_voxel_}; - std::size_t opt_point_in_voxel_size_{points_per_voxel_}; - std::size_t max_point_in_voxel_size_{points_per_voxel_}; + int32_t min_point_in_voxel_size_{points_per_voxel_}; + int32_t opt_point_in_voxel_size_{points_per_voxel_}; + int32_t max_point_in_voxel_size_{points_per_voxel_}; - std::size_t min_network_feature_size_{num_point_feature_size_}; - std::size_t opt_network_feature_size_{num_point_feature_size_}; - std::size_t max_network_feature_size_{num_point_feature_size_}; + int32_t min_network_feature_size_{num_point_feature_size_}; + int32_t opt_network_feature_size_{num_point_feature_size_}; + int32_t max_network_feature_size_{num_point_feature_size_}; // num_points - std::size_t min_points_size_{voxels_num_[0]}; - std::size_t opt_points_size_{voxels_num_[1]}; - std::size_t max_points_size_{voxels_num_[2]}; + int32_t min_points_size_{voxels_num_[0]}; + int32_t opt_points_size_{voxels_num_[1]}; + int32_t max_points_size_{voxels_num_[2]}; // coors - std::size_t min_coors_size_{voxels_num_[0]}; - std::size_t opt_coors_size_{voxels_num_[1]}; - std::size_t max_coors_size_{voxels_num_[2]}; + int32_t min_coors_size_{voxels_num_[0]}; + int32_t opt_coors_size_{voxels_num_[1]}; + int32_t max_coors_size_{voxels_num_[2]}; - std::size_t min_coors_dim_size_{num_point_values_}; - std::size_t opt_coors_dim_size_{num_point_values_}; - std::size_t max_coors_dim_size_{num_point_values_}; + int32_t min_coors_dim_size_{num_point_values_}; + int32_t opt_coors_dim_size_{num_point_values_}; + int32_t max_coors_dim_size_{num_point_values_}; }; } // namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp index 06dd65b4b805f..00bb5e726706c 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp @@ -16,7 +16,6 @@ #define AUTOWARE__LIDAR_TRANSFUSION__TRANSFUSION_TRT_HPP_ #include "autoware/lidar_transfusion/cuda_utils.hpp" -#include "autoware/lidar_transfusion/network/network_trt.hpp" #include "autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp" #include "autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp" #include "autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp" @@ -24,6 +23,7 @@ #include "autoware/lidar_transfusion/utils.hpp" #include "autoware/lidar_transfusion/visibility_control.hpp" +#include #include #include @@ -34,38 +34,17 @@ #include #include #include -#include #include namespace autoware::lidar_transfusion { -class NetworkParam -{ -public: - NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision) - : onnx_path_(std::move(onnx_path)), - engine_path_(std::move(engine_path)), - trt_precision_(std::move(trt_precision)) - { - } - - std::string onnx_path() const { return onnx_path_; } - std::string engine_path() const { return engine_path_; } - std::string trt_precision() const { return trt_precision_; } - -private: - std::string onnx_path_; - std::string engine_path_; - std::string trt_precision_; -}; - class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT { public: explicit TransfusionTRT( - const NetworkParam & network_param, const DensificationParam & densification_param, - const TransfusionConfig & config); + const tensorrt_common::TrtCommonConfig & trt_config, + const DensificationParam & densification_param, const TransfusionConfig config); virtual ~TransfusionTRT(); bool detect( @@ -73,6 +52,8 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT std::vector & det_boxes3d, std::unordered_map & proc_timing); protected: + void initTrt(const tensorrt_common::TrtCommonConfig & trt_config); + void initPtr(); bool preprocess(const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer); @@ -81,7 +62,7 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT bool postprocess(std::vector & det_boxes3d); - std::unique_ptr network_trt_ptr_{nullptr}; + std::unique_ptr network_trt_ptr_{nullptr}; std::unique_ptr vg_ptr_{nullptr}; std::unique_ptr> stop_watch_ptr_{ nullptr}; diff --git a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp b/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp deleted file mode 100644 index 8e3cb8a55ec7e..0000000000000 --- a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp +++ /dev/null @@ -1,357 +0,0 @@ -// Copyright 2024 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 "autoware/lidar_transfusion/network/network_trt.hpp" - -#include - -#include -#include -#include -#include -#include - -namespace autoware::lidar_transfusion -{ - -inline NetworkIO nameToNetworkIO(const char * name) -{ - static const std::unordered_map name_to_enum = { - {"voxels", NetworkIO::voxels}, {"num_points", NetworkIO::num_points}, - {"coors", NetworkIO::coors}, {"cls_score0", NetworkIO::cls_score}, - {"bbox_pred0", NetworkIO::bbox_pred}, {"dir_cls_pred0", NetworkIO::dir_pred}}; - - auto it = name_to_enum.find(name); - if (it != name_to_enum.end()) { - return it->second; - } - throw std::runtime_error("Invalid input name: " + std::string(name)); -} - -std::ostream & operator<<(std::ostream & os, const ProfileDimension & profile) -{ - std::string delim = ""; - os << "min->["; - for (int i = 0; i < profile.min.nbDims; ++i) { - os << delim << profile.min.d[i]; - delim = ", "; - } - os << "], opt->["; - delim = ""; - for (int i = 0; i < profile.opt.nbDims; ++i) { - os << delim << profile.opt.d[i]; - delim = ", "; - } - os << "], max->["; - delim = ""; - for (int i = 0; i < profile.max.nbDims; ++i) { - os << delim << profile.max.d[i]; - delim = ", "; - } - os << "]"; - return os; -} - -NetworkTRT::NetworkTRT(const TransfusionConfig & config) : config_(config) -{ - ProfileDimension voxels_dims = { - nvinfer1::Dims3( - config_.min_voxel_size_, config_.min_point_in_voxel_size_, config_.min_network_feature_size_), - nvinfer1::Dims3( - config_.opt_voxel_size_, config_.opt_point_in_voxel_size_, config_.opt_network_feature_size_), - nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, - config_.max_network_feature_size_)}; - ProfileDimension num_points_dims = { - nvinfer1::Dims{1, {static_cast(config_.min_points_size_)}}, - nvinfer1::Dims{1, {static_cast(config_.opt_points_size_)}}, - nvinfer1::Dims{1, {static_cast(config_.max_points_size_)}}}; - ProfileDimension coors_dims = { - nvinfer1::Dims2(config_.min_coors_size_, config_.min_coors_dim_size_), - nvinfer1::Dims2(config_.opt_coors_size_, config_.opt_coors_dim_size_), - nvinfer1::Dims2(config_.max_coors_size_, config_.max_coors_dim_size_)}; - in_profile_dims_ = {voxels_dims, num_points_dims, coors_dims}; -} - -NetworkTRT::~NetworkTRT() -{ - context.reset(); - runtime_.reset(); - plan_.reset(); - engine.reset(); -} - -bool NetworkTRT::init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision) -{ - runtime_ = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferRuntime(logger_)); - if (!runtime_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; - return false; - } - - bool success; - std::ifstream engine_file(engine_path); - if (engine_file.is_open()) { - success = loadEngine(engine_path); - } else { - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); - success = parseONNX(onnx_path, engine_path, precision); - logger_.stop_throttle(log_thread); - } - success &= createContext(); - - return success; -} - -bool NetworkTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - - auto voxels_name = network.getInput(NetworkIO::voxels)->getName(); - auto num_points_name = network.getInput(NetworkIO::num_points)->getName(); - auto coors_name = network.getInput(NetworkIO::coors)->getName(); - - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::voxels].min); - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::voxels].opt); - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::voxels].max); - - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kMIN, - in_profile_dims_[NetworkIO::num_points].min); - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kOPT, - in_profile_dims_[NetworkIO::num_points].opt); - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kMAX, - in_profile_dims_[NetworkIO::num_points].max); - - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::coors].min); - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::coors].opt); - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::coors].max); - - config.addOptimizationProfile(profile); - return true; -} - -bool NetworkTRT::createContext() -{ - if (!engine) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create context: Engine was not created" << std::endl; - return false; - } - - context = autoware::tensorrt_common::TrtUniquePtr( - engine->createExecutionContext()); - if (!context) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; - return false; - } - - return true; -} - -bool NetworkTRT::parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - const size_t workspace_size) -{ - auto builder = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferBuilder(logger_)); - if (!builder) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; - return false; - } - - auto config = autoware::tensorrt_common::TrtUniquePtr( - builder->createBuilderConfig()); - if (!config) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; - return false; - } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); -#else - config->setMaxWorkspaceSize(workspace_size); -#endif - if (precision == "fp16") { - if (builder->platformHasFastFp16()) { - autoware::tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; - config->setFlag(nvinfer1::BuilderFlag::kFP16); - } else { - autoware::tensorrt_common::LOG_INFO(logger_) - << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; - } - } - - const auto flag = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = autoware::tensorrt_common::TrtUniquePtr( - builder->createNetworkV2(flag)); - if (!network) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; - return false; - } - - auto parser = autoware::tensorrt_common::TrtUniquePtr( - nvonnxparser::createParser(*network, logger_)); - parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); - - if (!setProfile(*builder, *network, *config)) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; - return false; - } - - plan_ = autoware::tensorrt_common::TrtUniquePtr( - builder->buildSerializedNetwork(*network, *config)); - if (!plan_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create serialized network" << std::endl; - return false; - } - engine = autoware::tensorrt_common::TrtUniquePtr( - runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); - if (!engine) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; - return false; - } - - return saveEngine(engine_path); -} - -bool NetworkTRT::saveEngine(const std::string & engine_path) -{ - autoware::tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; - std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(plan_->data()), plan_->size()); - return validateNetworkIO(); -} - -bool NetworkTRT::loadEngine(const std::string & engine_path) -{ - std::ifstream engine_file(engine_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine = - autoware::tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - autoware::tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; - return validateNetworkIO(); -} - -bool NetworkTRT::validateNetworkIO() -{ - // Whether the number of IO match the expected size - if (engine->getNbIOTensors() != NetworkIO::ENUM_SIZE) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid network IO. Expected size: " << NetworkIO::ENUM_SIZE - << ". Actual size: " << engine->getNbIOTensors() << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - - // Initialize tensors_names_ with null values - tensors_names_.resize(NetworkIO::ENUM_SIZE, nullptr); - - // Loop over the tensor names and place them in the correct positions - for (int i = 0; i < NetworkIO::ENUM_SIZE; ++i) { - const char * name = engine->getIOTensorName(i); - tensors_names_[nameToNetworkIO(name)] = name; - } - - // Log the network IO - std::string tensors = std::accumulate( - tensors_names_.begin(), tensors_names_.end(), std::string(), - [](const std::string & a, const std::string & b) -> std::string { return a + b + " "; }); - autoware::tensorrt_common::LOG_INFO(logger_) << "Network IO: " << tensors << std::endl; - - // Whether the current engine input profile match the config input profile - for (int i = 0; i <= NetworkIO::coors; ++i) { - ProfileDimension engine_dims{ - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMIN), - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kOPT), - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMAX)}; - - autoware::tensorrt_common::LOG_INFO(logger_) - << "Profile for " << tensors_names_[i] << ": " << engine_dims << std::endl; - - if (engine_dims != in_profile_dims_[i]) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid network input dimension. Config: " << in_profile_dims_[i] - << ". Please change the input profile or delete the engine file and build engine again." - << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - } - - // Whether the IO tensor shapes match the network config, -1 for dynamic size - validateTensorShape( - NetworkIO::voxels, {-1, static_cast(config_.points_per_voxel_), - static_cast(config_.num_point_feature_size_)}); - validateTensorShape(NetworkIO::num_points, {-1}); - validateTensorShape(NetworkIO::coors, {-1, static_cast(config_.num_point_values_)}); - auto cls_score = validateTensorShape( - NetworkIO::cls_score, - {static_cast(config_.batch_size_), static_cast(config_.num_classes_), - static_cast(config_.num_proposals_)}); - autoware::tensorrt_common::LOG_INFO(logger_) - << "Network num classes: " << cls_score.d[1] << std::endl; - validateTensorShape( - NetworkIO::dir_pred, - {static_cast(config_.batch_size_), 2, static_cast(config_.num_proposals_)}); // x, y - validateTensorShape( - NetworkIO::bbox_pred, - {static_cast(config_.batch_size_), static_cast(config_.num_box_values_), - static_cast(config_.num_proposals_)}); - - return true; -} - -const char * NetworkTRT::getTensorName(NetworkIO name) -{ - return tensors_names_.at(name); -} - -nvinfer1::Dims NetworkTRT::validateTensorShape(NetworkIO name, const std::vector shape) -{ - auto tensor_shape = engine->getTensorShape(tensors_names_[name]); - if (tensor_shape.nbDims != static_cast(shape.size())) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid tensor shape for " << tensors_names_[name] << ". Expected size: " << shape.size() - << ". Actual size: " << tensor_shape.nbDims << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - for (int i = 0; i < tensor_shape.nbDims; ++i) { - if (tensor_shape.d[i] != static_cast(shape[i])) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid tensor shape for " << tensors_names_[name] << ". Expected: " << shape[i] - << ". Actual: " << tensor_shape.d[i] << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - } - return tensor_shape; -} - -} // namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp index 4e100f2e794d5..dd075a45cb29c 100644 --- a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp @@ -17,6 +17,7 @@ #include "autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp" #include "autoware/lidar_transfusion/transfusion_config.hpp" +#include #include #include @@ -27,25 +28,23 @@ #include #include #include +#include #include namespace autoware::lidar_transfusion { TransfusionTRT::TransfusionTRT( - const NetworkParam & network_param, const DensificationParam & densification_param, - const TransfusionConfig & config) -: config_(config) + const tensorrt_common::TrtCommonConfig & trt_config, + const DensificationParam & densification_param, TransfusionConfig config) +: config_(std::move(config)) { - network_trt_ptr_ = std::make_unique(config_); - - network_trt_ptr_->init( - network_param.onnx_path(), network_param.engine_path(), network_param.trt_precision()); vg_ptr_ = std::make_unique(densification_param, config_, stream_); stop_watch_ptr_ = std::make_unique>(); stop_watch_ptr_->tic("processing/inner"); initPtr(); + initTrt(trt_config); CHECK_CUDA_ERROR(cudaStreamCreate(&stream_)); } @@ -99,6 +98,51 @@ void TransfusionTRT::initPtr() post_ptr_ = std::make_unique(config_, stream_); } +void TransfusionTRT::initTrt(const tensorrt_common::TrtCommonConfig & trt_config) +{ + std::vector network_io{ + autoware::tensorrt_common::NetworkIO( + "voxels", {3, {-1, config_.points_per_voxel_, config_.num_point_feature_size_}}), + autoware::tensorrt_common::NetworkIO("num_points", {1, {-1}}), + autoware::tensorrt_common::NetworkIO("coors", {2, {-1, config_.num_point_values_}}), + autoware::tensorrt_common::NetworkIO( + "cls_score0", {3, {config_.batch_size_, config_.num_classes_, config_.num_proposals_}}), + autoware::tensorrt_common::NetworkIO( + "bbox_pred0", {3, {config_.batch_size_, config_.num_box_values_, config_.num_proposals_}}), + autoware::tensorrt_common::NetworkIO( + "dir_cls_pred0", {3, {config_.batch_size_, 2, config_.num_proposals_}})}; + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + "voxels", + {3, + {config_.min_voxel_size_, config_.min_point_in_voxel_size_, + config_.min_network_feature_size_}}, + {3, + {config_.opt_voxel_size_, config_.opt_point_in_voxel_size_, + config_.opt_network_feature_size_}}, + {3, + {config_.max_voxel_size_, config_.max_point_in_voxel_size_, + config_.max_network_feature_size_}}), + autoware::tensorrt_common::ProfileDims( + "num_points", {1, {static_cast(config_.min_points_size_)}}, + {1, {static_cast(config_.opt_points_size_)}}, + {1, {static_cast(config_.max_points_size_)}}), + autoware::tensorrt_common::ProfileDims( + "coors", {2, {config_.min_coors_size_, config_.min_coors_dim_size_}}, + {2, {config_.opt_coors_size_, config_.opt_coors_dim_size_}}, + {2, {config_.max_coors_size_, config_.max_coors_dim_size_}})}; + + auto network_io_ptr = + std::make_unique>(network_io); + auto profile_dims_ptr = + std::make_unique>(profile_dims); + + network_trt_ptr_ = std::make_unique(trt_config); + if (!network_trt_ptr_->setup(std::move(profile_dims_ptr), std::move(network_io_ptr))) + throw std::runtime_error("Failed to setup TRT engine."); +} + bool TransfusionTRT::detect( const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer, std::vector & det_boxes3d, std::unordered_map & proc_timing) @@ -166,8 +210,9 @@ bool TransfusionTRT::preprocess( CHECK_CUDA_ERROR(cudaMemcpyAsync( ¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost, stream_)); CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + auto params_input_i32 = static_cast(params_input); - if (params_input < config_.min_voxel_size_) { + if (params_input_i32 < config_.min_voxel_size_) { RCLCPP_WARN_STREAM( rclcpp::get_logger("lidar_transfusion"), "Too few voxels (" << params_input << ") for actual optimization profile (" @@ -185,39 +230,34 @@ bool TransfusionTRT::preprocess( params_input = config_.max_voxels_; } + RCLCPP_DEBUG_STREAM( rclcpp::get_logger("lidar_transfusion"), "Generated input voxels: " << params_input); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::voxels), voxel_features_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::voxels), + bool success = true; + + // Inputs + success &= network_trt_ptr_->setTensor( + "voxels", voxel_features_d_.get(), nvinfer1::Dims3{ - static_cast(params_input), static_cast(config_.max_num_points_per_pillar_), + params_input_i32, config_.max_num_points_per_pillar_, static_cast(config_.num_point_feature_size_)}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::num_points), voxel_num_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::num_points), - nvinfer1::Dims{1, {static_cast(params_input)}}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::coors), voxel_idxs_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::coors), - nvinfer1::Dims2{ - static_cast(params_input), static_cast(config_.num_point_values_)}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::cls_score), cls_output_d_.get()); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::bbox_pred), box_output_d_.get()); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::dir_pred), dir_cls_output_d_.get()); - return true; + success &= network_trt_ptr_->setTensor( + "num_points", voxel_num_d_.get(), nvinfer1::Dims{1, {params_input_i32}}); + success &= network_trt_ptr_->setTensor( + "coors", voxel_idxs_d_.get(), nvinfer1::Dims2{params_input_i32, config_.num_point_values_}); + + // Outputs + success &= network_trt_ptr_->setTensor("cls_score0", cls_output_d_.get()); + success &= network_trt_ptr_->setTensor("bbox_pred0", box_output_d_.get()); + success &= network_trt_ptr_->setTensor("dir_cls_pred0", dir_cls_output_d_.get()); + + return success; } bool TransfusionTRT::inference() { - auto status = network_trt_ptr_->context->enqueueV3(stream_); + auto status = network_trt_ptr_->enqueueV3(stream_); CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); if (!status) { diff --git a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp index 8bb70a821621f..563abd97698e0 100644 --- a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp @@ -75,7 +75,6 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) const float score_threshold = static_cast(this->declare_parameter("score_threshold", descriptor)); - NetworkParam network_param(onnx_path, engine_path, trt_precision); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); TransfusionConfig config( @@ -91,7 +90,9 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) detection_class_remapper_.setParameters( allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); - detector_ptr_ = std::make_unique(network_param, densification_param, config); + auto trt_config = tensorrt_common::TrtCommonConfig(onnx_path, trt_precision, engine_path); + + detector_ptr_ = std::make_unique(trt_config, densification_param, config); cloud_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), @@ -155,7 +156,6 @@ void LidarTransfusionNode::cloudCallback(const sensor_msgs::msg::PointCloud2::Co objects_pub_->publish(output_msg); published_time_pub_->publish_if_subscribed(objects_pub_, output_msg.header.stamp); } - // add processing time for debug if (debug_publisher_ptr_ && stop_watch_ptr_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic", true); diff --git a/perception/autoware_shape_estimation/CMakeLists.txt b/perception/autoware_shape_estimation/CMakeLists.txt index d0eb2aa5535a8..d7313111e6ade 100644 --- a/perception/autoware_shape_estimation/CMakeLists.txt +++ b/perception/autoware_shape_estimation/CMakeLists.txt @@ -4,6 +4,9 @@ project(autoware_shape_estimation) find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(PCL REQUIRED COMPONENTS common) find_package(pcl_conversions REQUIRED) diff --git a/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp index d39dce65d224d..4328246ff395f 100644 --- a/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp +++ b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp @@ -48,11 +48,7 @@ class TrtShapeEstimator { public: TrtShapeEstimator( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, - const size_t max_workspace_size = (1 << 30), - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0)); + const std::string & model_path, const std::string & precision, const int batch_size); ~TrtShapeEstimator() = default; diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp index b4b1f18832da7..fa3c3cb09bad3 100644 --- a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp +++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp @@ -29,47 +29,41 @@ namespace autoware::shape_estimation { TrtShapeEstimator::TrtShapeEstimator( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size, - const autoware::tensorrt_common::BuildConfig build_config) + const std::string & model_path, const std::string & precision, const int batch_size) { trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); + tensorrt_common::TrtCommonConfig(model_path, precision)); + batch_size_ = batch_size; - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - std::cerr << "Failed to initialize TensorRT" << std::endl; - return; + if (!trt_common_->setup()) { + throw std::runtime_error("Failed to setup TensorRT"); } - const auto pc_input_dims = trt_common_->getBindingDimensions(0); + const auto pc_input_dims = trt_common_->getTensorShape(0); const auto pc_input_size = std::accumulate( pc_input_dims.d + 1, pc_input_dims.d + pc_input_dims.nbDims, 1, std::multiplies()); - input_pc_d_ = autoware::cuda_utils::make_unique(pc_input_size * batch_config[2]); - batch_size_ = batch_config[2]; - const auto one_hot_input_dims = trt_common_->getBindingDimensions(1); + input_pc_d_ = autoware::cuda_utils::make_unique(pc_input_size * batch_size_); + const auto one_hot_input_dims = trt_common_->getTensorShape(1); const auto one_hot_input_size = std::accumulate( one_hot_input_dims.d + 1, one_hot_input_dims.d + one_hot_input_dims.nbDims, 1, std::multiplies()); - input_one_hot_d_ = - autoware::cuda_utils::make_unique(one_hot_input_size * batch_config[2]); + input_one_hot_d_ = autoware::cuda_utils::make_unique(one_hot_input_size * batch_size_); - const auto stage1_center_out_dims = trt_common_->getBindingDimensions(2); + const auto stage1_center_out_dims = trt_common_->getTensorShape(2); out_s1center_elem_num_ = std::accumulate( stage1_center_out_dims.d + 1, stage1_center_out_dims.d + stage1_center_out_dims.nbDims, 1, std::multiplies()); - out_s1center_elem_num_ = out_s1center_elem_num_ * batch_config[2]; - out_s1center_elem_num_per_batch_ = static_cast(out_s1center_elem_num_ / batch_config[2]); + out_s1center_elem_num_ = out_s1center_elem_num_ * batch_size_; + out_s1center_elem_num_per_batch_ = static_cast(out_s1center_elem_num_ / batch_size_); out_s1center_prob_d_ = autoware::cuda_utils::make_unique(out_s1center_elem_num_); out_s1center_prob_h_ = autoware::cuda_utils::make_unique_host(out_s1center_elem_num_, cudaHostAllocPortable); - const auto pred_out_dims = trt_common_->getBindingDimensions(3); + const auto pred_out_dims = trt_common_->getTensorShape(3); out_pred_elem_num_ = std::accumulate( pred_out_dims.d + 1, pred_out_dims.d + pred_out_dims.nbDims, 1, std::multiplies()); - out_pred_elem_num_ = out_pred_elem_num_ * batch_config[2]; - out_pred_elem_num_per_batch_ = static_cast(out_pred_elem_num_ / batch_config[2]); + out_pred_elem_num_ = out_pred_elem_num_ * batch_size_; + out_pred_elem_num_per_batch_ = static_cast(out_pred_elem_num_ / batch_size_); out_pred_prob_d_ = autoware::cuda_utils::make_unique(out_pred_elem_num_); out_pred_prob_h_ = autoware::cuda_utils::make_unique_host(out_pred_elem_num_, cudaHostAllocPortable); @@ -83,10 +77,6 @@ TrtShapeEstimator::TrtShapeEstimator( bool TrtShapeEstimator::inference( const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output) { - if (!trt_common_->isInitialized()) { - return false; - } - bool result = false; for (size_t i = 0; i < input.feature_objects.size(); i += batch_size_) { @@ -111,13 +101,13 @@ bool TrtShapeEstimator::inference( void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) { - auto input_dims_pc = trt_common_->getBindingDimensions(0); + auto input_dims_pc = trt_common_->getTensorShape(0); int batch_size = static_cast(input.feature_objects.size()); const auto input_chan = static_cast(input_dims_pc.d[1]); const auto input_pc_size = static_cast(input_dims_pc.d[2]); - auto input_dims_one_hot = trt_common_->getBindingDimensions(1); + auto input_dims_one_hot = trt_common_->getTensorShape(1); const auto input_one_hot_size = static_cast(input_dims_one_hot.d[1]); int volume_pc = batch_size * input_chan * input_pc_size; @@ -229,7 +219,10 @@ bool TrtShapeEstimator::feed_forward_and_decode( int batch_size = static_cast(input.feature_objects.size()); std::vector buffers = { input_pc_d_.get(), input_one_hot_d_.get(), out_s1center_prob_d_.get(), out_pred_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( out_s1center_prob_h_.get(), out_s1center_prob_d_.get(), out_s1center_elem_num_ * sizeof(float), diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp index 67402f68d63ef..c5450dc14adb0 100644 --- a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp +++ b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp @@ -63,9 +63,8 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option min_points_ = declare_parameter("model_params.minimum_points"); std::string precision = declare_parameter("model_params.precision"); int batch_size = declare_parameter("model_params.batch_size"); - autoware::tensorrt_common::BatchConfig batch_config{batch_size, batch_size, batch_size}; tensorrt_shape_estimator_ = - std::make_unique(model_path, precision, batch_config); + std::make_unique(model_path, precision, batch_size); if (this->declare_parameter("model_params.build_only", false)) { RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); diff --git a/perception/autoware_tensorrt_classifier/CMakeLists.txt b/perception/autoware_tensorrt_classifier/CMakeLists.txt index 88747a1e9240c..59ce7b18afcc3 100644 --- a/perception/autoware_tensorrt_classifier/CMakeLists.txt +++ b/perception/autoware_tensorrt_classifier/CMakeLists.txt @@ -6,6 +6,9 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -O3 -Wno-write-strings -fopen find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(CUDA) find_package(CUDNN) find_package(TENSORRT) diff --git a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp index ee16343b956d1..4f7a5865c72ae 100644 --- a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp +++ b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -44,22 +45,18 @@ class TrtClassifier * @param[in] mode_path ONNX model_path * @param[in] precision precision for inference * @param[in] calibration_images path for calibration files (only require for quantization) - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine * @param[in] mean mean for preprocess * @param[in] std std for preprocess - * @param[in] buildConfig configuration including precision, calibration method, dla, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder + * @param[in] calib_config calibration configuration * @param[in] cuda whether use cuda gpu for preprocessing */ TrtClassifier( const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, const std::vector & mean = {123.675, 116.28, 103.53}, const std::vector & std = {58.395, 57.12, 57.375}, - const size_t max_workspace_size = (1 << 30), const std::string & calibration_images = "", - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0), + const std::string & calibration_images = "", + const tensorrt_common::CalibrationConfig & calibration_config = + tensorrt_common::CalibrationConfig("MinMax", false, false, 0.0), const bool cuda = false); /** * @brief Deconstruct TrtClassifier @@ -84,6 +81,12 @@ class TrtClassifier */ void initPreprocessBuffer(int width, int height); + /** + * @brief get batch size + * @return batch size + */ + [[nodiscard]] int getBatchSize() const; + private: /** * @brief run preprocess including resizing, letterbox, BGR2RGB, NHWC2NCHW and toFloat on CPU @@ -102,7 +105,7 @@ class TrtClassifier const std::vector & images, std::vector & results, std::vector & probabilities); - std::unique_ptr trt_common_; + std::unique_ptr trt_common_; std::vector input_h_; CudaUniquePtr input_d_; diff --git a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp index 4aa008e42c966..7666ae4f9d068 100644 --- a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp +++ b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp @@ -100,11 +100,9 @@ std::vector loadImageList(const std::string & filename, const std:: namespace autoware::tensorrt_classifier { TrtClassifier::TrtClassifier( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, const std::vector & mean, - const std::vector & std, const size_t max_workspace_size, - const std::string & calibration_image_list_path, - autoware::tensorrt_common::BuildConfig build_config, const bool cuda) + const std::string & model_path, const std::string & precision, const std::vector & mean, + const std::vector & std, const std::string & calibration_image_list_path, + const tensorrt_common::CalibrationConfig & calib_config, const bool cuda) { src_width_ = -1; src_height_ = -1; @@ -114,22 +112,36 @@ TrtClassifier::TrtClassifier( for (size_t i = 0; i < inv_std_.size(); i++) { inv_std_[i] = 1.0 / inv_std_[i]; } - batch_size_ = batch_config[2]; + trt_common_ = std::make_unique( + tensorrt_common::TrtCommonConfig(model_path, precision)); + + const auto network_input_dims = trt_common_->getTensorShape(0); + batch_size_ = network_input_dims.d[0]; + const auto input_channel = network_input_dims.d[1]; + const auto input_height = network_input_dims.d[2]; + const auto input_width = network_input_dims.d[3]; + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + 0, {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}})}; + auto profile_dims_ptr = + std::make_unique>(profile_dims); + if (precision == "int8") { - int max_batch_size = batch_config[2]; - nvinfer1::Dims input_dims = autoware::tensorrt_common::get_input_dims(model_path); std::vector calibration_images; if (calibration_image_list_path != "") { calibration_images = loadImageList(calibration_image_list_path, ""); } autoware::tensorrt_classifier::ImageStream stream( - max_batch_size, input_dims, calibration_images); + batch_size_, network_input_dims, calibration_images); fs::path calibration_table{model_path}; std::string ext = ""; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { ext = "EntropyV2-"; } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { ext = "Legacy-"; } else { ext = "MinMax-"; @@ -141,11 +153,11 @@ TrtClassifier::TrtClassifier( histogram_table.replace_extension(ext); std::unique_ptr calibrator; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { calibrator.reset(new autoware::tensorrt_classifier::Int8EntropyCalibrator( stream, calibration_table, mean_, std_)); } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { double quantile = 0.999999; double cutoff = 0.999999; calibrator.reset(new autoware::tensorrt_classifier::Int8LegacyCalibrator( @@ -154,29 +166,27 @@ TrtClassifier::TrtClassifier( calibrator.reset(new autoware::tensorrt_classifier::Int8MinMaxCalibrator( stream, calibration_table, mean_, std_)); } - trt_common_ = std::make_unique( - model_path, precision, std::move(calibrator), batch_config, max_workspace_size, build_config); + if (!trt_common_->setupWithCalibrator( + std::move(calibrator), calib_config, std::move((profile_dims_ptr)))) { + throw std::runtime_error("Failed to setup TensorRT engine with calibrator"); + } } else { - trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); - } - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - return; + if (!trt_common_->setup(std::move(profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TensorRT engine"); + } } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); - const auto output_dims = trt_common_->getBindingDimensions(1); - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); + const auto output_dims = trt_common_->getTensorShape(1); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); out_elem_num_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num_ = out_elem_num_ * batch_config[2]; - out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); + out_elem_num_ = out_elem_num_ * batch_size_; + out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_size_); out_prob_d_ = autoware::cuda_utils::make_unique(out_elem_num_); out_prob_h_ = autoware::cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); @@ -224,7 +234,7 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) src_width_ = width; src_height_ = height; if (m_cuda) { - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); bool const hasRuntimeDim = std::any_of( input_dims.d, input_dims.d + input_dims.nbDims, [](int32_t input_dim) { return input_dim == -1; }); @@ -232,7 +242,9 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) input_dims.d[0] = batch_size_; } if (!h_img_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } if (!h_img_) { CHECK_CUDA_ERROR(cudaMallocHost( @@ -245,10 +257,15 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) } } +int TrtClassifier::getBatchSize() const +{ + return batch_size_; +} + void TrtClassifier::preprocessGpu(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -272,7 +289,9 @@ void TrtClassifier::preprocessGpu(const std::vector & images) src_height_ = height; } if (!h_img_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -305,9 +324,11 @@ void TrtClassifier::preprocessGpu(const std::vector & images) void TrtClassifier::preprocess_opt(const std::vector & images) { int batch_size = static_cast(images.size()); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_chan = static_cast(input_dims.d[1]); const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -354,9 +375,6 @@ bool TrtClassifier::doInference( const std::vector & images, std::vector & results, std::vector & probabilities) { - if (!trt_common_->isInitialized()) { - return false; - } preprocess_opt(images); return feedforwardAndDecode(images, results, probabilities); @@ -369,7 +387,10 @@ bool TrtClassifier::feedforwardAndDecode( results.clear(); probabilities.clear(); std::vector buffers = {input_d_.get(), out_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); int batch_size = static_cast(images.size()); diff --git a/perception/autoware_tensorrt_common/CMakeLists.txt b/perception/autoware_tensorrt_common/CMakeLists.txt index 3105523a509e3..d7d8026866124 100644 --- a/perception/autoware_tensorrt_common/CMakeLists.txt +++ b/perception/autoware_tensorrt_common/CMakeLists.txt @@ -16,9 +16,14 @@ if(NOT (CUDAToolkit_FOUND AND CUDNN_FOUND AND TENSORRT_FOUND)) return() endif() +if(TENSORRT_VERSION VERSION_LESS 8.5) + message(WARNING "Unsupported version TensorRT ${TENSORRT_VERSION} detected. This package requires TensorRT 8.5 or later.") + return() +endif() + add_library(${PROJECT_NAME} SHARED src/tensorrt_common.cpp - src/simple_profiler.cpp + src/profiler.cpp ) target_link_libraries(${PROJECT_NAME} @@ -42,7 +47,7 @@ set_target_properties(${PROJECT_NAME} CXX_EXTENSIONS NO ) -# TODO(autoware_tensorrt_common): Remove -Wno-deprecated-declarations once upgrading to TensorRT 8.5 is complete +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic -Werror -Wno-deprecated-declarations ) diff --git a/perception/autoware_tensorrt_common/README.md b/perception/autoware_tensorrt_common/README.md index c828be58c1c1c..54bfccdfcb561 100644 --- a/perception/autoware_tensorrt_common/README.md +++ b/perception/autoware_tensorrt_common/README.md @@ -1,6 +1,70 @@ # autoware_tensorrt_common -## Purpose +This package provides a high-level API to work with TensorRT. This library simplifies the process of loading, building, and executing TensorRT inference engines using ONNX models. It also includes utilities for profiling and managing TensorRT execution contexts, making it easier to integrate TensorRT-based packages in Autoware. -This package contains a library of common functions related to TensorRT. -This package may include functions for handling TensorRT engine and calibration algorithm used for quantization +## Usage + +Here is an example usage of the library. For the full API documentation, please refer to the doxygen documentation (see header [file](include/autoware/tensorrt_common/tensorrt_common.hpp)). + +```c++ +#include + +#include +#include +#include + +using autoware::tensorrt_common::TrtCommon; +using autoware::tensorrt_common::TrtCommonConfig; +using autoware::tensorrt_common::TensorInfo; +using autoware::tensorrt_common::NetworkIO; +using autoware::tensorrt_common::ProfileDims; + +std::unique_ptr trt_common_; +``` + +### Create a tensorrt common instance and setup engine + +- With minimal configuration. + +```c++ +trt_common_ = std::make_unique(TrtCommonConfig("/path/to/onnx/model.onnx")); +trt_common_->setup(); +``` + +- With full configuration. + +```c++ +trt_common_ = std::make_unique(TrtCommonConfig("/path/to/onnx/model.onnx", "fp16", "/path/to/engine/model.engine", (1ULL << 30U), -1, false)); + +std::vector network_io{ + NetworkIO("sample_input", {3, {-1, 64, 512}}), NetworkIO("sample_output", {1, {50}})}; +std::vector profile_dims{ + ProfileDims("sample_input", {3, {1, 64, 512}}, {3, {3, 64, 512}}, {3, {9, 64, 512}})}; + +auto network_io_ptr = std::make_unique>(network_io); +auto profile_dims_ptr = std::make_unique>(profile_dims); + +trt_common_->setup(std::move(profile_dims_ptr), std::move(network_io_ptr)); +``` + +By defining network IO names and dimensions, an extra shapes validation will be performed after building / loading engine. This is useful to ensure the model is compatible with current code for preprocessing as it might consists of operations dependent on tensor shapes. + +Profile dimension is used to specify the min, opt, and max dimensions for dynamic shapes. + +Network IO or / and profile dimensions can be omitted if not needed. + +### Setting input and output tensors + +```c++ +bool success = true; +success &= trt_common_->setTensor("sample_input", sample_input_d_.get(), nvinfer1::Dims{3, {var_size, 64, 512}}); +success &= trt_common_->setTensor("sample_output", sample_output_d_.get()); +return success; +``` + +### Execute inference + +```c++ +auto success = trt_common_->enqueueV3(stream_); +return success; +``` diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp new file mode 100644 index 0000000000000..0b58a797d8b9b --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp @@ -0,0 +1,108 @@ +// 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 AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ +#define AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ + +#include + +#include + +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +/** + * @struct ConvLayerInfo + * @brief Information of a layer. + */ +struct ConvLayerInfo +{ + //! @brief Input channel. + int in_c; + //! @brief Output channel. + int out_c; + //! @brief Width. + int w; + //! @brief Height. + int h; + //! @brief Kernel size. + int k; + //! @brief Stride. + int stride; + //! @brief Number of groups. + int groups; + //! @brief Layer type. + nvinfer1::LayerType type; +}; + +/** + * @class ConvProfiler + * @brief Collect per-layer profile information, assuming times are reported in the same order. + */ +class ConvProfiler : public tensorrt_common::Profiler +{ +public: + /** + * @brief Construct Profiler for convolutional layers. + * + * @param[in] src_profilers Source profilers to merge. + */ + explicit ConvProfiler( + const std::vector & src_profilers = std::vector()) + : Profiler(src_profilers) + { + } + + /** + * @brief Set per-layer profile information for model. + * + * @param[in] layer Layer to set profile information. + */ + void setProfDict(nvinfer1::ILayer * const layer) noexcept final + { + if (const auto type = layer->getType(); type == nvinfer1::LayerType::kCONVOLUTION) { + const auto name = layer->getName(); + auto conv = dynamic_cast(layer); + + nvinfer1::ITensor * in = layer->getInput(0); + nvinfer1::Dims in_dim = in->getDimensions(); + + nvinfer1::ITensor * out = layer->getOutput(0); + nvinfer1::Dims out_dim = out->getDimensions(); + + nvinfer1::Dims k_dims = conv->getKernelSizeNd(); + nvinfer1::Dims s_dims = conv->getStrideNd(); + + int32_t kernel = k_dims.d[0]; + int32_t stride = s_dims.d[0]; + int32_t groups = conv->getNbGroups(); + + layer_dict_.insert_or_assign( + name, ConvLayerInfo{ + in_dim.d[1], out_dim.d[1], in_dim.d[3], in_dim.d[2], kernel, stride, groups, type}); + } + } + +private: + //! @brief Per-layer information. + std::map layer_dict_; +}; +} // namespace tensorrt_common +} // namespace autoware +#endif // AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp index 5aa897983af72..b9b9048cd8204 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp @@ -17,18 +17,19 @@ #ifndef AUTOWARE__TENSORRT_COMMON__LOGGER_HPP_ #define AUTOWARE__TENSORRT_COMMON__LOGGER_HPP_ -#include "NvInferRuntimeCommon.h" +#include #include #include +#include #include #include -#include #include #include #include #include #include +#include namespace autoware { @@ -46,7 +47,7 @@ class LogStreamConsumerBuffer : public std::stringbuf LogStreamConsumerBuffer(LogStreamConsumerBuffer && other) : mOutput(other.mOutput) {} - ~LogStreamConsumerBuffer() + ~LogStreamConsumerBuffer() override { // std::streambuf::pbase() gives a pointer to the beginning of the buffered part of the output // sequence std::streambuf::pptr() gives a pointer to the current position of the output @@ -60,7 +61,7 @@ class LogStreamConsumerBuffer : public std::stringbuf // synchronizes the stream buffer and returns 0 on success // synchronizing the stream buffer consists of inserting the buffer contents into the stream, // resetting the buffer and flushing the stream - virtual int sync() + int sync() override { putOutput(); return 0; @@ -252,6 +253,37 @@ class Logger : public nvinfer1::ILogger // NOLINT } } + void log(Severity severity, const char * msg, ...) const noexcept + { + if (mVerbose) { + va_list args; + va_start(args, msg); + + // Buffer size + va_list args_copy; + va_copy(args_copy, args); + int required_size = std::vsnprintf(nullptr, 0, msg, args_copy); + va_end(args_copy); + + // Formatting error + if (required_size < 0) { + log(Severity::kINTERNAL_ERROR, "Error formatting log message"); + va_end(args); + return; + } + + // Format msg + std::vector buffer(required_size + 1); + std::vsnprintf(buffer.data(), buffer.size(), msg, args); + + va_end(args); // End variadic argument processing + + // Send the formatted message to LogStreamConsumer + LogStreamConsumer(mReportableSeverity, severity) + << "[TRT] " << std::string(buffer.data()) << std::endl; + } + } + /** * @brief Logging with throttle. * diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp new file mode 100644 index 0000000000000..d45351f97fd01 --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.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 AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ +#define AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ + +#include + +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ + +/** + * @class Profiler + * @brief Collect per-layer profile information, assuming times are reported in the same order. + */ +class Profiler : public nvinfer1::IProfiler +{ +public: + /** + * @struct Record + * @brief Record of layer profile information. + */ + struct Record + { + float time{0}; + int count{0}; + float min_time{-1.0}; + int index; + }; + + /** + * @brief Construct Profiler. + * + * @param[in] src_profilers Source profilers to merge. + */ + explicit Profiler(const std::vector & src_profilers = std::vector()); + + /** + * @brief Report layer time. + * + * @param[in] layerName Layer name. + * @param[in] ms Time in milliseconds. + */ + void reportLayerTime(const char * layerName, float ms) noexcept final; + + /** + * @brief Get printable representation of Profiler. + * + * @return String representation for current state of Profiler. + */ + [[nodiscard]] std::string toString() const; + + /** + * @brief Set per-layer profile information for model. + * + * @param[in] layer Layer to set profile information. + */ + virtual void setProfDict([[maybe_unused]] nvinfer1::ILayer * layer) noexcept {}; + + /** + * @brief Output Profiler to ostream. + * + * @param[out] out Output stream. + * @param[in] value Profiler to output. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & out, const Profiler & value); + +private: + //!< @brief Profile information for layers. + std::map profile_; + + //!< @brief Index for layer. + int index_; +}; +} // namespace tensorrt_common +} // namespace autoware +#endif // AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp deleted file mode 100644 index a8d504fb2861a..0000000000000 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp +++ /dev/null @@ -1,73 +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 AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ -#define AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ - -#include - -#include -#include -#include -#include - -namespace autoware -{ -namespace tensorrt_common -{ -struct LayerInfo -{ - int in_c; - int out_c; - int w; - int h; - int k; - int stride; - int groups; - nvinfer1::LayerType type; -}; - -/** - * @class Profiler - * @brief Collect per-layer profile information, assuming times are reported in the same order - */ -class SimpleProfiler : public nvinfer1::IProfiler -{ -public: - struct Record - { - float time{0}; - int count{0}; - float min_time{-1.0}; - int index; - }; - SimpleProfiler( - std::string name, - const std::vector & src_profilers = std::vector()); - - void reportLayerTime(const char * layerName, float ms) noexcept override; - - void setProfDict(nvinfer1::ILayer * layer) noexcept; - - friend std::ostream & operator<<(std::ostream & out, const SimpleProfiler & value); - -private: - std::string m_name; - std::map m_profile; - int m_index; - std::map m_layer_dict; -}; -} // namespace tensorrt_common -} // namespace autoware -#endif // AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp index 2b3b3f02f315f..9355732962e23 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp @@ -15,226 +15,367 @@ #ifndef AUTOWARE__TENSORRT_COMMON__TENSORRT_COMMON_HPP_ #define AUTOWARE__TENSORRT_COMMON__TENSORRT_COMMON_HPP_ -#ifndef YOLOX_STANDALONE -#include - -#include -#endif +#include "autoware/tensorrt_common/logger.hpp" +#include "autoware/tensorrt_common/profiler.hpp" +#include "autoware/tensorrt_common/utils.hpp" #include #include -#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) -#include -namespace fs = ::std::filesystem; -#else -#include -namespace fs = ::std::experimental::filesystem; -#endif - -#include -#include - #include -#include #include +#include +#include #include namespace autoware { namespace tensorrt_common { -/** - * @struct BuildConfig - * @brief Configuration to provide fine control regarding TensorRT builder - */ -struct BuildConfig -{ - // type for calibration - std::string calib_type_str; - - // DLA core ID that the process uses - int dla_core_id; - - // flag for partial quantization in first layer - bool quantize_first_layer; // For partial quantization - - // flag for partial quantization in last layer - bool quantize_last_layer; // For partial quantization - - // flag for per-layer profiler using IProfiler - bool profile_per_layer; - - // clip value for implicit quantization - double clip_value; // For implicit quantization - - // Supported calibration type - const std::array valid_calib_type = {"Entropy", "Legacy", "Percentile", "MinMax"}; - - BuildConfig() - : calib_type_str("MinMax"), - dla_core_id(-1), - quantize_first_layer(false), - quantize_last_layer(false), - profile_per_layer(false), - clip_value(0.0) - { - } - - explicit BuildConfig( - const std::string & calib_type_str, const int dla_core_id = -1, - const bool quantize_first_layer = false, const bool quantize_last_layer = false, - const bool profile_per_layer = false, const double clip_value = 0.0) - : calib_type_str(calib_type_str), - dla_core_id(dla_core_id), - quantize_first_layer(quantize_first_layer), - quantize_last_layer(quantize_last_layer), - profile_per_layer(profile_per_layer), - clip_value(clip_value) - { -#ifndef YOLOX_STANDALONE - if ( - std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) == - valid_calib_type.end()) { - std::stringstream message; - message << "Invalid calibration type was specified: " << calib_type_str << std::endl - << "Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]" << std::endl - << "Default calibration type will be used: MinMax" << std::endl; - std::cerr << message.str(); - } -#endif - } -}; - -nvinfer1::Dims get_input_dims(const std::string & onnx_file_path); - -const std::array valid_precisions = {"fp32", "fp16", "int8"}; -bool is_valid_precision_string(const std::string & precision); - template struct InferDeleter // NOLINT { - void operator()(T * obj) const - { - if (obj) { -#if TENSORRT_VERSION_MAJOR >= 8 - delete obj; -#else - obj->destroy(); -#endif - } - } + void operator()(T * obj) const { delete obj; } }; template using TrtUniquePtr = std::unique_ptr>; -using BatchConfig = std::array; +using NetworkIOPtr = std::unique_ptr>; +using ProfileDimsPtr = std::unique_ptr>; +using TensorsVec = std::vector>; +using TensorsMap = std::unordered_map>; /** * @class TrtCommon - * @brief TensorRT common library + * @brief TensorRT common library. */ class TrtCommon // NOLINT { public: /** * @brief Construct TrtCommon. - * @param[in] mode_path ONNX model_path - * @param[in] precision precision for inference - * @param[in] calibrator pointer for any type of INT8 calibrator - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine - * @param[in] buildConfig configuration including precision, calibration method, dla, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder - * @param[in] plugin_paths path for custom plugin + * + * @param[in] trt_config Base configuration with ONNX model path as minimum required. + * parameter. + * @param[in] profiler Per-layer profiler. + * @param[in] plugin_paths Paths for TensorRT plugins. */ TrtCommon( - const std::string & model_path, const std::string & precision, - std::unique_ptr calibrator = nullptr, - const BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (16 << 20), - const BuildConfig & buildConfig = BuildConfig(), + const TrtCommonConfig & trt_config, + const std::shared_ptr & profiler = std::make_shared(), const std::vector & plugin_paths = {}); - /** * @brief Deconstruct TrtCommon */ ~TrtCommon(); /** - * @brief Load TensorRT engine - * @param[in] engine_file_path path for a engine file - * @return flag for whether loading are succeeded or failed + * @brief Setup for TensorRT execution including building and loading engine. + * + * @param[in] profile_dims Optimization profile of tensors for dynamic shapes. + * @param[in] network_io Network input/output tensors information. + * @return Whether setup is successful. + */ + [[nodiscard]] virtual bool setup( + ProfileDimsPtr profile_dims = nullptr, NetworkIOPtr network_io = nullptr); + + /** + * @brief Get TensorRT engine precision. + * + * @return string representation of TensorRT engine precision. + */ + [[nodiscard]] std::string getPrecision() const; + + /** + * @brief Get tensor name by index from TensorRT engine with fallback from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor name. + */ + [[nodiscard]] const char * getIOTensorName(const int32_t index) const; + + /** + * @brief Get number of IO tensors from TensorRT engine with fallback from TensorRT network. + * + * @return Number of IO tensors. + */ + [[nodiscard]] int32_t getNbIOTensors() const; + + /** + * @brief Get tensor shape by index from TensorRT engine with fallback from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getTensorShape(const int32_t index) const; + + /** + * @brief Get tensor shape by name from TensorRT engine. + * + * @param[in] tensor_name Tensor name. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getTensorShape(const char * tensor_name) const; + + /** + * @brief Get input tensor shape by index from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getInputDims(const int32_t index) const; + + /** + * @brief Get output tensor shape by index from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getOutputDims(const int32_t index) const; + + /** + * @brief Set tensor address by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] data Tensor pointer. + * @return Whether setting tensor address is successful. + */ + bool setTensorAddress(const int32_t index, void * data); + + /** + * @brief Set tensor address by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] data Tensor pointer. + * @return Whether setting tensor address is successful. + */ + bool setTensorAddress(const char * tensor_name, void * data); + + /** + * @brief Set tensors addresses by indices via TensorRT context. + * + * @param[in] tensors Tensors pointers. + * @return Whether setting tensors addresses is successful. + */ + bool setTensorsAddresses(std::vector & tensors); + + /** + * @brief Set tensors addresses by names via TensorRT context. + * + * @param[in] tensors Tensors pointers. + * @return Whether setting tensors addresses is successful. + */ + bool setTensorsAddresses(std::unordered_map & tensors); + + /** + * @brief Set input shape by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting input shape is successful. + */ + bool setInputShape(const int32_t index, const nvinfer1::Dims & dimensions); + + /** + * @brief Set input shape by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting input shape is successful. + */ + bool setInputShape(const char * tensor_name, const nvinfer1::Dims & dimensions); + + /** + * @brief Set inputs shapes by indices via TensorRT context. + * + * @param[in] dimensions Vector of tensor dimensions with corresponding indices. + * @return Whether setting input shapes is successful. + */ + bool setInputsShapes(const std::vector & dimensions); + + /** + * @brief Set inputs shapes by names via TensorRT context. + * + * @param[in] dimensions Map of tensor dimensions with corresponding names as keys. + * @return Whether setting input shapes is successful. + */ + bool setInputsShapes(const std::unordered_map & dimensions); + + /** + * @brief Set tensor (address and shape) by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] data Tensor pointer. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting tensor is successful. + */ + bool setTensor(const int32_t index, void * data, nvinfer1::Dims dimensions = {}); + + /** + * @brief Set tensor (address and shape) by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] data Tensor pointer. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting tensor is successful. + */ + bool setTensor(const char * tensor_name, void * data, nvinfer1::Dims dimensions = {}); + + /** + * @brief Set tensors (addresses and shapes) by indices via TensorRT context. + * + * @param[in] tensors Vector of tensor pointers and dimensions with corresponding indices. + * @return Whether setting tensors is successful. */ - bool loadEngine(const std::string & engine_file_path); + bool setTensors(TensorsVec & tensors); /** - * @brief Output layer information including GFLOPs and parameters - * @param[in] onnx_file_path path for a onnx file - * @warning This function is based on darknet log. + * @brief Set tensors (addresses and shapes) by names via TensorRT context. + * + * @param[in] tensors Map of tensor pointers and dimensions with corresponding names as keys. + * @return Whether setting tensors is successful. */ - void printNetworkInfo(const std::string & onnx_file_path); + bool setTensors(TensorsMap & tensors); /** - * @brief build TensorRT engine from ONNX - * @param[in] onnx_file_path path for a onnx file - * @param[in] output_engine_file_path path for a engine file + * @brief Get per-layer profiler for model. + * + * @return Per-layer profiler. */ - bool buildEngineFromOnnx( - const std::string & onnx_file_path, const std::string & output_engine_file_path); + [[nodiscard]] std::shared_ptr getModelProfiler(); /** - * @brief setup for TensorRT execution including building and loading engine + * @brief Get per-layer profiler for host. + * + * @return Per-layer profiler. */ - void setup(); + [[nodiscard]] std::shared_ptr getHostProfiler(); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 - void setupBindings(std::vector & bindings); -#endif + /** + * @brief Get TensorRT common configuration. + * + * @return TensorRT common configuration. + */ + [[nodiscard]] std::shared_ptr getTrtCommonConfig(); - bool isInitialized(); + /** + * @brief Get TensorRT builder configuration. + * + * @return TensorRT builder configuration. + */ + [[nodiscard]] std::shared_ptr getBuilderConfig(); + + /** + * @brief Get TensorRT network definition. + * + * @return TensorRT network definition. + */ + [[nodiscard]] std::shared_ptr getNetwork(); - nvinfer1::Dims getBindingDimensions(const int32_t index) const; - int32_t getNbBindings(); - bool setBindingDimensions(const int32_t index, const nvinfer1::Dims & dimensions) const; -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 + /** + * @brief Get TensorRT logger. + * + * @return TensorRT logger. + */ + [[nodiscard]] std::shared_ptr getLogger(); + + /** + * @brief Execute inference via TensorRT context. + * + * @param[in] stream CUDA stream. + * @return Whether inference is successful. + */ bool enqueueV3(cudaStream_t stream); -#endif -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 - bool enqueueV2(void ** bindings, cudaStream_t stream, cudaEvent_t * input_consumed); -#endif /** - * @brief output per-layer information + * @brief Print per-layer information. + */ + void printProfiling() const; + +private: + /** + * @brief Initialize TensorRT common. + * + * @return Whether initialization is successful. */ - void printProfiling(void); + [[nodiscard]] bool initialize(); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 /** - * @brief get per-layer information for trt-engine-profiler + * @brief Get per-layer information for trt-engine-profiler. + * + * @param[in] format Format for layer information. + * @return Layer information. */ std::string getLayerInformation(nvinfer1::LayerInformationFormat format); -#endif -private: - Logger logger_; - fs::path model_file_path_; + /** + + * @brief Build TensorRT engine from ONNX. + * + * @return Whether building engine is successful. + */ + bool buildEngineFromOnnx(); + + /** + * @brief Load TensorRT engine. + * + * @return Whether loading engine is successful. + */ + bool loadEngine(); + + /** + * @brief Validate network input/output names and dimensions. + * + * @return Whether network input/output is valid. + */ + bool validateNetworkIO(); + + /** + * @brief Validate optimization profile. + * + * @return Whether optimization profile is valid. + */ + bool validateProfileDims(); + + //! @brief TensorRT runtime. TrtUniquePtr runtime_; + + //! @brief TensorRT engine. TrtUniquePtr engine_; + + //! @brief TensorRT execution context. TrtUniquePtr context_; - std::unique_ptr calibrator_; - std::string precision_; - BatchConfig batch_config_; - size_t max_workspace_size_; - bool is_initialized_{false}; + //! @brief TensorRT builder. + TrtUniquePtr builder_; + + //! @brief TensorRT engine parser. + TrtUniquePtr parser_; + + //! @brief TensorRT builder configuration. + std::shared_ptr builder_config_; + + //! @brief TensorRT network definition. + std::shared_ptr network_; + + //! @brief TrtCommon library base configuration. + std::shared_ptr trt_config_; + + //! @brief TensorRT logger. + std::shared_ptr logger_; + + //! @brief Per-layer profiler for host. + std::shared_ptr host_profiler_; + + //! @brief Per-layer profiler for model. + std::shared_ptr model_profiler_; - // profiler for per-layer - SimpleProfiler model_profiler_; - // profiler for whole model - SimpleProfiler host_profiler_; + //! @brief Model optimization profile. + ProfileDimsPtr profile_dims_; - std::unique_ptr build_config_; + //! @brief Model network input/output tensors information. + NetworkIOPtr network_io_; }; } // namespace tensorrt_common diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp new file mode 100644 index 0000000000000..44a944031086e --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp @@ -0,0 +1,241 @@ +// Copyright 2024 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__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ +#define AUTOWARE__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ + +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +template +bool contain(const std::string & s, const T & v) +{ + return s.find(v) != std::string::npos; +} + +using autoware::tensorrt_common::CalibrationConfig; +using autoware::tensorrt_common::NetworkIOPtr; +using autoware::tensorrt_common::ProfileDimsPtr; +using autoware::tensorrt_common::Profiler; +using autoware::tensorrt_common::TrtCommonConfig; + +/** + * @class TrtConvCalib + * @brief TensorRT common library with calibration. + */ +class TrtConvCalib : public tensorrt_common::TrtCommon +{ +public: + /** + * @brief Construct TrtCommonCalib. + * + * @param[in] trt_config base trt common configuration, ONNX model path is mandatory + * @param[in] profiler per-layer profiler + * @param[in] plugin_paths paths for TensorRT plugins + */ + explicit TrtConvCalib( + const TrtCommonConfig & trt_config, + const std::shared_ptr & profiler = std::make_shared(), + const std::vector & plugin_paths = {}) + : TrtCommon(trt_config, profiler, plugin_paths) + { + } + + /** + * @brief Setup for TensorRT execution including calibration, building and loading engine. + * + * @param[in] calibrator Pointer for any type of INT8 calibrator. + * @param[in] calib_config Calibration configuration. + * @param[in] profile_dims Optimization profile of input tensors for dynamic shapes. + * @param[in] network_io Network input/output tensors information. + * @return Whether setup is successful. + */ + [[nodiscard]] bool setupWithCalibrator( + std::unique_ptr calibrator, const CalibrationConfig & calib_config, + ProfileDimsPtr profile_dims = nullptr, NetworkIOPtr network_io = nullptr) + { + calibrator_ = std::move(calibrator); + calib_config_ = std::make_unique(calib_config); + + auto builder_config = getBuilderConfig(); + builder_config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + builder_config->setInt8Calibrator(calibrator_.get()); + + // Model specific quantization + auto logger = getLogger(); + auto quantization_log = quantization(); + logger->log(nvinfer1::ILogger::Severity::kINFO, quantization_log.c_str()); + + return setup(std::move(profile_dims), std::move(network_io)); + } + +private: + /** + * @brief Implicit quantization for TensorRT. + * + * @return Output log for TensorRT logger. + */ + std::string quantization() + { + auto network = getNetwork(); + auto trt_config = getTrtCommonConfig(); + auto model_profiler = getModelProfiler(); + + const int num = network->getNbLayers(); + bool first = calib_config_->quantize_first_layer; + bool last = calib_config_->quantize_last_layer; + std::stringstream ss; + + // Partial Quantization + if (getPrecision() == "int8") { + auto builder_config = getBuilderConfig(); + builder_config->setFlag(nvinfer1::BuilderFlag::kFP16); + network->getInput(0)->setDynamicRange(0, 255.0); + for (int i = 0; i < num; i++) { + nvinfer1::ILayer * layer = network->getLayer(i); + auto layer_type = layer->getType(); + std::string name = layer->getName(); + nvinfer1::ITensor * out = layer->getOutput(0); + if (calib_config_->clip_value > 0.0) { + ss << "Set max value for outputs: " << calib_config_->clip_value << " " << name + << std::endl; + out->setDynamicRange(0.0, calib_config_->clip_value); + } + + if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { + if (first) { + layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << name << std::endl; + first = false; + } + if (last) { + // cspell: ignore preds + if ( + contain(name, "reg_preds") || contain(name, "cls_preds") || + contain(name, "obj_preds")) { + layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << name << std::endl; + } + for (int j = num - 1; j >= 0; j--) { + nvinfer1::ILayer * inner_layer = network->getLayer(j); + auto inner_layer_type = inner_layer->getType(); + std::string inner_name = inner_layer->getName(); + if (inner_layer_type == nvinfer1::LayerType::kCONVOLUTION) { + inner_layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << inner_name << std::endl; + break; + } + if (inner_layer_type == nvinfer1::LayerType::kMATRIX_MULTIPLY) { + inner_layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << inner_name << std::endl; + break; + } + } + } + } + } + builder_config->setFlag(nvinfer1::BuilderFlag::kINT8); + } + + // Print layer information + float total_gflops = 0.0; + int total_params = 0; + + for (int i = 0; i < num; i++) { + nvinfer1::ILayer * layer = network->getLayer(i); + auto layer_type = layer->getType(); + if (trt_config->profile_per_layer) { + model_profiler->setProfDict(layer); + } + if (layer_type == nvinfer1::LayerType::kCONSTANT) { + continue; + } + nvinfer1::ITensor * in = layer->getInput(0); + nvinfer1::Dims dim_in = in->getDimensions(); + nvinfer1::ITensor * out = layer->getOutput(0); + nvinfer1::Dims dim_out = out->getDimensions(); + + if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { + auto conv = dynamic_cast(layer); + nvinfer1::Dims k_dims = conv->getKernelSizeNd(); + nvinfer1::Dims s_dims = conv->getStrideNd(); + int groups = conv->getNbGroups(); + int stride = s_dims.d[0]; + int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1]; + float gflops = (2.0 * num_weights) * (static_cast(dim_in.d[3]) / stride * + static_cast(dim_in.d[2]) / stride / 1e9); + total_gflops += gflops; + total_params += num_weights; + ss << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups << ") " + << ") " << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" + << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" << dim_out.d[1]; + ss << " weights:" << num_weights; + ss << " GFLOPs:" << gflops; + ss << std::endl; + } else if (layer_type == nvinfer1::LayerType::kPOOLING) { + auto pool = dynamic_cast(layer); + auto p_type = pool->getPoolingType(); + nvinfer1::Dims dim_stride = pool->getStrideNd(); + nvinfer1::Dims dim_window = pool->getWindowSizeNd(); + + ss << "L" << i << " ["; + if (p_type == nvinfer1::PoolingType::kMAX) { + ss << "max "; + } else if (p_type == nvinfer1::PoolingType::kAVERAGE) { + ss << "avg "; + } else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) { + ss << "max avg blend "; + } + float gflops = static_cast(dim_in.d[1]) * + (static_cast(dim_window.d[0]) / static_cast(dim_stride.d[0])) * + (static_cast(dim_window.d[1]) / static_cast(dim_stride.d[1])) * + static_cast(dim_in.d[2]) * static_cast(dim_in.d[3]) / 1e9; + total_gflops += gflops; + ss << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]"; + ss << " GFLOPs:" << gflops; + ss << std::endl; + } else if (layer_type == nvinfer1::LayerType::kRESIZE) { + ss << "L" << i << " [resize]" << std::endl; + } + } + ss << "Total " << total_gflops << " GFLOPs" << std::endl; + ss << "Total " << total_params / 1000.0 / 1000.0 << " M params" << std::endl; + + return ss.str(); + }; + +private: + //!< Calibration configuration + std::unique_ptr calib_config_; + + //!< Calibrator used for implicit quantization + std::unique_ptr calibrator_; +}; + +} // namespace tensorrt_common +} // namespace autoware + +#endif // AUTOWARE__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp new file mode 100644 index 0000000000000..be640f52147d9 --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp @@ -0,0 +1,408 @@ +// Copyright 2024 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__TENSORRT_COMMON__UTILS_HPP_ +#define AUTOWARE__TENSORRT_COMMON__UTILS_HPP_ + +#include +#include + +#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) +#include +namespace fs = ::std::filesystem; +#else +#include +namespace fs = ::std::experimental::filesystem; +#endif + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +constexpr std::array valid_precisions = {"fp32", "fp16", "int8"}; + +/** + * @struct TrtCommonConfig + * @brief Configuration to provide fine control regarding TensorRT builder + */ +struct TrtCommonConfig +{ + /** @brief Construct TrtCommonConfig, ONNX model path is mandatory. + * + * @param[in] onnx_path ONNX model path + * @param[in] precision precision for inference + * @param[in] engine_path TensorRT engine path + * @param[in] max_workspace_size maximum workspace size for TensorRT + * @param[in] dla_core_id DLA core ID + * @param[in] profile_per_layer flag for per-layer profiler using IProfiler + */ + explicit TrtCommonConfig( + const std::string onnx_path, const std::string precision = "fp16", + const std::string engine_path = "", const size_t max_workspace_size = (1ULL << 30U), + const int32_t dla_core_id = -1, const bool profile_per_layer = false) + : onnx_path(onnx_path), + precision(precision), + engine_path(engine_path), + max_workspace_size(max_workspace_size), + dla_core_id(dla_core_id), + profile_per_layer(profile_per_layer) + { + validatePrecision(); + + if (engine_path.empty()) { + this->engine_path = onnx_path; + this->engine_path.replace_extension(".engine"); + } + } + + /** + * @brief Validate configured TensorRT engine precision. + */ + void validatePrecision() const + { + if ( + std::find(valid_precisions.begin(), valid_precisions.end(), precision) == + valid_precisions.end()) { + std::stringstream message; + message << "Invalid precision was specified: " << precision << std::endl + << "Valid string is one of: [" << valid_precisions[0]; + for (size_t i = 1; i < valid_precisions.size(); ++i) { + message << ", " << valid_precisions[i]; + } + message << "] (case sensitive)" << std::endl; + + throw std::runtime_error(message.str()); + } + } + + //!< @brief ONNX model path. + const fs::path onnx_path; + + //!< @brief Precision for inference. + const std::string precision; + + //!< @brief TensorRT engine path. + fs::path engine_path; + + //!< @brief TensorRT max workspace size. + const size_t max_workspace_size; + + //!< @brief DLA core ID that the process uses. + const int32_t dla_core_id; + + //!< @brief Flag for per-layer profiler using IProfiler. + const bool profile_per_layer; +}; + +/** + * @brief Represents a tensor with its name or index. + */ +struct TensorInfo +{ + /** + * @brief Construct TensorInfo with tensor name. + * + * @param[in] name Tensor name. + */ + explicit TensorInfo(std::string name) : tensor_name(std::move(name)), tensor_index(-1) {} + + /** + * @brief Construct TensorInfo with tensor index. + * + * @param[in] index Tensor index. + */ + explicit TensorInfo(int32_t index) : tensor_index(index) {} + + /** + * @brief Check if dimensions are equal. + * + * @param lhs Left-hand side tensor dimensions. + * @param rhs Right-hand side tensor dimensions. + * @return Whether dimensions are equal. + */ + static bool dimsEqual(const nvinfer1::Dims & lhs, const nvinfer1::Dims & rhs) + { + if (lhs.nbDims != rhs.nbDims) return false; + return std::equal(lhs.d, lhs.d + lhs.nbDims, rhs.d); // NOLINT + } + + /** + * @brief Get printable representation of tensor dimensions. + * + * @param[in] dims Tensor dimensions. + * @return String representation of tensor dimensions. + */ + static std::string dimsRepr(const nvinfer1::Dims & dims) + { + if (dims.nbDims == 0) return "[]"; + std::string repr = "[" + std::to_string(dims.d[0]); + for (int i = 1; i < dims.nbDims; ++i) { + repr += ", " + std::to_string(dims.d[i]); + } + repr += "]"; + return repr; + } + + //!< @brief Tensor name. + std::string tensor_name; + + //!< @brief Tensor index. + int32_t tensor_index; +}; + +/** + * @brief Represents a network input/output tensor with its dimensions. + * + * Example usage: + * @code + * nvinfer1::Dims tensor_dims = {3, {1, 2, 3}}; + * NetworkIO input("input_tensor", tensor_dims); + * NetworkIO output("output_tensor", tensor_dims); + * bool is_equal = input == output; // false + * @endcode + */ +struct NetworkIO : public TensorInfo +{ + /** + * @brief Construct NetworkIO with tensor name and dimensions. + * + * @param[in] name Tensor name. + * @param[in] tensor_dims Tensor dimensions. + */ + NetworkIO(std::string name, const nvinfer1::Dims & tensor_dims) + : TensorInfo(std::move(name)), dims(tensor_dims) + { + } + + /** + * @brief Construct NetworkIO with tensor index and dimensions. + * + * @param[in] index Tensor index. + * @param[in] tensor_dims Tensor dimensions. + */ + NetworkIO(int32_t index, const nvinfer1::Dims & tensor_dims) + : TensorInfo(index), dims(tensor_dims) + { + } + + /** + * @brief Get printable representation of NetworkIO. + * + * @return String representation of NetworkIO. + */ + [[nodiscard]] std::string toString() const + { + std::stringstream ss; + ss << tensor_name << " {" << TensorInfo::dimsRepr(dims) << "}"; + return ss.str(); + } + + /** + * @brief Check if NetworkIO is equal to another NetworkIO. + * + * @param rhs Right-hand side NetworkIO. + * @return Whether NetworkIO is equal to another NetworkIO. + */ + bool operator==(const NetworkIO & rhs) const + { + if (tensor_name != rhs.tensor_name) return false; + return dimsEqual(dims, rhs.dims); + } + + /** + * @brief Check if NetworkIO is not equal to another NetworkIO. + * + * @param rhs Right-hand side NetworkIO. + * @return Whether NetworkIO is not equal to another NetworkIO. + */ + bool operator!=(const NetworkIO & rhs) const { return !(*this == rhs); } + + /** + * @brief Output NetworkIO to ostream. + * + * @param os Output stream. + * @param io NetworkIO. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & os, const NetworkIO & io) + { + os << io.toString(); + return os; + } + + //!< @brief Tensor dimensions. + nvinfer1::Dims dims; +}; + +/** + * @brief Represents a tensor optimization profile with minimum, optimal, and maximum dimensions. + * + * Example usage: + * @code + * nvinfer1::Dims min = {3, {1, 2, 3}}; + * nvinfer1::Dims opt = {3, {1, 3, 4}}; + * nvinfer1::Dims max = {3, {1, 4, 5}}; + * ProfileDims entry_1("tensor_name", min, opt, max); + * ProfileDims entry_2("tensor_name", {3, {1, 2, 3}}, {3, {1, 3, 4}}, {3, {1, 4, 5}}); + * bool is_equal = entry_1 == entry_2; // true + * @endcode + */ +struct ProfileDims : public TensorInfo +{ + /** + * @brief Construct ProfileDims with tensor name and dimensions. + * + * @param[in] name Tensor name. + * @param[in] min Minimum dimensions for optimization profile. + * @param[in] opt Optimal dimensions for optimization profile. + * @param[in] max Maximum dimensions for optimization profile. + */ + ProfileDims( + std::string name, const nvinfer1::Dims & min, const nvinfer1::Dims & opt, + const nvinfer1::Dims & max) + : TensorInfo(std::move(name)), min_dims(min), opt_dims(opt), max_dims(max) + { + } + + /** + * @brief Construct ProfileDims with tensor index and dimensions. + * + * @param[in] index Tensor index. + * @param[in] min Minimum dimensions for optimization profile. + * @param[in] opt Optimal dimensions for optimization profile. + * @param[in] max Maximum dimensions for optimization profile. + */ + ProfileDims( + int32_t index, const nvinfer1::Dims & min, const nvinfer1::Dims & opt, + const nvinfer1::Dims & max) + : TensorInfo(index), min_dims(min), opt_dims(opt), max_dims(max) + { + } + + /** + * @brief Get printable representation of ProfileDims. + * + * @return String representation of ProfileDims. + */ + [[nodiscard]] std::string toString() const + { + std::ostringstream oss; + oss << tensor_name << " {min " << TensorInfo::dimsRepr(min_dims) << ", opt " + << TensorInfo::dimsRepr(opt_dims) << ", max " << TensorInfo::dimsRepr(max_dims) << "}"; + return oss.str(); + } + + /** + * @brief Check if ProfileDims is equal to another ProfileDims. + * + * @param rhs Right-hand side ProfileDims. + * @return Whether ProfileDims is equal to another ProfileDims. + */ + bool operator==(const ProfileDims & rhs) const + { + if (tensor_name != rhs.tensor_name) return false; + return dimsEqual(min_dims, rhs.min_dims) && dimsEqual(opt_dims, rhs.opt_dims) && + dimsEqual(max_dims, rhs.max_dims); + } + + /** + * @brief Check if ProfileDims is not equal to another ProfileDims. + * + * @param rhs Right-hand side ProfileDims. + * @return Whether ProfileDims is not equal to another ProfileDims. + */ + bool operator!=(const ProfileDims & rhs) const { return !(*this == rhs); } + + /** + * @brief Output ProfileDims to ostream. + * + * @param os Output stream. + * @param profile ProfileDims. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & os, const ProfileDims & profile) + { + os << profile.toString(); + return os; + } + + //!< @brief Minimum dimensions for optimization profile. + nvinfer1::Dims min_dims; + + //!< @brief Optimal dimensions for optimization profile. + nvinfer1::Dims opt_dims; + + //!< @brief Maximum dimensions for optimization profile. + nvinfer1::Dims max_dims; +}; + +//!< @brief Valid calibration types for TensorRT. +constexpr std::array valid_calib_type = { + "Entropy", "Legacy", "Percentile", "MinMax"}; + +/** + * @brief Configuration for implicit calibration. + */ +struct CalibrationConfig +{ + /** + * @brief Construct CalibrationConfig with its parameters. + * + * @param[in] calib_type_str Calibration type. + * @param[in] quantize_first_layer Flag for partial quantization in first layer. + * @param[in] quantize_last_layer Flag for partial quantization in last layer. + * @param[in] clip_value Clip value for implicit quantization. + */ + explicit CalibrationConfig( + const std::string & calib_type_str = "MinMax", const bool quantize_first_layer = false, + const bool quantize_last_layer = false, const double clip_value = 0.0) + : calib_type_str(calib_type_str), + quantize_first_layer(quantize_first_layer), + quantize_last_layer(quantize_last_layer), + clip_value(clip_value) + { + if ( + std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) == + valid_calib_type.end()) { + throw std::runtime_error( + "Invalid calibration type was specified: " + std::string(calib_type_str) + + "\nValid value is one of: [Entropy, (Legacy | Percentile), MinMax]"); + } + } + + //!< @brief type of calibration + const std::string calib_type_str; + + //!< @brief flag for partial quantization in first layer + const bool quantize_first_layer; + + //!< @brief flag for partial quantization in last layer + const bool quantize_last_layer; + + //!< @brief clip value for implicit quantization + const double clip_value; +}; + +} // namespace tensorrt_common +} // namespace autoware + +#endif // AUTOWARE__TENSORRT_COMMON__UTILS_HPP_ diff --git a/perception/autoware_tensorrt_common/src/profiler.cpp b/perception/autoware_tensorrt_common/src/profiler.cpp new file mode 100644 index 0000000000000..433cca51f2b4f --- /dev/null +++ b/perception/autoware_tensorrt_common/src/profiler.cpp @@ -0,0 +1,113 @@ +// 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 +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ + +Profiler::Profiler(const std::vector & src_profilers) +{ + index_ = 0; + for (const auto & src_profiler : src_profilers) { + for (const auto & [name, record] : src_profiler.profile_) { + auto it = profile_.find(name); + if (it == profile_.end()) { + profile_.emplace(name, record); + } else { + it->second.time += record.time; + it->second.count += record.count; + } + } + } +} + +void Profiler::reportLayerTime(const char * layerName, float ms) noexcept +{ + if (profile_.find(layerName) == profile_.end()) { + return; + } + profile_[layerName].count++; + profile_[layerName].time += ms; + if (profile_[layerName].min_time == -1.0) { + profile_[layerName].min_time = ms; + profile_[layerName].index = index_; + index_++; + } else if (profile_[layerName].min_time > ms) { + profile_[layerName].min_time = ms; + } +} + +std::string Profiler::toString() const +{ + std::ostringstream out; + float total_time = 0.0; + std::string layer_name = "Operation"; + + int max_layer_name_length = static_cast(layer_name.size()); + for (const auto & elem : profile_) { + total_time += elem.second.time; + max_layer_name_length = std::max(max_layer_name_length, static_cast(elem.first.size())); + } + + auto old_settings = out.flags(); + auto old_precision = out.precision(); + // Output header + { + out << "index, " << std::setw(12); + out << std::setw(max_layer_name_length) << layer_name << " "; + out << std::setw(12) << "Runtime" << "%," << " "; + out << std::setw(12) << "Invocations" << " , "; + out << std::setw(12) << "Runtime[ms]" << " , "; + out << std::setw(12) << "Avg Runtime[ms]" << " ,"; + out << std::setw(12) << "Min Runtime[ms]" << std::endl; + } + int index = index_; + for (int i = 0; i < index; i++) { + for (const auto & elem : profile_) { + if (elem.second.index == i) { + out << i << ", "; + out << std::setw(max_layer_name_length) << elem.first << ","; + out << std::setw(12) << std::fixed << std::setprecision(1) + << (elem.second.time * 100.0F / total_time) << "%" << ","; + out << std::setw(12) << elem.second.count << ","; + out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.time << ", "; + out << std::setw(12) << std::fixed << std::setprecision(2) + << elem.second.time / elem.second.count << ", "; + out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.min_time + << std::endl; + } + } + } + out.flags(old_settings); + out.precision(old_precision); + out << "========== total runtime = " << total_time << " ms ==========" << std::endl; + + return out.str(); +} + +std::ostream & operator<<(std::ostream & out, const Profiler & value) +{ + out << value.toString(); + return out; +} +} // namespace tensorrt_common +} // namespace autoware diff --git a/perception/autoware_tensorrt_common/src/simple_profiler.cpp b/perception/autoware_tensorrt_common/src/simple_profiler.cpp deleted file mode 100644 index 2bcc1c4f9da06..0000000000000 --- a/perception/autoware_tensorrt_common/src/simple_profiler.cpp +++ /dev/null @@ -1,138 +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. - -#include - -#include -#include -#include -#include - -namespace autoware -{ -namespace tensorrt_common -{ - -SimpleProfiler::SimpleProfiler(std::string name, const std::vector & src_profilers) -: m_name(name) -{ - m_index = 0; - for (const auto & src_profiler : src_profilers) { - for (const auto & rec : src_profiler.m_profile) { - auto it = m_profile.find(rec.first); - if (it == m_profile.end()) { - m_profile.insert(rec); - } else { - it->second.time += rec.second.time; - it->second.count += rec.second.count; - } - } - } -} - -void SimpleProfiler::reportLayerTime(const char * layerName, float ms) noexcept -{ - m_profile[layerName].count++; - m_profile[layerName].time += ms; - if (m_profile[layerName].min_time == -1.0) { - m_profile[layerName].min_time = ms; - m_profile[layerName].index = m_index; - m_index++; - } else if (m_profile[layerName].min_time > ms) { - m_profile[layerName].min_time = ms; - } -} - -void SimpleProfiler::setProfDict(nvinfer1::ILayer * layer) noexcept -{ - std::string name = layer->getName(); - m_layer_dict[name]; - m_layer_dict[name].type = layer->getType(); - if (layer->getType() == nvinfer1::LayerType::kCONVOLUTION) { - nvinfer1::IConvolutionLayer * conv = (nvinfer1::IConvolutionLayer *)layer; - nvinfer1::ITensor * in = layer->getInput(0); - nvinfer1::Dims dim_in = in->getDimensions(); - nvinfer1::ITensor * out = layer->getOutput(0); - nvinfer1::Dims dim_out = out->getDimensions(); - nvinfer1::Dims k_dims = conv->getKernelSizeNd(); - nvinfer1::Dims s_dims = conv->getStrideNd(); - int groups = conv->getNbGroups(); - int stride = s_dims.d[0]; - int kernel = k_dims.d[0]; - m_layer_dict[name].in_c = dim_in.d[1]; - m_layer_dict[name].out_c = dim_out.d[1]; - m_layer_dict[name].w = dim_in.d[3]; - m_layer_dict[name].h = dim_in.d[2]; - m_layer_dict[name].k = kernel; - ; - m_layer_dict[name].stride = stride; - m_layer_dict[name].groups = groups; - } -} - -std::ostream & operator<<(std::ostream & out, const SimpleProfiler & value) -{ - out << "========== " << value.m_name << " profile ==========" << std::endl; - float totalTime = 0; - std::string layerNameStr = "Operation"; - - int maxLayerNameLength = static_cast(layerNameStr.size()); - for (const auto & elem : value.m_profile) { - totalTime += elem.second.time; - maxLayerNameLength = std::max(maxLayerNameLength, static_cast(elem.first.size())); - } - - auto old_settings = out.flags(); - auto old_precision = out.precision(); - // Output header - { - out << "index, " << std::setw(12); - out << std::setw(maxLayerNameLength) << layerNameStr << " "; - out << std::setw(12) << "Runtime" - << "%," - << " "; - out << std::setw(12) << "Invocations" - << " , "; - out << std::setw(12) << "Runtime[ms]" - << " , "; - out << std::setw(12) << "Avg Runtime[ms]" - << " ,"; - out << std::setw(12) << "Min Runtime[ms]" << std::endl; - } - int index = value.m_index; - for (int i = 0; i < index; i++) { - for (const auto & elem : value.m_profile) { - if (elem.second.index == i) { - out << i << ", "; - out << std::setw(maxLayerNameLength) << elem.first << ","; - out << std::setw(12) << std::fixed << std::setprecision(1) - << (elem.second.time * 100.0F / totalTime) << "%" - << ","; - out << std::setw(12) << elem.second.count << ","; - out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.time << ", "; - out << std::setw(12) << std::fixed << std::setprecision(2) - << elem.second.time / elem.second.count << ", "; - out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.min_time - << std::endl; - } - } - } - out.flags(old_settings); - out.precision(old_precision); - out << "========== " << value.m_name << " total runtime = " << totalTime - << " ms ==========" << std::endl; - return out; -} -} // namespace tensorrt_common -} // namespace autoware diff --git a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp index 990433ee277a0..ba422277416ab 100644 --- a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp +++ b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp @@ -12,102 +12,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "autoware/tensorrt_common/tensorrt_common.hpp" +#include "autoware/tensorrt_common/logger.hpp" +#include "autoware/tensorrt_common/utils.hpp" + +#include #include +#include #include +#include #include -#include #include #include #include +#include #include #include -namespace -{ -template -bool contain(const std::string & s, const T & v) -{ - return s.find(v) != std::string::npos; -} -} // anonymous namespace - namespace autoware { namespace tensorrt_common { -nvinfer1::Dims get_input_dims(const std::string & onnx_file_path) -{ - Logger logger_; - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); - } - - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - } - - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - } - - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Failed to parse onnx file"); - } - - const auto input = network->getInput(0); - return input->getDimensions(); -} - -bool is_valid_precision_string(const std::string & precision) -{ - if ( - std::find(valid_precisions.begin(), valid_precisions.end(), precision) == - valid_precisions.end()) { - std::stringstream message; - message << "Invalid precision was specified: " << precision << std::endl - << "Valid string is one of: ["; - for (const auto & s : valid_precisions) { - message << s << ", "; - } - message << "] (case sensitive)" << std::endl; - std::cerr << message.str(); - return false; - } else { - return true; - } -} TrtCommon::TrtCommon( - const std::string & model_path, const std::string & precision, - std::unique_ptr calibrator, const BatchConfig & batch_config, - const size_t max_workspace_size, const BuildConfig & build_config, + const TrtCommonConfig & trt_config, const std::shared_ptr & profiler, const std::vector & plugin_paths) -: model_file_path_(model_path), - calibrator_(std::move(calibrator)), - precision_(precision), - batch_config_(batch_config), - max_workspace_size_(max_workspace_size), - model_profiler_("Model"), - host_profiler_("Host") +: trt_config_(std::make_shared(trt_config)), + host_profiler_(profiler), + model_profiler_(profiler) { - // Check given precision is valid one - if (!is_valid_precision_string(precision)) { - return; - } - build_config_ = std::make_unique(build_config); - + logger_ = std::make_shared(); for (const auto & plugin_path : plugin_paths) { int32_t flags{RTLD_LAZY}; // cspell: ignore asan @@ -120,523 +56,595 @@ TrtCommon::TrtCommon( #endif // ENABLE_ASAN void * handle = dlopen(plugin_path.c_str(), flags); if (!handle) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Could not load plugin library"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Could not load plugin library"); + } else { + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Loaded plugin library: %s", plugin_path.c_str()); } } - runtime_ = TrtUniquePtr(nvinfer1::createInferRuntime(logger_)); - if (build_config_->dla_core_id != -1) { - runtime_->setDLACore(build_config_->dla_core_id); + runtime_ = TrtUniquePtr(nvinfer1::createInferRuntime(*logger_)); + if (trt_config_->dla_core_id != -1) { + runtime_->setDLACore(trt_config_->dla_core_id); } - initLibNvInferPlugins(&logger_, ""); -} + initLibNvInferPlugins(&*logger_, ""); -TrtCommon::~TrtCommon() -{ + if (!initialize()) { + throw std::runtime_error("Failed to initialize TensorRT"); + } } -void TrtCommon::setup() +TrtCommon::~TrtCommon() = default; + +bool TrtCommon::setup(ProfileDimsPtr profile_dims, NetworkIOPtr network_io) { - if (!fs::exists(model_file_path_)) { - is_initialized_ = false; - return; - } - // cppcheck-suppress unreadVariable - std::string engine_path = model_file_path_; - if (model_file_path_.extension() == ".engine") { - std::cout << "Load ... " << model_file_path_ << std::endl; - loadEngine(model_file_path_); - } else if (model_file_path_.extension() == ".onnx") { - fs::path cache_engine_path{model_file_path_}; - std::string ext; - std::string calib_name = ""; - if (precision_ == "int8") { - if (build_config_->calib_type_str == "Entropy") { - calib_name = "EntropyV2-"; - } else if ( - build_config_->calib_type_str == "Legacy" || - build_config_->calib_type_str == "Percentile") { - calib_name = "Legacy-"; - } else { - calib_name = "MinMax-"; + profile_dims_ = std::move(profile_dims); + network_io_ = std::move(network_io); + + // Set input profile + if (profile_dims_ && !profile_dims_->empty()) { + auto profile = builder_->createOptimizationProfile(); + for (auto & profile_dim : *profile_dims_) { + if (profile_dim.tensor_name.empty()) { + profile_dim.tensor_name = getIOTensorName(profile_dim.tensor_index); } + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Setting optimization profile for tensor: %s", + profile_dim.toString().c_str()); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kMIN, profile_dim.min_dims); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kOPT, profile_dim.opt_dims); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kMAX, profile_dim.max_dims); } - if (build_config_->dla_core_id != -1) { - ext = "DLA" + std::to_string(build_config_->dla_core_id) + "-" + calib_name + precision_; - if (build_config_->quantize_first_layer) { - ext += "-firstFP16"; - } - if (build_config_->quantize_last_layer) { - ext += "-lastFP16"; - } - ext += "-batch" + std::to_string(batch_config_[0]) + ".engine"; - } else { - ext = calib_name + precision_; - if (build_config_->quantize_first_layer) { - ext += "-firstFP16"; - } - if (build_config_->quantize_last_layer) { - ext += "-lastFP16"; - } - ext += "-batch" + std::to_string(batch_config_[0]) + ".engine"; + builder_config_->addOptimizationProfile(profile); + } + + auto build_engine_with_log = [this]() -> bool { + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Starting to build engine"); + auto log_thread = logger_->log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TensorRT CUDA engine. Please wait for a few minutes...", + 5); + auto success = buildEngineFromOnnx(); + logger_->stop_throttle(log_thread); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Engine build completed"); + return success; + }; + + // Load engine file if it exists + if (fs::exists(trt_config_->engine_path)) { + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Loading engine"); + if (!loadEngine()) { + return false; } - cache_engine_path.replace_extension(ext); - - // Output Network Information - printNetworkInfo(model_file_path_); - - if (fs::exists(cache_engine_path)) { - std::cout << "Loading... " << cache_engine_path << std::endl; - loadEngine(cache_engine_path); - } else { - std::cout << "Building... " << cache_engine_path << std::endl; - logger_.log(nvinfer1::ILogger::Severity::kINFO, "Start build engine"); - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5); - buildEngineFromOnnx(model_file_path_, cache_engine_path); - logger_.stop_throttle(log_thread); - logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine"); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Network validation"); + // Validate engine tensor shapes and optimization profile + if (!validateNetworkIO() || !validateProfileDims()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Network validation failed for loaded engine from file. Rebuilding engine"); + // Rebuild engine if the tensor shapes or optimization profile mismatch + if (!build_engine_with_log()) { + return false; + } } - // cppcheck-suppress unreadVariable - engine_path = cache_engine_path; } else { - is_initialized_ = false; - return; + // Build engine if engine has not been cached + if (!build_engine_with_log()) { + return false; + } } - context_ = TrtUniquePtr(engine_->createExecutionContext()); - if (!context_) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); - is_initialized_ = false; - return; + // Validate engine nevertheless is loaded or rebuilt + if (!validateNetworkIO() || !validateProfileDims()) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Final network validation failed. Possibly the input / output of the currently " + "deployed model has changed. Check your configuration file with the current model."); + return false; } - if (build_config_->profile_per_layer) { - context_->setProfiler(&model_profiler_); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Engine setup completed"); + return true; +} + +std::string TrtCommon::getPrecision() const +{ + return trt_config_->precision; +} + +const char * TrtCommon::getIOTensorName(const int32_t index) const +{ + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return nullptr; + } + auto num_inputs = network_->getNbInputs(); + auto num_outputs = network_->getNbOutputs(); + if (index < 0 || index >= num_inputs + num_outputs) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid index for I/O tensor: %d. Total I/O tensors: %d", index, num_inputs + num_outputs); + return nullptr; + } + if (index < num_inputs) { + return network_->getInput(index)->getName(); + } + return network_->getOutput(index - num_inputs)->getName(); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - // Write profiles for trt-engine-explorer - // See: https://github.com/NVIDIA/TensorRT/tree/main/tools/experimental/trt-engine-explorer - std::string j_ext = ".json"; - fs::path json_path{engine_path}; - json_path.replace_extension(j_ext); - std::string ret = getLayerInformation(nvinfer1::LayerInformationFormat::kJSON); - std::ofstream os(json_path, std::ofstream::trunc); - os << ret << std::flush; -#endif - is_initialized_ = true; + return engine_->getIOTensorName(index); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 -void TrtCommon::setupBindings(std::vector & bindings) +int32_t TrtCommon::getNbIOTensors() const { - for (int32_t i = 0, e = engine_->getNbIOTensors(); i < e; i++) { - auto const name = engine_->getIOTensorName(i); - context_->setTensorAddress(name, bindings.at(i)); + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return 0; + } + return network_->getNbInputs() + network_->getNbOutputs(); } + return engine_->getNbIOTensors(); } -#endif -bool TrtCommon::loadEngine(const std::string & engine_file_path) +nvinfer1::Dims TrtCommon::getTensorShape(const int32_t index) const { - std::ifstream engine_file(engine_file_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine_ = TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - return true; + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return nvinfer1::Dims{}; + } + auto num_inputs = network_->getNbInputs(); + auto num_outputs = network_->getNbOutputs(); + if (index < 0 || index >= num_inputs + num_outputs) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid index for I/O tensor: %d. Total I/O tensors: %d", index, num_inputs + num_outputs); + return nvinfer1::Dims{}; + } + if (index < num_inputs) { + return network_->getInput(index)->getDimensions(); + } + return network_->getOutput(index - num_inputs)->getDimensions(); + } + auto const & name = getIOTensorName(index); + return getTensorShape(name); } -void TrtCommon::printNetworkInfo(const std::string & onnx_file_path) +nvinfer1::Dims TrtCommon::getTensorShape(const char * tensor_name) const { - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); - return; + if (!engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Engine is not initialized"); + return nvinfer1::Dims{}; } + return engine_->getTensorShape(tensor_name); +} - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); +nvinfer1::Dims TrtCommon::getInputDims(const int32_t index) const +{ + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return {}; + } + const auto input = network_->getInput(index); + return input->getDimensions(); +} - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - return; +nvinfer1::Dims TrtCommon::getOutputDims(const int32_t index) const +{ + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return {}; } + const auto output = network_->getOutput(index); + return output->getDimensions(); +} + +bool TrtCommon::setTensorAddress(const int32_t index, void * data) +{ + auto const & name = getIOTensorName(index); + return setTensorAddress(name, data); +} - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - return; +bool TrtCommon::setTensorAddress(const char * tensor_name, void * data) +{ + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); + return false; + } + auto success = context_->setTensorAddress(tensor_name, data); + if (!success) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Failed to set tensor address for tensor: ", tensor_name); } + return success; +} - if (precision_ == "fp16" || precision_ == "int8") { - config->setFlag(nvinfer1::BuilderFlag::kFP16); +bool TrtCommon::setTensorsAddresses(std::vector & tensors) +{ + bool success = true; + for (std::size_t i = 0, e = tensors.size(); i < e; i++) { + auto const name = getIOTensorName(i); + success &= setTensorAddress(name, tensors.at(i)); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, max_workspace_size_); -#else - config->setMaxWorkspaceSize(max_workspace_size_); -#endif + return success; +} - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - return; - } - int num = network->getNbLayers(); - float total_gflops = 0.0; - int total_params = 0; - for (int i = 0; i < num; i++) { - nvinfer1::ILayer * layer = network->getLayer(i); - auto layer_type = layer->getType(); - if (build_config_->profile_per_layer) { - model_profiler_.setProfDict(layer); - } - if (layer_type == nvinfer1::LayerType::kCONSTANT) { - continue; - } - nvinfer1::ITensor * in = layer->getInput(0); - nvinfer1::Dims dim_in = in->getDimensions(); - nvinfer1::ITensor * out = layer->getOutput(0); - nvinfer1::Dims dim_out = out->getDimensions(); - - if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { - nvinfer1::IConvolutionLayer * conv = (nvinfer1::IConvolutionLayer *)layer; - nvinfer1::Dims k_dims = conv->getKernelSizeNd(); - nvinfer1::Dims s_dims = conv->getStrideNd(); - int groups = conv->getNbGroups(); - int stride = s_dims.d[0]; - int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1]; - float gflops = (2.0 * num_weights) * (static_cast(dim_in.d[3]) / stride * - static_cast(dim_in.d[2]) / stride / 1e9); - total_gflops += gflops; - total_params += num_weights; - std::cout << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups - << ") " - << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" - << dim_in.d[1] << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" - << dim_out.d[1]; - std::cout << " weights:" << num_weights; - std::cout << " GFLOPs:" << gflops; - std::cout << std::endl; - } else if (layer_type == nvinfer1::LayerType::kPOOLING) { - nvinfer1::IPoolingLayer * pool = (nvinfer1::IPoolingLayer *)layer; - auto p_type = pool->getPoolingType(); - nvinfer1::Dims dim_stride = pool->getStrideNd(); - nvinfer1::Dims dim_window = pool->getWindowSizeNd(); - - std::cout << "L" << i << " ["; - if (p_type == nvinfer1::PoolingType::kMAX) { - std::cout << "max "; - } else if (p_type == nvinfer1::PoolingType::kAVERAGE) { - std::cout << "avg "; - } else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) { - std::cout << "max avg blend "; - } - float gflops = static_cast(dim_in.d[1]) * - (static_cast(dim_window.d[0]) / static_cast(dim_stride.d[0])) * - (static_cast(dim_window.d[1]) / static_cast(dim_stride.d[1])) * - static_cast(dim_in.d[2]) * static_cast(dim_in.d[3]) / 1e9; - total_gflops += gflops; - std::cout << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]"; - std::cout << " GFLOPs:" << gflops; - std::cout << std::endl; - } else if (layer_type == nvinfer1::LayerType::kRESIZE) { - std::cout << "L" << i << " [resize]" << std::endl; - } +bool TrtCommon::setTensorsAddresses(std::unordered_map & tensors) +{ + bool success = true; + for (auto const & tensor : tensors) { + success &= setTensorAddress(tensor.first, tensor.second); } - std::cout << "Total " << total_gflops << " GFLOPs" << std::endl; - std::cout << "Total " << total_params / 1000.0 / 1000.0 << " M params" << std::endl; - return; + return success; +} + +bool TrtCommon::setInputShape(const int32_t index, const nvinfer1::Dims & dimensions) +{ + auto const & name = getIOTensorName(index); + return setInputShape(name, dimensions); } -bool TrtCommon::buildEngineFromOnnx( - const std::string & onnx_file_path, const std::string & output_engine_file_path) +bool TrtCommon::setInputShape(const char * tensor_name, const nvinfer1::Dims & dimensions) { - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); return false; } + auto success = context_->setInputShape(tensor_name, dimensions); + if (!success) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, "Failed to set input shape for tensor: ", tensor_name); + } + return success; +} - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); +bool TrtCommon::setInputsShapes(const std::vector & dimensions) +{ + bool success = true; + for (std::size_t i = 0, e = dimensions.size(); i < e; i++) { + success &= setInputShape(i, dimensions.at(i)); + } + return success; +} - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - return false; +bool TrtCommon::setInputsShapes(const std::unordered_map & dimensions) +{ + bool success = true; + for (auto const & dim : dimensions) { + success &= setInputShape(dim.first, dim.second); } + return success; +} - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - return false; +bool TrtCommon::setTensor(const int32_t index, void * data, nvinfer1::Dims dimensions) +{ + auto success = setTensorAddress(index, data); + if (dimensions.nbDims > 0) { + success &= setInputShape(index, dimensions); } + return success; +} - int num_available_dla = builder->getNbDLACores(); - if (build_config_->dla_core_id != -1) { - if (num_available_dla > 0) { - std::cout << "###" << num_available_dla << " DLAs are supported! ###" << std::endl; - } else { - std::cout << "###Warning : " - << "No DLA is supported! ###" << std::endl; - } - config->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); - config->setDLACore(build_config_->dla_core_id); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); -#else - config->setFlag(nvinfer1::BuilderFlag::kSTRICT_TYPES); -#endif - config->setFlag(nvinfer1::BuilderFlag::kGPU_FALLBACK); +bool TrtCommon::setTensor(const char * tensor_name, void * data, nvinfer1::Dims dimensions) +{ + auto success = setTensorAddress(tensor_name, data); + if (dimensions.nbDims > 0) { + success &= setInputShape(tensor_name, dimensions); } - if (precision_ == "fp16" || precision_ == "int8") { - config->setFlag(nvinfer1::BuilderFlag::kFP16); + return success; +} + +bool TrtCommon::setTensors(TensorsVec & tensors) +{ + bool success = true; + for (std::size_t i = 0, e = tensors.size(); i < e; i++) { + success &= setTensor(i, tensors.at(i).first, tensors.at(i).second); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, max_workspace_size_); -#else - config->setMaxWorkspaceSize(max_workspace_size_); -#endif + return success; +} - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - std::cout << "Failed to parse onnx file" << std::endl; - return false; +bool TrtCommon::setTensors(TensorsMap & tensors) +{ + bool success = true; + for (auto const & tensor : tensors) { + success &= setTensor(tensor.first, tensor.second.first, tensor.second.second); } + return success; +} - const int num = network->getNbLayers(); - bool first = build_config_->quantize_first_layer; - bool last = build_config_->quantize_last_layer; - // Partial Quantization - if (precision_ == "int8") { - network->getInput(0)->setDynamicRange(0, 255.0); - for (int i = 0; i < num; i++) { - nvinfer1::ILayer * layer = network->getLayer(i); - auto layer_type = layer->getType(); - std::string name = layer->getName(); - nvinfer1::ITensor * out = layer->getOutput(0); - if (build_config_->clip_value > 0.0) { - std::cout << "Set max value for outputs : " << build_config_->clip_value << " " << name - << std::endl; - out->setDynamicRange(0.0, build_config_->clip_value); - } +std::shared_ptr TrtCommon::getModelProfiler() +{ + return model_profiler_; +} - if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { - if (first) { - layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << name << std::endl; - first = false; - } - if (last) { - // cspell: ignore preds - if ( - contain(name, "reg_preds") || contain(name, "cls_preds") || - contain(name, "obj_preds")) { - layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << name << std::endl; - } - for (int j = num - 1; j >= 0; j--) { - nvinfer1::ILayer * inner_layer = network->getLayer(j); - auto inner_layer_type = inner_layer->getType(); - std::string inner_name = inner_layer->getName(); - if (inner_layer_type == nvinfer1::LayerType::kCONVOLUTION) { - inner_layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << inner_name << std::endl; - break; - } - if (inner_layer_type == nvinfer1::LayerType::kMATRIX_MULTIPLY) { - inner_layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << inner_name << std::endl; - break; - } - } - } - } - } +std::shared_ptr TrtCommon::getHostProfiler() +{ + return host_profiler_; +} + +std::shared_ptr TrtCommon::getTrtCommonConfig() +{ + return trt_config_; +} + +std::shared_ptr TrtCommon::getBuilderConfig() +{ + return builder_config_; +} + +std::shared_ptr TrtCommon::getNetwork() +{ + return network_; +} + +std::shared_ptr TrtCommon::getLogger() +{ + return logger_; +} + +bool TrtCommon::enqueueV3(cudaStream_t stream) +{ + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); + return false; + } + if (trt_config_->profile_per_layer) { + auto inference_start = std::chrono::high_resolution_clock::now(); + auto success = context_->enqueueV3(stream); + auto inference_end = std::chrono::high_resolution_clock::now(); + host_profiler_->reportLayerTime( + "inference_host", + std::chrono::duration(inference_end - inference_start).count()); + return success; } + return context_->enqueueV3(stream); +} - const auto input = network->getInput(0); - const auto input_dims = input->getDimensions(); - const auto input_channel = input_dims.d[1]; - const auto input_height = input_dims.d[2]; - const auto input_width = input_dims.d[3]; - const auto input_batch = input_dims.d[0]; +void TrtCommon::printProfiling() const +{ + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Host Profiling\n", host_profiler_->toString().c_str()); + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Model Profiling\n", model_profiler_->toString().c_str()); +} + +std::string TrtCommon::getLayerInformation(nvinfer1::LayerInformationFormat format) +{ + if (!context_ || !engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context or engine are not initialized"); + return {}; + } + auto inspector = std::unique_ptr(engine_->createEngineInspector()); + inspector->setExecutionContext(&(*context_)); + std::string result = inspector->getEngineInformation(format); + return result; +} - if (input_batch > 1) { - batch_config_[0] = input_batch; +bool TrtCommon::initialize() +{ + if (!fs::exists(trt_config_->onnx_path) || trt_config_->onnx_path.extension() != ".onnx") { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Invalid ONNX file path or extension"); + return false; } - if (batch_config_.at(0) > 1 && (batch_config_.at(0) == batch_config_.at(2))) { - // Attention : below API is deprecated in TRT8.4 - builder->setMaxBatchSize(batch_config_.at(2)); - } else { - if (build_config_->profile_per_layer) { - auto profile = builder->createOptimizationProfile(); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kMIN, - nvinfer1::Dims4{batch_config_.at(0), input_channel, input_height, input_width}); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kOPT, - nvinfer1::Dims4{batch_config_.at(1), input_channel, input_height, input_width}); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kMAX, - nvinfer1::Dims4{batch_config_.at(2), input_channel, input_height, input_width}); - config->addOptimizationProfile(profile); - } + builder_ = TrtUniquePtr(nvinfer1::createInferBuilder(*logger_)); + if (!builder_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); + return false; } - if (precision_ == "int8" && calibrator_) { - config->setFlag(nvinfer1::BuilderFlag::kINT8); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 + const auto explicit_batch = + 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); + network_ = TrtUniquePtr(builder_->createNetworkV2(explicit_batch)); #else - config->setFlag(nvinfer1::BuilderFlag::kSTRICT_TYPES); + network_ = TrtUniquePtr(builder_->createNetworkV2(0)); #endif - // QAT requires no calibrator. - // assert((calibrator != nullptr) && "Invalid calibrator for INT8 precision"); - config->setInt8Calibrator(calibrator_.get()); + + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); + return false; } - if (build_config_->profile_per_layer) { -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kDETAILED); -#else - config->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kVERBOSE); -#endif + + builder_config_ = TrtUniquePtr(builder_->createBuilderConfig()); + if (!builder_config_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); + return false; + } + + auto num_available_dla = builder_->getNbDLACores(); + if (trt_config_->dla_core_id != -1) { + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Number of DLAs supported: %d", num_available_dla); + builder_config_->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); + builder_config_->setDLACore(trt_config_->dla_core_id); + builder_config_->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + builder_config_->setFlag(nvinfer1::BuilderFlag::kGPU_FALLBACK); } + if (trt_config_->precision == "fp16") { + builder_config_->setFlag(nvinfer1::BuilderFlag::kFP16); + } else if (trt_config_->precision == "int8") { + builder_config_->setFlag(nvinfer1::BuilderFlag::kINT8); + } + builder_config_->setMemoryPoolLimit( + nvinfer1::MemoryPoolType::kWORKSPACE, trt_config_->max_workspace_size); + + parser_ = TrtUniquePtr(nvonnxparser::createParser(*network_, *logger_)); + if (!parser_->parseFromFile( + trt_config_->onnx_path.c_str(), + static_cast(nvinfer1::ILogger::Severity::kERROR))) { + return false; + } + + if (trt_config_->profile_per_layer) { + builder_config_->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kDETAILED); + } + + return true; +} -#if TENSORRT_VERSION_MAJOR >= 8 - auto plan = - TrtUniquePtr(builder->buildSerializedNetwork(*network, *config)); +bool TrtCommon::buildEngineFromOnnx() +{ + // Build engine + auto plan = TrtUniquePtr( + builder_->buildSerializedNetwork(*network_, *builder_config_)); if (!plan) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create host memory"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create host memory"); return false; } engine_ = TrtUniquePtr( runtime_->deserializeCudaEngine(plan->data(), plan->size())); -#else - engine_ = TrtUniquePtr(builder->buildEngineWithConfig(*network, *config)); -#endif if (!engine_) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); return false; } - // save engine -#if TENSORRT_VERSION_MAJOR < 8 - auto data = TrtUniquePtr(engine_->serialize()); -#endif + // Save engine std::ofstream file; - file.open(output_engine_file_path, std::ios::binary | std::ios::out); + file.open(trt_config_->engine_path, std::ios::binary | std::ios::out); if (!file.is_open()) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to open engine file"); return false; } -#if TENSORRT_VERSION_MAJOR < 8 - file.write(reinterpret_cast(data->data()), data->size()); -#else - file.write(reinterpret_cast(plan->data()), plan->size()); -#endif - + file.write(reinterpret_cast(plan->data()), plan->size()); // NOLINT file.close(); - return true; -} - -bool TrtCommon::isInitialized() -{ - return is_initialized_; -} - -nvinfer1::Dims TrtCommon::getBindingDimensions(const int32_t index) const -{ -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + (NV_TENSOR_PATCH * 10) >= 8500 - auto const & name = engine_->getIOTensorName(index); - auto dims = context_->getTensorShape(name); - bool const has_runtime_dim = - std::any_of(dims.d, dims.d + dims.nbDims, [](int32_t dim) { return dim == -1; }); + context_ = TrtUniquePtr(engine_->createExecutionContext()); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); + return false; + } - if (has_runtime_dim) { - return dims; - } else { - return context_->getBindingDimensions(index); + if (trt_config_->profile_per_layer) { + context_->setProfiler(&*model_profiler_); } -#else - return context_->getBindingDimensions(index); -#endif -} -int32_t TrtCommon::getNbBindings() -{ - return engine_->getNbBindings(); -} + fs::path json_path = trt_config_->engine_path.replace_extension(".json"); + auto ret = getLayerInformation(nvinfer1::LayerInformationFormat::kJSON); + std::ofstream os(json_path, std::ofstream::trunc); + os << ret << std::flush; + os.close(); -bool TrtCommon::setBindingDimensions(const int32_t index, const nvinfer1::Dims & dimensions) const -{ - return context_->setBindingDimensions(index, dimensions); + return true; } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 -bool TrtCommon::enqueueV3(cudaStream_t stream) +bool TrtCommon::loadEngine() { - if (build_config_->profile_per_layer) { - auto inference_start = std::chrono::high_resolution_clock::now(); - - bool ret = context_->enqueueV3(stream); + std::ifstream engine_file(trt_config_->engine_path); + std::stringstream engine_buffer; + engine_buffer << engine_file.rdbuf(); + std::string engine_str = engine_buffer.str(); - auto inference_end = std::chrono::high_resolution_clock::now(); - host_profiler_.reportLayerTime( - "inference", - std::chrono::duration(inference_end - inference_start).count()); - return ret; + engine_ = TrtUniquePtr(runtime_->deserializeCudaEngine( + reinterpret_cast( // NOLINT + engine_str.data()), + engine_str.size())); + if (!engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); + return false; } - return context_->enqueueV3(stream); -} -#endif -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 -bool TrtCommon::enqueueV2(void ** bindings, cudaStream_t stream, cudaEvent_t * input_consumed) -{ - if (build_config_->profile_per_layer) { - auto inference_start = std::chrono::high_resolution_clock::now(); - bool ret = context_->enqueueV2(bindings, stream, input_consumed); + context_ = TrtUniquePtr(engine_->createExecutionContext()); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); + return false; + } - auto inference_end = std::chrono::high_resolution_clock::now(); - host_profiler_.reportLayerTime( - "inference", - std::chrono::duration(inference_end - inference_start).count()); - return ret; - } else { - return context_->enqueueV2(bindings, stream, input_consumed); + if (trt_config_->profile_per_layer) { + context_->setProfiler(&*model_profiler_); } + + return true; } -#endif -void TrtCommon::printProfiling() +bool TrtCommon::validateProfileDims() { - std::cout << host_profiler_; - std::cout << std::endl; - std::cout << model_profiler_; + auto success = true; + if (!profile_dims_ || profile_dims_->empty()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Input profile is empty, skipping validation. If network has dynamic shapes, it might lead " + "to undefined behavior."); + return success; + } + if (engine_->getNbOptimizationProfiles() != 1) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Number of optimization profiles in the engine (%d) is not equal to 1. Selecting the first " + "cached profile.", + engine_->getNbOptimizationProfiles()); + } + + for (const auto & profile_dim : *profile_dims_) { + nvinfer1::Dims min_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kMIN); + nvinfer1::Dims opt_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kOPT); + nvinfer1::Dims max_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kMAX); + ProfileDims profile_from_engine{profile_dim.tensor_name, min_dims, opt_dims, max_dims}; + if (profile_dim != profile_from_engine) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Invalid profile. Current configuration: %s. Cached engine: %s", + profile_dim.toString().c_str(), profile_from_engine.toString().c_str()); + success = false; + } + } + return success; } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 -std::string TrtCommon::getLayerInformation(nvinfer1::LayerInformationFormat format) +bool TrtCommon::validateNetworkIO() { - auto runtime = std::unique_ptr(nvinfer1::createInferRuntime(logger_)); - auto inspector = std::unique_ptr(engine_->createEngineInspector()); - if (context_ != nullptr) { - inspector->setExecutionContext(&(*context_)); + auto success = true; + if (!network_io_ || network_io_->empty()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Network IO is empty, skipping validation. It might lead to undefined behavior"); + return success; + } + + if (network_io_->size() != static_cast(getNbIOTensors())) { + std::string tensor_names = "[" + std::string(getIOTensorName(0)); + for (int32_t i = 1; i < getNbIOTensors(); ++i) { + tensor_names += ", " + std::string(getIOTensorName(i)); + } + tensor_names += "]"; + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Number of tensors in the engine (%d) does not match number of tensors in the config (%d). " + "Tensors in the built engine: %s", + getNbIOTensors(), network_io_->size(), tensor_names.c_str()); + success = false; + } + for (const auto & io : *network_io_) { + NetworkIO tensor_from_engine{io.tensor_name, getTensorShape(io.tensor_name.c_str())}; + if (io != tensor_from_engine) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid tensor. Current configuration: %s. Cached engine: %s", io.toString().c_str(), + tensor_from_engine.toString().c_str()); + success = false; + } } - std::string result = inspector->getEngineInformation(format); - return result; + + return success; } -#endif } // namespace tensorrt_common } // namespace autoware diff --git a/perception/autoware_tensorrt_yolox/CMakeLists.txt b/perception/autoware_tensorrt_yolox/CMakeLists.txt index 17b31fc7e8df1..cc0d793151781 100644 --- a/perception/autoware_tensorrt_yolox/CMakeLists.txt +++ b/perception/autoware_tensorrt_yolox/CMakeLists.txt @@ -10,6 +10,9 @@ endif() find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(OpenCV REQUIRED) option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp index 483adfbdf2757..7d49df145b72e 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp @@ -18,6 +18,8 @@ #include #include #include +#include +#include #include #include @@ -44,6 +46,13 @@ struct Object using ObjectArray = std::vector; using ObjectArrays = std::vector; +using autoware::tensorrt_common::CalibrationConfig; +using autoware::tensorrt_common::NetworkIOPtr; +using autoware::tensorrt_common::ProfileDimsPtr; +using autoware::tensorrt_common::Profiler; +using autoware::tensorrt_common::TrtCommon; +using autoware::tensorrt_common::TrtCommonConfig; +using autoware::tensorrt_common::TrtConvCalib; struct GridAndStride { @@ -70,31 +79,26 @@ class TrtYoloX public: /** * @brief Construct TrtYoloX. - * @param[in] mode_path ONNX model_path - * @param[in] precision precision for inference + * @param[in] trt_config base trt common configuration * @param[in] num_class classifier-ed num * @param[in] score_threshold threshold for detection * @param[in] nms_threshold threshold for NMS - * @param[in] build_config configuration including precision, calibration method, DLA, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder * @param[in] use_gpu_preprocess whether use cuda gpu for preprocessing - * @param[in] calibration_image_list_file path for calibration files (only require for + * @param[in] gpu_id GPU id for inference + * @param[in] calibration_image_list_path path for calibration files (only require for * quantization) * @param[in] norm_factor scaling factor for preprocess * @param[in] cache_dir unused variable - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine + * @param[in] color_map_path path for colormap for masks + * @param[in] calib_config calibration configuration */ TrtYoloX( - const std::string & model_path, const std::string & precision, const int num_class = 8, - const float score_threshold = 0.3, const float nms_threshold = 0.7, - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig(), - const bool use_gpu_preprocess = false, const uint8_t gpu_id = 0, - std::string calibration_image_list_file = std::string(), const double norm_factor = 1.0, - [[maybe_unused]] const std::string & cache_dir = "", - const autoware::tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, - const size_t max_workspace_size = (1 << 30), const std::string & color_map_path = ""); + TrtCommonConfig & trt_config, const int num_class = 8, const float score_threshold = 0.3, + const float nms_threshold = 0.7, const bool use_gpu_preprocess = false, + const uint8_t gpu_id = 0, std::string calibration_image_list_path = std::string(), + const double norm_factor = 1.0, [[maybe_unused]] const std::string & cache_dir = "", + const std::string & color_map_path = "", + const CalibrationConfig & calib_config = CalibrationConfig()); /** * @brief Deconstruct TrtYoloX */ @@ -168,6 +172,12 @@ class TrtYoloX cv::Mat & colorized_mask); inline std::vector getColorMap() { return sematic_color_map_; } + /** + * @brief get batch size + * @return batch size + */ + [[nodiscard]] int getBatchSize() const; + private: /** * @brief run preprocess including resizing, letterbox, NHWC2NCHW and toFloat on CPU @@ -266,7 +276,7 @@ class TrtYoloX */ cv::Mat getMaskImageGpu(float * d_prob, nvinfer1::Dims dims, int out_w, int out_h, int b); - std::unique_ptr trt_common_; + std::unique_ptr trt_common_; std::vector input_h_; CudaUniquePtr input_d_; @@ -288,7 +298,7 @@ class TrtYoloX int num_class_; float score_threshold_; float nms_threshold_; - int batch_size_; + int32_t batch_size_; CudaUniquePtrHost out_prob_h_; // flag whether preprocess are performed on GPU diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp index 7e2e327bf6f5e..74d8d73ecaed4 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp @@ -155,13 +155,11 @@ std::vector get_seg_colormap(const std::stri namespace autoware::tensorrt_yolox { TrtYoloX::TrtYoloX( - const std::string & model_path, const std::string & precision, const int num_class, - const float score_threshold, const float nms_threshold, - autoware::tensorrt_common::BuildConfig build_config, const bool use_gpu_preprocess, - const uint8_t gpu_id, std::string calibration_image_list_path, const double norm_factor, - [[maybe_unused]] const std::string & cache_dir, - const autoware::tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size, - const std::string & color_map_path) + TrtCommonConfig & trt_config, const int num_class, const float score_threshold, + const float nms_threshold, const bool use_gpu_preprocess, const uint8_t gpu_id, + std::string calibration_image_list_path, const double norm_factor, + [[maybe_unused]] const std::string & cache_dir, const std::string & color_map_path, + const CalibrationConfig & calib_config) : gpu_id_(gpu_id), is_gpu_initialized_(false) { if (!setCudaDeviceId(gpu_id_)) { @@ -172,13 +170,29 @@ TrtYoloX::TrtYoloX( src_width_ = -1; src_height_ = -1; norm_factor_ = norm_factor; - batch_size_ = batch_config[2]; multitask_ = 0; sematic_color_map_ = get_seg_colormap(color_map_path); stream_ = makeCudaStream(); - if (precision == "int8") { - if (build_config.clip_value <= 0.0) { + trt_common_ = std::make_unique(trt_config); + + const auto network_input_dims = trt_common_->getTensorShape(0); + batch_size_ = network_input_dims.d[0]; + const auto input_channel = network_input_dims.d[1]; + const auto input_height = network_input_dims.d[2]; + const auto input_width = network_input_dims.d[3]; + + auto profile_dims_ptr = std::make_unique>(); + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + 0, {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}})}; + *profile_dims_ptr = profile_dims; + + if (trt_config.precision == "int8") { + if (calib_config.clip_value <= 0.0) { if (calibration_image_list_path.empty()) { throw std::runtime_error( "calibration_image_list_path should be passed to generate int8 engine " @@ -189,19 +203,17 @@ TrtYoloX::TrtYoloX( calibration_image_list_path = ""; } - int max_batch_size = batch_size_; - nvinfer1::Dims input_dims = autoware::tensorrt_common::get_input_dims(model_path); std::vector calibration_images; if (calibration_image_list_path != "") { calibration_images = loadImageList(calibration_image_list_path, ""); } - tensorrt_yolox::ImageStream stream(max_batch_size, input_dims, calibration_images); - fs::path calibration_table{model_path}; + tensorrt_yolox::ImageStream stream(batch_size_, network_input_dims, calibration_images); + fs::path calibration_table{trt_config.onnx_path}; std::string ext = ""; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { ext = "EntropyV2-"; } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { ext = "Legacy-"; } else { ext = "MinMax-"; @@ -209,17 +221,17 @@ TrtYoloX::TrtYoloX( ext += "calibration.table"; calibration_table.replace_extension(ext); - fs::path histogram_table{model_path}; + fs::path histogram_table{trt_config.onnx_path}; ext = "histogram.table"; histogram_table.replace_extension(ext); std::unique_ptr calibrator; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { calibrator.reset( new tensorrt_yolox::Int8EntropyCalibrator(stream, calibration_table, norm_factor_)); } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { const double quantile = 0.999999; const double cutoff = 0.999999; calibrator.reset(new tensorrt_yolox::Int8LegacyCalibrator( @@ -228,22 +240,20 @@ TrtYoloX::TrtYoloX( calibrator.reset( new tensorrt_yolox::Int8MinMaxCalibrator(stream, calibration_table, norm_factor_)); } - trt_common_ = std::make_unique( - model_path, precision, std::move(calibrator), batch_config, max_workspace_size, build_config); + if (!trt_common_->setupWithCalibrator( + std::move(calibrator), calib_config, std::move((profile_dims_ptr)))) { + throw std::runtime_error("Failed to setup TensorRT engine with calibrator"); + } } else { - trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); - } - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - return; + if (!trt_common_->setup(std::move(profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TensorRT engine"); + } } // Judge whether decoding output is required // Plain models require decoding, while models with EfficientNMS_TRT module don't. // If getNbBindings == 5, the model contains EfficientNMS_TRT - switch (trt_common_->getNbBindings()) { + switch (trt_common_->getNbIOTensors()) { case 2: // Specified model is plain one. // Bindings are: [input, output] @@ -273,16 +283,16 @@ TrtYoloX::TrtYoloX( */ } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); if (needs_output_decode_) { - const auto output_dims = trt_common_->getBindingDimensions(1); - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); + const auto output_dims = trt_common_->getTensorShape(1); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); out_elem_num_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num_ = out_elem_num_ * batch_config[2]; - out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); + out_elem_num_ = out_elem_num_ * batch_size_; + out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_size_); out_prob_d_ = autoware::cuda_utils::make_unique(out_elem_num_); out_prob_h_ = autoware::cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); @@ -298,29 +308,27 @@ TrtYoloX::TrtYoloX( output_strides_ = {8, 16, 32, 4}; } } else { - const auto out_scores_dims = trt_common_->getBindingDimensions(3); + const auto out_scores_dims = trt_common_->getTensorShape(3); max_detections_ = out_scores_dims.d[1]; - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); - out_num_detections_d_ = autoware::cuda_utils::make_unique(batch_config[2]); - out_boxes_d_ = - autoware::cuda_utils::make_unique(batch_config[2] * max_detections_ * 4); - out_scores_d_ = autoware::cuda_utils::make_unique(batch_config[2] * max_detections_); - out_classes_d_ = - autoware::cuda_utils::make_unique(batch_config[2] * max_detections_); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); + out_num_detections_d_ = autoware::cuda_utils::make_unique(batch_size_); + out_boxes_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_ * 4); + out_scores_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_); + out_classes_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_); } if (multitask_) { // Allocate buffer for segmentation segmentation_out_elem_num_ = 0; for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections size_t out_elem_num = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num = out_elem_num * batch_config[2]; + out_elem_num = out_elem_num * batch_size_; segmentation_out_elem_num_ += out_elem_num; } segmentation_out_elem_num_per_batch_ = - static_cast(segmentation_out_elem_num_ / batch_config[2]); + static_cast(segmentation_out_elem_num_ / batch_size_); segmentation_out_prob_d_ = autoware::cuda_utils::make_unique(segmentation_out_elem_num_); segmentation_out_prob_h_ = autoware::cuda_utils::make_unique_host( @@ -387,7 +395,7 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) src_width_ = width; src_height_ = height; if (use_gpu_preprocess_) { - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); bool const hasRuntimeDim = std::any_of( input_dims.d, input_dims.d + input_dims.nbDims, [](int32_t input_dim) { return input_dim == -1; }); @@ -395,7 +403,9 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) input_dims.d[0] = batch_size_; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } scales_.clear(); } const float input_height = static_cast(input_dims.d[2]); @@ -414,7 +424,7 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) size_t argmax_out_elem_num = 0; for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections const float scale = std::min( output_dims.d[3] / static_cast(width), output_dims.d[2] / static_cast(height)); @@ -441,7 +451,7 @@ void TrtYoloX::printProfiling(void) void TrtYoloX::preprocessGpu(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -469,7 +479,9 @@ void TrtYoloX::preprocessGpu(const std::vector & images) src_height_ = height; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } scales_.clear(); } const float input_height = static_cast(input_dims.d[2]); @@ -495,7 +507,7 @@ void TrtYoloX::preprocessGpu(const std::vector & images) if (multitask_) { for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0: input, 1: output for detections + trt_common_->getTensorShape(m + 2); // 0: input, 1: output for detections const float scale = std::min( output_dims.d[3] / static_cast(image.cols), output_dims.d[2] / static_cast(image.rows)); @@ -530,9 +542,11 @@ void TrtYoloX::preprocessGpu(const std::vector & images) void TrtYoloX::preprocess(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -567,9 +581,6 @@ bool TrtYoloX::doInference( if (!setCudaDeviceId(gpu_id_)) { return false; } - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { preprocessGpu(images); @@ -588,7 +599,7 @@ void TrtYoloX::preprocessWithRoiGpu( const std::vector & images, const std::vector & rois) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -610,7 +621,9 @@ void TrtYoloX::preprocessWithRoiGpu( src_height_ = height; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -662,9 +675,11 @@ void TrtYoloX::preprocessWithRoi( const std::vector & images, const std::vector & rois) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -700,7 +715,7 @@ void TrtYoloX::preprocessWithRoi( void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector & rois) { const auto batch_size = rois.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; @@ -722,7 +737,9 @@ void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector< src_height_ = height; if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -770,9 +787,11 @@ void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector< void TrtYoloX::multiScalePreprocess(const cv::Mat & image, const std::vector & rois) { const auto batch_size = rois.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -806,9 +825,6 @@ void TrtYoloX::multiScalePreprocess(const cv::Mat & image, const std::vector & images, ObjectArrays & objects, const std::vector & rois) { - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { preprocessWithRoiGpu(images, rois); } else { @@ -827,9 +843,6 @@ bool TrtYoloX::doInferenceWithRoi( bool TrtYoloX::doMultiScaleInference( const cv::Mat & image, ObjectArrays & objects, const std::vector & rois) { - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { multiScalePreprocessGpu(image, rois); } else { @@ -849,8 +862,10 @@ bool TrtYoloX::feedforward(const std::vector & images, ObjectArrays & o std::vector buffers = { input_d_.get(), out_num_detections_d_.get(), out_boxes_d_.get(), out_scores_d_.get(), out_classes_d_.get()}; - - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); const auto batch_size = images.size(); auto out_num_detections = std::make_unique(batch_size); @@ -903,7 +918,11 @@ bool TrtYoloX::feedforwardAndDecode( if (multitask_) { buffers = {input_d_.get(), out_prob_d_.get(), segmentation_out_prob_d_.get()}; } - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); const auto batch_size = images.size(); @@ -933,7 +952,7 @@ bool TrtYoloX::feedforwardAndDecode( static_cast(segmentation_out_elem_num_ / segmentation_out_elem_num_per_batch_); for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections size_t out_elem_num = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); out_elem_num = out_elem_num * batch; @@ -972,7 +991,10 @@ bool TrtYoloX::multiScaleFeedforward(const cv::Mat & image, int batch_size, Obje input_d_.get(), out_num_detections_d_.get(), out_boxes_d_.get(), out_scores_d_.get(), out_classes_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); auto out_num_detections = std::make_unique(batch_size); auto out_boxes = std::make_unique(4 * batch_size * max_detections_); @@ -1020,7 +1042,10 @@ bool TrtYoloX::multiScaleFeedforwardAndDecode( const cv::Mat & image, int batch_size, ObjectArrays & objects) { std::vector buffers = {input_d_.get(), out_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( out_prob_h_.get(), out_prob_d_.get(), sizeof(float) * out_elem_num_, cudaMemcpyDeviceToHost, @@ -1042,7 +1067,7 @@ void TrtYoloX::decodeOutputs( float * prob, ObjectArray & objects, float scale, cv::Size & img_size) const { ObjectArray proposals; - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector grid_strides; @@ -1298,4 +1323,9 @@ void TrtYoloX::getColorizedMask( } } +int TrtYoloX::getBatchSize() const +{ + return batch_size_; +} + } // namespace autoware::tensorrt_yolox diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp index 94a3a37a4d08f..2048279dcf3f1 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -83,19 +83,18 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) roi_overlay_segment_labels_.ANIMAL = declare_parameter("roi_overlay_segment_label.ANIMAL"); replaceLabelMap(); - autoware::tensorrt_common::BuildConfig build_config( - calibration_algorithm, dla_core_id, quantize_first_layer, quantize_last_layer, - profile_per_layer, clip_value); + TrtCommonConfig trt_config( + model_path, precision, "", (1ULL << 30U), dla_core_id, profile_per_layer); + + CalibrationConfig calib_config( + calibration_algorithm, quantize_first_layer, quantize_last_layer, clip_value); const double norm_factor = 1.0; const std::string cache_dir = ""; - const autoware::tensorrt_common::BatchConfig batch_config{1, 1, 1}; - const size_t max_workspace_size = (1 << 30); trt_yolox_ = std::make_unique( - model_path, precision, label_map_.size(), score_threshold, nms_threshold, build_config, - preprocess_on_gpu, gpu_id, calibration_image_list_path, norm_factor, cache_dir, batch_config, - max_workspace_size, color_map_path); + trt_config, label_map_.size(), score_threshold, nms_threshold, preprocess_on_gpu, gpu_id, + calibration_image_list_path, norm_factor, cache_dir, color_map_path, calib_config); if (!trt_yolox_->isGPUInitialized()) { RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); diff --git a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp index 243e82c65dab9..63c0ee0cd3e8a 100644 --- a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp @@ -46,7 +46,9 @@ class YoloXSingleImageInferenceNode : public rclcpp::Node const auto output_image_path = declare_parameter("output_image_path", p.string() + "_detect" + ext); - auto trt_yolox = std::make_unique(model_path, precision); + auto trt_config = tensorrt_common::TrtCommonConfig(model_path, precision); + + auto trt_yolox = std::make_unique(trt_config); auto image = cv::imread(image_path); tensorrt_yolox::ObjectArrays objects; std::vector masks; diff --git a/perception/autoware_traffic_light_classifier/CMakeLists.txt b/perception/autoware_traffic_light_classifier/CMakeLists.txt index d132577743ab0..181037caebfa5 100644 --- a/perception/autoware_traffic_light_classifier/CMakeLists.txt +++ b/perception/autoware_traffic_light_classifier/CMakeLists.txt @@ -34,7 +34,6 @@ if(NVINFER AND NVONNXPARSER AND NVINFER_PLUGIN) if(CUDA_VERBOSE) message(STATUS "TensorRT is available!") message(STATUS "NVINFER: ${NVINFER}") - message(STATUS "NVPARSERS: ${NVPARSERS}") message(STATUS "NVINFER_PLUGIN: ${NVINFER_PLUGIN}") message(STATUS "NVONNXPARSER: ${NVONNXPARSER}") endif() diff --git a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp index f9bf2509aa2ae..d47cb1500fffd 100644 --- a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp +++ b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp @@ -51,13 +51,10 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) } readLabelfile(label_file_path, labels_); - nvinfer1::Dims input_dim = autoware::tensorrt_common::get_input_dims(model_file_path); - assert(input_dim.d[0] > 0); - batch_size_ = input_dim.d[0]; - autoware::tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; classifier_ = std::make_unique( - model_file_path, precision, batch_config, mean_, std_); + model_file_path, precision, mean_, std_); + batch_size_ = classifier_->getBatchSize(); if (node_ptr_->declare_parameter("build_only", false)) { RCLCPP_INFO(node_ptr_->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); diff --git a/perception/autoware_traffic_light_fine_detector/CMakeLists.txt b/perception/autoware_traffic_light_fine_detector/CMakeLists.txt index 80d6e43c098ed..dffbab0e77681 100644 --- a/perception/autoware_traffic_light_fine_detector/CMakeLists.txt +++ b/perception/autoware_traffic_light_fine_detector/CMakeLists.txt @@ -39,7 +39,6 @@ if(NVINFER AND NVONNXPARSER AND NVINFER_PLUGIN) if(CUDA_VERBOSE) message(STATUS "TensorRT is available!") message(STATUS "NVINFER: ${NVINFER}") - message(STATUS "NVPARSERS: ${NVPARSERS}") message(STATUS "NVINFER_PLUGIN: ${NVINFER_PLUGIN}") message(STATUS "NVONNXPARSER: ${NVONNXPARSER}") endif() diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp index 37ffca4a9526c..d9e0471a43d62 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp @@ -75,21 +75,18 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt RCLCPP_ERROR(this->get_logger(), "Could not find tlr id"); } - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0); - const bool cuda_preprocess = true; const std::string calib_image_list = ""; const double scale = 1.0; const std::string cache_dir = ""; - nvinfer1::Dims input_dim = autoware::tensorrt_common::get_input_dims(model_path); - assert(input_dim.d[0] > 0); - batch_size_ = input_dim.d[0]; - const autoware::tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; + + auto trt_config = autoware::tensorrt_common::TrtCommonConfig(model_path, precision); trt_yolox_ = std::make_unique( - model_path, precision, num_class, score_thresh_, nms_threshold, build_config, cuda_preprocess, - gpu_id, calib_image_list, scale, cache_dir, batch_config); + trt_config, num_class, score_thresh_, nms_threshold, cuda_preprocess, gpu_id, calib_image_list, + scale, cache_dir); + + batch_size_ = trt_yolox_->getBatchSize(); if (!trt_yolox_->isGPUInitialized()) { RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); From 76aa83fcd1a716692789fdc50fed6369c154cb43 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Fri, 10 Jan 2025 17:35:41 +0900 Subject: [PATCH 15/59] fix(planning_evaluator): update lateral_trajectory_displacement to absolute value (#9696) * fix(planning_evaluator): update lateral_trajectory_displacement to absolute value Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/metrics/deviation_metrics.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index 82ba86c65d6af..9b5959948f8cb 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -58,7 +58,8 @@ Accumulator calcLocalLateralTrajectoryDisplacement( autoware::motion_utils::calcLateralOffset(prev.points, ego_pose.position); const auto traj_lateral_deviation = autoware::motion_utils::calcLateralOffset(traj.points, ego_pose.position); - const auto lateral_trajectory_displacement = traj_lateral_deviation - prev_lateral_deviation; + const auto lateral_trajectory_displacement = + std::abs(traj_lateral_deviation - prev_lateral_deviation); stat.add(lateral_trajectory_displacement); return stat; } From 7d63242e089ec25e0a976d4b6c3c8cda21def59a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 10 Jan 2025 18:02:48 +0900 Subject: [PATCH 16/59] docs(lane_change): explaining cancel and abort process (#9845) * docs(lane_change): explaining cancel and abort process Signed-off-by: Zulfaqar Azmi * slight fix in formatting Signed-off-by: Zulfaqar Azmi * rephrase sentence Signed-off-by: Zulfaqar Azmi * rephrase and replace image for cancel Signed-off-by: Zulfaqar Azmi * Cancel explanations and limitations Signed-off-by: Zulfaqar Azmi * revise abort figure Signed-off-by: Zulfaqar Azmi * revise flow chart Signed-off-by: Zulfaqar Azmi * rephase sentence Signed-off-by: Zulfaqar Azmi * minor fix Signed-off-by: Zulfaqar Azmi * finish up Signed-off-by: Zulfaqar Azmi * offers change to reduces for negative connotation Signed-off-by: Zulfaqar Azmi * minor fix Signed-off-by: Zulfaqar Azmi * move limitation all the way down Signed-off-by: Zulfaqar Azmi * precommit Signed-off-by: Zulfaqar Azmi * equation mistake Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * rename subheading Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../README.md | 277 ++++++++++++------ .../images/check_able_to_return.png | Bin 0 -> 26510 bytes .../images/lane_change-abort.png | Bin 222968 -> 22119 bytes .../images/lane_change-abort_computation.png | Bin 0 -> 19345 bytes .../images/lane_change-cancel.png | Bin 175745 -> 25706 bytes .../lane_change-cant_cancel_no_abort.png | Bin 138829 -> 16484 bytes 6 files changed, 193 insertions(+), 84 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort_computation.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 0508dc753a2e8..c5cdf0bb68bc2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -722,47 +722,129 @@ If the ego vehicle gets stuck, to avoid stuck, it enables lane change in crosswa If the ego vehicle stops more than `stuck_detection.stop_time` seconds, it is regarded as a stuck. If the ego vehicle velocity is smaller than `stuck_detection.velocity`, it is regarded as stopping. -### Aborting lane change +## Lane change completion checks + +To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. + +For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. -The abort process may result in three different outcome; Cancel, Abort and Stop/Cruise. +If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. -The following depicts the flow of the abort lane change check. +The process of determining lane change completion is shown in the following diagram. ```plantuml @startuml -skinparam monochrome true skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title Lane change completion judge + +start + +:Calculate distance from current ego pose to lane change end pose; + +if (Is ego velocity < 1.0?) then (YES) + :Set finish_judge_buffer to 0.0; +else (NO) + :Set finish_judge_buffer to lane_change_finish_judge_buffer; +endif + +if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) + if (Current ego pose is in target lanes' polygon?) then (YES) + :Lane change is completed; + stop + else (NO) +:Lane change is NOT completed; +stop + endif +else (NO) +endif + +if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) + :Lane change is NOT completed; + stop +else (NO) + :Calculate distance to the target lanes' centerline; + if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) + :Lane change is completed; + stop + else (NO) + :Lane change is NOT completed; + stop + endif +endif + +@enduml +``` + +## Terminal Lane Change Path + +Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: + +![no terminal path](./images/lane_change-no_terminal_path.png) + +![terminal path](./images/lane_change-terminal_path.png) + +Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. + +## Aborting a Previously Approved Lane Change + +Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met + +1. The ego vehicle is near a traffic light, crosswalk, or intersection, and it is possible to complete the lane change after the ego vehicle passes these areas. +2. The target object list is updated, requiring us to [delay lane change](#delay-lane-change-check) +3. The lane change is forcefully canceled via [RTC](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/cooperation/). +4. The path has become unsafe. + +Furthermore, if the path has become unsafe, there are three possible outcomes for the maneuver: + +1. **CANCEL**: The approved lane change path is canceled, and the ego vehicle resumes its previous maneuver. +2. **ABORT**: The lane change module generates a return path to bring the ego vehicle back to its current lane. +3. **CRUISE** or **STOP**: If aborting is not feasible, the ego vehicle continues with the lane change. [Another module](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_obstacle_cruise_planner/) should decide whether the ego vehicle should cruise or stop in this scenario. + +**CANCEL** can be enabled by setting the `cancel.enable_on_prepare_phase` flag to `true`, and **ABORT** can be enabled by setting the `cancel.enable_on_lane_changing_phase` flag to true. + +!!! warning + + Enabling **CANCEL** is a prerequisite for enabling **ABORT**. + +!!! warning + + When **CANCEL** is disabled, all maneuvers will default to either **CRUISE** or **STOP**. + +The chart shows the high level flow of the lane change abort process. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE -title Abort Lane Change +title High-Level Flow of Lane Change Abort Process while(Lane Following) if (Lane Change required) then (**YES**) - if (Safe to change lane) then (**SAFE**) - while(Lane Changing) - if (Lane Change Completed) then (**YES**) - break - else (**NO**) - if (Is Abort Condition Satisfied) then (**NO**) + if (Safe to change lane) then (SAFE) + :Approve safe path; + while(Lane change maneuver is completed?) is (**NO**) + if (Is cancel/abort Condition satisfied) then (**NO**) else (**YES**) if (Is Enough margin to retry lane change) then (**YES**) - if (Ego is on lane change prepare phase) then (**YES**) - :Cancel lane change; + if (Ego is preparing to change lane) then (**YES**) + #LightPink:CANCEL; break else (**NO**) - if (Will the overhang to target lane be less than threshold?) then (**YES**) - :Perform abort maneuver; + if (Overhang from current lanes is less than threshold?) then (**YES**) + #Cyan:ABORT; break else (NO) - :Stop or Cruise depending on the situation; endif endif else (**NO**) endif + #Yellow:CRUISE/STOP; endif - endif - :Stop and wait; - endwhile - else (**UNSAFE**) + endwhile (**YES**) + else (UNSAFE) endif else (**NO**) endif @@ -772,117 +854,137 @@ detach @enduml ``` -During a lane change, a safety check is made in consideration of the deceleration of the ego vehicle, and a safety check is made for `cancel.deceleration_sampling_num` deceleration patterns, and the lane change will be canceled if the abort condition is satisfied for all deceleration patterns. +### Preventing Oscillating Paths When Unsafe -To preventive measure for lane change path oscillations caused by alternating safe and unsafe conditions, an additional hysteresis count check is implemented before executing an abort or cancel maneuver. If unsafe, the `unsafe_hysteresis_count_` is incremented and compared against `unsafe_hysteresis_threshold`; exceeding it prompts an abort condition check, ensuring decisions are made with consideration to recent safety assessments as shown in flow chart above. This mechanism stabilizes decision-making, preventing abrupt changes due to transient unsafe conditions. +Lane change paths can oscillate when conditions switch between safe and unsafe. To address this, a hysteresis count check is added before executing an abort maneuver. When the path is unsafe, the `unsafe_hysteresis_count_` increases. If it exceeds the `unsafe_hysteresis_threshold`, an abort condition check is triggered. This logic stabilizes the path approval process and prevents abrupt changes caused by temporary unsafe conditions. ```plantuml @startuml skinparam defaultTextAlignment center skinparam backgroundColor #WHITE -title Abort Lane Change +title Hysteresis count flow for oscillation prevention +while (lane changing completed?) is (FALSE) if (Perform collision check?) then (SAFE) :Reset unsafe_hysteresis_count_; else (UNSAFE) :Increase unsafe_hysteresis_count_; - if (unsafe_hysteresis_count_ > unsafe_hysteresis_threshold?) then (FALSE) + if (unsafe_hysteresis_count_ is more than\n unsafe_hysteresis_threshold?) then (FALSE) else (TRUE) #LightPink:Check abort condition; - stop + -[hidden]-> + detach endif endif -:Continue lane changing; +endwhile (TRUE) +stop @enduml ``` -#### Cancel +### Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers -Suppose the lane change trajectory is evaluated as unsafe. In that case, if the ego vehicle has not departed from the current lane yet, the trajectory will be reset, and the ego vehicle will resume the lane following the maneuver. +To avoid abrupt maneuvers during **CANCEL** or **ABORT**, the lane change module ensures the ego vehicle can safely return to the original lane. This is done through geometric checks that verify whether the ego vehicle remains within the lane boundaries. -The function can be enabled by setting `enable_on_prepare_phase` to `true`. +The edges of the ego vehicle’s footprint are compared against the boundary of the current lane to determine if they exceed the overhang tolerance, `cancel.overhang_tolerance`. If the distance from any edge of the footprint to the boundary exceeds this threshold, the vehicle is considered to be diverging. -The following image illustrates the cancel process. +The footprints checked against the lane boundary include: -![cancel](./images/lane_change-cancel.png) +1. Current Footprint: Based on the ego vehicle's current position. +2. Future Footprint: Based on the ego vehicle's estimated position after traveling a distance, calculated as $𝑑_{est}=𝑣_{ego} \cdot \Delta_{𝑡}$, where -#### Abort + - $v_{ego}$ is ego vehicle's current velocity + - $\Delta_{t}$ is parameterized time constant value, `cancel.delta_time`. -Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_on_prepare_phase` and `enable_on_lane_changing_phase` to `true`. The parameter `max_lateral_jerk` need to be set to a high value in order for it to work. + as depicted in the following diagram -![abort](./images/lane_change-abort.png) + ![can_return](./images/check_able_to_return.png) -#### Stop/Cruise +!!! note -The last behavior will also occur if the ego vehicle has departed from the current lane. If the abort function is disabled or the abort is no longer possible, the ego vehicle will attempt to stop or transition to the obstacle cruise mode. Do note that the module DOESN'T GUARANTEE safe maneuver due to the unexpected behavior that might've occurred during these critical scenarios. The following images illustrate the situation. + The ego vehicle is considered capable of safely returning to the current lane only if **BOTH** the current and future footprint checks are `true`. -![stop](./images/lane_change-cant_cancel_no_abort.png) +### Checking Approved Path Safety -## Lane change completion checks +The lane change module samples accelerations along the path and recalculates velocity to perform safety checks. The motivation for this feature is explained in the [Limitation](#limitation) section. -To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. +The computation of sampled accelerations is as follows: -For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. +Let -If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. +$$ +\text{resolution} = \frac{a_{\text{min}} - a_{\text{LC}}}{N} +$$ -The process of determining lane change completion is shown in the following diagram. +The sequence of sampled accelerations is then given as -```plantuml -@startuml -skinparam defaultTextAlignment center -skinparam backgroundColor #WHITE +$$ +\text{acc} = a_{\text{LC}} + k \cdot \text{resolution}, \quad k = [0, N] +$$ -title Lane change completion judge +where -start +- $a_{\text{min}}$, is the minimum of the parameterized [global acceleration constant](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/common.param.yaml) `normal.min_acc` or the [parameterized constant](#essential-lane-change-parameters) `trajectory.min_longitudinal_acceleration`. +- $a_{\text{LC}}$ is the acceleration used to generate the approved path. +- $N$ is the parameterized constant `cancel.deceleration_sampling` -:Calculate distance from current ego pose to lane change end pose; +If none of the sampled accelerations pass the safety check, the lane change path will be canceled, subject to the [hysteresis check](#preventing-oscillating-paths-when-unsafe). -if (Is ego velocity < 1.0?) then (YES) - :Set finish_judge_buffer to 0.0; -else (NO) - :Set finish_judge_buffer to lane_change_finish_judge_buffer; -endif +### Cancel -if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) - if (Current ego pose is in target lanes' polygon?) then (YES) - :Lane change is completed; - stop - else (NO) -:Lane change is NOT completed; -stop - endif -else (NO) -endif +When lane change is canceled, the approved path is reset. After the reset, the ego vehicle will return to following the original reference path (the last approved path before the lane change started), as illustrated in the following image -if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) - :Lane change is NOT completed; - stop -else (NO) - :Calculate distance to the target lanes' centerline; - if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) - :Lane change is completed; - stop - else (NO) - :Lane change is NOT completed; - stop - endif -endif +![cancel](./images/lane_change-cancel.png) -@enduml -``` +The following parameters can be configured to tune the behavior of the cancel process: -## Terminal Lane Change Path +1. [Safety constraints](#safety-constraints-to-cancel-lane-change-path) for cancel. +2. [Safety constraints](#safety-constraints-specifically-for-stopped-or-parked-vehicles) for parked vehicle. -Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and will be not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: +!!! note -![no terminal path](./images/lane_change-no_terminal_path.png) + To ensure feasible behavior, all safety constraint values must be equal to or less than their corresponding parameters in the [execution](#safety-constraints-during-lane-change-path-is-computed) settings. -![terminal path](./images/lane_change-terminal_path.png) + - The closer the values, the more conservative the lane change behavior will be. This means it will be easier to cancel the lane change but harder for the ego vehicle to complete a lane change. + - The larger the difference, the more aggressive the lane change behavior will be. This makes it harder to cancel the lane change but easier for the ego vehicle to change lanes. -Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. +### Abort + +During the prepare phase, the ego vehicle follows the previously approved path. However, once the ego vehicle begins the lane change, its heading starts to diverge from this path. Resetting to the previously approved path in this situation would cause abrupt steering, as the controller would attempt to rapidly realign the vehicle with the reference trajectory. + +Instead, the lane change module generates an abort path. This return path is specifically designed to guide the ego vehicle back to the current lane, avoiding any sudden maneuvers. The following image provides an illustration of the abort process. + +![abort](./images/lane_change-abort.png) + +The abort path is generated by shifting the approved lane change path using the path shifter. This ensures the continuity in lateral velocity, and prevents abrupt changes in the vehicle’s movement. The abort start shift and abort end shift are computed as follows: + +1. Start Shift: $d_{start}^{abort} = v_{ego} \cdot \Delta_{t}$ +2. End Shift: $d_{end}^{abort} = v_{ego} \cdot ( \Delta_{t} + t_{end} )$ + +- $v_{ego}$ is ego vehicle's current velocity +- $\Delta_{t}$ is parameterized time constant value, `cancel.delta_time`. +- $t_{end}$ is the parameterized time constant value, `cancel.duration`. + +as depicted in the following diagram + +![abort_computation](./images/lane_change-abort_computation.png) + +!!! note + + When executing the abort process, comfort is not a primary concern. However, due to safety considerations, limited real-world testing has been conducted to tune or validate this parameter. Currently, the maximum lateral jerk is set to an arbitrary value. To avoid generating a path with excessive lateral jerk, this value can be configured using `cancel.max_lateral_jerk`. + +!!! note + + Lane change module returns `ModuleStatus::FAILURE` once abort is completed. + +### Stop/Cruise + +Once canceling or aborting the lane change is no longer an option, the ego vehicle will proceed with the lane change. This can happen in the following situations: + +- The ego vehicle is performing a lane change near a terminal or dead-end, making it impossible to return to the original lane. In such cases, completing the lane change is necessary. +- If safety parameters are tuned too aggressively, it becomes harder to cancel or abort the lane change. This reduces tolerance for unexpected behaviors from surrounding vehicles, such as a trailing vehicle in the target lane suddenly accelerating or a leading vehicle suddenly decelerating. Aggressive settings leave less room for error during the maneuver. + +![stop](./images/lane_change-cant_cancel_no_abort.png) ## Parameters @@ -1095,3 +1197,10 @@ Available information 3. Object is safe or not, shown by the color of the polygon (Green = Safe, Red = unsafe) 4. Valid candidate paths. 5. Position when lane changing start and end. + +## Limitation + +1. When a lane change is canceled, the lane change module returns `ModuleStatus::FAILURE`. As the module is removed from the approved module stack (see [Failure modules](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design/#failure-modules)), a new instance of the lane change module is initiated. Due to this, any information stored prior to the reset is lost. For example, the `lane_change_prepare_duration` in the `TransientData` is reset to its maximum value. +2. The lane change module has no knowledge of any velocity modifications introduced to the path after it is approved. This is because other modules may add deceleration points after subscribing to the behavior path planner output, and the final velocity is managed by the [velocity smoother](https://autowarefoundation.github.io/autoware.universe/pr-9845/planning/autoware_velocity_smoother/). Since this limitation affects **CANCEL**, the lane change module mitigates it by [sampling accelerations along the approved lane change path](#checking-approved-path-safety). These sampled accelerations are used during safety checks to estimate the velocity that might occur if the ego vehicle decelerates. +3. Ideally, the abort path should account for whether its execution would affect trailing vehicles in the current lane. However, the lane change module does not evaluate such interactions or assess whether the abort path is safe. As a result, **the abort path is not guaranteed to be safe**. To minimize the risk of unsafe situations, the abort maneuver is only permitted if the ego vehicle has not yet diverged from the current lane. +4. Due to limited resources, the abort path logic is not fully optimized. The generated path may overshoot, causing the return trajectory to slightly shift toward the opposite lane. This can be dangerous, especially if the opposite lane has traffic moving in the opposite direction. Furthermore, the logic does not account for different vehicle types, which can lead to varying effects. For instance, the behavior might differ significantly between a bus and a small passenger car. diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png new file mode 100644 index 0000000000000000000000000000000000000000..1f01b6df5464ad77971fb0eea37c587b3434fc85 GIT binary patch literal 26510 zcmeFZWmuHm_cp8uN~oZKD2<4efJzAnLrF?AbP7m=bf+SUlp-N5&A<%O-3%FS7>@{L);tLlpT$7iRR=;oo z-yit<0^w!g=M$p~kAXifx~R)aUV!z}u3fmmctKuTLetY|V}>XpV(Gkdw}_>-OT9vx ziGtW-U{aFBpDiOpj!ALi=GWM~GWI2^O+D!>O=6IRd>jRnv^l$aMH$*SO@H8YfY$P5 zzX0z_vKMG<>G8|dC4ZxVFZuglwz2i4bRzB>3B^o-7w`xf|Lc!?$>IXRX>WXTrpf-t zXN+_Bg#MmP|LqCfKZ!WRcVf~>leZ}2gZ1Y`l4n$v|t9+Wc^LB|19v4knB`C zqqF$e|8(P*SoAKRi3Xhc=6LT;J}jD)g`eGepfe|(hn^1!`g=3X3xN%Hc)RceX3c0y zP$zf-SylyKp~1U!`RcdIS?}HoN5oc+k5{azCU$4?AIpEN95~0iSXg}%IQQruc(b4B z!5(=Fq1P^g1HIs9!_&G&H|*-j5L!h>_E-$6QkKDw z@9TDKlA?Z7<)o}n!DOyAJVz6orPN9PS2l4?0z&_cp6+ho?gbSxJ#<}Fohr4A@*xkH z^;*$w^v8bEa`4_PA1gHLjMTk!H>CD+F9}bbiE#k7d?a6^^YV4t1UnUIa1Pf;8WW5b z##0dFf9grYXBCZM zWR#eSdm|Awgjn&k_<)|U3X2J5IIP;Wci*J(&wH#uss6s=L>uFYk{waW5VhXA@@Lrv z31C_J)SG6~fbV!AJ_lC;mET~NsS4~A?Ar0;WhkiER|a7Z-Vt<0&`@cz#N_a@Ur2gv z5$3k~qnQA-IaOIHi139+NJQ!#8R=(S20@PGt$WfOcb1ShcP}mA|JBn4yo-RMJWYS8 z9iJtgBa(>xKE6Su$S4N$JV}5n&*!;)u1QW&x2*Ck1U##tMI7Oq>*EzyTvHRW(av|M40u6Uc~*uges-9+xqa@n}N<2tfv`V2Tv4P){*zE zKq*NeU*PyCm?woZ0m4vi^X#G42SvrSBIdvMiIte_bO-Xw>f|)U!L;kTaXiA`2^U#miOc|CvebYIf3ZWyh@dHdNHG>kF!`m-=zDUtu{LBO8Z01s@rM3 zJdIDYR9U{uQtg>KkM`)Vr205?6-4I8f8y{Qu4RMvk&u@gD_{fbT-r3|;z#}V-TqNo zCU72)^^%deSmeYur?jL#5*4tzfI!GL2MK^LoH)$#<-KSR(+we}RNr98Ty8A49dqwQ zMn&$&$!ceZLsaXEPK=pZ^q|sltSYJRe%2!|yWB+NJAJstB|LAmbZ2#6xUwjwrA!>P z`ekFbeu_VNv{7R(&Z0kAsC9je{CmAOW_5z?`=D!~N!o|tyG84rh}K$J$HaJ!D2J-~ zw^^19J>%n4f2@?Os|ODsqt0htAn>T_}F>mi1xHJru!;|T=Z6k zbigdxeT|J#4}dE~`z`T)bPV1N1Y^5MrDPRv|C3gu0IXY*h=;?FD|?7?<&1k$txSrr zo83UFs61ye0ZmtyTR>0)Y-Kj%*@yJB5B>A{hl>mx>te>9^8|wKqEe1MUyP*Iycp)E zMLPfSI>isfcgTBHLVu+KkM7PX>F;fyEO2RW9ir6C=0vvZcqhV?jS}Ydi855PEC*8M zdoz9DRdp|0g1l?m;I3(((e!KkV}>4vO_W7-v%(FrJm_h#wqY!VyVut!N4N!;m&>q* zkKJSsj};-)>2bLU1??QOdv|^$EPF&lPKcwBBo%A);ydi5T4~wA!c(8=kW2B zBHTW8LyngFW6{;oEgs(Lb$~EUyf4}awV?}KOJaa;^jV74-pGzOQXqDI>dEs&t%zo( zFo1-~vM~XNYKf#`U37IO54&bGrn!D-ws;bs z-mMRal>K{QhNJ)wCaNjKigS#Cc*NWk(rl}P%k}cwE|!kMk-;OVG=lCL z^~3QU0sEV%3={c_?*%EpC*Ax!x~@{(1`Avs)pvA*e=A!{)qJ$11m34B@Ceu|FsLpe za30cpLSSnY{gZB+CVbT_L?qBi0$f@+aSJb{Lwk*$65i$Dk!4i?@zSWUf;2O*c|6g z*A4fmNkIugGqNEZ;MrsCzBU)nh3%W+7KIJhZ&LwM{&GUmy1 zjLEul=O4L?0lDuW`$m50l{KBwawtn4Rv9&0Rj@AI98t;s!*ip!^Ak07n#ZgcYhAVW z6F#p!^Gbu`Yl72c@k}y$q(%}^TX2`5voog9!eL8!r4pX{19c5j7Q~!vC);fehWol# zgk|*>-(?pe{p)vfJ+@~BUd=V>P}7@9{I$6SNkAdo^yIH`Q4`2dsskMZ7@(Is-u}&A z04K$WyGB&MPphpeQ2W|Xk@h|hYRz!cwD}XFyif803r=V{Qu04aUQhv+JWIX9EQ4FJ z>jj>XTNH;6kjAZ`G2fGg;KNrFxz6w@ezI4=%VZG^%DWz{;kbB*i$VV-h?8~g;ps6! zb&6k9*iQ+FU^Yr)5-lvf5}x4i1T#3U;)^>SlihjzTb)k#05>E{`r+%{-+@j1lmxIM zeDU4$=hc^ful+(7*jHTIb+bPaD(DTl9Q!fT1%)cvzH7e=88ULf*x=Kd0)Hng=w+Bn=ZVdQU7=}so=Lz(Ide9 zEkSbzV*YrVpsSR?e!jM_N->a9{Z0h2>bX~#dw5Sl&56J_nM@ZZ~d0*9TTv#+upaY68t&Oo5qaUbD>SFyJ?~x@BYXH zq|oMXg~xsy9B|_~=NN!h%qQaU1S5Zcc3~u)QCsyU&e1egirqGE8>hZfY?JR2_*l7s=r^pfcFIuB}Qn=fb!2a|C|c$c;!5R zrCnK<|LF4H4~sA3_7y3j{mXm&bGpAC9x?=sYvz6R9~1b`uL4}T5YE3X_Je=h&%d7w zas^IR-s1)L-)!t(&zVO8>C68j&8 zn-Wd?ocp<}Eq1WeBZJezmIm$}6Mcw({jan7qspM~}n{^xIuIRsW)wD73V=HD0SzZ}jy3EAlz$Ig%c zb8+$Kz(;Kdi>9ysm(Pv?8c7A6hzt1W|3ox%(IC*-aqBG}BfB);(_*MW^-zWVj7`AV ziRI|)cP(_5y>WeE6znfXAmGxMTzWd0G7*K+?{DS|l>S?p;-i3%?4}<0QY+24OmKFF zal{-=Ic{#HJbUc71w_y-QhiT6Vy_a*0S6(Mee;MeGT2dwYuNX{OMfC_Z&Nt$S+{NVM-3%1{CCjVo{P!|2U;A3g{; zJLNXtC4KhTwknNB|K*smN6J!nOs7_nZj5d#A-V>=3xlu|*d__sm#`0j97(7iyy`R_ zt}326Z@Q#;h7awI{FgDdUV0nHW_jic^BRAs)U*hmnWeb5pzb%Uv91>n84t z9eyUs>$Fcy7CR$Kb+_vlA(@x2 zQ=5;uZ#^GKdvoltaQ|P&NC;FEt(=!G;y+fJLm>hxiK4`8cp48rE%n6@q$WL`uo=$# z_+Up(XLo6R1jxAgP?ZpE3Ve%>9OQbGBzXvEaMso6aG^VeHOj>b(NGUAQfm!Mb`D$W z`ohZ*AG7jqzIA4}#`k1@s&JwdYTo@xO-PXSpGX7jBWRo)h~M>=E$_&>9^(O-WqH9= zr66{uT9Jz8skxl`;rm39^8>hwfajbzX1$>3d4XTPkW)XcP^5PAY3<_?P{8>nwFEM1 z48vM~!H-7iN}~TV_%?gpAcJ=KPiXqmRQe>!MT`M?T5}~tF%d6!J#%lVXX27shYoNE zh5@Nogz6-mrQ^fA)#EY!_JL&}O0Ku)La#0SS?47C!P>Blojz1hT zKaL$UDjmvJtmWl6)oJvvpP6lJ^gG9*xW)6;%OOBX)7LMIe88z!m@uVsv71!HeSAZ= zbfcHwb|W5(F-%K8fDjIOMbQc^NPfa2Aih`Y{spn{qvq-1G_k=bGeeBwB zq&HRSQ<>u2!#?WRbisBEmQs+hD-c2zlj_wm>xp%PA7qzF#)embpZz%Dx7BMr!$M#7 zC3bhvf7hWnexO^@Mo$l#6>u1zyRNnaU#XZfAfxEcSS*dwD`Rv23@{kX=Zk$Tv z_54Qme&3n4Z@_iA3Zi}cRy>1bTJ*&m5{EK#%m<$OpB%cHo0$p>ToV3!-Kk_0`#Qmj-D5*`rlK`V%I_U_Z70wU>f zAbLWaukqQ*3hafvM)}@SpKaz=btiYj@r&LR5f8astz(y+ISHB{MQMJ!?Nr>!cV1yO zN0(}lcZqGxtNbwTwOP+dEYC(J%bBidFwGE(`~&L%5{Tyz0qF|0C>4;0^Bh-yQ>LRj zWji=|apGKCElWC9YT4HHaWqFMDXU4^Sldk{zCUHNmP>znWy)jKq~04O8pX?-@@6dOg$j?os9wd=#9%%1Ns&(?tiFXIr2v2&V7VXBdr!}P#xRA-HBj9@COUca z>fbTZi5;-P_^1d8=IGmaXU$Q;DYmeNNr6IRN5R8Y(|RA2`^e+Tvoj=*px=58x8d{N zCRE+ht+AbPBnicbyTo>UbekP8LwiJnpSuNe)E(9JQ65FnlRz0JD(aLWirOfJ-8r%? zYILyZ`AoD#(S5{nOq3LP=?0-!tQexCWW`Y#^b8H9a`BO{X1Kf z0|(B9QW4^r5}TLmn$mZh-b^s(x9fb@4eN{&98nBXt`~OOz=fN!9Hmm5kpkAklEIbB zvreIYd%K-5o8=HH$R` ze|$MVg9cFX7(Ly0a)63=448mo_+)75aS9Z6Y=LEewuhpUC9pF$+E z72>bkt8UN%2z)5jWn4NUu7yj)h*iG$Jf{K*pDrD#YyM@L-XC7}O%E6GXu(_^vsz{j zraZBijo?LberMI#y>BaohuDyX+k3B-Jz{)q{~cRzv)aN}Z_1C6N~w*ry~JbUyBRo>&(aOb6x zBND#wTGnHtOA%7P@`wdo>tu`m&ZS67oJ^_G_nHUR`E6TLm$MZZ4tv)8;Yt;jCK3qM#O;!`*Ps7?ASuJoy-ezV2KYP%y$91ag!_8X$g-v-006A zb|rD&>Pxe5LbWKGHQ|HaA4yj;;HtSGaUl7x<0d220CxPmDuA@Na88yp^cvmcHn9Ye zG3-&jN1B-XE=&CQLFH^ozD7<$j+N`y^u%RSI_eR2W88f)dLnE~e5`%L>l~(8_vX_3 z@^m@Vehn2d>jBVt9VNGB*H*xeM1gUme~F2#2B^Fw9xr30Kx?At%JnK61|>wHTISmn z!|D=BHdRL5XVKg6F^b|8(5Xq9-_aM6*A3`(PO8gmlR*`{15bJLoyr`y(}Bd+qK_&T zVMu-?#Ja}oh z=Q1$Cs{-2ecJe(Ql-&~C9h?NvMV4+aGC5twAH%#MQfOb9H`0lc-ezMk*vDE)3x4N; zc%C$xZ{A_~LRb-A%Sjr?y7?CR5Pq~!CPc~}BCNTpQD&tk0+lAxX40vbxh8^|b}>{< zQJ3<;8cfxC6p;YQt|G6bFnr{$?R zXFOmd+uZJaAlJpkOvWEn*1%x6qw&?(t90>v;G-S!dBhOLk#g&}PxK~&6C zvTN*tMoxI`%O^=&YAEXUQJ9|(jflSiu#RP(<(>YVu}CASuMXbOb$*(j3NNJD*Ny%L zf4ncZPHBZ+l-rCrE2V%^L5Rcs!2#j=i~5xgDQ;F{{R9#P4X2OW5mll44~hI+=6BD2 z{N)0uE#Af-Qkknv3n=OGrSXy3Z8*_X+Y2DAdl z8|r-w2~-Puc`9KuHPvaN#15L>i@}MnuWW|WiEIFUuCi>!xbZRLfK6)Y0;=eiYk(pS~- zA3A@HL~mZD6Zmd32HWKDr_iy2`>%s4>?R&-b3y6F(VG@Wb`u5!8In{Xpv0kU5LzfF z0Hb|*&2qAvHEo0AJ%?7|DkK;JF52RVQcvt~>)foIO7=kTLkUOAtTnWmvgjp=TQAuY zsEAGQi9V0Wis5+EFWd_?io21t1^NW0!*+IQ7KMA-7%;05WMHugdCJpNcz2khM^Vh8 z{*M>fUq!s307|`$;+I-GnSzR#qs>xW-4(|-M#JU^=E05{I>y}xyeLM=n@_vN6rycj zL=`E+7)LEQP$43fx6cT|j?AJE}np21Ju@d=QJVi}wZyx4J5>VZ5 zN6YMxBURq*{=!abLw?M8$W zZ{Iwe&j?h1V^h!GpnM7PyqearRxw0Bv z%m*C2&ab_uFhSO#GuO<5S{OrQA=B(yWqE%4eS%xQ%(4;Au?p0$b7Bc5>z0=IpFP)T z9}U=#C@|kk)WFbZy5JMPE^Dh3Jks$D#s?MeP~5)sD~<66u(zzrhbt;NxQI`04@7(_ zPHh>3^&&xzS%z)pIz*nVyCo|<6gkarmryV2SA$W)(3tWyp!$W)I~vB9kaW9u%?x*5SxI8I@wU8p+1cbe)fasXO>+0V_;jklq*zn{XnWcC?ly9oj@Iu;VwU2KH~N7j zum)MAa>Q$U2mz1QYV%Ni8ZI(MY|#r19d^sxhUEuS^AM`@NBQ4BD+y@K4|Cd_EQc{2 z#20ASBE8`qzO9S|PmMIJH#3p8`!M8`_@us(5lS<|ygTdRYO>3Kn`ty&ws;cWeWiTx z>zClmT<51Qn8Pt+4MQWNSn)GT$r>4N$NxV)NW0ddZ7}np429a;v!nZQ`qK(ecE4F~ zq`;~>{7-jf$D}f+A_U*^+bI#;abHP+1*dy`xOFtX7!~S9ADs4W;t5$$AfD*DK=By8 zU(0NY=#*ZWm8pty@+!pECMBRD$>wk?S;&DnzH-g>5*p=U`Yq>;sEAjI?J4aR1)JgG zIOu#FWJJEoENk#1qiH(n{?Sq*|IuQqsDnYn*ltcRC8yT+!)xk?gN}(D04nORLHtEs z&&bFOw36&%aLF3Vrd9Q7o-aOLo2<-y_l16$)yJg!ag%#{fcLOcX=gc}Pol=P3K%(Y z?TV1x@1i*$03gG>FbHt+7xT1pBYn*F0PfXR-U=`dzptF);*uukJ`+ls;%jZl#`Yd>)w|70nDh;Lo{-Rrp9Nxb^vBKBb*Gc zGRym2)jpA!+fsy;%#OLaVVz~B{VLtIhT1FqQ7Oo^%rrGlEvPdbR=1hthTK3Si#(LR z9M=1`$7<*3h>~+x2HZZt3}$j$saZr*tJ*5W#YJc*z*HwHEu%XMdl_=fcw>L!aqRoM3|AU0B|tb>0B@IYP+50nCWq%FFR-ryZ`QCcA_ zqXd9|?5X2WS^h|Y_CN&B5c>-NlW%Bwa{ZUKQgPVvn)Rd6gqygS;Dk@?e~`5N-;e-h z@75iZaljX?gld=~6^iBs_|$cKka;30ze|P!n|YYz9KtW?zPX+w%9c0idcDZhmQ8z@ zCM%a!*;S*yY+)RL0qETWrFY1~o?`As*ECrZkmy$S@IwKITx;{Cn!(p(sVBZt+sJ=n ztA2$Zg{`qW*)wPL0&02tg|_!F$>sWLml?#J;*(Gb>g}(uuNd-YXl)LyzaV}Cv`CjF z??ScQ)wibIy}vwm*FbGKC?t9lRqt5s1Gupq#&*rCGT>-Kp7Yb1S;&6ktZ@3?UN2SCgA?##jVr=c2-fK6LV>e z8Nk90*}sACf(ZIK!J{1KseL%44NI%;26&UhwUJ(+tFwX^MP=;GKGB>a>|O@u)Sk59 z(x1#Ezi)1{lrhHBg_$a7IdNZ9M0Iy&w6dt++a5HJ zc&S_gIM`d5U!X=?0ic*VF`HJ~{9C>ku@9OVzkwC^psyF}5$h*sZyWQGFlEP2P9 zbqIWqwdsk5sgicThC{G+b%T(X^GZcBYszPe3u}FEXS+PVendH?53DJxW4s@BdakH0 zg6nVSRXb;2V-WZbM(4H2#)?6?8=wCCCNnnb*m!u~8DQ1rO)GZ_mhPE(@pKX_XVq*>Y_qt+r^SNPi64#6Nd5Wf+pN?QXg`xrNb#*9jZ=xqY`@ zUy1aOv+fyrdyQrT=+4+pjY79pv=RPTgC7etv&m%i*ppnkC!Rm}6a60T5rqTe$f5u> z?H&)`c6koCE$O4%01idMUH1bkW55(~)_HbxhMjTj;pY-}45t>f{&a9(!ttT|=Jc9> zEeyeS4q&ZXbvlp6OvWr&$*3%mO=4l*{@s@urRPduAtd_fP?PmT=R0m{k<8GI) zww)!(K3O~$A_q$FX1MLld0E9Qd1w8n)&;Fh22{Q*VwEFWZb5q$1IZ%IQ>$n$!;-eLY0R5WdKc8^$ucgwT+A56 zY=32-(uq{`XMbk2Q9-idNRE=UUqsnmUBr|_X)LFf&exWZnc?bnew#N2qR)27zZV4h z{f0eoJ?Pmq#zk4iNP_>4rQeHPFPN}eu`MbWt@Ws7H^yGR`l_+-(9bMWP~{hj?z?zR z@LIFr>U)BlN+(YmUn*%wXqLY0i$;8AKhP~Pf1iY|aB98mp}1Z=2mt7Jy-Tz9SNq1N zt6l7I6(ey5fS^C4xc6+KetYMu+;x@RaX(qSG{JIY_Shr#6hT9W6vIs>&;!;l-0w24qLK-L{Fx9g#CrP@|l66{T}9fhrqKvkIHu#)n^KScEe} z^v~OZctnf<+mcq0PGRZ1sO~6H|Le0Pe;?@iSMBT%=%1^7im?zd6ezvjM|CZA2Vb;L z`=c2G4(kS!=()hBy=U01h$yi%`lS8>gi%3oo_G*mH}^a=ICCJLTcbm-+{Oav#<*!P zmtd!M_@J*8G}`=UD+j>W0guq9RiwAH#i9)}fPE|vW>BK};L5@q@>1`XQN748&+3|d zOpE`1EPelbf93xIYc3i|wC_=UOC4F)OX4hY1^K+}Ph8S!R%f90i(=nV+gYs5m#D=v z44G7n<0A3-hW6S68fXsXQqVWqX_V;9Km(8>!)@LUu3~!Vj;!eD@VCjNApyURt7EUZ z#{0mwTa!zY*m@AwyxeB2f;H9mu`b)Kjp{nArY`@|$;##~V8iEhU(SxEV8I-p(>~&Z zzCubtzjE`ZICOte!|XfZy?23$E=DsA^|nL#sW;H})hN&gL}4)LOY@~GHD_er@Q;dq zzGsHQCEO>Clq^-jAjN#cE3^~K1D__HcOgP>XPv48)HS&_=yF;+Q^ z_MUi7OBCohU7ud}qAHuCm3m3EWhITntDHpV!D5ZvyktSqO(Bm}yauL^j<*qj{-H0zl_A4Wa z#API_rjIo7Zz_p5LQ{5DGaV?4aGgt+7}i>Zs!tLg8Frw~zW_>n8w>47T>}rs#1)}v z-0I(}v#68_rf556IInas(h9q-nv4L2X(&_h=vaRuvq5Jo(cE9c-ZN zj}OGNCXksOt526ZS3dZ$x}dN!`8C#f>NV-pIqy$?XYEv5-GX_>h@;IJq*n2es|o_z zPe4_*mhW+mVN0u<*hBxDNzh@#p%#jF@$2p)R4r3xYY~TWUu#5iQ*F$;ApG1gf@WVh4*Jq}{ zGH>_xzs#{3ct!qVEWKj|${J5^y>QAPeDWVjfsThDWaaci&V|n!ZoQXCtG>0O`rcI5 zeBUyxeU1&_1Is6IyePBS*NyFE-ZOmPJEe_b@tav$6i*{{?e9wxoC2U6XGad8g^h$U ztO>?US;{H2>B*rM;q>%cTZ&ieL)I&O z4Qz1Owz46G5Qyf`c)5aU6<8kPp#I}g5$@fTm<1?)ZssQzGK+2=n4Wi3QXV z(V$gnBr0ej$)uQW4gNBJd{ScJj&&QW7St&iE9?$udgH3(DF4#&#O$y|r^+NqBs3?4 z&3xZpm}aPZ;!e<2vYl(;by4-IY_~W*yydH%ev8_&<&mz-J9SAn}nECHU=Pkex$=Vl=><;KKHYU$l)VO9Gagw}(FUpCK| zsE{+Yl{6Y<0t8w%J9R*_(H33-P12+6&siETLQYR$zXzDN;M-1S$&Z60(Ctl!hBf05 zaDhRzsBhalbE);w&0~;k{p|i;#eJxDnHi-#2l;AzYVq`5D7Rxj5qY_<9F|c zR@Tsicp6Vj>L0p6mikksavF{^kh~Oqn=O;&GZfPwGi7vhZHulUhtWa-8kG)!8EK78 zDFrFrOA^ds@|az_b#Z6rvzws3_tOLGp`UFR*i?5G3B-(wKT9&u_5LQ1ir3+MKQhK_ zn($sipucT_wJ~bOB?{oOkMf@lulQa{#;;wvT1{8KrrDJ}%U}~JYSMI}w#3br!|$srbZQ^)gUda{?vG}N8!g}A&A?97vt)fg%B zd*YZH%cU<+=we#~%kj=v$nA9-n@Ded-6|Y)T|FeG<6evZB^dv{vqp$e56Dr< z1G+2AY{b5dN%b40mVFqd0G}*_=!NveZqDeIs?)|ej;MUQlsn0)!~T03<((Vg<#Ylh z!%6>8C|{_H_rBvf+u*HyQ>7K7zEf)2dbzg3OjdAa9Z0VVjq1JSudRazJv#$09sy9a z4$uOb;V_w3M)h2crk|;;U0N7n-Kg%4X{8U2GbsWP6%qe#z&G}==f3fSrHXoww}g;D z+q_ovUc<)pvKLsU(=tv-sv3bAg%K4!s_aQtE~bWGG#D}-T)MfJbsNX|$MFo?!UNGW zu45%@03NnZ$FHNs!*y7shG5{=avcBmRlmGPUsR>Ox8Zn!q!wsJQe9?$i0gjC1Xaok zT!t?p_+$3Bi6nvCh1IcbZTqtS7e+-hJw%< zMFs?8KPQlfF{5+&NAimAe$NH9#Q+84Q&FxC+=v}+TaTE40DyIfC6Vj%>2w5R z8HdScBEKOE9G7(rO<0DCet$$NW~Gt)+(~0dj7Z=;(JOw$qm-%adddPl_V!2Y_>ZSR5oB|l|*`FLyr(Rj!l zUj0J3#Fa$R^~Y1yN9VbL1j2zfX?%AkF8<2p`f<73M$jXJKOEjJ--`qSda2km%$7^6 z2;B0!oF2c5MvZ{utew;q(h8sq&;^DMHzxa240%^H%7?Tn>|lfYKbWNK09ciKL+G#! zzHz$W?-CI?@MQ67<=yyxpCNhH>I-bVt&IFRsYjEx0^Y-HmFD$vFj5bAwWd(k+;dai zUM*;gXl%WhePTo%#(`6HL9<|{(nobgZ8dX;wcLJ)rgn4rdVZ*sgkgBf?*!r94dCkB z_9D9q@bP{ZnTq1`kBvUNCejd6K@XQ zGTS>!$sB%bsBHJ-%)$oF95D+)O^ zhHIEBL$%r=?lv?BUg`yCcDH_qTIXSd{cTc;gYJnNza$8{jcfTdhqgrj7Eqk=h#-<) zbUp5-wrA!Nyi@e_8^6sk+XMxd5;9TP4We&j5RnGHmIXA=8-}N=UVW8>O|r@!ZTw=) zWY3P&E(07z4@`cET+-R-0SEMQ&Rm{%1hxC}7fZeFPb`KOs#{OJhFGo+xq(sz2exR1 zha=2}R|nkz(DN;ik18|X$aFFMyp2yoTW_W?R5 z_ct~1tRh?f0zg+)^gw4G*)`v~g+wpX?BxZ^c5*&f7ta7#FVX#r4417Lz&F_m)fqMO z)ma3W3RMAdGuS@$Fh(Fd83J4jqWv(Nm0PC()_r^M<^egq-*BoI+FE-pGc4_u;1{c& z1V~o@+VE(YcEQb|d^|ALb41KKMUE+207|h8rH&hYfu`*V;ro~BOiCK&S6>4-wRyb_xY4h_roF2bYUW}Z;z*R=SNnAqh zhG4yQ8sK4}t}t;hh#ic{a(h7_@ofM6d}x>W_4uC~!-5Mo-qhiLXCM}o#U=WI*-|sJ z&Tyx%Z#i5jhVyQecpvatjsI95DX`4${Veaq|3C>lr1|X-;ky{jNFa#=GyHr|H4o*C zwHY%TDR(?gqp9%Of2e)Suq_Y<#00nu*$NsheDpkI>I3Px-1rf8kr(=WM9yW_Z_LPV ziBb^zd_<~}l-A0A>N4W;9h%2~xd5`A=S((FX#^e0`cs6fIZ{G9qAKIK^xt9&5nqJh zZ?DqZorF=9lb{i_qr_GXU{JFb2A|giVQp%}Nb%iizNicpnGt@c8)Qfu;&i~wlj@(pwA9& zsat1^kN`SCw3|pMSx!`W5zH`KffC1SCHZolLFfg-VS2R#211{=Uc7W!r*ye*#;bM4 zm4P&Z&epME_pN^UMmfNwR-6f~wQeu_!fUCw3$dIMGMo%?qeei|UKRKSSAPp2`@D^6 z3>FIaBYS6k@eFet$C|g02m*#9Yr^I}3s9YEJ^*k5$EcF@8vKR zh=C0episLbH8|oadckg@Zh~tKM%kqKp4k~)t_04;KFN?dJxctGUg z9p7JI`#|Sg(^k#Cvd2tn<@5_thX$bx7Xh0eO-fLaO!-Tk0rHE{X(=9om1VWS^vt9` z=7egh(W_t+QP&r_1v-25XU^v%;nTzKaQ8Kf_-y)9K5N$-%_{eLXn&z&xD4f#Gd=7U zSG&JVHShG}4YbaPBxF>L@MlYUUy|YNtfjt7_KHDRbVX#c z8m*d?Sr6sFB0fhOPAl5&QFv7LkiA`w0E(Se;q@z7^x`LbD>#f|0go+2CpXRCd&tIg zUd+JI7K1|Qr-}L50n9=@0Cn4(uuLm|(JqDTUi9%JkT35CAx3?%;HuUzMl7Si^wl@9+%V%lB>3dwWI-kMMMvyQZ;dz^$98i zxJc|T5;<@K0yPiWvRMYB&W@5cXDSD9%rhD<)Xdgri-9Mt04Hq@66KpDhcpXOSjS{u z?q5j@XwYYRetz9DvS8|RGJ+3YZJ zSE=$lv)}#v3f2C5{46UCNNdm&&M*Ju2;z+QE*>s8X|$eQ3#wDK8iN^L9LQ`CS%+tG z&jvd?dQR~-xmjlQo_sG&xxnzR(Zr(zkOa!%7wLsHBWAuK-^PcJ_9#Wh}2aFb_u65#)^vG1^uv0WWn8730~=x2N_4w#vOEBY_Bb}AEzq&FrG*kRfzi@t za5tNgLhE&7&FUFStqiS0t7L)s{&`#wqI&2UrqeQWPw)*cq>|yrgMMgk{2sak{--T1 zP>Xy&=lzK?m7=wm*CF0ekGT=~8o(N@YLH-88XVH(3jyiv0WY&Sg`uLvv|g{s<+`2N zaC%MxS+wEsx33u2KK{6MK8l zYcq88dV6Ib3((bC^xi_k3*vE{S%+!>z_dinOKp`YR@j$BfHvI&##^Y;IoNzfBBdGm zFA_Y|Kq)KnZ^*BC^5EMTd@FY2n&fA*B2eVn@M+H3N?JbxX(4q~JBu|I0Py49R_Rjz zpH%Zg&^!E3aq*~vtCJ}$dwVvkh1RAvjGJ-sj^jVTmruBP7}f*%+7)BvM12k(LaDV% z%;l2~fN=;QmrQ-dK_Fptp=`TrH)`Ua-85-4PK9-8@gDRq(crC_A^MU8ZsmP?Hy1j_ z+)P^ZCu0YGc~Ck*Brw&%@w&opHrcL5N1?a30HFd5KotT>B9J<{7B94a(4VdIg4gBb zcwm9%sKATkSNgcQ1hoSIWvuQP)XRPV?Gq$a2b1al#M2~r=FoMgBvo9YIjSYexf+X? zjHpbMOtx~s2MrE~54hYoZCi0M8~$C>0xaY2gr2>&?IsNSZ!z&iuXKwA@wkhc!&voj7`6L2m{hW=#&iP_WMTogwtUOBsH?NaVk8e#iOBKYMsij1Rf0 zemg6j?MIIF3kUgQy9qmh@^u6tXGuBUv240S-Uq9u+U3@ZTGu~x$ONQYvE}$)Z%IEm zT-w-W0ftoH+-#F(#wT9#-eu{vdQHiAOr#YCkm&vn4&J@>1K?nAyygpe9xI;MAImIz z-6I7+>-FI|N>JNM2M2JmNls{ph&XVN#*Ea@LJJbmPH!aE7JGEfj2S=8b)vR>rP9Sc zW~#)^ka~p$vF8xq5+3r?wlmv%^|Eq1F|#en4F8-dqdcR&t9SBC-N95xdgE+XH36Qh zdxm;qYFiN)@h0+jT07*0Rx-vs<4(oK%eX<1R8j3;1KGI!mLvn-!942eU~rl^^{mZ{ zv#+Y=&a@HY%S7g`WHEzdy-#&vw7A#Sd{f`}&wOFDDxOAeVg$XtKtO|T^-mIHmRDNg z?YR4D!yb%eVZ!XJ-x-6#ufKSV_P*2BWpNib1$`k(>OWJj3)<-blNPGqSL4o~^qA!o zvqSyNr#?tWSj@NgRpeC)La#KE6<^xd;$;Mnh2M3rBA-ot*negWxNvk%^6%;mCq82b zf#xP0I<+eS0Wc{@+OWgNu=MW%7s&`M&Uj7mJO4bqn{0-A^eF8H^Pf>;;Nf>Af!dpk zDFQ=~w6eD=H27Wxq1kR%ja3*f5=c&RQ1Z;5 zZG?Yy5afDe6`mUf^yD=J%)7{FcwauRF<`!>vTnS&81bmSz@ISq#qJ2%WP&>J+q!7B zveIG?ts7mdjQ2B(;=!qAPZ6vDE&~$n_-BMlnlYO4b(;8y7`>^CHkJ(k+0H`5pp;+k z$CI}b5bB|_#}$R_(Ss7t0Yk7A8#%7A4Ng1uHVVJ>*NomJifdi2H-&;j#8SyvTEVFDGiPCEqXE^wQ%0SJ;)uL%H{DiI#DSLP|%p+DAmTEa{Xj zyRl4Bq+<(Z%{G=&Dxqx0k|hkrzBdR-2-#)djy?O9VFu6lE;`TqywCf2{~I&rzUQ9% zw_M-rdtKMaP4a9X%3wjvSsMtAw-q&tJLBJr#6SWQ$#sv#kkiOl;Ncp2O zEO0L)<;=*PQT+DtIpS$U`Sgtgq}P+(zjv8_hjbr(5J;xkj@EvSyRsMQ2GC*iUY?NZ z2B>rQON2-+SWv_U&qLymmL(VlnfdgZ9OwFH8WLxqkj+~duI`!c$^|Q^Rj8D!qvTXt zZW@R)F9Q2qST^@HQJG~Y;3EgLMS5GC8&(k8Gdlo=t?MYQo8}1pisF7504mZ(Q8uM(_>I-Ft$cV;H4_7|E2$ukc9`jIhh=7{YRrn&5}`lb z))ot3_i@_bjB#sWBLj?-NJ7k?qBiahF{zWir{(?goCe%Gh!%X1)na?+{njRVrj$H; z;pHulr2It8%rF~!Dn`b)~3~TWZ{Vi?fDtuja;PVy5kI&e1<-`-G zu+7WYgS=HVe{;9@u_e~(6MIL~9(YxK&DYaiol}R_-+#)>X^@DcqqeB1&$^t*EDwGl>M^;l1S+BFlm9mxU% zTQ_*WTqxNXS$?WPAxlv&H9jge|0*i4sA#N5`Li?tfxjG9xHst$k{Em z+B@tW+g5NJVvvT16Jhd%<#}^h^|zhhNS`!Dz)C6g=E<(zNe;df-Y6Uoo5gKYb_+Aw zExyoi#Dmd!9noC2mO1YJ?Gi_tSH#6O0W<#leiitPda5JSY1d=w{g@BQ>s38W>s&`Q z-U$LqhSEKXtO=uG8r%zoreJ||`92+fZy6P!-TqdI9Yd2Mq!6Rk6t~1xuhAJdsL=BP z#OK|XnGVc?a8C-tZsEiy-B9|`xOH>Mjpf!p=}lfIXRY@LX#)2z+cd`gBKM$%Y@+1} zaobAFQG*Acn5(Zm23z)YZlfc!RMAtQ?9Lk40Lwqy&$Q{b(yr?`OB^rCoarm>pw(nu zI%XPWR2L>t2&}{zwpAD=-C0H-5u{N7g>gb7{fSGR;g}T7PujGjY^Ni^f!IwiLm8ai z>UW*XhuR@&oo8P`ceSKqiOxpCO1dmY9V_R?<~2cgoo9gGf|H-5E0}7Z6~|0THOsL( zQBQ1i95t|!TuPG}!qUiS30pofTHJKDz*8pF7?&Y4SeAYHX|Y`!hC5CQi&M#dxO z4%1_<-e&yy%G6Vf-fUakcltl{cQDsZlmIo6QL?DS!sXnWVjq=}k0=A|^KAw;ACobk zf(U_bSNH`;%?$(^O)%Nu0~LnC3C}kHXe9`wNSGrq1f0Z0lLn=cqHL-$%DklgiQU!3 z*WN-%+ltiRx0pvn0#&EPkfy;0x&$T)S0%SYo^1{zTRlZ>cjNsil9IgoGf$%(32=cVJ@5RUvQw2W1OeQSx>aT#@{CH zfMYtmrpvd6Gteqz3QjkC-`yay4~zpOXeB)(-y>ewrVnbUcBOw!ye*gNoFZr&tJ0d~INfPv^L|A~lRlQ^mRmD~lkF+A z4W;I=f*d1<4}l(;$3;YR;wNrj9AM69!DdKxW|H^FfSBK&*FR-7U{+V^Wt(vKjr{8& ziV;sjH0PIkY|75gO!cY74$7w{Oj06nj)Uc1o`q-`ar_YqFu$c<0Zu{#gVj^q>CjE2 z;!4%opjpD6{&_j)Uz{N=tSrgJ8aRv6nDEb=W+y1URr;jdIrCEB5&JH%gnp#^(K<*FXdj}U~YlxCHunh?)+GJYeURS)n`pU_OiSmJY55&7?Z!pzr0 zh$rz%=fy_dhI=t1;tyd`?O>T zZ)b|3L_;e6bbs7Q{^6-z7g^lu?8%G_WcQZ;lgQF;B(WK8YCOjQNXic_L-xC3nvG_pDW7mkwG|>IiTu7Bhzm?vw0wnxpJZ( z#3*KTEa*H0+-RvujXpVQJ>QysLo^clK1itLSYwP0M0z-klNYMl)Ae)zoV7{cygDCr zbl|R6XlTc{Hh1L{*-J?3%TlYdUp64tD!UQ%&Uej7i@zTJw|5u>W)fxPTHi1!Bqs&9 ztR-VdAs?gwfJyXurSx}@S#$=x{)KdQd2Pik_erxQ)_oEkR}_pi0WGCH7_OSF!zvlx z(h_N^55Lg2@}6JHn|*+A0(0_>!&iNzv)M{8{w9;ap*$2^kpuv|pJ>*#0@Zx6k&ouW zQlHZRQCbEoqS9K5CXO7IbXiV*4~Y%4n+~czhLB1``n%CnnY>r7C_&VUZ#TN}EQ7Be z6ivo*stj>Z`aJghC#^w2mRSJXtfUp2XI~u3mudLE$g(qy>J0RkcE#nD5zO*ZDnJJq zqjpH!=yfPYcRo)23=qB6sBr4PVC5~cI6i=U^fz1J5-EVoB9{AoTE zITM0zjftRxrwvDfSBevZm-=<7Q+t*&k$^3q`XkV0n&vED*{Q&G(Nr8(S385jm@9?j zLw$-4Q6BRgVJ9>0`&4aLs}z5R^jS$w^5R^`Am_yxy7*sN#5pCN_$){wt7s4#_Ddje z(O=an1yRR1zAA;aCUX46&eELlpgaJC7ej}Wh8m@#N1EE9KtSw3gc_ZFe9uQrP_OO_+Qu zVlCCVri}%lkbf$Icvw1frZ1OX4rE9^TAL%_6KE4P$Y~;U&^HHedhlg&wrw>6FgMFI z0I%;gURv_AJe-~d3%&Vh76RD@KRlX=vTN8+HvZuYx=rO3?0r(;3^o50%wdy0Q+8e_ z)pI1lAd*N zR=@k_icTSZ4Bvo9t@`D3tuC_Q=DNJB!#mn$lIkQ3z_b?VL?E{Hf1$Rh7#Dez${8*_~lcHTurt$}ovPn}DWqw->+ z%}K8bowlsDV7o#GS!*x?)veLL*ia4zURdq27tb8s`{RTz$eNdg9{)woF!<^NdHI*S z@Nd8UpgW$!ziU*EX#aDv|Cz-0ztWy2Pc=dKq$})((>sv5PDCu_7*K-L$N=<8;{f*t zbF|Rv4m&)FR!_%@AXPAej}P5?0ZTwdtSa!hza$q#xOGu7vQK`9_2Ih;7r0NFH{#V! z4n*n$SW33Uyie@9-Jxl$ue*gZ7Sjw3i4_mOjGnCFB=Dx6|G}g$m}@s=|?mo-$hhh*mhc_5hAC_6Y&8zYZha+DAg|!LI5dsyP+PpMq-qalm;E}>05$m2sn%SBj}rE zs6W9BqK!CTW_s-!Rf>{=y<tMT@6pM9&!cQ`Tjz01nYrsWo80it`q%M|}qTT0Ld)C@Ysj#jDKDX-Zi z>}!~sra{WkR%{09DX>j>nG?{ScXc z)k#%lj~)CJiRZ|oYx(SsUh@l-WEpvRf6IJ>a{Uzq;tY+qj(Vh?1=Naj%p5kZu8A-uZi zNiod#i6w%bCRc)>OC;d|BKK`rt7KHugP!Hm@ z2ocLr1Lx6@SxdxCPxp$+1>tr8nq63Ret8+A7I10N7b%l5=gjHGVO(fH@ZA47F0Su~ zs;~s04Aojs14AhqM;|p zdxZrDRE$CiVQo$dMz8R0K6d~A&D2EUtjjhWbrtO(g1m@Z-Kzk?$D1%@l1@AL^q{YN z-wgb5_!OPZNW8vzQ814g4g%>qEUQIH`e2iK1LHfT$ozR2kGpWl^&Wt$(-o&yPHBet z7dn3k!27<3l9w||>;2<%DiI?*&P+PyOI4Yrvfr)-e?8K$fp<{-sn&zE6hyZ2T3z~UCZiomawkKO=?CNp&Y!s+RU)2R%<#GQijmjo8fY=-Dr;PcMswt4HMgo z@~HK^sA+rAti=&xNlX+oiBO$6)H%{ZRVKc9WvWAM>0$+OKv=Ez;Lp9ua#Ba zIi*Xl86n8S&Sc<4YTOc{`&RqiCS^$$JeVfy5VzWEfh=Gs3yL|d3~<2tAOR`bQ}5-S z0-HfMAgAMi|I(wS2nsDqri5jU+==_MqFhXlKj9$93#6Try|-azTS_3iOj|ODa3%PV zk`k4=Bui#ACNtSX74Bk?fg7~#Gj0X23T56Z>xVQgesD^r7!&qcz{(8!#KhysCgCh3 zd0u6qMaihU1xikf(<>wm_EQ5YQeMI*RQ48+yjJeb6R=rwAw3pque;Hn3d^#!zVm>J zS3p(TLPLzqKm@=%e3g$&S+hsZcBjOPgft(vOl#P7kj*(dvqT;r5uojI!Fqn?g9Pu{NCaWnEu_q-t7Ej^a~_05-EmC z^0=2De1L{#>l{toymQF$4i%5M0wciu^7B0>&zX%3+JNLikoFp~CUj z=G+dL)Z_;__y;K{`3);3H(|4;a?tKsVEZh9LDR`LzN$N_3ENr1je|^-i5Dn)c>H(h zjZBERxe;xkoRvy#23hABa;DJfR7}MsViw{(lQa{R93f*(6o+A)yhNxWf+bKz3fHzJ zKjgR0JQ+|yxX*(V-uw(o^T~U*Ei1L5{8QA4bEV{l#nHNP!gJw0Hgqev;YpE?dO!D` z8ZH=-ey_(QeqIIg+YLZ(W=)O9d&;*K_T$J_EDdI@!UFv55PLaS9MJv|59|Q`gd~Ax z(S{HOmAxIeNz37HfL88@h_5Y;JB0|L?z*hbTKUkisM@MRf{8zN-Jq2aiZ=L0eeC5F z;-encqz$Cz>x<-Z&<>9;y*ji&TZj4wLzs4{O|CiS)V9njn=>PHGjBnoEnQW5y zT~t)EN5=+4PB=c$rrOWVPP31JL)MdO7d1TarS^~6$9Zl0uU}6;WVuf%5lCSF@jt(w f<&fn-{T5{(Bf;NJ@P{ARp;El6`bUP`ZSQ{p2!G@< literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort.png index 0913912b6a332683a5d3a5a13bcdf1297c85a4bf..41e2bddbdafba1bc01a7aa07b7e9fa322e5bdb0d 100644 GIT binary patch literal 22119 zcmeGEbxAZ6L^gZVudCqe?L`F&&4jKy@1Ox<5R75}y1mu-AaDEN>8hEV~+%y9I zfZE9k^MRC);Ov2b5P*mZd{l7OJW7LdR}if4ZSy`P5#jUBlEp~yCZG(3BJcwjQWrwW z&hbV}un8j17E#d0ZYK!kef!bHyLy1v8Ip~hsDv0QI2$aqT~D;ez=wpIkYsz9!fr!S zq`-=`b?MvV^vSH_gvMZzSDd65dx2B{3OYKvUjVp>_kWM}18_d__Lh;vSD!(k{&RQ} z@q+e7@Pd*2_uwXa8kV>Kj6h%q z8TEEm^9oYPas3t8QVF;B5Fw{frceY{aCo@=oR-M`_Hd5}{^3y-=seO=ueH-{C@B>~@G?fEEGtvJ}B3L2_gbD~9p5(iKj}M9jNezag{l6Cgk#X`% zXS3ns8cApOORh7`Qmrv8RIb3| z=rfz<^1<0UmxwxR^V&mFhMGoD8XqjFfE4yqn9=ory~Dj z2^b^Jv}{AZWW3pXyt8Bu3KeDbc*`=xvrK|jW$KA#hR^OCp~ld z3=Q+ovkeRl2&ow5=cx$8kZhedBw35z3X~nLv|^vMJhFUyKIRC==D|z*;Lu5$pss6- zqeKL%^)?ga0>U8j<3H2IP4YP<JFGvboe4xZcL<&4KIoWSf zQ3IrvOA9Nt&QuISG6#kfe2Xu4kbLsMl^t0|QrUC-m2`BnT;osqj#N3-2o;N0CtR;i zhiXQ%%^EBVwc5A^a4eS^5k>X-igR(EaTs6ga=<_(27o{$sw(+9{<9L>1>drHJ#lht z)j?A!mA22&s42v^4~PvXGke{L?2X8Y?q)nWA*!r@XOP=`h~F;S|Ix++J(?lhCX6Qw zCeEq6-hq@wN+d>?OL?au5Sw~{6ivE91;x{{K0sw-*X-E%a6ULrz#w;3r_=S?TvXgI zoaQ^Lrt43GEfZvf`NiiePmd;7X2X%>fSFlMGkxe%elTuAUeImiAsqjImQ9PW_Gmg6 z#@*e)?OG6ithcG-&n;uud4s$xue%xrqOaj7XCDmo^<$wPsjgHEjGk#r85rZnCfy2h z)10RSR7A=6hTTYg0kc`CNqwHcTQHkQcp|J9<8j!Z`uK%R@^p72Y9n6F@?)Lp^b`h% z(_#DJd`*?-qic6>FOkU-+w@M0%LTpb6uCqSH?D@RUW7!FgGl?k7mM{x^805ly`3O~ zZ?U+|F+5l5V7&I0Fg@F;5XGgSq^2hUN75yCsQWBXCgoz22gT~51+FCE_uBX^VpckFXV-L13vCD|OF{nn zVwu`BhBW6-61?MCgal33BCMOSEPf0g%hdDW5Rm4L5stI11TEcmyV14bT$0PsunTzi zYcViOz!dFXVWs>_W=zQ7u_R6x25!|#keg*Mp7etsZ3?j%bG}%Z(AlYBZliuU&`Q_E| zu}4q&W=G@6{0J-#PEK_wT6Qfmi(1EhqrCzFb(51O-4e1|$LDjH6^|PY_XZ2>6)YaS z2FJbZuhDkeIYN=$fma7rj*qUWujljZjJ9Yd{gX>Js<@$?{eXqWT39XpkBdJA^=Y!( z)_zd4S_?qe>eh?m%5M=A5|@&K7mCElLQ=Hf9Rm%iXbt3f{y7@QLPt){I}k(aY3 z>OM*|YQ^G7ecyiOHw^1OlV}4mBvD79ROBBYv`uunP*Oqp@v<$$Gc=w?4U0vJ4?H11 zS6f{UNmo~w-t^LVtJPMi-h4hg#zUl0TTTwC++=!y&dFRfo*z-0s5_okEgvaLM77o! zF%S+nG^xfYN3SoE64%pww%pmcpCA`^X~*0(-sAaLiIsq|y2@Y&-55Cs1f~`>r}dwx zFTuI~~=Dk#MuS zvY|a!_M~M|j~kAaImvh@8Iw}9OVna8{VQitC#2WCwWe0D1o>g{!}9hU?cVeKNt9n$zpyVqj4_tOz@Cs70?8-vO9N{RXHLqh7(HX)GuXpACFc3LPiI})Kb&qv1vbY$x_P9q z>`s@Uui&tjhl4a{S*TGzY$C^%o#o8eoQ-Eo)0>Stc6q3k5kVw2DKY6^p=+T?r`&la z(bc=SxZK)rLG#Dw7Zm9A54LIf?v!>fdu4nj852q3v_X<%#l9EsX>91rF`3L4`r5#I_o;x-*lI7*JXL7IMRc&t-zTZF|APqj~1-67^U_4pqT%+wOT z^|nIS2`!b7EtbsBv$=0Vernj(oPKT_X@$OersPphdxp`T_EJvs&>9abGdO7Dn-K6|m(M zF1OQ;aLoNDdMMG@8uMgwyF4vKe_X33L5-HuxRix@#RLwoI!jzb_glghJRUs!p$Gg2 zDm|VNbkwGaR)hUe5H;o#WO2_1mc^Z7bF3zK-DBUM@HbIN+Fw@Ef-5U4C&W~fl2op? zO!-r!1Y+D}uqd9;w9A79y}V>0Nz@FEBB1G&8zUcgj1T9ka>7BxdGv)-4i>B{_Md|6 z0*Y9_O<7lfp&w2kn&&Pa?S};@-8St%^PpK*C{-#;>-%MtpnLkA_3RWgj>boyD9XJ% zIhA$iFd)Nod$55Om0((cmH*);9q>q_RRyLjEQo3OPLyUdHIC%bx?w1V108wAMOfpS z+R5R&D!rTQhZPJKST46K+dbMUvro0{ampG2s8q`F$#y$O4g8(RUJFgg8MJDF%C8Z6 z{X>wepbDZrwriUW-`I0lLD74bYu+}Qig<5rZlWCYDD$4sVp*AhH8nLEJjrP9eYdp* zmGpLF&P<>y4Byeb8nz9ai@Esp2~y`LeP>wJy1EqJH_U|aw(m`)PCuBJrq{h5#g})k zco>b=;m^vgJw(X4LgT0g?lbxjModX+zB8A7ZGOzQ*O#`bhA0 zWpBy|e^(}u)?jxen5b!s=bM+FRMg$9dhgZ(S!Q)cT3iB~S1NU0rMs>}wIs#n%8g^w zywY+8EqQu82}9Cmh)?|yqX(Xqm1UW6^0e27uNVWDG8{OM@1_1BAmKHf9Lv+`q%@oL zD#-EI4R}})k#;NA+V&B>pa`jHxhrzOX{MrRZ+}Ag#Q!_Mz10T4T=S=L^gOXUX!ynm zx8}fq)?=#IC*0kh;q`>cbOLwUhniw7++^2UozNyZp@f5YL<$UQtl>0 z()~t*bGEGwx+69wEiJ+;5(@&+2nLN-plqRz(5Ul{`|@q_3T9ZX-#w?LIDx$g;3XBa zK^SLU$FTmy{V&L;4XczaVc#BJ+(puU0TVpfvojd6Vw729Ypgj=A?k1XmP{;j(VF(q=>GVI$;S?3)V5qlMzV zAbfZ4y~+HwGp~nN(%e@l#fl~Q;3`4zxTn19;wtreDba+~%0WQb5dYt>;Yp^=f{?(7 z(~L&fS7pKTmAYNmsuk6NpZ`~QDph4P>MFcJz~>Hch>1B}cKWe)1cf|SuE7!I+Ob(} zHC;$a#I@8%(~TGFY1XxH!(A4i^o-M$N(2CXq2~RMzVMO9j3^!qpYh_V=sypn zkIoQy$WyX-KGs1uF@6d}zz#$mOxW1!@Eb3%(&8T$zzEqfnH$TZbXz;%4_g0vP*K4Y z9axJftEi$WYd%f6{U*Tg$fvwas{gFED6U-VsY7Kh>%(BhtsDw6sc2UW(VB zxeZEBgCV!(O_v(q+e)P?cnrGGpV>1TkAdU}0ohQXoKz~C&zV(gz;ubS-v0eb&a{Jt z_9&N$erS9NGV1)CtsV3xl&m+z`Tn@$pGCqC4n|WtHkK$@E**PCeh4%B#&oVI^3qHzhwGA^bkUni09}GX zr|o_-nV+>h%&NDGZAI?W%Lisizzb>^sF(@&C+Wd^r%g(yY+%jcbkr+tho%Qq9F$Wd zakh7tCY(1zjA8;nH3{W`=PHtxFcI^~*ds1|Fvgk>ijbO;ucOJ1&3^Z@n91`|!w=mb zE3E@1r0c@SN)v4;h+@f&69RFNlt+ZV#SbUCe!=;WE&>9D8Pg|-i2HS~Nk@T+q)V%I z-hs#C3E9WkVz*`ATGGHUqrD_1hLBD;nwDg&G8T;5}zaR66s^3 z*(~k!Y+{w3&BZV)_Fg1VAsf9^$breP{$M)J$=>l;+;6`asl$c^FE}8|7SL{*OUp{( z30--8bgA4trV@=@GmReWkW67&(+We=5&x8oB#E^DF3TU)rJ$C+9mp!<&xGO-72vS6 z&vQj@M`yLLN5;r^>Mwo8Jkfj#ffCf3Jvqazr2NU&4&y7iU_n9v}?kPymOnbCIYTZH1qnW^(JZ@CdAg(Gof zi6l7XK9OfazX}hQ`A#1m{@%75(xLaz50laQdI*!WoDxZa2qX;^F0>!p zm_{@lR;H(O<9TD%XKzdZ_)D@;H2#A^@lt?F+C%sy3?|Ll*3t;jlfq(TB1wsS`dL!( zZNZE~d`IdaF*fN)PFj5EPmo zzjIsW&+UysfrljwYE&sAex%9CB1!+uDE)|xWWDS#TcnRM!ue5780JX6bAMNME05CS zXzo2KSmKv28}?`WfV~OPoA?%c3J3&LBuHPc*@Gw%fWiRCK}|c6E%e_Pc)JVk+c8M$ zTf%=)G9~9=>=^f*XWJ3VFH`K&kAOn|5=Lo}Rh+KV^GF%%g!WsNnq?|)m9%T-8G;fOx z+X;1M#|(+i4vE6mND&@RU{HS2*{PO2D|z zfxxef*zQ`<5k+eljr2C7qv0*a1?GqmqcD*4h~cB!g;nu&lrB^Q_wRAR;C^)v!jK>X zKl8aZQGaz|rvZ8bFpx6ds@n3L_0R8zMv{*vBrbJJT_Si|)b2+gkGUpcn(AcDDB9Jt z2M1m(&DsXsSJqlkkR_1w#g0YV_W>)TuI#L8)*JN432j88OHhJG!QmCu2@xug0yT_9 zIe78S-Ur|U<_2l(0n3=e;`rq^NNhADsr1=W8l?5dmJa-@7*gUdEs1u1U^GtfiHzl4 zh(v!FZmcuofNf))&;#kRw$*SIgKK&3pLP!HEWm)%kh`N+CfS3gcGNuhN3iIv>PlKB zBXo&So7>x+mJP&otg~_$KmeL@@9gZ-z5CzQfIVW!~H-uUpl(7ZYlO!8rwa!DlC8Q6xmAt`!pUkA=ZiDjL~< z`k;}VgQA@lI)fdnnYcYw^*Dk%E#mvl%P<6EP{FH674h7;^kX~v-JTvQgmio?eBllv z1gB8BdHLBtx)4f2QbQtzEY)#F7R}j^k&$n|Ob%xzFPD3kq$P*;*D@(cihd+cf%9sE zBoqQQ^r2aYtJ;jXB-J<3?&SSlHsNpURAK<+dG;MSoeJq@|}Ze zMCK;W&4_B6$-cxQpIdmlil*ZoPdOY zEyI3ZZsYVyO2kNC&zf%j$j7@3I1n5cPt@XM%L2|ax|j_gs&k|}V? zJ>8jh_Dn<;EKKGL3S1mi#OoW1afq+|wF8$UH}>{KB*nYprxf(#<_I?Wa~wo>H`Q({m_UWzmOe3DCPbg;rC zrRau%C_^<}<3Q9;x|r-xNT--SmQ_`An8MIjYycH8O%u9xe=Eeb@wn>Ov1 zeN~tCIMy5Cb5<B5}K(t7^e^8%1B5S}#Lc+E$S5Bu$1 zq(&Viu+d=Dg-=c(m%2sb-LK{{5?(hMt7;`HTSaaoI=#x8eR{H%n>q4)-G47Sy^q8^ zEQ4+2aqfY1`r0SOFz&>4fX*r%a znm~THpJRJJPIHm~yJ-cQ@6v(e^27vseU{1|%;Nk8i%XlmDN2)1hgvCO5R3Dc9@j@b|7i~SAH;?dj|uYjEQ zPc!8^ngHLws(ojCWIww~~dtkT?5< zl8H`05~;4ly#|7CcRXa%7=V4%?&nvHwEzL9Ht{1j>SIq|OAu8*>#G83;9_qN!6XC{ zb1tlC-P&17wX`0V>rV!#?KCZEHSwpf_pAT%h(=4*@lOSa_PgN@q@F3t5P9RqESWeF##-D6|memaRv|{1>P^M_7MAyDqS*&4# zYpod_|2#FE5_Zo$*F5yBrdX`daqQui_V}E?BE8&#iEwoch;Z@hO=qDB*7>=1FeIbg zjKzZSEr30s~W0%P_29u?7RI*Mv< zNFI@$9PUe?sqB@?O`nX66sPXbgN9vT&@qZR94|43Qs3uHe0_lT_P&E(EjyvAE(m`b zPjzEv`&J?6tw`G*I)Wbm}N+bk-|J*G)HRZC}y?CXjLs%R%b9H?=-v$Mh$Q~<0 zB;Ku;kJ_YCx4Oj66dcY(D4L8i1h7qp8}59_+si{D1b4zjK(fnx{qesd`6ebs%kJ$^ zPL8Emc{Q6yD?%g=63h{hLnVInh9Gs8!U9lNU%#FDMhd`Dlu7{M)6b|q^r~Z3X@war z9UCGs06jt8P7HXTf=J2wi#H@S#V0a8Nqv*f!C}k!U)eoajCV8G;r^V8eJdp0RFD40 z%h)&OKs24n%XOxOdIO=t`@|#DYYbi4uEjsn?g7+n$2Bn9@j#{k@F(V}iH&M~lkj(> zz)0S@gD;_KD+9T~u$N6lBF8L^vEf^7TZB1Q$&__tIk^BkYjzl*F{0+yp%6jdE>VZW z)Y}K7mhP}ixm|JS3duWSTnS4Bc`lU_A0UziUjW^FGQcC5r6vXs%FCZ+`H6?8NiM*G zm3o;|Uw3!Qc(bdOYP)8DQ70;;*wIJ>H;LuON0-Soo{KJv+S)6_YgWo-1i1gV7{7y1 zn1|WyddpFiKKDpz1rS$5=TtZoV*P1tY(|Q;PQSGQ`7NFp=}xAk0i(1~$X z~@IlvByAv;X3e^C%o$VjIL9V^!5{n^=q1m7E-b<~L@u+4z-L z+u`pa5*hhGPq_i+4>gkHC6*5_y7rc!q>D^)f79w!3^*dHPg!9E@ma2wRc_=gS`6-A z&`)Brx4IhQayc#oGScTb?L#SL3%)vec^e>n6MvwEr{iD~Rvh1CJamkE;FD|L>F#OT zbfK!9A0uJMq_JRm0P>|WT;~c(KU$+U$NW4+$`8z-@%0W=;hIN+poaTpmP2f}xngx4vywXIzHZ;-^3*JP)JtU$`SIt%qScax| zS;VI>+ANI+ZHOR}-(3bE$*yDorGb^L1`QP+n9dHVOlHAecxGjOJiD~t(wPv$O@Uiu z!7c|f(Gb#BoyQ@i5EihlMxwjRM*k>;De9b!q8#I9+$nLp^5PNM=GM zRxVuTBga%aM4qR1DqnFtqDEV|ROV)kGt!G3kc&P_JBj~}A_JBTc~3|q301kI*}8Nd z2(fT^wbE?N%Bi*BPSFl#v1LN{uR8*2-X!nf%Dk8?dQynKLq~ghQ3n>0HO}bLG=gjdzl&#sMvRzQ14wbuKda{qZv zOb6EYUPAEezwP=j#0CUPC4g7N)6>&NNGMQoyURr-k@w?AP@s<%aC&MDGa4gb0|t7m zNL8w9J>&yKl$m+xnoZ5RPRiG#IHpsDKK=b7LCEl;%PmcfCw{GdL6Ambzgt(oZ%mVD zEK5&#D2ZpZ3WUS+!TAheo3t`up?0hhgCRv35a1>4N0oqoe z?LAGUGGBxaG`?LyDVqV`5eSF9PM5~P0U##8KTYhkzrDquTYOOyk~R{&mQM@VS;=|_TT&qQ~V4Lm6-mog*Uk<_R22>=zcmL}Zs6+-R&Y@zI{XaI&A{&zkHEz zxeKF{Fk*uv@;L_|N#_dVe}h0&EC|y{2r7@fs>ytHKE{R%taZyEUc&ZPEOIJAjsV`S zK)ADnku+SG%Jubi-E5-&UuAOx#oQ^kUgU4n{9~4(AP^X=VE=1g|MwTbDm$1h>uw10 zyQz)CB*sG35;UNn66kuhPe?-2ZTG6`9nvX1u-Xw`894os1vn{3z6IJ=p6Ckm^Zg?u zN<0Z(@i&(hgAl`VFW{Zo0?Kd-YoEn(bBx_bRgv~^U||n6Qr3q2GqKdXyvHYU zz7$jkU>_Z-!F(KmPC-EpTGe!=EHRVml*n=e3BsB4(P9IFNl_6wB_-dI$Bhmz9~d7$ zf7*2)G|8$NutvX;jhy}CMF1kTv5r@=Q*n!Oamy^_^WnUhky@TuoE%|ZNO3=sjv{3> z7PDMdK;%oWb0m!;sMYOeeHjY*g&%c!FpEG3kL3?EuV2$!BwGpsqbsQ^j{HkvSfsaW z*#TFIn{g8`lt+(%5(`>qixpvjHgoH_Qb+ zss0?7RCE~kSrCf7~KKJG+o}IbSLcY@?A>S-z6WN*OM3=d5e$^s>*Ciqj6PUL}Hj>9%K7d;;h!O4|i@&C3fVohQmOiZdHL-nqQnkCabbAXZaE z@v=FXoPCy*NW4WE$KZR}rKBXW-Mv=%^)jTWWJs#-0);LW0x~AqVs7yl zS_}Mcl6Mn4-Aa4Frh^a06S+`$9uGE4wu3ZZUEpj-g`uCrzMwn-yY7zVV#fJ0WOZerj5;t�zoI~=eIEP3^i|B;#g6)56| zFYly#-@%}*e!D;EvwOTx2t~@d{?1-3U?sQs2Wnj{0Xc+g;pM&9MlcA>_doj}^x zZ%iS2zxp0OAaS@{QEskxvqsn=FxchNqHOc@ad;vVv|OP~OiUaPKkkgAjdvT$ z6M7N_7HisuoPRLM@+G>9r_~5WD3Dez`e9`{3lC^cRxcti$SuC zokI(6QHI0U^$Sl`BTp|b%4(ZT2~zUITp;;n2)lLN!7dpJyr72yjH!w)N!U9e{Rz(F z`RE}=O8Az@lmpE$Qb6q|%bn}p%|JuNA=ejbx?#YvRD%4!Lq9eQFl0xfy&FglE-HLw z)Y)f@Ev%<7%##71Q|n+w8ta|d4NpoFY#sPbAFB2B4{ zXsypnVz@H9)(8ASe6>zlOVM}Ni{}xAMy;O7Jlr3WR#LR1F_)yfyIXr|cYMHYtJHkH zT9EYqvvo&qE{XbNah%riTnu#(QM*7ejYho$DPDB7@i-AI_6HP3qfw#0NLv^NODl_FG^!|Qof%Z$UYt_x|EuE=CS!1`22&q;hTP5>_ zsUnp|>nv!emW%S{)cW_jVH^&dL$imfHL>0g`r}0EUR`j-DFEiQmQ;|=H=$;gWi*=J zc)Va1C*p2nhgg~OXFYYxd&_Cm|wscJ#pwtf*-G3-*4|4eIz*!mU3(~eZMJ}$$P5tT9@1DjZ9R6&M^QrgEaH9A6JkkW{mUkW5X-W)G0)}(Pb5tSQB z!@BN~a$a3d-kJdo|LDF#%t?B;L7^NCwQ{@{DP#XDC6M_hK(d`zhOkl5t&-2F^8ww< zRR$kXZZ6Y0A&=Liz~n4hH%7TPp==Qu<+G^YW@DYXH2K-Ek1t5!uPGA2K(Ji zxv8)S54W4%ingav%)$8e$6+nZ<3&@{H_NVXkZlr;Wq+~4(G8#><^ z02!3?U6Rr1dgjNxqs=Adn?%}xClHfw^X$9bc~hI4uMMvt05#B8jWy>iqIVKv}v zpwN{dTD*42(x8ST4prHTr~%xj0NhYIp0fQjE&*lz0e;n`JpEACKVH8Txr$UUy)I+x zW@FJwd*|I?EWzF4vJ*DmC-6jdg@=pd<-kP|K}1%fOM%lSwQQ?zm{|@7y5A@A_D2}L z_mZa<^Y885t_g31Fz7#P{>X;|GROedz6dJfc1z<$G#H+r0tRLe#@FWVwY$he3pL9c zUtWE~eX#@je~8cst1T^@?q6*K2*oESC*N;w{h;fxQ(8Z6lh!~o&Xq`KgDOgic+ArU z5a{t*6M5q0^{f>S*y%8nA9$k(?j153@^h}roReeNpJ0yxWeVV zF!wk;Ggn8#j4Y0hGa}=x+Ig<@*amBfNeu48_gd;_k#Qh-eDM8w5nXQp)44y*xFi+x z>7hsz8TEYEa&Nlk-SzRjAA;eK%uSG}NOr2hq(BnYV<^F)^B~Rsx=v^`8tcTuZFXEZ*T^NQ?^#N`-(ti0rRtZh0*03AF5`G%^Uyoy9O z%X)u9Zk0eq`acBfCHsB1lcLJDEh?qe{X+7tBa)(k)S8%F{Ns2RyB*z5j+4T{^sRDQ zb{Iox=|1ePz$~K*P1#`EHmO5LpiIlJSQM@JFob!iT#^+|)l(}C5FM0y({ zmNlm8(NxFTLvPC+8qnTR#mtADV!~hLS}D2~Xlt|YymKJI>x+Fii(?`1#M##snR@wI zH>4J35qSY@raBSl)PxZoo=?=QtPMl>+GTb7+o=(dAvb{~jjRT|m|7BHk?)5z1 zC43z{@G>0frb+t%u)(u@7wawT*zIL`ybqfV2IF=1Vo2v64*>T0`zC=qAAoQP>;r^d zwB4Vg2%d|fU--Yqst&rJ0XlA@kuP5rx0EJh1q=8;q`Bh zHK*P3ORoa^zT!exj4^LJVN|Y8ytHCLzElBQ`23p#0|UQ$z@HW1dnt&r zn6qFTdOg_ep=e?;iOk=2N%O3=`@CvAh~%IrAOvk&9s}cu!e#lOC_e3$tMSg>*fTC~ z8>RnC76{Dd^yDJIA&HA)n&$k2;tM2>>uu}pqG3uQYplFgM{4LgBQmoQw@nlqt_SS(TDHhACbaBSgpgKGt8-3QCKLl?8S1n>~yC7{6q;Z zFXrgT^2Bb6B9Ka>()hN{bT%**>fnBi-`LfNdIJ9VqLIdDjPPZfMaX}mOc3}GS^K9$ zo*-H^KSs}t#VH){%dGIr_#{2aA?*ON#>*92t%W*|g+8{F=ztRqwgghXJiYtt{U>Uu zQN~Y(!>L6vpWNB>0>2_i#K7I=9R6s-uV}l*f(L+muRHr%^Le?Xs`~^jdj0;lTd3IF zy5K~_#ERR!94B94aPbeqnA?sogPJ_?zkm&$h|BbXK-1fm{n04J3mUdc1ZBL!5Lz7u zj>$XBT&2iO)54Q~x*;6)`Dzd^p$lwFsscz$-kY53J788vSKD;GZh3D{ZrQd0&-vU5 zLz_0wFwqwMAqHH3*Q`Qkqc`Fu874>2JX)wzoJ8Qc1(__6?Amy~eUt9KPoYqv1OUJA zxF1%1x)UnR`&fwiRm$Q29h!;S&Z_#&R~EZx7?YRbK8WG z5$u_!*3C~MfUAP_Io}y@zV5^lFA1TQCK){?iPi{9*qE!w*Fe**YFG*Vnw6D!zT##) zQ<_Bh1^)keLU-N(CGKp^yM=m-uv_IfdMowM7|BMNiW4mtTSqg;(uZS*lfZVjFRrO57NLq(P$QF!+SlliVpT(KGAtg1n!YEN;ZARS<35BqsAz3wm1wTK)sODL4%m1)t;jF$qzYp%G@2b1FI1asNna|;6_2~jiyv+}cdTZELzB_g;z)&;)|#sd3Vi~ZwsQxa+nF)=aGAt|AV6<(kR z0ASuft{A|ZCn*%_Qma=+(@h7#Bz~Vxf-pl$Y=X^l1AyXAd!%R+)XwIRY zJE6Gff!+hCnJ_d=AD)TT+WP1yGAN>75RRN-g~SYfW_5b6ZyzSF20jyt&0&a^+H4PD zmi{~!r&euIfnslxR}zTHjZe65%0>98!S_l~Wx81L0L+IpaGxJuFgQeVp{At(-Do1? zl5}U9sfx^~C7H>@ck!!}Fi;j!T!EmWplGjk2HXNW%xjx}8p3*Pz>$urh_u7Lz+aWn zK*a)R<_)Mvz1!uim>sqTHE2z|^;$WJj0D!O9a+vxedZ}ei7Jb`zFi(|5Ttak6$4(RURIk<@KV*9*I7C`joZm))*BJ5#Wfl_ zSy_}4GX8OBEGpwaso5vYw&DG~O4A4paifpVXlf7k~QQiR|ZQh{WKe2TLT zVIbq(m$yPk%%f3;$9Q#I@9rg@AhowQG10~4)HY6u2!3uUj~7j9O)V?O;B-wBW%;GB zSai0b(R9YwGLa^eOiA-WQJqVf=y)@m%}{SdP!bnnF|`A`6HhZL+E`MvWJfIaAmSdV z!DNwDl2>h+c+LVfJb!LAHVY$gp6}*RUPc25nh*d^nN#t({Spll%6P~6QY#(eRjUbl z1Loxl!=7lyF7eoC!rrLm_oX3g{Mnu|rL8gpnz{p6{iDl+cmMx*=)$pMyzDikgziMi zkvQzx0*TJKwKBY@uQ3p_VstPt^)`bM_rvGkFdD7`u&$W8B1xeD$OkGS>K-(gZ?&7M z_Zn_!%|zHtypN~WTQ+)xpo~C5!MIU8M)nKm0XU|+g2^jk`HvF%<;Y`hBbSMd7OLi zuw7D3v{G}mIIwgW5DN8v z!XtWo^Y{`q3G#miU~)0=AY`ap8*h6%bTT0yR5gNVm^E_ z&OlNUj-sSf+%xNoEPC6Xnu=5KtUOhsToJB40j~HM91N{RmvPv&2U5xlhW4_Z!$)uv z)K^2pM20J$X&a&V|$1{0PPwI%grLd@8>@LVVk;RHELaldLJ;3*^# zP!AG7K!&Ctt5=dytO zeY*Gs>7zjgBTuJ612p^m^4JLkr^vtBiokZbfp?%;4b<&uW5U~}c(lYJjPCkKFMTO` zOyF`~Xds9G(hVdIn5*pdun!lk7Hn$XMPgoZg1A@ypk7)HF)*q)U^_LN)wXhf$@WB) znMS2ojo?-0ebaX}?LvDp>Q4;7vbQfA;CTxFZbJKH67td|F~=`x?KG8sjH&_fs4-+9 zsrCGgc;h2yCJgnpFJnY%(z0e&K>-n)5RC9(rkn=vVV!_KPBjGlL3Gt!hwywfJs@|~ z0I*@?m&aC|UyKqm#TKOuw@4XQONzgJ!uBRY;rC3)Xw~qfqU6(gVpph;UtHu*`u6-5 zL=mLlj`>OpjS+Emr#MN;ubz$g?Q}N8Hm&+<<){7uRI1R76P|We9`}sjZHx9G@M5Kk z$YSQ=jhOvuS*}uAQ(=EM_sdRSuuY>3f#qH}t`#Q&dlma~5Toj98`={T=yNFu-|w~2 zfLj8AR9`8@{PwABqzYtkbd+wSzaP@OXslcNos5i(H{jxn#EF1j$uG)J%LgBe#qV}T zHUu~RuA8ZY%A?f1P*Wwc$g{#MA8RV__B)W+UikTJW`g2A!1GiH7#Jq1K&WQ4BBXTx zQUve{%FpX%QoAIcFMUhc_QovwLQQT{ina+vwK;`K#l?CB_{#RnGim<4O%jhVGlWqx z(Zu8|&+g|uw4i@HStU~ksczUWa~^sj5)GB`FaEV^MB2r{2iyjS_PI*>Q}RM+=(2Pg zUar2X_=3Ln9Au2#pda>qZK;0q{KD1*SQ|?WB6nY|ss9qOLzwp>_xsS5PQxlfi=G|+Ex8w)J zL#Et=G9F=>n@oR;^;e6w-3$o3ErBymxIDkv^4_lRXIgskSIQoDJa5wX0+tpE>j3)f zxPiex2sdDYg)a|BfN&H#Jf3493?eG;9?Xk-1@T5kRwaA92q=e1dtCpzgTG&8*ntHD zbNIFuroTLTYMQV6*FfQjgn<)O|BXTn7+|vQ@e0dPt6ibn9G`VN5w5cjlcq!M}|W=sb(G zTQ=y40c6bl+*@mfXSiu9TKHCA_rJYF_;YyWX+MfKnu@v;cw&u-TaL7m9zcryy}*#@ zv3)$x&Va{abh)I!vD?_NVdF+HqM?vY1KbXAY2h+}$&s5&&}|tsY}l1tXEt0<0&0Z- zq0&xAxcXmi`^%7!L;%fvKthC9iO+YD5#2_fgBdkp?#S}SrV0+mf@L}YQq%}c?hsB~ z^rPRVerRPFgw{tlXnH!{D~E)?h{Ln$Y3{o5zqW zAxv3ILJW#ZB9T2tmQb=~N#;F6me=+EH`lqY-!i{*?)%*5oX_`r@j{!b8ZTgtZ29Of z^~Vuz$FXWh0|1-5;QslFiw;P}If#c5g7o!ZQEK!jxQxl2DupA)o$d9KQuE(kMLoa) z10|DJlhvZhG^6^tRiHC}_X9tBblz>1rM(oibLv2FyuWNtRBYJ}p)1u$y=QpFt z%vEYyf^lf|7h@PX{F1IdGtggzw%6VZ(3Qqyn^Mfk6FcK_C=KhRc3o)$X?DC`qj1$L z>}J%DcD)phE5?Sp^jHUQNB`MP#yqjSQc{iA(@?|hZlkR}*%O1jJr|y1C0eg2+ntI) z#2$!}<^oEpY4UPP){|q6@yAvb|B~k2wt*rpL%JX~*K95G{1OmY6cs zP5=Z9@!7^>${}t$fm26@_A_gH0Hp#UDk}WFTT;`6ER6&@l732vukeHnyfavTv~)SZ z{*|0w%yjUUexzjKa$~kNzJkT4z4V1*(ICGM$p_yiGdWBIoS<0ah6H3IVGvJcTsq6% zk5CT@@{sOrY8+BM)_RA*AcRqlhw@}OV7jzVAaGqYKEeAElF@A7#{paK`}QqqU?ha6 zBYG!a#=MqcF*qOJ?MGzm9xOEz*C?B5s5yDY{aM4`s77I zR!OWPk%ULKPxTE_g!HkmYf#!VgWp;gx=&KYYqWhN3!2>frI96LN(B51aZpQzf!5Sp zo5~XEedYA(1ZdDDfv@f&HO@X$X7Sl7W!eXe1Fqd15!doY6a-*Gfx(8jG-A04)8b$4}X zaCT|63?;7F$fw*Y9Dli{?9F1dgDDA0z=*U)a$2WfuK@kdd(ZM%=BZCyAr;@Mj%tpL zj*%D7U*YD3YibJojl**n@O5bIlm7<4kuzWFG<%`DBc%2)$p!=P?$(0D7up!IxUN6l z>#ne;VasE;-?=%q*8la^SJTGt;9(}yZjtyikDul$_g|&_4qr7& zSL6Xp&K!SM{_YsMU#uDPk1CR>{uj^>j*H2U`U}_Wl@>B->n2<{mLzNGpud)qQ0w;h z)D|`I3IAA==*AvHM#kNGW(w=udzLzOi0N8~Kg2Zi?`z4=F$#i{15Kv~#`m+_I#Z(f zWt0RfK|LV$mAA*9hLv>ZbexO!%h#(1t{r>@Q&;S!{EBcw>Fcj!A-*rWsIW0-iE$H@mW;YLo12dl_IWbX0!B=yxS2CWbg4j}^C*4p@cWuKutum84?9YynB$&F z$(m!*z7!swq~LR-JaT!~@6M45Xj|64xQc8gYas19jXi_KTr)MtVp5A)SMwnAG)^qr zxdFxw?Po(-p3;@YNg-73O29?(LaSQ-z185`2hR9>rGIxF0!9UGzNqa8!Lfm1*lA+? z^3rB%&hR&iw$od?7ak1KbFPF$=n}T_$#of}EQl`yUR4Sl&G|Z9=Gc0l<3rTTEz0`5 zflg;VJvKw|J9`;@@gKfdVY%0Sg2vayLdpvqsznMdytIZh7%I^NLF`5!?n zfRu&XWVHmRAp8XNPw;CXmHHwO6J{hHNtb&o=2%rGZT3D{TuhTLprDPp!t%>7`$v9J zXKa6v|D;9pwlN?SBW;m{1i9nm*=fIq1h`|d8d^PE9L}S~lzhIT5L3%06yul5>|(E? zYk9dW)6$kOXH+S*h6WO+FAc0CMt*)dS@X|SkThd7k?Y?>X#CAU1ellirzEqwYi;(0Mj+x9QNqHv#pEneaggHcf+XXeWH6tZ6B(yeDzl zokM{6n~TA3cXFYdpCa0lJlj#K5v<|DlH~x4Oi#lnt!9Bw;${XEi)=s_v{id_zygG| z1pB_Br_l{exlzTvuC9@Hak>hr#te_|xw_`e7rK^Z1{p;kJZ1K!C(inVo|!%mr_!0j zLHwqs5o_z7w!Ebs9kcGQ0|Iq&!%iY=V&W6xlHg{se$REUKY+}0BPsrh z>h8)v@AnlQ2q-6IUv{jiq(l!l@63^~Ath@-)KGJcZ>_u#HKn@|zx6wuFUXo=h(y z*hG~#A#OnGf1U%=gM#|(cN)? z=4PiGoOMgyg-7QaOH~t9+Vbqxl`O*ekgiT;=dYU`Oz;Xg4-Pe}AxRFq`BiHimc9fy zh85@KjbI1vUUY0mO_*L-^iVD@?nxY)pm_8m-G=cZ_&$ zM$C7^x>Ohx{RS*TC(q(IzhA9S79ZMnDy2fYV%$AZtN_wog&d9e!Mz94738}kum_|D z%j*A&nAS4LF=f?SVMn&zA2zutC^I+{&aiPaN!(dNP(M!HXXv`n*`5PsBI!C9;2aA< M=$q(0K7k7TFKX##kpKVy literal 222968 zcmb?@cRbba`+rteB(q3pAVSJ0q9bHwCL#`%aztiEX2_0|MCKu*5{hH5NLFR<5u(h4 z?Cp2Giq`w{{eC}>_v80ZN$1?J`*q*fd|uD%@>5fhqoQD@*tTsOm4dvC#Qko9v@gCAg^zYW!H}3Dsyu%$IPb^6J z42za|cgI(r_T8O5M@t##kB6fK4cT`~eIS>TA(lC`TW!Z~6!8u$yCI60peVf0EoONm zzeJ)a^SDI8@l3i;wzU!q6Xv$|b19Cw1ub)$H($A~Ezg~m+D1T3gZfv0WN^PCaQ8lP z!{+e6U4h1ukeJzl=3hRa2E{%G-_KB~CE4}w-hc*m2Srr3jgXA}&cFJ@NdFE>y0tow z{a>#@gX!DzZ}+~<{Us$0rb_H2lgz)mKjhd6sZJ67+qY*AwuSHOa1D9<>lIK~cjJG( zcj63w6qaLbP><$ci!hnc)Q*37_w092tt4bZM$u7}`~RKvz=Pel$NcNP(^TbebN7B3 zVk7mh)sMaY&GG-RcY5D9<$iRj*WN!~@3}SB`f;LQvY0ThV6`AH%e1ZYYox`5sB^E& zLRLqn@lbD|QSLhlr+J)|=k_J-+arl#FZB!T_7vZ6jduO^`JGngb>)%9OiFdVSYX`Po!i0gnK3Gdd#rvP?tQiHT<)3-q{u&`w z!?Gtz+M0`ysygtQ`(GcuLkvQ(H{lX!cE0RMwk^$8(*RSUO0xCOtp}2^tFeO(vQ9Zb zE+jLy6IP5S6FMjwzy0qI(!yEW1e=4xj4*z2-clHp0-}KoTmSsE6_h&}4d&>|P^_C- z*Ug-))9Z_Gb#a)>$DThsgXM@=by?^!etI@=nzz^bJzp!%qzOaHq>%c|-P@!oNhem) z#W^%YRk9=Belq4lqTce3>vI)(yZ_t~N(FhqSZ_(m+(b{;T;=RY6TV)0=SRQd>cq1N z$6Teb9AS<@*_+CNild;xa5u+%DgKA8#ty@Qg?|hee9J6qKE51-l5TJzrkMABx}DjY zfIUpoGp|pI<*#pL@S?D#t+59l}1gICiafwaa zKaNN34xIUi?K}6GffQL5DPiNbu}$wUN_3_W8f-LvCC|oW&hm#|ao=#ivQy}#LCL4= zURS3}#m;$7)MP^C8z;WMY2337h5oObK7?Hf@hQX~ul==W_^10hu(wCW=bF#sy_nFJ z&BV;d*2=Bc&BzDO!)Zx+c8s#6dH%XXH;o|mb_{=&>ZSz`<~<1+lL#T z;@|E(jT0zYZPZHBGuc?_-7p(V&B?ye@HTb#Xt55FF0&9#!M&K_Pelb( zdybW}=3IG4;k3RqbhG)H`h1UlZ^zEltA?RG7cxd$QZ9vXDvv)puk!ja-zCnXv$+@Kr5y8UiPfpM^RSi9sFOD1_fN0CqGlD#UFonWSsM=!D3*6Lzp%J6S#onA zP&7z0r!cfNP2V)qqBzfuIcsL7?zFwZ#$20$h{?p&+!iN>E}0RDX+cWSYNr+ zm3>pcB;~#aUkI0KHi&6gmqiJFc`3}m)e7J4x`MxXUt-=;YG((&aHjToOef=!i-xKa zbB~IaM^myf4g2jU__Eu}<~vOV7FP9cHONlv(`4k=!(`oPnNGJVC1J{y+z}Qd;nazh z@?5njnQc^py%o^TQA;iwuD}a*FO0RM7#q0Eg&N3t!+B>uKcAd0GP+bhBrlL0DRT1$ z7+KrcWIdkcb2S=ut8E5uH{UJ~>DuzA~PPfAyByMmdNXL+0k{I6Hiq zh?M%AL)Y^7z1@Okl8b#rk)jqcD>-LeBX4FuxtY^rH}T{_e>GRE*~&zLMYqkDQRAaw z%aL0qU`wta(Jz8k8i#|+(MI2X7s&fD_H?gSI{N1FdUlt&sql^FS7!s6b;ep#Q?F z^8QDRij60ky)siqDR4`G?J2$ThhjMQo`i9kLwhl~AP_w=-;85jT8oUDDEnn(>3ZhQ zSi`=~bsi}?SGYFcr7SQ@Zz!)NBxpd_X;FaBzAIqH|SWM78a{s1IJ`RL5jKJm=VvE^1|sYm1wTtSar?v z+!(&~l7+26;l}Drokog9R*P2JM~Xz})o+#NjqcixbE98k!YuumF=|K8x|1*{W7NoG z@QneB;uE=Vz0kCwps*kG-C((Mb_IJjmfj1LjIUGG4|>YT3al`Us@EUhO(r&7bpZcS zwD*V=hR1!oegP;me=vRG@Vf#Jg`EY86L>u>6-$9!!^(@;LFB7qSepA#`r28DOU5BK_sSY|d zjOZJr5a0Ohn9)OmcIYR`sfo68C1Wh|ZF{dV_hg-pKckh$mty}x9txsI*^MQHqPkXf zl=Q<9oqkdU+{7!>`D1A|alYTBqVH^q$O{Y?5s8TqLErkyEh1Rafk~abP`)Ux#@=KQy?O}g1aSqI?{|Ir#0x>UND<~jl@#5=+!d{m9^((;mpw^$W`jX|hntDE|74Z& z`W6?wmuMX%w_r3c`}s1ebDKfU=po4DC?9s zsPT9DLqVt7@Z)N_G}0V25~oX9DTMm<=@uBc+d=+&o)>SdI~hM;U;GkgusSn#ElukY zZz_h+^@Liy>u^)@een`>-woRJl=R|JJ0-PTqX52a%amz->*_=6CRr>puSyEpWT=Fq zEX&9zn0fM(w61AhloRl%J29{$XMc=VXHx<}(QsS9#`@Yymwm6xP>z(q)ZCTR>V{k) zbpcxD-LSW-oQxPQYP?T3d)%}jpqvIz_oi;*wY`ZzxYJE%x%VW zui`>vT0HAvA@mSK;AxXpS=j*@<^$bMlSMs?Pb*G*Nr@Krba|G~99Hk3QuuJh_+Sen z@co~hCT(4Eu770C3BOl%aFmX3I-ce|SFH1u7f)Zwy~5}zaqOnp3PJDu&#BL2Vq8X~ zmf?&)C-oSKc09g9nB&xL{(2<=3l00+j((IUX9llK!;1^NqDvP;J`6D6m$6~b&<#dk zZ_j*vSGZ%&HEBv3qPMmD2==sjV(rg64WtF`LKJG56JM-dnA-8yHf!2x>d@Foa_q#J zT@*Zp;B1qs*AhcD4bEQA?|SRLJ^eJjVLj#TIk&=irdCG<)*Zr_>0-_-p8#~!4cZdU zHz4xcW{(x%7Do%x<}YpRmSBrW*vIeKkVX>}Lz*7tJY6kvrJRiEC^?gIv3Bkm z_q|2sE#=$Nhfg-~ALyqQuE!2Jl-(s??+2&(6hwQJcQ-9uj%Uo1FYm)vPPY!OLOggq ze`O%XfP;}Fv@kyVHbIyJsq@m8u!+p4kZG;~ARHj1y6U{E|o_l0nyu$EpGjD zJ(&|dyf?xaSvqX$B$W0xW?WNpdq5r71ZJxiBEf6AN6yfVD0Ov6an;lIX2bz@vW$xP{rVfs%<%CgbkH>?Z&wJh5fa1<`N zcZsN$mq35U)58rqZH3gAv7Xc!s;AeQ(;=JA$!(c`E1ME%!bFmeArUVsRMPUMV!6(w zXX$RBoYGE`KD36S>t}&nx269 zD-+*6Esq=UZo-+>DPtaB?I<%b++#vSc_32x`AWh(X zlQ>Gg#^9Gm;`P{hoJH>^{8aceOanRJ^sd>Kw5M`=tze%=2%(* ze-b*Mh{{iEni9PT`LZqVNk>_Mnz^!5UDp~D6j}>!+iYZv768`9b<-O?IHpto!V7&^ z6)Qz|LPc!k;D(;Mw1OBab^+4sFy`>;tU5ytJ)XZXO`{8jJ^8jt-$(-kM^1ODtA{Ly zFyI?s&9z?Yf?FPYaYMVxkbA#_b0Nx;u?AC*mCAVEu45d14Riu$pc>#nTq!&2>9fzV ziobaAN=dC%C983I(Y$V>O^OF&NPYZ%w0f>I-P+p%deAIpCrD!^yL$(#6=jK;Zy8iG zPO25W6&EOHnR#Dv{Nd>L*m=G2M7rHqc}=0Dr$h4#y>9j`xNUwF@>veQ$In^_;zs(r!}m)w|LFOzRhW;Nm4DskVA37V8D8SJhnOo4AeZ_~9s$G$ z^9zz=9C@yHpAC@0xO*6mw7-5Dxc6k^hF0OXRGGH=-Ch+ug~#kC^m3Z6y+W+ta;P@i zuUW8zS|}l7>`vK!ia-b1fymN#BKvy`JrvcqY%!nY)7OuU4xt^grF zjp}S!nr%|WzaiQ=I~Hr#X(H%Ow`K@g^(|f!M_CSk2$v5x3Ilu+9Ih|f$cm|7d(W+- zlX*Sx5>*}V^FoZO-Grv=KI+*WEFwp)Yd?}1(kQvXAf5h*3%q#-Ky>DnJJT^&$`NE* zD^>S-w}xLnnA#(4A1#mmDaI%j@?i@tzV3bod?$@XTRmh8bgK-Sz8W|u89;m1UN93i zT$F!xmkH~eFYaz11gmx2C8t|GF9}J3-SS9srQQKJjqpweZM|Jz7>_{4%GbSXZ_c^q zD%kG3@keo1$!xBR9E~or&*|s(DA=y<2T);k`aK?WGpO;PY4fuOE|AW<_Ph&VsytG- zYviEjnJxe64^=VgUAK~f#(D~J zHs-S0&@3}EM)=klt*jdtN;&~O8H*EZV-O!_+I371#_rb;d~zwNUT< z7%7?qUgh)`eHLr{@!jNMihoHv1LrIA9Z0}wK;7+5tBo1fhi7f zCjC$}$!0Onh)6J^M?y>6%&j*`y|McUh8>!!-4I9o-Tr$tQmN1j@(9Ue{DTh}E zB?cv~t;wpf;RA2oy? z-M5FL?Y@L+pB>#9sP8gWO6sZ)IxLIf{@Vwd1=E`*^*ktp>5DCwTvyR5c0sJU@vXJ{`Y2jloYd3 z3*j&gWw;rcM-NBeS8)#=QH`FGS$0TSJ|tFBMoB^7kZ4>NBS=76bfSf_Q$XKEu;;_wO9$yE7w40MOx{~7+7aXY zBhPFrE|v+>M}l(gwFdoZB0 zw4Zn(?v+wpiySXQaPuzrQr=$ImDG`5vh-oMy4cgFJ4{w%cd|)#&+c$cY$u}Xue)C+ zRT_L|f4dhYlWwYR)+)~knb5FNr`MMV(=;oocp2FOQH&e|o{)COA+P&Lv@+-u>aWA3 zc4E|>bRYLzK1IDAWb`@~On(%$-9J!*4cTd4S!Os~azs0j8RGy(Fcol&2Lf?Dj2;6A zDD)gSHl{9C+jZR>veQ>iyj$rcRQ%LX4smy#MOlC>Kj06+LwsX?5|3-zpQRj{-Fbs| z1@wAtS;}BC@`)=Fc(T{i4~SwU*yV{}3Vk9%m}uJPi)7Vtn`&AmtqZ7hI(VTubcMup!j^ z{BQX|o_bcy-=jq*^f}paB)42w~IC&+h_U?rRcCQIv6S8w|Zg!dy6GlC#^Tw&FgUMa03^ zaA+E_DVeom?@3H?6xVVGJB^Q~vQeu%)*^5{t-#C0CA}rM0BTwgwJz#Rm6qI$mUO>{uY;N01=KQtZLx|F~mOhy~5ERbJ8jnuKIXcFTr=p&TiBA^V ze7L)6G*kjHGTxszZ7PMq2`fbq(-(A*Vo?YRQG1@Q;O>qGrpoeBXb@LULg@x?$DpS3`ij@#avHM|Mx1;i##!d7 zBsvdDSywCUXV;*tnlPH;CFDVQnApX3@<)yah4vac75yJ3EJNUpgU$TM<5sdzS5*5F z^$%6?-9~icWaF;utx%3Ziq5@QB&5l;8rUy%W?uhzu6M@2Hq}&y5A5GPon5K|DO@U1yKNjeNSU)cuCuIwbBMR@fH>70 zP|I`!1A=gHx1}47Z|)EX5_m(JRg1WWsv%V^D*(;2@!4I=EjTCNVx}xTn~%bX3-gz# z$4+^~Sfq0wsV}@eBOkT=Ar`Gn8HBh;UA4B`SO;kIVd$6lu;( z=TLv~euZ=V<0^O9B`fz=)ioqVEEzxgIj&%HSz?%0!^ce-uBWQ~YZk0ytHEsPKC zuwDuai02(dd795c4KN$dTv8(z z!>}5LcC1ccX+E#o@x(Z0#7*LI8S(j}6}$lbWgHfISR2nk20CNE@u*~dIpqR~W8MKpE3((HkgPBU(v%XsC^hpECKqFtDYX%dpx@rXX z)F}T}@D5f(UEYST!ft4(%cBO=O5f2dikCt>fq^ol?~)a~=AkgXE0AEiC46eAP3Vkk z=CvJbwe4Rs>;TJo6G{f_Ig-o62Ou6+M`ABV(fTxBbVIvpfgS!zP+c08qNAF({cevo;uSIKMf#LSH4zVsNLdHnip)BWbzSyhT}@|@)WKmMl-w}PSofWt znMz}wEM7?yHfcOK66d!1&4*HQ6~5=%1ILdcrAo~o4u$Zf3sRPcx-UG+h>&W$LC$_c zDvE5(LqE}PMo{Ot_vB4nMWPr7d*jFR&)G>9*AmzZLL-0X3t;@??l9hdhAzrCklVN< z<;5*adF8IXjxSi&!C>ie@Ui!;_c+aW7$XkbRiA_sCw=)<6x3JeAsJig)#&mFpgEWy zyq?qwPV3&3qJz{fm(#Jpl$rh5iXa9g?%wijY&<{iUF|aAJyGr5F1iBeupFsTQ9J&^ z|J=K24YzUGFGGH`2+58aXpvGUsz|2geX}8yEb9dioW1udh*g}kD5#7C3ar@%lTaz~ z)8SJ&U2nA1nPu9QZ#$+Zk@{%^_z$@oDq5{Cbq3J7rtt+e-Yn*rW6vPL`Va^AP|vfl z^VAgT7=P3Iaee!qmh>DbGv`~@T#vlTX!DYgI@WpGZ$ko47+*c1?$7zml%W){3iPgi z+O;Q#_Bug6y2jRn(02;#Cliv}WY&}fiiDETuSuEd<<*Xs^6EBN)kd9E;L`>JU3PZa z0!cHcfQ0bGL&MR$6K8VOcC=Zcb9=hS`p3o+BA(?OBz6?6OoDrw_IiHN5>XdR{Tiy@ z)kTy2lui*?-g!`6P6?G#FSwiDuXV9(=S6Q|rLL+0$nhFjSArv1V)hee_a&E~8Ki^J z6D$ZEC8apd-5fk_G3&q-DQ5eE)n&F}{XT^62ub0B--{)BjQqO=s2ArzwE0rA*G%HT z^B@BnjQny#9O0(I@E{5^os9ns3UjvF@9!L>O5(f1sLp0+2=Emhv-&J!3c+mIc1cJ} z>?-ycKYBI;>vug*j?w+RB4!Mp@oI58`D6sHxO6+q!NSL!StVfmU8BLb*1;WWeGVVE zfBF;J2`{{{@(n#+Q4q{oW&nxV`hDH38`lOZ0(sT5PPuO{YX1aq&YI0WtMXm*Q1`yj zF8#_5uiNE3^YLn0$vehNxlB{l=y+bCddNLDE-K$;J85m?=X86q-v=Kbz&~B$22odp zoqGNIK_giL&tjLAd{m9P9P2g5lPLhx%DRU)sfd5vc+6R1+U6@W)OPnaUXm7l?KOnU z6myy>S|8U}XHGph{>i|1#CfalB{D=EBAg(eG;8i-IB;T{dpEpQb0HAD$ z1kc1!|2*XP{qyr(7L|J=0V$FfJ)20et8XEM;_^`ZZ|+y~*&Co)TxDijf@;6MxX34m ztCwD1k!|!k#t#7_i`XrUU$$vCNA7^9c0YvZuOVPNkhG5YQ7Dqxm#t`D!sXswU!SWP z@5sCfq`$zEDpCkeQVp!25w{JfKE6&;j^vz^m~X$Te3byb=cwTweXDm2hk|$!NXxSv zu+Q#X)qKTM20fk=htwO==%-r|JsiS3Kp5mTwCCruX~DQx;x)wi`~y;JavxY#2tfB=m0 zd%;n?zo1@#3%Nr`+OH9VdJ9M>Jso|!c>%sV!Lf)v-ItbH$YCw6diWTn4{M>ws7*@s zXGf`tP~e3;B1;)Ib|f!^L@BR_zpydOR2zxQX}zfdaGvm>aa4a9f5(fnz{md1#jG2l zU99Yj#|-LXVoDuk#Vz;RcU$pm#@TF_rUKqra99}!g`b0LzsE>Zau?h+TiZ-x7&_y; z%E@;UZ%f%_bcm?(i%i6og%qN;(XHDX=j_%I5qEK^v^bOx^GIwMTJ|n#R!t#y!%) zJ-b_RwlMzn9VpG|K-{IY7Y@_YjwI^)Dwt!PpA1M)IDNa0cepbp+K?=Y<{ZmMKi(d|S&amH>p8Rg=Rx@G z=mvlsHKFC)Br~iS%9AJNX!62TVzJLt5Z`!Xs+8$v|D~}{MNS`HOhlNaR@ZilxI%bn z=k5hzP8$-uit6YJsLy3-^B0UCD*znyvwtX8J$n}b!;zf*PG7+7iR!Bg_%QM74Qtgm zO%QZ&TesDCq8ntay~F@Vyf!!5Vk1z@F#Aj+(LW_V>^TC&UkW_En_cbB!Q2A5T)d-u zIxDI*_0rJBv&(P2?dDpv3tY8dNw15Q*o~>Vk=l3EOFfmlpFNN7s=TJ|R7T)^yzW#J zF2A3EbZ=i!gV72Q#(I=3+eW?elk5h`ijQ*D8=Bh(xXgD{?tECKLU(L1sYex;kr2}h z@jzLO^RxouzN0OGT6(S^${`WgBL{ICUDN$#z0uxa!`r}J(HlN^ady(%<9x(9teXYB zW@Bc)Q8n!fWbHkQ;kpeCyb-qqjcfPj49Fm|c$6j9CQV%g^2o!HEONiQs7XTR1C4i` z(uXHi`L@N&GG%vLD=pvwhAHryq-YtN98ebRX~q$i0kPs*r+PDQXQJl7p8j`xg!WlO z5VbrfgiiF578*epNZcA}d?#ccpDv7!m)%1zLN*bF^~~DsQ_%n=7`|E2S#bVeH!fb~ zU><8IUt<=&kvnN>CV$moxl51o0dc^(w*?fDyJx}x+>Pe;D3BbsSOAW*4)_gyCmi=# zAmP=lazhHv-0M94y3*`vpvbffix7rpAmw%9RJ+zMF;@Fp=|!}etNKI0u5-C|Q5Lwa zQQ?$-Vf*ZARv^ZjQ7(nN8w({Hfwuu)ZBSB4eNy@Hm%L7RVOr{n8k2G$(NaPpbLOBs5LVoj4t@Y}Ir?-Ch`a4myF z5V{x3FckTILU0K{^abh0i~J!44x(Za`Jfygq+J6D=u#~ZC!8QzQM_5eIWu6)mVp7BSwj~#NHa{5$9Z`VNK)<30~yQV9p=0cmU%3#=#Nw*`E z_&#La=px5Z#dvHWA>B8vL(MkvG}ZnLyxlc^Jozy(vdSnmY&kD6^SYbgR1kM{%)5=% zq0{EHUS)!4wtaT(mqj2qr1d#VE;P*Ub%6fF;Z%nLzw(tlJIjWWla4V1p}>UY%=|LM z!1ZR5i@~@q^tVX-nLL5l(474Qq$0FUI|AtrPo;lL=v$PxG?v1@vILys-QHv?auRYJ z*29kbLc?x3OAabN;y4mfp%JKoI;Veo4Q8Bg!ohF-x>gm3`V!zW-5vzG?HqbI-sH}t z8J~c(RFbnEr9qa_)5OfhfUw^UxQ!9?>I;f^F1Zsb!OPbW9_)wXbqVi8S?YY5BWjRv zRx_4%^ap7@SRV{q=2-OelwFvrM@NQae?clgQaDm1g>zRS6Os}bq}Qmg8T0e!ylXn0 zgQmH0<+UP!P2DoXmL?7HUL|FbTIrM%gV?Z~&S;dt&8(C%U^K=|k^GVzF`s!h4$V|UG08z}`jBvcgMQV!HldMnyg=c}i& z2LTI522h87ARs*F?tJ@7@larpt zJ*a_i`nqW0Q&)tjg*l>^T@N@e&T8P?HrCBOR?566l~WQXA=Tq&Z^*MT*1jM`j=$3v z3OQnd&2x}70rMe`hNp4`16j0@TK-M^JCQ~UNDHc!&!}b%ze`2y6$1l#!Yd=~Y3Qub zk|RP@6^O7^)s<4^{lLZhg-U366(Zs+%Dd-cPIZv57$s&8C%)#iWOJS>t&Vu`I95Ox zSA{sq4Lu5Chs%uk1gxd!ve86$UJ_H5u8V;{=*|;;+r+;-I^XSvyJ7G`wl2)Bqn_d} zq!Cu)hlaa5`Qpuc^6h|%m+wbJaSW6ARe6E3fFP1ze-S=)KxVYB!G}wRH7Sg#iR^XRg zuf3>CS=R@8MUkHTGie{{i4H#v>o3Q5C#E((-wlrG`EL6(|KISmG%`$-62Uq`^EC9V z;MXkt#-beDcJYG4krB8#yHb)hzLcvtanFi_jtdhvf%|MbRDbcJrKmSB1TF!~vAb?I z2Ul_ZlfwX&==INQd}$=iy4hwU6)koURzG@jiwdaDh0Hefx3fa7L8#QzyL2P6;xg{2 zUyg%9e83~y9p&Q5XGnCLr3(^9W3rC=tyi>#`&JNSp%iqK9DKIpAygv@tvkKZEwt~s z;Nd_)Oq;5H&XM9L&Swjq?u$V~N8C$Q%E}*d8O(}Uoq?#46lfsB9UYSU%j#eWNp`<^ zj&kM?L_MIy9CAzbA7;QSS^{sKK93^j{x(9|z6H7%qCe^v?59b9zT>6gAztxyNWbC6 z=6_Zh!=q;M7S_}8#LN^=+43m=_!d0)Geq@oJ)sYW;Slzy=NT$=LlC|00_6bAz(7d8 za0g1or=WOlH}g@n3ql_waMUU)S$yhO7uOD2bz)@9ELdHEEABj0gc#_X@@PS+>(&Uiy?Jk|lE3hk<5*0%~XRpBTYTi7d;gnlDlxa{KgzKCkU(B}okAGnvppSC=>@$K z`F&+T+A4RUi~)|LL~t zr5O%nbGN@?8svZ99143E2-^E7wysbZuj zlSA%EX97S)Vc$|9mAKZLXESuqfGd(I7ef7)fY%&0ux``0&w`!}T~K@tNf8#(y^yU7 z_6MBP%Y+uKdFZsd_PIHVj=y5M#!u6ST=UR!_d_8xm(BXBePG$wqg%?JMLj*?16FZ3$&}Vfs)@Af z?Sxc&wtt<~VerjSl72;yM{fpD$4g0Oy+7eU`ADEtb~jUkdf~PXruv`dT!KuQ*5o}*crKmQ#fP^$TMDx~}H-?G2?pkM`%!{g5*i)`pHRWZWazrn0O z0>UvuUhOp8;qyt49DCrz+5u_`owKu&+Ir;@RI@&_hjyB;;ada=f9tbTfB_3sHalp_ zN@nvt{-?qC?e*v%ZJT^c`Ba=-i2m$pYo_1+=Py~i$WtIhoX4}j9cBMlm}8`6=t(6a z@8CW+)@Gbd5XJh-9=nr)Y1+@O{;NUaFQ2o`-I<2_J)Hi^{`TOVMdw(43*({p4g+70 zKdDanb4BbG=nvFB4QGD+`Z#p9lKgtnzki~~qLS=P$TW7Dalaw;x%9i3yL;?nuU9*&Umf^U z@cy~qzu%kty8AhJ+gpd))jp{1SqS=h3-A_sJkThv?c{CuOI(Rz!&9ezuK)M$*wwIv z9qnM6`zzMVF|1OMv~$UqYNZvVQ=A3tI5kN^un?TvlqR@Wzr-W`}0oxnrb zn|PyhjK)k}{4m#_;{f(U)2i<|S=paA<4!>j$LqeR$Nc*y;5?zf^`O(`(2+44*R2nu z2#Hx7sQ)-?;LRLlVMCX=y3Dh@WB5%;$)MA%@4ksB|HxhVx?3Rv7z}7t;WN3#3=q6M? z?EnnnOjRQJWBG0F%_I*4chX_xdmbJ5bxe%{@PxIbs9k@baMUhj+s4d_(wiT~VufGIZJ!<&-eTF0U8u`2O$(`LVBP|bnV2kIcc(E3FZ~M{x~=kC%n0lMwrdd z@dRWEO0aPL!IL|G9?zDX{S?KM2ZK|4_K+PLR7-B6|5Fq|Y~3q=^*gY$A<7{w&~WyT zkAa5NaKADvB`lb(;Z>5zhc0aq!#8)1#YDf|d;#__l4C{U(mI|yl*0J4kRCwIe59lU z1*V63Nr^ZAdVyB08G*pd=ODZ&vp{BHo;e&T z>#blI4sf6+?B~=2wNk<--O+I`rMBO{+pEg6*#Bo(rX~cp;h&VUr3n67fUJ}aI}%cP zHQew1#{>o|$W;4FH|^sIl4GyMrEh!gK&wKSWhEKXy_qKd*t?Md9RK{syq^N64NH$Z z8js$9R{lfpZ~tb@zAsosfK(*0bePQwrVgY0!o-ddienBtAS?Vr>hb=ULxCK#0gN_x zXWCH3k9D}2A(Eqfn({xyQ{@bX+k8lgzFP?Q&vf!_url>A2Z_>2u6GOPtSf)N1vMnE z?>AA#YwowkYlEM&d&(t}fRIQm1FxcS|u zVdW8a&o(+JIP29NwEt;45t(LyCY`v?<9Ww6pJyb89Qg_3Wte4fjPJwJ-$(uo1&j00 z#47#Vc*aC+a4NfJ<@b#r{r|V|eeRm}##MH~rDNn!g@`eJDE@njurUw z#}JCs*T76G5<;pDwXe*-Uk`FFn!!MEVj!-&_T!DJGEh7P$2B#BOAqufgd91&SC9I4 zUjRZ40fU`{=#MxB)j)RiliqH9Wo+EhK|Si(!y{JJH%D9& zOJ8}sTL1Tu9`z3V{j)_$>{jd*tb-&JW09$ukWf4pYWu678igeUg!%clTl{|CZ4v4* z$wPc?FfVAQSFdWu>K)6Iznd3sUGO}zU31+heq5;R0R(@!CH#NjFUZnri-d`=vZ>Ve zbS~hKOvNfp{4u%5S{ly8e3mG6ONc*^LyC2>%Pi&zN?If<@As1B_oL7OA?JGEw|TPe zM<~m?qB*oZckH7oi8Wf{=(j#hxz}+xZXQ^$i(N2pxEvl&W{XYK+@Sv;z`+ceWH}{o|vb6Ws z+xbJaz1Ge#mi6qyaNk7_?xT@chF89UZvGxfRmfT+WM)1JZm(#kT8%l8||_HBp~L=to(=4(C*f3V$$W+4zA18g`$3676*! z5WNmqKz57PrEA$%ahVH~y}baU;)}(hm$<1!XVVWV(t-2O+%iXA{NItkqyL5E-9e?1 zgFi@{Bg2zZ(mP=WfAJ{Q8zSIh+Wv@@ddZ_h3iPs z^EfN%bp-ALoPPGF$yPpU6d=sH5!qbQ9VN9E27cy^TY5Ggh zL&y^()p1BR0`xMFiYBI?Gh~h-ns{9=(?tsm6ywk)Met`_L1v^5P{)xgKc}_%9t2bj zDCwH+$cP#TDBt5BD)C!MK;*jQ=`i{{xsy_$u9EAp=E-0EhpM?i6%QWzVU0}CI zVh|OBdfH7RQH4+vpICjI*MXSzQqm zTTsn^$rXrH+T0uJAl!&wxlE!jAt1t$MNn9Qs!4hWFkX7fr-e;h+Y#ayz{c4KJB-6; z@0H|eyNH!ZZlvWM$O2|aPqt4naF6CeV%mWWVF1A{Ql@W2RG z=chYw4D2lt*Hs567^u@Nam1jwyEWZlGA(6B_-1Ewkod$2q+5!wBLRm%)u2eLGeEQO zLO{d3^j;_*6abxd9JtEIT2gegUW}~6oG0_|97nscy}-UQOUNI2)(jL5s7437y#St2 z>64exbz+|Pg^}g>^?Q8KEC&Q=0hVJ%z6D{8H9#&fLJ&eHG_G+i^CTp< z8>VwBNNpc#m&JTK8RfSO9BUDpS>;}vd-}k7zUDZ8pvQR+ZxQThemt`-V*OIxM|hqI zGI<7wT{=G0tlcG)%R8QdaRIt=H&SRW5l&>t1JYkB=eh8{!nq|VM`xv8%Bju%{%hg4uSZltia|L`o#$8zD{?4WTVtai0;o{ah#nX|_NDqB1B zX{98a4#R!Vb&!8ku(uLb8eiTw+o*SL4FnrR_&0;P_XjPU5CY6tS5A6lI9noyb{*za zTnA#XQrRfXnt{Pcqh%x!t1lIL{A!T7ItXnAx(7rRL*Shyk1Mxp2XiQP0N(@;N2{=# z`(lAz>P;w%t&iXa%3%1{$V8FNQ0)Y|F#e598Yy#H-dE;=fgtf!5$M|J^^&I+A3rK8 zb?Txbr4VL+0q5O7<)LJjI zY)J02U!)UrK(qmk5LxUmZ*wUIDIeq<;@p4XbJ>GUk!rE2#KTy8L;0#4n~RY7fUrplF7!IX^>9fS$1*i( zXgsT~;)=5L80iSq6?(k_+(Olh`gG-4qxo8vJDHSmtuNMf*Cd<;B5tKAw3mjizpXU& zp_t4?CaWpe_QG{_PcW3igcYHV4HzY0cUr@+59H8l{)_bYkZBlnq4C{w=5Q_H z`a5uRKFesjlDCJ@SgDXM;Fhq63dOUM3+*zf?R?FCQ3NP|2;X8nAw-48DjGNsxvV>J zO2Fx)T#X%b?tgR7&RQ+@xzSZ0@25dxHJ_Ykl2id`Jzx?#9rn`1r-)f+?z?hlhX;%Z2 z!sKMX*?eyVaNi5aQm|+AnUF2(o(g2$ADMdocB0<_hhfCC-o=u7-D$D@lbSH47Eg+jMG)X39P_Bg@ooF|(-hvA+ zC)sWfKCr4wuU@I0E~*Q0BAP}G zMGIg}EXt7aiqMEPU$U`QCnU87{gl~Y;|h96#q7p0(7!r0cB5<&X|skx<#b81YXP)k z;DJOkyCN5|*y}VYfw+L~;{yzP4sUykLKRK}Y4jpApscc)>@Vun)~!B^m0B2+=%u*$ z%#EQ+y`dz%v*V2W9{h(mg#{q*%|-I6=Diq3-)Kw2b1sdYicm|pltW6?{L}~{0KD`L zq;|Bio7KLG!>1jXqXw7ne}IllQ)s~}aC7k@MFueG!n@prGq>;6cH^Cmi#|QOFs*gz z=9icd5Q&vaV7ws_gK0h1ePd5^39EkoEvq^`m^qtj{iSBYczHuwIbTg4Gv5AM@Mh}- z-}1r{y<61y)jkG^*k#dxA1E}+1VLs*Hl+z$PvXFa{vR#CPm7D>4-{w=U9)hU?q!(b zKR;eKSg z*}Z}R)YPIL*ww}*;WoVi(Qk;66zAf8_6-^&^0q0N$cl?N@OGsHan7nDtP2fAUO1G@ z@9iqDIkBdVw@(e}?GVD5bu{k0@a!YBMrDFP<~eB?a(;4g5KZax$hqo!W`Ac-93(BZ zA1I0L_RuquyYWLm{L$eDsczx3OXtOl)V$Lo&2s4R*RibU%ESwRJ8s!>LA&D)0nut# zF$nfcXly6nGkb*h(U(x9!^;Kz)(a(_9mDy3f+2kn#9w72N)uZH3Te2FAl&roF6d_2 zOyqy+>1JH}9UD+X5kk-39U|(fNen_ZDIh->k&s%W`=GZg4rO3^#lE-LWuOLH@?Hp8 z_Mw`}hh(n7Kv46cZRwbn1(-Jq6c8ZKhilcf-Izi*NPGZal}a1?3?pl=Olts@W&`Cm zGq9X~Z*TGAi?Q+gj5xZxTDEP-unC}3&|l00$ZPHTm@ANxcOuk7rS|QU%IJcL{FF;1 zy}XIa8apE~VfT>va~s)q`!P*P%H;WQ)=>_h{R9inRVmSZf#@OP!?LRk5e-44=-ZoZhYIOo6BPZ%Uy#;;j_3oQ=5Sqi?atSy9WMP&a8(0V-lGSL+hnEq*VOPFOZm~ttrq&1LNhsXeAS2Fy zkhgy*38zn3Hk1csvsBes$@QEpmU6IBQRCJo8@J)u@zC`*SCs?X-= zC-OTQ@*UFnD zuSE-3IU#1;`)^{#znQJ*BgCfe3*hc7mb2XY$TkD8!*VHokf<}`M2Amsxe<`2LqW#E zMTA`o;m%wFv!DcuF$P=>eK=BOUA6Sr;#$zBL zp)=6Xxp^{rkxWK(6HC^gHsBA1(2LU>cxXjO9dYjaCDMSk%;43_7n?XZbe5mmVCHHntj1IhNP6d#vlTE{|!kcO?zz(jUiIhsy z|FB(ti5`5qiw8a%ITQsy1DUN9zU&M}?TCzavXtfuRPrL;&XQHkUQ?_xS@Rb*g)eya zO7~|gphEIGtX1~v^p8(ZhQAs4PZz0wL|t~fpa3h}y6o7q0k0@~zF$&MH;T}m<3*qj zxv-AQe9vvTcsUA!kYebSl|?I!bCmONXp9#0>Ru4`ztbf+<;Q3SMX$F$cg<6nVuk2Q z_8rJw?X*?{^xdVr+m;7X9#C?W4WTeQRBqV$$a8R+#DG@hy(;thv(m$Yo9QOOXCW8U?wt z$MB&xX4fE~3=78I6JLMfm~b!%<)-eE3a2Vskux7DOj@u#8bAN_oXm8Q3*5y$4+Z;yc#?JTI&rIK@S0{<&5bJ9HKCiS}nvA z$?JRJZK(W|9PI(9im=;E4^;2fR6&x@q-beEF|dS(7Qk=Mk&;&{tGaN>d|aEP>aHLV z9viadyeN@A`Ue`qZ!dHmz<)k9f6?@C#Rw_XHAp>P=g-&;v53x_zv8zacY!?3V-++1 z%ml8*+_wI&n2=K#bFn&W5T&Jf80`V194%1l#MrOeY}wW6Mm{rmcz4u;D!t?0L!6tn z01i-eJ_J6?Y|#id$_+`j)V?iHcy<5*U#^BixS>HAxKKl_@i<;-#H)Tl2roZ2ew;>? z0ORZsFmNc@%Yd!t+iG(D^2nQRvOHkNG)w@6bQ!1>)Is^l=RB~6j=TbjYOQnYluhW@2ni

(BLtBT-s?3%j;-xPC*?WGF9@IR*NO>*uoj=g z3cM3Lbr9y&P;ev>;#Y+5_R$o=kLbHkbY>8|sR$9^D*?)i(1ud8RD@0VmF_-OF6}C* zH;EYX`_c_$Ha`;h}UPL^QZhyV);0=bG` zj&ik_dMXWA-0ux=kM*B_wHHw`C=~D<`QvWto4Y7!B%bA|_rmu#1@qe_hFAs-KnfCi zvC*PF!T6bd(yHOaUc= zb1{8Oxqcc{*Tq0-87ZG{c+f9?h7Ahv0f|OyKK}4HKb)@9hd)0WxGIFDXn*<=%H!`z zb(j0kw&?RfjpvSg5<#4Els57WQNt}cc4*wxX!u?J3{*3=77>Eaa%=S|Xu@R(DF{|2 zUWk8O0EU8K7iTIC+T)7Urm|$P30hT{dLY_1gWgo^yBB-w0lQSFp%`X%r=|KirU3IB0`ovg|#&DoGUV6s{i?f zJCk$T5q6<@qWJqe-zVn8?lpyQAT2_q{UBNff;EF*UV7^1K)7e-BfI~cKJd!as24ce zu3F%e1G=B7zcnGczAXnF{;xlrQkS5_A7bA@q1FhOIY63}(6p(aBcxiW2+o+CIf@m4 zoXB8pjCaRhr5InF>JR&RM#|L=PFVha{hm+7&&k4#3xpkn!cbfy9O+d0ov;s zuz?mYsu2q7I8WE#hMWELTOVC0O%}QKO`vE5khsR+2tPcQ4J(#yKW?~s2WkkP9yP_X z*3N^DP?H!d#$5(MZSZ~iV`TX*%1sL}6hlBhGL~G&|4u;mz}SHxRZ?Mu3kLz6&Y2Vd zJ)|XYqMZqQfmHz8>l%1#F1k3RY1bfHXq$J7bL!=bPhmt9pLn&-e=~;CUH|xCAR6Iw z0h79H>C(&Ip3JYx-e$BQ`UU@=qR+}`DhA_1z~71qM?kYdY3}k6*!a_fulAaLLm=%4 zWH|LD5fL4a=Ii3rMbO%sU~U`v)kixf*Nq1K3e;+}0aA6r7J%;NQ2fq&6V7!8;tfM| zqr1h_j$BFAU;FCk(5~BGRd&Q=J~qc(2D-`yVBK7`fyik#D4!MAp*F%mor`ZpI#Y$7 z;K|?JaR%?HY=G=uyz>F9UYxrpDtR!N7pxCW^L56E-g@cb2YNpwB8%gEa)eXo5gY46 z)+hHq@=yfey{FoX!^YO{I{f6qd8wGhyu`$F;f~eX1&-n+?KL@1E*?8(<=jTrpVzT` zozeQUpydpuY2U}-xS5^Hr2S$0F9k#SP4EuLVYIW+wgV=;^8qQ;ll?CR@B`c=u;FFrl$7~)3YQ0 zw)WMZA26Trkx;k&Y+i@1I)VuO9(?J#R*HgS<4k4;LZoxG2U65B zVk$)N?Itr~S6y;GSN?b&5g{hS^wJ#*`CaKsr#?aL)9WG)#8T}-DatpEzl z)=7jIJ`HeMCmnNEY7tp42SZVUu`vWCXT0md)Q;8{C%p}UG66SxK{do1>Wza_SHnl0 zIHV_^*4RiyP#FM=pKY^Ei9GrqjI5x==*c+2zH1Z^?Kg}@DLQg4E9x((dUmhC7>yT$ zvJvR_%3Qh3ZHE<478fzZJQm4vg;bCs)aB?h3&D85UCXFS&${rIP}t^x#CR!Xw}t+q zcKx)x#4Cna2KAM<3NoXXfXfe}Iw5~4VNi}-DzjDPY!6Sf|0?Jmf3RoYR-GURf;BPF zQk61c5Q;tf^hiw0QOjM(dYkG&N1>m|1y3oF&486>I0NMaj}nZN{$?{^#|}}4%DB4t zFiD8qDVDbE?@FSQ{03nJacaa@&#*H&r@L2r{?oauR&2$zA74=8AVo2iWeBC-(s=(e9h=4!s}1S6Y@Q zk4=S;%}pqw{{VRk3P`M3&3{{68C|VrK47&Ppy9Y<9#SIQqjqqr%g?z?JV|nUPss5+ z!2Lk2#A+-r{(+R-fds^~$>1Z7;l<~#&6|y_2}c?>XkJVEKr;>(NQmolLr&pQV9<=V z?^tZ7_SV!8WWk+$i>%D+RJYFx1xY_+cO zrMkdr2_{5^I68W{*{XlZsLba900@FzZ2>1$)+@6*KeThkrW%msCkA$_HcKxy)tnkQ za{et75^n||`Bn5&s_ZjubSq)fPcU&;L1b1(D+)KZQz+}gJi8$su zPyC?5f_3;nP{RqLQ$g7Pa`>Q8I1xnV!G#(B!0(c_GzrOl-j!L`RZ-&GNRy1F4p%Nb zBlb1S4ZrMDw*~4+Gk)Zj@6d*_DB7kx#ZY+%+^?*oHM7RRx&k%oXzb^u7J&SlK(sKs@GWLRI_ zvEjV&vVA6l9PWE_o5{rcFmHg|GIz<@QGP`&a^b@KY<%T$qWu?cn`ts%b);JXGK#8{ zo8KRB1ltWKSf9$+#qijIh`$YzeixI!Oqnc!7gx37wA$#ptT7)-WiKCoq1mb)k3rR7 z|8n>v9NvPaTE_xN*-DUpiQaL-81-s-UQP6A-NDjRYpbY$gG1VYv$?=1_T9UMg^vgM zJo?);N3l}M%ibk-?von_Ip){F`ahph~z=-VX-2H*d0qtm4$c0xHDv^hUh#!kC zmUCp4wml>tPA`6kv+x#0ywM3qlZ86L7te-)tEIoN=8LrnABd4@K|p~v~+g-#Cy1T+*+WK*S|8TDI5 znrP%+T13e;bJ^}VL!KOaqhul*B2hdp%Y*tRVzC!`M6@<62vi9XEbX;^lIMTB zwAkl3@fPpNUB=v!GL94BM`L9No{hZ{E#SKI@eX(^RkbMLc)|Lj% zSd7WzSfD0K5KKE}+8%z_dBvrfoT4h`Vr6opSi7g^$c1CcC?UCY9j@hr603-5Q~!1m z%28g*Y7g`JNP z<$0%1vg)X!p|50&z$vIg~$(e;k6A7FsIY%Sm~>$xo;P&sgja7s5YOE7<@( z4r2X#KkKfW-x)huNShXj424ia`Mq__VwK z+Xu+NQC{vI_+=zzQ9})2a%{$)4KwN=E@tGP42t18C&1^uY!=P{RA>vW%N|1I9`x-*^N#Q1!A!eQr-b>_*T z4`8I8kNxt7WJ7bYz8|Da+`Jan206V4Chwn-xUuNC9Gxzc#Z8S96*#0>bvAsz+w}oL zJ4J8YQl}`{m?<~|n<{Z_9Ce5Rs*L56TYm*fC=8ZGVBwjbCMN3DbLDkay0yF$2RjLr z3kNO>ubZoP$w(W(rJxmq2-|nC>G~VZAYvp*EYrkrsT0}`Jpkx;UI)kce2uF#Wb3_L ziu{PzMvXp21#U=b0=>}MVB&m>eMQ^pB!)B9ER}=1Gv-#u7-?g7$$=xZGg$X`DM7s? ze1raKN-dKh61WEUf%P)-dVeV)IH4}~c0-yq1g zxO`lHb)m6)uG@cfcJR&mKA4^W={%M6OmNL4M>p?AK$U{P$RIZV<4HFJ+!CwKSliRg zhFNO{>XDqmMA4d({V6s3VO3sUs1RElDQa@Jy>qQ(mdIB_(2GYTjjL@ zV};;-5e`jZYp%xK{E?5rExE{em_%aW&GCSG=cSkq^7vXXeY(?uj2t?QpH>BsovT<@IPgY8;>8>$LFUpoF+JmqgARRd#-*lm4t<#EDo&Ef*h zeyp!-_y5MqPMtMy&}BGWQ|I-LU^eVdHqAtC4#1_jjdcE40|FRq-HtC@8+-PQ$lh61 zO_^ieB;1%m2xvAMh@m6@sj{~(MNuy10z3Y`Rx7?T23k|jQ%qI&)@QQ07dD4G3H;nQ zHsXg;@!*sEi>3Bk2Xr?DX98%p^V}ACYj42x;?&hA(T0JfQEz*HpzG``*A^o{2HkFB z7We!lvxLZ-j^{3&cL&*HwlQrHrjyTy0m z9FlMrd9R;v9ipjhMY*0U6I9o36denxOe%NVYuYFH6nEPqA`;rY8}y7=))Ce9W6J|V zEUXw)wM~7a(KHmMbbUl`q}Sg4F%qSpCw!rrlN=F@$(%ArA*kzYk2|(;5o~UuuotWa zsVZm5`dTOB>2B-a)hQRenXg$&nbqGE$6bG^%x+s+6p zKQiL@`!_d7Jf#uhQSr2aeSO60|7#=W$40`j=IDq-cF(%#a{>bfC3o@c?R5>cC3U`B zpzMtrs^Zp_{UcC8T(@kie19Djv?L+a497E+9ba3D2@Vy1Sc;4he?$q*U(zU`hkUG6 z9pg52i2O0biDJ^{1YCia*R&b>(B83y=m!ri6Sm%rx0@vHE~@12M4s5XtnWrUf_5v7 zGe*|fL-T4InJOmg(te3QHm{6&u5*_R9g=kqp`-&wJfD4{DK|Mxf2=>Z%n_g}`OfeMInu+TqdjV2iUV;!h8JHfB#9UD5k?Z|9@T<+dE*VWNgUfN#KqIpuu zbrlCeX(SZ>2HgF@6xNR_b`v`KDj2rL9zn6+b>Md4*#6YrQ#zPDvclx#WGR_=_Vo#& z-|vQW4@U#!ROBNEvj~sWDdwi7uw${B(?_)b2@Ef zbANl8e?J!cIz|W@!EY_%KYg&_16Rvk=j0Sly0l`of)lRAJ^1yYufJiNZx> zQ6-IJT^8%KFhzMnFr2p-QkP?B4+4Hn*YC3S+d^$WJD376`;Kl{8#afqk!|#N^hs~q zA(rx=SMeVk{p&d&(_r|1-bSWt12))!zwi>KRkDL7b4Lh`DJN==(pGHj*E5c0#4l{t z0{kZMo68pj0^NYSK6I=ereSSpY1%Nfy5nDtZT{--)@b9A0qk(mGE$eQto zbX_wz)|ToFCJ&iY!x?56o(I4Brd|)deAi2015RlPrGuu?IO!&~(nI6hfZifg% ziJBMGt`h-rY1^!(kX7`*OSb+(e2TsV3Ayw4NLFO>cX$i$2QTRS>5M<#8cu{XIuUf3 z_`zojgsoISnz~DB5BwQ7wLqqp6x<`^KlIks@X zidqobjBFjnhhT)N)KxsAUE6^^y-wtwr84IKMgNHl!VS!n0VU|U@X{pco+@A`lA9w!KR&1-_yNK zd1K;WzfLA6Ic)6V!JV^V-f1*{BMbkdIm2ncQS_G10_f2GZ(wj5{=1a?xngf=kObuO z!Et)V^&JGsM(-zv)+OAKii@;4_5r%3mqUP8?+T9fhMjy1ahI!!48?wl;%+MSPAG`i z9cfjT94~!e-B!9TrRbj&H;NqQZC4;p+e|?W`@~jpB><1%5+<+I)u^VrZ&R~ud(_tb z@Sh)kC}Og*j_TtM7z*Q%lAb^0b^!Yggv(b~=H{c3{?II2XZ$Ze zsBpsYj|Y9dvYVpM8y=-U#i;nZX8OxN+q^Epr!|2|OHHPWf{6}>H|LF;N`GUY{`G@c z?cnd{2J-Ep_;cff2sB6?OI8`fr8v?=DtV@^?W-7)x>Vx|wBQ-$}U}3o8U7sT2V=DUJxR~%1a7ILFjd&r{`qJ;}hIZZ*HF4@tAroaNgDX%Bhl-vu zC{ym+yf+69jRA6{+~0Mnn=e%qN({t+FK$qTnRdIw|3{n>UIzE}-)Prg!t{sa1wyQo zhhTGO|3wMT?|<(I_azpWCvPjt2|;=Y1ANI7_i2Z3>fteM2bjV4tlzT^HF8=TK52WQa!Pe{;WMTGu60Z3C%RlZz!^_BD4{gPC1q@*JxTi+n z|Jw(!fcUN4wB4Nj4s@~^)7F^&`GWuwJ;Bw(!QDDzamQf}Lbxb8ZtM3h7TghsVS@E`Oo{lwLstwZvFD#)I$7rAf#ab ze#^uWoJC3_KTFj5w+EQwpb;=NG)ZgjIok-}DKY4# z_YC!(YW>g9`MaUjvQRa|LHRs|pkfs1JT-Adr+Z5-;KQHw5OJ!-tDYK!L6dDj>Y&G3 z@>^_mCyw);H&8upH1Xq;ZiFGg(xL9cZmMUm-)6*gN* z=DMPtUN~&SV`#>hu11TGtIs}Ja7AZ_ze9DNmiOESiV@(TbRp8 zvNBYaextl$&8#7XFgvyrU)X7Vu$W5_fXO>(?!|=15FBI%2(dI!$>q>x^qX1N4B!vm z0B~>Li#UQazg>&q4P5WkBwkmKsCIbIr%NY&w%y3+7l_%EmHu7I-u-DFr2$MpM|d-H^a&;YkX7;|UTuw>Cbk7?OKdPWB1>b<3j5ko3^d0=?9_ z-H9y#udr?3(f7day=NRMT*{%ktL2p*f|Wk!y6`m(pywZ;;eruVbo&F=H*t@-`5*Qd zh6hRuK5UqM|Gl)}F6s;t0!xB+A6|3ysV>xjCBG5&@D+X`fTC$%R{Y_MDRDz&@M~~; z>DrZrx(<2MPnKpRKHH{r4v8!*YR$a)i;&iek?N5WHL)* z3uG1b+pQ866zo0@O?}|{muQhScaj*HBC$}kikw*sv^f3_zz)7s?tfN(Y!{GiVu*eP zmY`|w%UD1Vzizd_7E$_>Ur2z(px=a6#8j?n2TJUkDO~8b)iM-&5_LUVb>1oX220LH|kg`Ep?H*dOF|O)80`-q4dq(pZu03;2IG?@*WF5>%dOIJE zX&PWO%ghs#X<$SyNQonWiSCpF!<1x{VYB=92)jQiQ;v*(rFfr5NGX(#*C zlrGkF{j+U5w{6SThGbFnjnF@DXlT&ZDchFVnmU7lI&7pMe+K1brl=n)aNMy^T52ld z9!bz8JG2L25jYE%dicxP{UufFuh@ON>?sB!+Kpf#Viz05u_}Y(7sJTpRO~dpult z6A#Wgy%^{$g;prctK%%IkMK_?G&KO8=kpN8jV$4+-QwQ}{O>Ci_ZIB>sx#pMo05%T z!CQbbxAq6C2y(&UP5&U^JkDt~deqTlmK!c&E&~zD_|qDvLr{#&G6g(v)+GqUVhFu7 zb150(o<|ES#$WB~R*Q?uj7cq;isAooDD2u^fCdc-z`H*$E9 zU?0+NW+D{QM}bn`3IN6sCG~3!8l9@aiqUl?BU;{9+0i6pwI@fWK!e5^K{Aa3HHkxu*G0ZD6Tv z_gS#K6y&nL=V0wOHIoMwmQWl1vO5?rrNX+5 zdjOw;hDVcv%jx{v80DQ%XG>lwqpPkgfm=U5CS586P2bUf6G0z|gj5Kih}feYU+s`Jxuk8x<&|do<;6s* z+Kq#@lXMcduX)O;YWRT(CYF(Ce&>F}W-UPLbwD%lFn)Ep1GEW-079#1xY{GW0!l3m z|A=_YW9I?R#|@@E!Jk#-%l=h(4WkDOKmGVN)21#)7w(=?#B>4g+ymh4OP5Rmnj@h* z0+Q}TwRuaip7kL)U_V);!T)j`LR|o0d`T5Kuz4$$V*>u@$^W$2PZr?na*rs3{98u_bIvdK_@o&^{+BVH)u9^VNu|eW35EYYh}Bt1S{68C={f|!K<56M`~ND_ zfhvFy*1*BxUm-u|J$)gl5;$c0`q@SRLv%w@3f0~gEPf1OrR`~hcA(6Njo`x~Qzd}VWJ|s7Xg&Ck1GI#i;NnYde|cdew!mB*!Ws@ z_iKZ5$&h?_8v&cb;u1bGSPm zAO-TphF+KCN@Zut4JZWUG6ZJ7bK7Oo6>zh=%vS8Q3EHDh$*_b}G-<#w{>g~}&hyQx zx(Eo6to&8vGJw@Sjp3jEpn}oX(7QhSDs{>?^opOA%b#gc-m_ zkqZ8il}8#5ZFREUfSlx9jmzU>ySTFnK>=+|@9#dKf^gcT25Xy}wR@fp{W^)5RlETj zQzXU8*e^Rik_}uS97aGqt2>QYM{X~@=Mj$rr`^p@2SWnwB!Ikuy$bkv;1bU2 zFMO1HF*=1ht68xU1lMMll&CenPmo#!)B8ug7Z`wLsI4Wo2G#i&=tA5WO5CVOeUS$KxEHCK}%-idVG zH?KyzZ=arsYjvdj9RE}M-xb?o^`PwQ+17%X;-Pc#8GxCA+9Kuc)tp0X=G{w{Wz(F+ zX&X;q^7sHWjII5br3i)V?l=wOk|Ku@Kwr2Ql~#>d7Bvy<$;IK8C*jg#X!1-#u|Pjd z7Sp-+w1pHv8thmfn{o&{207un>TAzcL|z9FbZQ|n!AJdK{y5F__Y?i`IC-*{RnvH(}@9UQ+X?jurg=phB{rjuc-mAqFHS;up3JxJX--|ENzI+tuq%FXRgGi9H+*m zHhlx^D@Jf$Mn6&Iw$38hPw+024)vP5KITq&vtJru<};OV!?%TR{&rI^Y50f}gjn9u zHCekwrtC0LR9EbQn5Y|&P1eyh+j6#2)E{**T_HtF#!f%jS-5J9fW_mHIJeC#PF^f! zYHQKD@&I?>oYQy8aS+2e$$DUmDV^&7x_CUR)o5^!=^CKYb;rf)z>Z}(lwQeq^l2lo z6H{9`ehq7WJ_yNiqam30(PKqV{*^n{cb3)GZ0=jRwED_LeK*oJDXaSC=H|rX7YOJT zI1s-Fir-R&nNDnOTRd7iaj4gB?|;9h z;40H4L=a6Yg*op$w0ALx6Ca7bIZ$mNwN?8yb&?g_X&~0%g!b~?BG$Qx?uLGaqm_~& zcdl)X6zN>Z2q5;Jx2b^7M=-?GVMZY5W@Bc|{LqZvff<-eyi=WexQ~W4-Y29)SO9w_ z0sf_R6I_hCp(W+5W!av4{ZmvhLg*O)D$Mqqy^c~xd!*bWiAn3PHsJkZxOElRf-b5* z03M*g-ue!H$2)sX<7Vd;_L|PMbgaSi;Y&G6suM zU^%Z`Tmf^#2bxL8EiH={j{73q36&kOeiY!=`vBX|MOzn%e>aij;t7~YL`I&0oE0u< zJs!P6ci*UJ!fU~jWDUz%ep*4?t&RB!LdEV>{-C5uR1TZ%v8-XdC5WKjxk`ZNe)2D{EcaL2fR9IUJm*BMX&oCpr{ zdX0W_7vMD?P%4YD2_Z2@Q zJ^b_pJ^bk@xqU84oq}uA$MLK7mm{WF6lt4n2zx*!ssxE!1KW@v5^s>4vMZbnzX^+@ zG0nOHVA(yRj*WTWfvkj^#kEFiwiJAtcCM4>a7m{b^+DJ`qU^3^)vH_nTz2PoVnZUy z2`dIpy%HS{YFuVAdYsGsSy+Uwe(syA}KAneQJK zN4-OsT{wSAuV|jIuo&fQsol$+oN+xVzw4CX3~yLj0yuXi>dasBtdAwU!g)&~98IqW z0o*h&t8<lmqf#^=bCwrSAmWnRKE$Wb~ESOAQBaBt72LNEC#C;_gMLhmTt{!^s_jd zF)2kzzOBr%0fvdIZ6|9X$oT#k(gMJT@mTsRSNnbaS7h!udzwCw?eX^t7A>^0d?3r~ z#=fXEm>wBBdg<%AcCo7}(HC?++zfXrvRTbujE>Bb;cMa0O*Fo7+jpkh%#6NndNgD> zvP@0AkTyBtfze|=gRH=L|uTO5yv{z2sqZ~u`%vnav zgKt@PCWCDcFRv93x*~O-*=0KJ&7DN);;Cxn0!`6vhh(^|_>}?Coa^)9gz5zs(rUe)lBzGiB3Z{XZD-6od@%i zV;eFOr`lO>66qUj_4Zgq!7|W*p%+8$)FsVNcAuVI%BXZM^Jk!E>G+u&A?8I5AjT)9lK}q*hg!B`M;YohVo!p`4)VY+zRj zEJtYwez>x>ET{!Y(7O?O8>;K_tMQ0(MI!tAZ4D5#HD$l-Y=!0b(g$mVHjuk$kFl|W z+nYh37l#yy8v>(}$W74eS%UK9%?JU18Uzr_87z|aKp*W-EA0Ici}FU)+t1fTx^2m?Je#d~{Kmt$da812d ztut6ZX>c=NW$BNKq}I?8{8<%7i}cOCY7MQ~ulmLC`t~9^4?2OF8LUQ=kJZPX{7^EB zD;aF4Q+UuLldS4JS^vwa=}u!A#V*gy0>E;&2~ z=jpTKBu^7*1*SX-e`%9!-1yN&)YMFXeKFTqQ&7QR6AXN>Q%hXOe_mLA36A5^+kGRcfg408QE8xHgYpV|qg{~5MOwrs7D<88d$=`euf%-hv245 z>H)RAVp3-dfmDNcb`E%z1_TSW@fd1i9m>a`d4m|=U=_JK$3Hlrr7oC>6S^VqLUc_D+_&8Rnzj6d|0wb8U-z?)Z z5NXs(E5+5JU&xKUaK`K>Hi#}R^`fg4m-HwlQY`Y@BPi?~zI?5JmdT|t-KOJRjPovE z9Y>u(_(}S466GQ*t%j&mp5D^+U*D};6u{slDG<8KK+m>zI88+mTyXODpT8<{@1pea z99v?d_#1~tG~4Jm3sg<7q7SBt5%0c0fPYvHZ`ch#ro%SdwO=ww_I~Y3%w*=OZjZxZ zIbw&DPXmp~lol%;j)D`Pf)W^hdI=gC{y3a?YGLW)^AN*GtBCfVn_O;Q5ED2#tfhdR2T8N}i9ZP*};1)y? zIIg^VTo-QO(1LPJG3zot~b*+P!XyYa1vMw#uWKlgw5}pZC2L|^( zO3EYtdcpZULC1Ma)H`C$Z(TV&q+&e8XQNZqcD$epj3ZHsPL)_naSk=q^4c%K=gy_A zuE~(EIWx(l^5w`8iJDH?65>R2!_7^AJa%Z&GrB$Nn{XT11ZVtEnN5WW#)Z_Lk47N` zZS;<+vWrN4B#IeN&mTWc;Ai>ZxWbIX`TV`!hAtucu^s$vR{e!BsV#P*@@VwTPWL*? zV)gK1b60KdLwdRAlg37=L+%tSP#!A%X4~K!)Sjsxo$BewsMWrjvN-BLOfDT=*`4E3 zdFeY`GACyiPp0PYwFc|&?W)TWJ*TC#p}`)@)Iu{o$*dZn{~ao!2#Rklw+^AX=LPI8jub`B$#7}H?(pK09`pz1 zt1`sFLHw)eRWSuWAhc3cRHWIV1sNhE2mtvY3{!}^e}c&CLI&vt4BMjORk&A?M5A*w z9~H2bRsR$Ql}jgjUFYmGVXm+mAakUPw?1x_eI=;c6@q=GKJ-FIa^@#{O?njv*LeI9 z6KOn(+?jK+dBy{ZU+YnrWRxPwb;?)rY!7*a(~<^Ha8Zq)qJ8*qgesYfPEg$ALmXX$ zxOsnLGP{vx{Aa}4)qq(Cv<5O6}n`F;K0ssXpPk>jTvje8U?Gs7*eUJkIQbVhpuxlG#&gHBkM_ZS6)BIPlo{r z0rS5PUWVz$2$ZG=oFG!Z67?XMI)mb*c+G2BZsTx{3bqG7dycNx1Y#+0nCY&09id+@ ztv5Z4NN+;xq3tS!6mOy~M%K=QfvOJSdB7IqaM8UM`1!#?P;@chpsBZZwtvz>F!jZv zYzx^goL!_kOAMsTN+H)6t#aphbt5dRKmZ6YSu$~9RjLqbsGfN>U?}bweHaU&;>yaE zJ4K7#9gEVMRj+Sl_(S(Nh0Ck}1J8sSLzG7GG+~_{tF6n&sKxPMsJDNRDnkCU_ruhTl)W3V1I$&JSQ32<<%Z956uFL01t@R7j?@T$ zL@BzBkSJySI2*hJeVj1!>dyOA!lo>en(edU_%y2JxceZ`=M#EVyg|aQQnR0>TU^TN zd-SKYhU}IPpbH&s7PRph6liq?Oq3<(8!vUoON{o}Fj|YciZCyiwxt;?RZ21RqK0{} z0xA;#lt3XUfm<4TarXyUppz0$3=n)Nd~$;5Y#jko)UHqiC2;gj8I=-S1_ zJ#tbQxikG9?CFO-PYcWGJ5Ka8YS9^LaT=be{FdZ)A~Ta``Ssd{0P=gR*Z`Nd2D@G= zBa2WBm|j*|Cw5s2!=PPg={_PenY!bk3x*>OQ9g5OS>pKd{Js38_v{51bEm$nEXFWV z{XAu?aUbV#s469qPtmPq`^g%SQGv!0jsIjDKiWdC`LK%8E3A+=|@8BcWvm0=8c-rJ}}hGcqO7PggxgBDmjuziQ{@ zrrui`UQ~Xjy2nmMr%+Vp%0=_-aUEob~+b)_72lo@p@C;IXdBuIAS=9Ey$6Prd zKRRJ~J1>U1cWaz3tnYE%)Hg7;e~I#Ygh%iKIYYjg$9;l!pi}UIPYi@$9q791ujg`P zmhF9ww|h#Zvr5L*!e_OOfXPqWs-ik=Mk0H(t0}j=fEn#kTOawRhkv|}^s5BP)rJWF zQXjd|$gm1fq{RpGyO1u_>T zCy*O@LHlSqC98@ey1~>}<9kymOU>2D7CQw^25tK^MmAgNNk|ov`VReB)8_4{wx2;^TFta7oQNYoy0et*-ONX;(gd7nuxw+gLJQdRqMU zjkx|RcWxd50vXIPXz94YpLF#kaE9Z1Wcm3#N=_^zQYL^c#1&M8 zB(G5xJba#%3T*DRy;Pd^$FAlO3gqvtAszG5jo5+iAw2u$+Dpwvjj-${<31wx?qrsg z8%g;M%}2`KYy{+b z3=h{711bfvrV?+_ZBTz z0XuT065BG>uZ@MDu{ANVqwE&^^gRX@VFQ$D(<(MRGG_To?y-WLk|H1O1 zBP!rMM!h|^EHScDpK3V%!rkg~YRu7*+ z;H#E<)(uBx@KMA|loF+x`y6&>)h>g}r$uDP`GMW%r>Te6XgklqZLo& z5x>u>t>FsFU$3Cec}xVPs3#L6mIoQrzte$rXcykS|9k`dwM#(>-f3 zWAqDRV5XWP3fs;LHodp62DxDB5+A0>0bVS%Y*I@lD#QQn_=Wl2J;_-GuYr6IhCjGu z@2xpGFx^adEwg3O@O|{B<&h&;Sp9cT?b`Q{FLw=ySUWE``KiI&NUBK3_(h7~{CRROX zkz8r8zghd$_GaI}ey}hrM!&-y52O!l=jsJ$5ar297(GJ%Qd?~-N_UP8AB4uFh})gT z5Zfs#E(1nP3?Bs!1r7C1oMW^w?rP#I_G`kAA%xrA?EQNt7Jw)3FbVs>D z!t*bVEI-@L^WcM)3L8G90uz<^;*xp3%9FukgfLZt;|AYj_I=Q%z1IA*_7c<5Bf80- zwgV#1B_U1w*uHSk1l0o_XEcRQWhFhebph#L*caugn&YWT@uG;JFCR$AV(#uD2umM2q_h@ByTuEm zPpLGzu}upJV^F+ncfwub;($TE*J3nfisL6fKcE*BjrdrYGW06o9`R)N(_H^bd@#;b z&Y`3DN&S=k9j!8X7xOeeNVPqA{qm{{578tq zY3u4L&{CSxQQW3Ih+;*+)|-56#VBHuhwm&)$YZXPE0)2OsMSD}_G_1w6Y(Y%?s4I? zy^9^cj8W`cz+*TC3W!wgFzz}`NQoWh@-?ve1dM8IwJDFhPprb)xwD2Q*>RLRG51s3 zn|s6tMkEA2U})o%b{#*?DY{yWe|+z8Xo-6?8p|&grE^x4z{kzf=jOYzvbM)b5Sh93 z)3s2m%2Y$IiCe3Azf^~m_0`O0;iJng8MDuK*JSYHbE0+&cYXX68Z9iesQrw=6cgDpQoZ$Dvc6hq7IiZvPm&NTC5)B^mGiQ9|)&j)NjSJHl1zau~iv0 z##~mp=0u6lDX>v2U7frA;ZLvQV zTi+V}EKuhTj-tAB?U!y`GE($W*HHeZ$6)daYs{@5FK9Fwmx=r($%ABQr|+F)eK4twztJG&8o z?-jYA_F!!TJ+wNXw}g}wiOYu@57l}HIE^@zNG48Jie_haCPE*GaET+rB($HyyJwme zW`<6+H}DSR>)srmTX|Y_J=G0Okn_a)I7sLv*rl-siIUt6(XPhN#8!qgF^c~`zP>x2 z>h}NN-sjkRZwisU&vB%b&_Y&5MfN5#j~O8=DIAm(itN2dgk$ebluh>fUFR-!f4<+( z?|c7McaMj<-q-b7&)4(yd@1V1_HhI*{-k)S+JZ)^nIGPLx8$8%OS66vJG-BR(oFPa z2hsZOWm{We4L<6lOm&M&( z%?Bq_0{hK$?sZo08c2N2by#{A4$kD{d=Z@K73NIeDjG(9p9x8ghVh56&2>T*UlGBE zYUnyD1f~eEDfJf@7yX*d;O_3yQud?4n;*`V$s<$@S#HM0P|#AQ z1v9DU!HH!ef}v2mQvBBezijBg9&wCEG*JYy+&Pu`s^QUnY|?Ts98&zv>a~GqI#+)g zGCgU;=^=}%uee$++M`oQL(lOgz3y^ZkCW0V+59BCHfff@?WeIdN1eI&V(2LyJ54og z5|08bT*$-|cRl7`c5SkUCxPY~OA6G!1^{GuCEY`H)vUNc(T>F45Vqh?3dWBENw384 zgwT(SjCK!b9MjR#edqJACB?4-)DR)-5b(wb?GfaJB_kxI_P2C!FrpX9Om|Jh?sPn zoIuW}iEW=$?8{1zg|5%V-GI(M*}u-)w0Cmv^tP|y{@sn08YOI(n9)iGO9y62eqjEU zMt=ST_BDu{sNa4{9s3!JCj~ZPh$eZPH3L!-!N7xU)Vr6RhtA7fqE@ddMSFzmMqP(rkPskjnjbw2UWfJ4# z#NIJtZp_~-(B;Y#_z&0eFE0ar$|C~B*HxEK^aHx=7 z)eTOMp?b34uiN?|tM(+8|Aw7Z#z+@=Lc0i3l8+!}C_?Q@e*Wfyn!zn@LZ-sUkI}R= ztu5t8PgIjSoJ!#>mGS@eq6Hk>exKjMLNR7iSWa-rUB@zS z=`)&SS20vJ=2@8(<^a`v(I=ZOjrL&qg=UgC{p^c-GuG`6)>Zt{zW$%rcHTSd7$rpo zoXRX0GhuGK=#c;7tB%D(R2x`ZBWlsfvP<86CpmJ)!6Gy*|$G`b`lp{ke2;;=Z{1m{;WXZb&U7CBLA55^xW zIG9&jw%HZ78qxiDzD8lFtwKiU;&r1)DCnQZS_wBfFuF#0n<_Km;z|-bm*<#=y+DVx zbymA#828fTjU{U>yXI;BlJZ<*0;Vywm6I^=A!=kTe%gYE@Z|6$-}CoF_(aO^#zc0^ zgjDvYn|m}a`M_-;*K{JUAdp6Q?=nN(c6cY*^^T6A$_J#8G_gqOB(S zhWirrF)xW1w~G&j)N5fXLVU5k4#?`PR?ea5m_z}0=PTk&lne}u5>qI~)=KWZ6vs#Z z$I(TPa6V#UZ18jqc}hweWss94+$M6IZnHa5U+YE7{;#(mg69H~g{totL!Q!)dtdl@ zLcp#cba+kD-F5a=jlwt4jcQ#bByXQ$9UL6nw`*LA8${ZSZ>rp?egI)};w~fmb?#as zTB7`BS%`uvu!9)eY&!Dv^V0+tUP@W3&$UAKMwi#SGh|*TKPyo_qL9V<5uuhyC*&u{ zi=XiRmVa%nKR!ce9@X_*)Gqk=PP+teosmN!5|UrWndh_-H)ELGM4Ox5PZJzMp(iIN zY+|z@!}_10>DRvk{9jQ|Jk3GOg{w6$)J8!2rg?rmKW`6djYX2CF9i^ZVfD1?3FyNA zaf@v9M9M57>Zet(Ty6;n7p;aS&x73{-%kBNoj83)axM? z0h7XP=Us1I;OHi++;d+4a&)32AoSMJ*-(tLvdAlh4kF(OFh2(>8W6>w5TyvWubjrd zmoDLxT)Ud**vq$kL8STQhn34m!>~y8Sd(NW)|-}#(FBYK=kFQZnWwNphoKN~>~!o9 z6C{h1C=(?!Ek5N#3UGQqWNPXp1?h&<|8@Ei{9mVkve4TtU8p@tZ9)MLri61 zyty)ka>JaPj_C)5gSHA(&PT-XL}Oj`&kg_Y(7kxC_U;P;H;eUZEiwe@gu9j=Uy9ao7wwI_DUy|yIhgP)TF!jgFS9XfWOtVU7_sTjR~~T0 z=H!Bdk03#*_FB`EJ^Onb_)*AI7AI{S^5-){Ne`FyOw{2h8q-&X3at|*70BbR2Ho^Q zqcT(;#pLqDvkOrybzT*2Y1ZR%dUPUqF)>)az68z62AeRD_rXw0pvbDY zWCyy)AE{+9*?`GKHSTmSt~o!%WHi#)C3))X1^m}{@ss=4SLr-4?|C+G3y1V-Xd3>! zg);W1-}bVu;(xcqkOX1wr#~DZ?@NrZ%%a!%;mzw>QfM-G%U73lDRQyVpI*A`tu}D= z^~*2SK`I_0Z?SEJiEv;z&FRbnD{papO&YQvg5w(5cXPj~K={D1owhdDKeqE9l)f5g454)20 zC#Sko2|;%e{QDScIo8~KJ`!>@4=xKOhPp91pgm=>rjt+aHGKI0XSNY`*Z{$dsIRZ@ zhD^`=s6gkq=~y}}mPUu`+%ET^O#yj0rv7A*#o79JkJwgsZHp*;t&Chwx#oF6t*K#H z)BXC$7WO+9c?Sl0yU(_95?6G_g|@vj*L*S zutbE065W6J&}^deF@~8S3O0)tM|0_6^ya41P4) zWal^QM5DDETUyKk4_L3lO&II}yJ|_W4~t4%1FKM5z!K#f`ub0kl9*iF-MOWt=o}p# zW!5UU9KdXZ$^Pd2`tGj#Vp%qyyFz4g%6^%LIO)SVOV!K4&zLErUxY-b zbMb@(b6tIhxN62l(%$~OzbBwP-@M!P3vZr?F!FyQ0jhsuC|`PZOsyJNBJB z#hs9_uwp-?j1<%Sc34fpYgdQ$7~cHf`N4mU*Xt<1#U74kumDm)FUbA+c$gXp*9Qc2 zswF{Ex4m@pbAo>#%G7^>fF<#+w7?u zwg^WYTnHj<@$Ddk4a#)3`59(~dUSmJ{AL><317s_CS8b$iRs*9qof)!dhBG<+-*hR&t ze9#?bD3{8=UybpdzT{;%XV&rL9*ne##f8EkjyGdrsF*yzIkgPYM z5iMPTU2fr>oz4IXe<6svdk^y{W!7~<&?TC@{(rbunsrWpx4tjQbgzTxMs6%2&YQmf?RdLL zUVCj@h2V%Bb*w2EL`QX;^q(rsX>X*sD?7E5fLxfgz=Dra12vr%!d8ztT9~18hooMiB*Ox27CO;1_RJ-y0U22>COL=z@u$~s;m^(FP(l;<*2HX}HvXMsj^vpO6 zgHb?cEg%f~=(wrq(gNWjXZ6Y!aAkpuLY#79d;9xo>FFxa`;|a;LE!v(XPHx=n1Ep( zt;FxXyaY)G27<8oa{eCxi^T4|2@{q!}t+)ujb-asyaw5wGFaftc(QjX0hwTmN zsj8{M-u0(Yp;nidRj=C$M?SFN{!~D{{pgYC=?s1J!!CjVWQbHBhZRj4sVRq=E~&mRV|T_kKkGDAx0?o|P#j>ZoSdD-oWE%l78Sj(Nl|!w5p3(_Amn=u*_c8DjyfkH^D-s? z<*O5aAODaP^+M`GLuC|Ncr%=ntA4~HeAx^FEVSYX{ z4V3_!Z$eX|c=PL2XE*m>ZT1D8zIM00C4eQW65~X>%if)kCQC7(BFIFKi~c$ zHQ$5s${yG^+P4Mvt3@e#?fg8f2FplE)@n|x8`hditnDT$??Q!M+hOL_^h)fK8wAZn z#NHL;TlJrltwcq*M7yN3@2q}qU>^bly8WxXa;j$q|y(^{{~W;xo`DUtPnw2#-7HoO@jQcuL>1R z%T|Lrx}!MI^l&7VQ)}1dxc-sRvO3G#QRW%xuL)RG36-E{5%$cq{+$ok4iiaaPf zr1iVL^*s60?`aSa-990uh+%%;DZ13`O2jPwkimjQ_Jy5@aFf4pb*4y`t08WrQsuZX z>3vk4@Yj@=_kngSn4=&B;~6X;va@g8y2b6=n>A!@=ppkExLl|at&1FM(yLeVk))l$ zVAvH5qy&Rmk8cs$Mn*=V5fQ4FFNb)pf+Q{qGY0yuQrG1bg%Mw40||x7`WY8MrVW!| zXsZ#6nP<6dV-i2d zK#ZWh&rK|+%`Ha>e!>ghC$hzac&J%_LXI#|WY34sAnRMBzjtrkwAk}0psCf+S~WU5Lef%>`#}oHTk>j*=<1aE+~l1`PNtRDEz6- zGy(4%xkmzp>nGHmIf==RWNQk8u)n7s?7DEd(|5)78s}fz zLzmS1E11N_#v;RJMrBvje0-F8dV7;a#_povhUP#!LR{hvmz!q#trIS7LZ6@$O_)oz2ap`S-txZKteYBR6Z}#VX zP7(VHTw@|picnjfwp{)c0q+QSAewvlK9@#4MxM@6+Q!ec1**y>8&KG(DU_tlenNmt zM$q7Qjm|eU%)$Nf9oijMr3k86;uTW5TBqafXuj(>1jB5%YJ3y}O6-F2vxtZvir#$s}id~t?D3)HoVHd`}& z@xa`U(&U%9&Dj8g!u!(VV!HhNe5n0!jju8=i}{}yy>THRfo}lXJVq&-V4%MiOcj4f z@dXk>(?9~LU2yGQz8Suh?Z}(zRV#X;L(;I1v@_mq6yuD5{}uUMuol+PTKUP4_U!S{ zFj)Bqa|u^_clw#Nmt|>`()7fHb95w`zsfA8OKQ8iSGC7AL(WV6|WOd7eExUr8Ycw;(b2&uNz^ zS7%B4okxdRe(R?&sK<=OgIEMaahibACM!2P78g2DC;_^#0L?zEt>r9ZO=?zKBq2@f zXkS{H0+km!fvz=;pc^>8xTvNC8um{FOv?=ruDRM@faQOWSk)KMfo5e50aSY0av~Dx zwY&5!f9t`|u(5&L_Z8eDJ$=3gYG_pbIQL>wIY~?5V8Sb_wwH|5%7MVg`fA16hlNQnIpqO% zduu)Rb#amSv9#1b2!yvTje!k@B3;~?V^v<#K#K)ceOY0zr>6&}%2*k-w0?h*0^Gjz zDs}c*uN%|t&C~aby|BB0%2faUkZ1L)2@ej%N>J)78H&rOI@v4 zY`$aP*NWofLF+|V8(q=WbvZ)EdTAm$(UMd))I5Vy?D=y5T)eeLIxR0OEX1&D{jmfW zqPQ0?X2HPSihI6VM)x$Sqgn`wuKIsgU$xFStd_7U7X8*66(XUjmptksG`nb#W-@ z7XHDRnVGlPn)ks%>SYQ|hX+a<>(7WxhRD0GtGL8ZF+2vSXhfw~8|_&_1oKa$p)d_z zr8DWeCAa*H0 z0>T$A>s-QricmqjbYEHo{?tF3qPA(h$ZbhyuWFw!v#8J{y^e#BiC{DrRpW=;JG`+n z!XYOenp;elOMql@0AYt~j-&X)IaI1i<+7-k)cUx)$oNfLpK9|`cp&TM)^i$K0H|x1 z%LE1m%RyuoUF2STn^iwEq6iJ_?y%CD3#<9ZU9rP^olU3S7cT~tp8Frp4{?E`EY<3c_f?2o-f5=&sxH!xH|50uujZv~LzVl!MpO#_Q+rq)uJ-kdig zmI#FfdvI9DG=CqEV%geATBQai<2~^D7liC^7ZM2`<`g%nSpym`im1XY*ir6E&>V4(F} zRET<$LngbwFYq)B-kT&Dogj>R^Cs4_%+tHpRw%Do2+#5;KOs|3Oe`fk`-Rj`-Ijf} zS#3Hv&>7FGEy@^@#zXCLsnAZyJS}b3r}y7|N8kiZ2gcgB?tKbo20gN3KhPqo9~rfs z2AzWt5h$^k80ZHRAWgGEJy_4)Z{=;!rMgfhCKUc3A9!65yZdgPQYlB|C66@RZKWb8 z-L*5QdyR;vN}2M@skFMVjFdR_tpVeCdD3;*+ZH7ca>=`Qe|+T~Oo0uPe;(HXXt`a6 z+o>w>BTvALs9u>9ZzF{nH{xY2=MAlbsF~vzoG=&8?o1AQ1&l9P*EpoTO zncwA=H23t7*c&MclM~qm4j~Dbp?b0%O;%RctdH;ON-kXzhMJm3kG+}p`S!i%^PEH9DNhD1}*TxwlgM_b4a0Ea>A~n{{d5)|8Q7!z_ zAo-0;m1Jk`VS)>^5=zF12hQI7uL|0u0>+;-hYrYXSFs<&cO<(qVXUM` z8#$)W%I>i&(tFb7jsD@nZSxjUz>*C>=qP29FRP53+~oF`M@xg#Ue*R>gSH$_%%_wY zD-`^-^rIf0xo_V-T-)B=Z2`KK&m^q}UOVnjFjxX)CKi`r$NX?-MFz-7c9pWFhNfP^M60P1(l^hkJ-Y#V{OV}JlgJd4x=)Ho1Vc(Qpe(59A<}Z5oTxw);vLX8_eH{%R)7xnXT2AaaLyInaIScr)8ZBI^$AA_QQxPm_E`YY6M zF~o9j z=tiH-`v$djmW5SXpASRw>-ruQwT&~)eFQy2Cp7%~R5T0yAgC5Uh9dwAhRK15h{$ix zOMf{eTfRkm=#>Vao)BG`=AZiUfZhbH_&O+;B_I@U>rn^zmPUaj7d^t>i^=Q4D*k)OHGNsfBNVg0>tMUevNoV2Y>d@+Pb z*bINh2foEwKvO|=69{8{eH)Pd;X`zE^pwNLck&Vdd*M`7$TOG5U@z`zQz)1(2(9Y{ z|9UFu)Y@)xGMRNpvJdZ!LIxhu<8leHG7w#VBzVO381MVz$BC@e$i1PVTXI8?k`Fx_ zCc7ucGPiFB9=zdk(MpBhe~8oF4YRbg2k%=t)Z12Aq9qFV?p<`~!1LkZO{J`i20FVu zQkl@%si`Sbhz$79pk|%CpnLl^&BLyjNYHw46%YFe;Tl8XF*hbP@ddE#AOe{I6$4#Z zA|J>c7mYBv{%kB4?qW+Z4wyJYH>s%mVMrpiMn*@) zESkv-J?iiih3Yx~FgCIZz^T+o1>bu z<1c5vGjDcP-l>Zx^ZgPs;X@6<$N!-^pRJX?*U}Q~YgWMsAnEfZUi{9I=yf1KL_n^5 zl&5cKVP#)29=7d&(ypW5Wk zjzrLhWC`rod3Wc+zYn2U$cvE;FL59<_LV?(=+3H;3A>ec)Y6Z>NC@CbKBy2o<~m{n`xc&w_moJxGnoP8)f7Q;bP-oMeByr? z8Y0txV{q<#{%QORmQJ~&J*mQXl4bG1AXqz9xL?%8g#e8}?vw3LzVDlajml}#t&!QY zzq<-k4&~B#Ogg#x_}%evM&e93_2pgw$w^xlA%9Gv zgaz~QG2k-_NhHsMhyMkeu*?f#mhQXkD6<3Eo~3pEOQU{fY$$u}EC%`ESX>a@*CM5KVZt1Uge9v{n~i0$ns2nsCDV%faC8 z*t~z<0E0(0I@wg@BcX)%6}GP@iuiBxL}Az^H+(eDy6%8YsKc=~$y8aTL%xI{Z}2>p z55yP3 zd=Si{Iap*3r@NE|6JuD2-c)%n1dzq2_OU#k1q+SS*ShiZf|2!GS(3FfUEx zpW~2|3$=sn)DdhHEY48S(9B6paf}6fhKjJ=9Uk7Z>S85mWD>p&GXyQTs(M1gXsR;fg)%y(ddO+f20BgGd8^UQ*NlG6O~g9i_;T)!UFWOl=M z7p%~oRz8_kHcYYJ`qqJw;Xncqd={|zpAXJ~s(JJ9ak@P*xPOD)@P5FA|9w_>;-f<) zlZ8Wbe|lrAPG$DR{Z}xBskPlHWMUuMZ>u>nzJY88+f^%~;d0cBB^>){u1?{nySPA7 z>s{=CV4{Xq7JPLK-CM^gBhZ@Wg(Q*^ zcy)788=vVwq_X&<=E{_|fkC)c_ZMKc32`(Ad2km;io=arTd(|y>gixO9*cyqa8)vM z9EQ6@WM`S@YDbYq@W5VzOHj!eDjnJ}IXOA)A)s^%KPYJEX#T~XyD6uV@VS8R3(6r6 zrd3Aub1|*RtSrA(H0PfENMK^6f>38`ZP#FKL*JKJNRV*SD3+`@i zZLcn3a8E<93|f=^$43}4@yW_a(H_t$?U!q8keFdlQ$tPfp)uyW{Sf5lmj5; zG!67BWqJ+vz1V3%?RwdsrTwpOZV+0parWPAjIRy9fU~jj!=_wIIq0O0(9!NDRpz_Q zHh%&wJk+SXoWm5FbMCfohF*+G)uG)~`BG<2Pj@%7Lms(YU!RPdJpgQG{M{_32{!ao zJ0Wdd&+F=(S}+7cDksss{bVYKtel)iOk!g{u9iVr0)$gv4!S0ZYdkDqv7@LXptOo^ zfEE>HS=$u{F~)U5sQIv{`CwFDyki_HkhaWTNGa6T)z!Y1Q+d+ub!wD=dJGccRLUuK zLoqTe!iC9!VcEi_UH9H}?(SquNnKs5rdG%U&3m}1+8T;*dy9ie-X?{8(o zT51$EdHZ#5LG{>2C$1MXXVA zii5YXY6}5G@=FID_@*HQ? z0Lf@uafVq`+I}JeNF+Jz*|S)zCxQsZma)+ICxF#j<40CPDt$9129iz3%O~VsB~9(t z;$Bg7z#`?>RDGgBrlR@|hdd&7e_zI9nc*rA@iVSgpgIaO92?fXc>~zKfZ%tiMy0LYpIOrl0r5bt zuRrZpjusws^D`t*07S7RG!kR^+Q=btzA1FSt5qoge|_G*bxMQ>GR=VpGKY2+I$7P> z-BkuKR)O}jJ+pw=vN8|v1_Ff|Yx)tpO3H+57w`iDY*+I1-AoRk=*KhyazW;M> ziVY*2i|npPH)|t!={e^sx70eh2=iiQ#w(uJ*oHUAe_kC$Hp|B2mbRf&+F%W6PtX2- z0xC-xpCcI{EENK1sV@eBUXs}pfYduN)ZVp(l|_3D)m0+`DuA^`V%F7QWI;LEW*8QU zNJ#3zPK>brY+dr7xeAjl826OV-0bwX24cpO8pB~3k{_qDOqAA2zENP$ezaP{E-u0J zTK-YYk^A$#;wM^U-O1B>j$&7HbX-mrFV`BmL%bOuilYKC4UMLzPJrEFap16}r2%S( zG0S;_NAD2}1iXtBedEs(%FBJMwKOyuf##if*(>B{$gzsoCxL)tuCE+YWk}@E;6R(# zHT|Sq5VoZSI79Ny{cB;MsWSZ2b94hs-rbUkIqkfFpVS4d@$gynfDXVZ1=Uw)P=PEF zj*goPpX_VlM?%4SYq%h}^H@rDU*C0~fYJ`o;;qs+{0*IrEP=IHrjwge<{u-%?!*ud0rdj?d~?68tz2{-vcGU^-#Vhp?18Lb!gN>nqyb+NKbn zCGI0gwfBdW`cN$4HG&17=lqZlmvr<}A7|dHOH5>t%@R4`Ddz7Ix*@*xhE=g)a!Sm9REA$nEDP^m0V!tSOzOI4Tq zbD-{>cAIOZJlcxYTGuhP5KkV8bu z&F}ow8Rcq{2Gf69W6u7YkbuES2V$AEViVE}p_Binad~|5OXI}q^>wBEY3pP4JdKzb zWO~n-PpXEQ@AG8efr=O2-f=S%C4A+u_sIawI{dwxiqUdi;B;M62@OMLWoBgH0)_W; zn1&1@1eyktB%N$SQdRRaE&%NffYE>b+Sv2IiJMva@nan@1k4(OAs~T? zt4WjK=Ei*iUf~Il+ss<yo`}fb~Z-r`-0jlVx9KDEP zD8T+&TUatKgGr5U=TBuf&wycpsi!boy7iwtSiVQx>xYx_m6t$C#kDi;p6{|_^M>Ks z<|K6r!vlcRq0+J{nEPkeBq%Kt#Tt&^hIW#4;y~%bxBQSEq1E=a({t)3bpbxs(tC&I zJwLyPhCNkr>7v67-7%|X)ftU5t3IDuy8^N?BB|Dv?QJl|Re;YFXS=L-#q64f%kmfs z11JUNuZ@{ZelgW>Da2T`RH!CYE#nCb6BQSsohsHtOnTM7J9)W|_XWy&MIUxFzBG8q zzQSVXNAv|W9Co({*L~+Gg|1z1BEL{U_QJ@Cn5$87?l(6i!U2Qe>_NV5{>uyn&{0?w z!s{7-u{O0#*jHUahTX41Ax%wM$xqdFKeD|fT`l-P&8(!--<<*d^licitB9V?>&Y?T z%pcL^VPOU^F`h9&zE1AX&-QaCTJ|Q`TP~Tdy>y>GcC(Yhnm!3)f^*wyRmbP1__LOKy6!B^SOs}4CUe^T2x}*J9uw4 zqf(*I$W!nQAcQov?6O;7q26b~Y7>N8hl(M(5zHZ}_uN@;#>6W2#NRJnz1sFgdH-d&Ha5Z~M0h3qzzvJ^CNxm(EG&_74WRBm6*Sh_s`CIF&etgikF_@C+1 z2oD_)2F&Ywv&UK&y`&_T1_3_mlm(yIWeNH20valqX`}B`9CEBr?I2dAaF*R8Ar%P7 zD+yUVRiFbuT?~d0-$yuhX2f}mv4h1VTwS9pq(D5XRM=lw@6_aJY2m)egLmE4b*RSu zf`+a!al7jvJV|+SK&)Yy!iY(OZxPBGFgEN9oVA!@@rx(byk13w(H4zETJW!ZjpH6+(0|6ox#ue5n^= zPQJ39G=C92C0P;>1ai$3I`CP0-Tk)yB6(|69z0ZwM|HkKI1o4Tcwr8DT9qFq5+?wluMAfX77tubVAaP=b~L$#2%P&Rt!ps1~HE;DboIL5dtQ~4e*6T z)9CoMk#m4_+T6p>UeK673KQ`OzCzPp;F!H2~=~A>;HH}{$epZ=l zz%p?E>5s;IYsb_h=P3)nVJv6O7XxcJ+up{FRVG@ zjghjg-y{`*fpKM3dMvGonHVZrwD$d?bP;iCk11@EdOWQ-CpYJTz9ALJXfgKgSnp}k z&0GHbsd)7bwg8_puy~hijs)b{!yKVK-8*oo6exY_g0oWm5UL)fh`c(bMF%%hxvdI= z(GkxIX$gre(~un$#}zPKvE19sNyutu?jw7#?= zaMYYnio9dr6h`Qt&Rbv?Y9U|IE{1k+^LZi-%Hsgwdl}%;vDbc$K4E;1h2Z)&qIO^* z0^@tn>-;np<|iDHU#3Ma|>w^^s18H!D z<<)HSQy-vud6FIV6z5|Fl;W`U%BZnTT3RPA^v)f?@sOMX6Rcyy!^{q$5x1id0m%7P zNZZ57Ceu>&C1&Ou?_3-#En!Alt#vf?7NioOG2FOud-oKlZ>O+zlRL}dB`*X zZvXtQJs=m1G75+0GCs)A3%d5Vdxs%8h2n0sKH2MwBx`(my#F;-l9T`mKS}U)kNWsg1WeoOJm3X&+Bf-Ctbtr-cSeN#Bc# z5QlZ=PGlMZz*BbW>VQj48Z!h<4kjmx7FpR)Q3e({8G&(@BM1SQm}R#CKpmpOp(Xn+ zXxD*PZ56!>fn?cR#efmH+BANUF0wQ(+;SoQ&TL1aY%PH>u)0hr!LM1n-giqct$S+1 zzz+WKAs^SJ+Cbzls}se+GzI*nX(cmFhOK@QkT z8#pAZU z(tx(ndJI`piwMA&#IBuxYr9IV+CJ!!EJLmD3IF`X)g z_=CWdnyRNl(3CJ&2P)Ny4JJO2G6VAqqxBHQWM;EQ$J;cG6L(ANSWOean6)h0gx!In zr6cBzn{Bkb^v^)%9JLH{z<#pPE>0^okB>*&Oh!5acJkKoF<5QIrI9K}OASioMW?#o zSrUUfrfzss@udg@LH`cO9#>%j+i`ZJS24ULt@x(L|FUlZ6iFcav!*@%1(iuN2kq`d zX3>+GYm~~~_&a(>=eZ7rGY30?+43 zn||$V;~zYCKdSHI{a7g}9D|Y_U)gSalP^>)li`{euzp_e9R^3(eTqVOl=iMdECFlW zE{|OH{)4)jYGa6m04HHSIXS8GBFIpiOj{KW%Cw!Wvsvt-OAb6Gm(i3=B!ZH(bi80b zo6FrkIz7V+7jl)KFrR(dLRWA8o62r8GtpQP>2ya&qKuCMUj*ya4@Xwt;zX4Xq?p6f+78g;fR7v>T4FR$YY1E5q%vO#n6U!CCeVks4eADs& z$^ZmJHE`ffrVP7L!$jvulph3_eu;gae_s%%o;&!_PC+v52_r zw2Xa4u){+7i)hU&|6o&sZ}Z^xCNaEB_f^{SZ~wH>8U)vyjA~c4_^~cjFAiAr65w!CeB(N11iG0S|AoV$&F&Ml*_7fO{)yP|7^4_Z78>NCuP#rnza_7tFSdtX=W zjFh3{3_)uzV25lv87yGZ0{#{{x7Ie5&|w==nV&8W+Mv6KPteB7^4isr!LIV4S*>qi zFymu>zVsp*jdjZ`U3e-wi6k2o{n&)v`6@0pd7z0p>mNuiCx;Rg3e*f#x_Wg=SDys& zxUBM$i|d!P;0@5W163shx7=lif4$p({c^7oCU2!hEF4OKpnmG@V{7>5+`tIYrhY=$|Z(C2BcEJc? zW!hNp0DyT0C%Nc=fK2H%kj1&HJG1>sk*CISy1MYr^#aB_L`163%ZHM&i)A@EW z`w4|8;q=@pRzfJNisp3)aI6DftJpq!h^YSABI=S7c{h6j!Te)G-9ctMZ8^-h*vPAi zy$+T78OYQp0tJ4R3>v&RL_tl%Iy#_0>44X-%xaHCC)daeCYZnf_+_-J{Tz<;h z>jwlBVOLYO0D@u6kNM2wRCKDpSpr!2VK34{%E=Qm;-XfbB6Qh zi2hW9fvDJd(rn#NYIz>5W^oRPf7n43bW}LX$xs~())H!hOs(^)^~1so zU5BM|;!q&E`{Bel3k!?eSebt?F=^j12v0ij1O&WV8e05oH>t|a%uN}^32y2$ML)-G zY{oGgpPnu@X?dytPG9I99ZUY-zc1Ax#Om{B^iAV|wfGKGBY`qL(mO9`$flQ9D`;>bs|DXQK%w#i z6A9;~L+AfM!r0P8PYR(j9(yccS>KM$Xv9PD_3c6Qm>V-)Q_JkkgZ44)ur0wxECMxa z{{l}mj>;;P3B07rA;W`*EyqgsP`r?i)WuWr=gEmv7AKDY5v8fAQ)}J*i(g(*`K@nl zA#05IaStaM$q4q{LY?DxAGyly%RMY$w6(Rx2sGWv@UN-ELK;Vn)vM4X#GyV^v*m(6 zv9S$$Tg5scW)1>1qd4lNGuc*jJdBjiRN&(2HpI+?QJ4E z8`TJ%^We8CkoV@z9Fnq(j%3RbiKn`=D*yien1mT)1wQ_Caqn5_ZR&z%ofd+i5@e@y zul@h+hq$$2qi+#Cgw!TS_Z1}gRvzgxP_X&0&)pB?-eal<*3Kr|C3`taxDX|;B|RBXqx4~_&LV+Ne>0dT zT2r3{VZHmx#rRA(xY!%dwv3F>m763#cgI8GUl;|y?0x5DV+vqt8HYVlO%VH3pBS6~ zsMYZC+m;`U`PAWrYw>jd76GplB`5{H^9zB;nEtkWSmS{C% zR?Xvl^PV_OSXeYT1VJnr>fM$oc1825N><*tzhKW!b}Q7QVgfVz{W% zEAV1^^WWJfn9Mt%!=+N{f*sZLP7eZh3NFiL z{ub%xB3V*9Ha_n(of#@}+sM$bjdou&#I52;$zJg}P_e4|e{8*VSd{JaKK!tBE}?Wv zO9;}9pn^)NNT*15gXEGTElQ`PA|)-kETJ@lbS*8g?84Id-l+IIpYQwo!{hL9<8bGm zIp>`7nwd-J6Hv)IH2`(d@5OR|XhCZ+*2kEC1|mMSDS|Ot&Pqx|x3j%{q};%=uR?(3 z0Nsyng$fD|nYkw=CiO7TzE!FZad#N zy?uL-hL)fbPhC?R)6{fOJst0n9WT&AqOW1OwE^Pq#x&{dXxOz}GVTWt0IAH*Eb6{DMF!9RbLUvA@^vc(XLT!h zGOZCQOBla!>$Y#O-`o#+Mvm})**~lt_tGeQ1l^oDrdDq>u+hIl zs_iOSsK{6NK{dTFp4o=$BD_S%8}q?nixPfrL2 zvRlvR%Q`s{!R@y!dw4e^KOb0xKz=!SfQ2pLak<3?7(WjTuG8Mnpa%f$i{w=Bsi9$@ znx&LdacDs!J?+p?&U;X5BBjo~I_BHtliAEV_X>kQ-jqKj2?Ulu2+*=%2#5*G^C*CB z{3GZL&cEX)d#d>7H&bZ?nF{1WQ>i(|C7p5y8s3AM+o+i z_nn`0gVCcbS&@HtRQ@gn!|u0g(7pPKBquxalWqfdDVU9t^o9DA-uMaG`f1^oVFs~| zp-H6P<|;bWeokCP>N*kgZY&+qkzy&?weN$lE;9=t)?W2Uuf5nXekDirVamzya@76M z)BCr)gkr%U3)WC1eNxM}$?SfB!<6TsBSNWDVkiT_7y2YqCXqfykw@A>0mUyK;WRL1 zstUx@OMY3lijpF0FW>DiOXsvH4~Qin9ekw`##h9$;x0`Iq5Rwbd;d-ARB_k5vJMgnCP0o+GJt(=5(ub%F-d>(W_fS;IdJS`kN@C- z#~>8wQOGugVu5c9A>>?>oj-moPgldMxtBbal7$N+u<#8(>fvkX5k`q0N;kfTOsHDr z@{O3J@&?r=r_xG|#7z&%+dQSP?(54F6%*p+FKw!ThR~@byv7$}OB0A7!B>_Ck;esM zu`y%({VVAm&^!9v^x%w1N|nW+@J>9v{KOmozRV0k5!Aivyhr5lywnTHMnLsg+V@ZCbE!A16K92c4)w6Op_x#{eTp2Mgg{awMDIe7zb!;I9T;h~cZt^%?SL379Xmmm_LFf9xg^rY|d5 zRxzNL-p1lJW~|w>THwJ;2E%bNNf?4j3jCO7;;C3`|baY;IRov+0!-6iD!0>Eb%C}e3 z1}OW>w=U=Pik`1m_2Dp9jv{_jJ%d_LL6SltpMInMCsfza^trZQvxK#ur-pWRwb zAjQ}-7$yS@dj_8_8C^!H>{TWQ7A7W&$*rylOI){+-rGA&O+%#xjA5rch?S0uzbB`N zc%aHIDPitp=S7NCfP~%gb*>iq{o2)xoPBRv!~CM^mNKOoSo z3T2(dq>4$D$77`~vLe(U9|&HR)N@Pu<4D1J*;HkRc zaY=36#;E?c-miFRuy0Qb$LlS@g{S^E3si%!fk5?rdiba2uXUeg^`{DQ0)UQ_7rpW_cPCd`>YF?`!8X{tnP2b$K zlNyi9%v96UOP!gW-=rn@xnlmq`u}CqR=ng}cZ3iG435x!Y_z51e*X z?fsI)#UjRYY1Cxhft`dv4ro{*TMdDh!voZeX=X=H}iwBj!mA0kMyMv8(NC@VpjDI?LOIBC|l0;Z| z4K|(wMU*{O(W%Z`dfu9|xR{sMkAX|!AOOKdqkBZe>-LgfBa-?wt8jvemzPZx*jD?= zw4a&d(z(!+xXd`*@9Yq~Ef`Ps;lm4a^XgjByn+I9CZ^b8+sbww0-7bp=leCb5AxW=_DxqINon4R9{EonPI}$a6#JMY-30zCkFvq^f zDF+8cLuxq>yYZ^-?w*OqI?9g~F;{!TCsn0jZ`e)sV>z~1A?xdr2;xFDLti^uyr7)0 zx7UER5T-C@PR_wulT;>OS^A2KxObr9kOJUr$Ngfj7;CLeff zYBEcklAtYDEY5qUySh9bFt(32y#)}YhEsQXk5*o_{u8>`hMmqa?sP0%O3~%aApWYM zahgOdN>$Cm#epAPplSw9mxuybQ|;uf<2B+^)4!JcYvp*>K?T+D`8LS@eyEKa&}vmp z{x`J=U}3A+-suXwvuO^(H^d}>uC7d*1hS;IvlJEbJ(36c@ny>^8WY<3UVWmJYre}2 zmq{{|?X-Fv9?ox1-ZwJ1P}I>}7-kVJF)+Qp>BGeM0Qe+%oO}pA{VC?@3TCUiKM1&5 z)x@2TPebqZMvt*Y+icUc`w1d185|$}Q`|_iz0~i7tAh9A$^aO+h{zRIMXNgH2wEL5 zrga)`nIoYWf1m5Tyt0rfK16ccOO@x2c|HRdsxWU}02w=?$(sc({!Cto&wclvX@23N z7$m&??k8aQK}1Bn(a490hljAmnoAHKvg1NeOgw%@!a*eX94it3S+e)XkJ;7NmGr6G zPE*dLh6hRU9w&R?QG^L#5CG(3F(oUFIaK2IZBWjubJblm;La~RV3Zr1|p2$8Kg zlB39$Apx74_GGG^aUra<=w)VS$F>|BydO}ejsAmP|AU^kko(q z5{&=64gwX_GmnQ2&itbw;0q{j&*0=rP$!TUt3)yx5q~2?FbchxVaBi6Yjd)*0SdVq%b}9+d`NST;N%;yl$3N z`P#M!-CNIcDmf;c~fK=Q~su{mFOkYf&-|C;roZ{~j3?lX`KNqM;dUw5qC?pX_^j zk_9s}gjRUsipBc+y48*s>g25bi^1K(ym3B)K6m&1ERmPe;tV9@VZ@a%(&iNl+Mb>d zB_DD=)Th)nN-qo#BLqTfYZ8yqs~-TN9`l;BSr>WQ+ZW-uja2*^h6Yhb0Su+ii>Um9 z1x#Lw7glyv`iz@3IKzMmh|N0X{r$83+N&g!(~kUv`M@iqX`NU?YOX?$<&H2)na<)U z%P7W9CB&2Xpi&OxF<~6fjRG>#-`^9^>xuYFu@g5k|EonxX%J-3^x_Z!}?QUeeR zgSy#?!w6IC;VM$1Tf&dIZ(hL^U|~^=;UrQbj&|2&0R`TlZl`D~a&xXOlAI}M&N0Shf^?5KaJb!w(I9D))=ex$```cJG42doz zD7{Xd50A$%Bdtz2Ji92=ieWkIJJrw^pux_ zqqA9THLYAlfQXENK~+Hky&quc}#)E(ebdWI?wVBH7IE!kNS} zC+X&51Gan()TsJBXIV}LSrYT|x93Z0UC^J++dDcY3jSYlwk8L$c`b!a6$HmdJ5vAq zj#dpaCyFUXaRGR6Pc^3-F>f;Z{ZEu5k0SP?led>o8VtnRF6QTge`_-tGSp&zhp~A$ zOAyAZ`^8ZJxH{O!GF%syylLh1cIv>WT5&f-cNK_DKi=|xeE4w_KZ{%J(50urx!#2Y9I@lhYt<|QO);!v` zCpM}vi7NyJW%S;d>x!#P-ARIBF$T#Y4_A%KlICrLSn$zLV#nz46vgR1-g*OEl$EIY*lF zbh7qlG(T&NgL(5*-|Hi^?iVjXR;8%c5ZPZ~^{?H2`8}x~gdnD-mN$7&0kx9PT}5Fn z{5N(;Eg)PAuQ(&IJ|px|&eADK#5a>s3fHzxjj9WhE;A4$26z~2Xa5EwPDEfhjudKe zzQqKWp7tysvif#tgfR>+geiyxuN>#wRy8rcGV^yVqjS1(S1*5no%-x|ESDIAvyQKc zMbUpdnLTJO=bQ5V>WhR1)AMpy(9x#K?F$~ZQC(I)^!G8!#vCkP>DKm>2=jjJF@v5S znHp#u6o{JQxoZ9xDZltiwqHN<*2t6L9G9v6p(=JPr$8J&z<=*QrJ$D}x3UvBSn=4T z9vQ_60+#UHF*2H;4WaK{G--um(W%(Nd_=?!eZ@(bZotLlEDuvxQv^O^c)krb^m)&f zRtrMfdoCzH=y2bq-m13MrKRdpLN>(GCGxU}i5+}4joW&##{1WDR~BgomQRAv<|KeZC!CQYG9aC%E8H6o+SriX?VdKmWNUIh))+pzD5XHSa|;A=~F~n z41_&f9@hHBNU!8?9>V(|PjMZQgWG^{V;svAyNwi@#t@jDuBGIsygFtA@c;SihiW7v zbI0-W**S}~Wfx-s@bd*KZ(#4!05HwihNGdcZHY@8^Y-22kx2q|8SH~;ic97%K=Ah6 z1SG8eNAWkEmP~U1mrUD21o(?ApQaUrcYnO80S~B8VJn672kSAe{RtvzQoZOq~khy%Xu^=(>wtpYK^0j0e5q z56^YLjAaR9j|$3f`O!QRn~wCHzH2a5D+KhXQ)2K?^1qmP!%oB`@!67YY~n9O|1O9C z&tqXTf!jLj;NegQL9zXuhe%(tS{46(8wBI#eCtq-2>iJQ{2@lD_;;K&wQ4)S@1{Xa zC*xgTdwLeR(Z~x)oVP%cin;D$UGewpnHzx&Ac@OdN*Uy&ne7N6K#B}+lH-N9)@Ps= zy<5dv@Go}NGm=mf18>kfJ<~qOrlqB&5Hs)nbjyLPT1?`ujdgKH*~YV_1OdO7v{vT>W3cF-!2~s-&Q+(G)%5`oz{&F!19c*Vu+A34WM4raR-RU%pq7D%j zds9E@oz-)fM}1JSjE{CRW!M}h+LAxsY~KB;?&^96`pgyCX z2RZuTj-L8Zp6(WA=!4bLTep9z3sp8wJ6Jh2%$QF7%wbg;_uQoJC@C4?H)g~WZtn=S zmq`_m0@_^`j9N0Qo)srEGT7tN8WcpB{KLS<$ET^O_1R%c^z}+F^q}QJEQ-bzf&7`6 zDDMNyQG{p&*CXb@U9qq#YXMga=6_y*NGLel4!0pII4w-Hbj~G)_u695gTpP5@R;R3 zHg>7;W?09u=bQ0FZ`^lCpMPv8iJptvnT*FUOkbz#!A;^d9cuJ$ce8VgcpVf|i{YkP zrTO<)|BZehe6P(GmbrijUOBHRg04urJjj&d6(_)9l|MVy?=RjBbGOk}W}70pEl#a- zkw`A8smhCiznd0lZFzaa`{q%m@6Lm2;oUS}D~>1GEW&^=_%Huqz6C{=cqdxM3@u6%Z&4hR@l5IsvZXp2JFmy2E%~@Hf%E~Rcy~A^xr6>j?T;TLz z(MI#w_1A+~%WR#fv^)Yv0KGaATwPs{dM#y#o1kuqe^K<62?kh|A&BsVyIPUx^BzCG3!wNL0T4l^ zT6g>f5qXe3h?0^R8mBmR!jJI^=)vUxo@a32a=2rA@Bu{tuAyw+%IWNZ^5KeD{n<)d z%G)e;O-)T55b;XdrfN3a%aFm6f_y%L6KFd)zQd{VbaNa7y=v^e+XzR+MMlM*eJ8?T^lkr8mU$_*4OX(FkCp{u|mX7NVRZsx?17l3jNtwgK_KN zX4U`+&p06T&zrQ}E>u_4r5PEKx8P7o{s*YL>^^a>SIfBsoRcsf7fTkXR*L(LezPsk zou~?+K6#R;aRzS*593&v^-sg@=$IBU1%W^5K)7-SD%tAy5CyB94! zABMeaBlU0eYi3jhs;iq$&l#j!=nu~i;I3H>b*g1ltCn&-YteM|h?TT&{k>I~#BlM~ z>KUIgi3@onfz_-aNLYm#tm5r?%2P-fj}&q?+M49sWMj&tt^NrLET4Q<>XKQs)8EC&?sVJD9gy7s0& zsH%;R2sq*okU8K2%g(b%(S7_#f4ZeE*!bCp7s)mqs(q{*tDjGEw4|{4-Suot3CWJiMBq&x@I+~fA^0SAds8$xj!6q@Pzs3tpW@>wjp2G zOZ2Z^#Ji^a;_$j60Y^3|k)XKqz4`TOw#zU%;~A{ZU=eQs0Q^95*FzMzU6iM2>^}*D zND>e$5Ga_>j0*Mp_}6!8J?)i2P1n87icu?NXh4faOusA-XkoBQ9{%1|A~vfGtjps^ z!xshUefE)-a}gBjJ15qS2S#3}+XA27GZkuP!@I{fM#-8y_$JcCgjo5a?-5e%FNWfu zX#$fuc5{{CtTZ&5e8w>sXUK3K5??+$OECckzJ@7({Ket+JEWB9z={$OS!e=X|73;=( zA6AbDI+V?~{K;fb;iOUYP(`jmr=!THPce(N;_LjI zW(GBY)p1Wb)MMrez4!8~Yie9}Hg!d>Uw5v_{s(C(iwO(ImF=Ay3&$5rHVLjzk%z4f zd3=RdFB9+hUkC@hGyXa!y=1ye?bI-TH$HgPSZ%puM(9KRPb0m;erUBfA!{vizMx8& z(R+=>LN$eal7mV_e0Q%we(}%htMi1gYV}i8HA_3&hXULK|*#?2S_Ku;epEhkP`f7p%h=&9>OtU2gc;G@jX9k zpr;a(m<0U{apnu$(o~UK9{0ZUe!rzfTgxdSuinT&@!IOoYgTpAhY=LzF6=)Y8=*zH zO1hdF@($soYI4T;aVo3mBXQ4j>9iV$<)!!cgf9?tZ6Ww^Z{2(3>XkS~{wS z4ORS_PG02>x+ib`5Ig2}kaJ!w?llz+mi$LnESaB32a4doWX5?L5b{Sqsc(rMZD|2D zO+cx<;tK=ZlFNgGzoZZWs!lJ65lTJ*B>%FXsOc)jwK(}a{LKr#(|rt1X*7}V0tHo) zwtnQvkP=OU8E);hYjN?3_f=F>bP@wL+wnb+a|7Hx?~lK10C@~FXCjvj#-`;DaIdw8 z)!V$A=@n~X_Na!yX)Ni)+avS&0M2S_3~Gd!JYRH&x)N-ci+XQC)Wi{-m5js5LfFBlZzkz z{H`O*-gMjDm3rf*N!5YmeeW{X*{oTy4dGl5BJsOQxS79*ED)QcGMY~!76H7h&2 zytQ5$Q6_2SpBbJDf_!WR#QA2due&gnVp>N_AZgal$s&ZnopVFEic^|{(@~3SWYaCj z*pWOJy_QJ6g)bYtw{Jr?LJb=XPmet-?4&c5wmdYTfPM8I(_wKU8tdxa=u1BODK%5#N{QeXWe z(QOQ>#|Q+$H^bEHDo!l#1jU_*KO5RgUA~S}EAI(}JIKcR)#*VHh&Vm~xUu~TBre_7 zAVFT}8KQ)QfsRR1)}i1ywR1F*%}D}sAx3s{Wts_3n2obGYr*#?yVRi5@aa)+?*LGb z@oQgP#^VQ%WTSB!#yiOwTG$iwo->Kf^_O4+;@?@JAuOw#Q1g&*TW zO?4@|UPtO4jOuI7c`~UU%-~XRD%gdC&(qlMJiBf;O9V_Hr%U4(h?svPPZr{II)6n5 zu?R0Jnl0AUY=vOHI6Kwn^(^?l6Exp$tQ_MZYTrZ-0MT6n zU`;xZkG5CRmfpQBFUk(w{PgJ#T8&G>HB5$6-NmXM&jwkKyHVQE>Py|SVXCX4iM1l* z@<*asIWX%a`q~q`yW46jB`UqE`4Ko)Rjo7j&6FrKT0uI>^+xxcz5ruZhCF3g8*SQJ zS^n{$5uu~dGv`lo5Yxxzc*L|)!eu&{0k|)g9_{RgGRji0+lL`nW<{$N4>_G#T4lM) zGe0PFD}xUR+3a8-X}y%Xs$Bu!lI*Vuzb=VGEiFu-a>b-r_(_#s>cbQ=84Q%!%ZAZ9 z-^1$SYHk6aH?hLs&C6in$_4D}9}C!bVoa&{-=Ytw#Ky6Gt2_wA-H7F}GPCecB&!2a z1a=pKjmJ7qvNPa{Og6?*z$xFf@eu(93DZiagsbwS2P`#%Vo^lRpgDmxu4lNa13iHU)oUBL?(^9R6Q?viDV$7GI-;_@)<=Aa9B z_$?+Y0VxLuoZ)PzQ}N9iIxAZ%8-l7&ORKmFatWNcK_pEQDy;2WGi(>@xYHUy!Ek2B z<7%PLR{gF%U2=IT=~hSiM=x3*4!OYPz;PM6Z}#4i-r&*O+aAbgn8b!jNefKhxCY$q z5yX$a?yGL~k(8e6Vbhm7%=@|b_6_De!4l)fZVaR9nfShyK2vbt4Zio8UO^H=L%d%HIN90Rd70=Bj(k0& zV9?=033J^l|Iia8wy>wEE6O|Uk?L0mmB54}1 zhS1Q)X9g<3%{j3LTMaCHh;BYYe>qKU*hHn%65i${wqpzN$pNgIo{l-9^qFKMNLEf@qHU~pFz#YOCmzV(sBsp8M`1`p0VWK zVgfx|R%yzO580f(elPE&6MK@bF_L;i_u)rJ&4GiV1Z}SQK?=SM9snl4kqtRS#!&@?%W#Rjm zv0%bXXz&PNuq}YWr+Lcc6_SlZ-Z8IjJ{3a(zb9aWlF3Fy5p) zHu5Lh>yZsXN?lNqQ$P_lwOfriBV1R#0Kk5pS0@JnmfP(SDvT23=n`E1q~bZR#pX1m)EZCtND;R7AGCf*rrIkNDXg&vg{=< zK5=zl>@}U`j@mWq(itF^nkPjLtaTQ@bbdXNXAKf`SfLENpxl4H_wvJK0T4$3#QzgD zVxaQ>MP?fUL(86;uuz)_1gsVU4Klx&79@wo1cYxL#hS6b?`Jc$I09VNea%@BQ=#D( zDnn$i*Np-)!~2o%gM~?j+QB@7gFLcLI{)Qqeeii(y&r<;A(CFZb}LSi~wzw`9;Hdv|arCWph7QBErI)=nK`dYJlR`SGJo| zH3(=l`j&86{bm8xZ~uzVLEFb?FMyrZi`_j4dBxNtr*mdWU^kAq-?4B*@yGG3ccI95 zrSg>lMxWJy z!jAMKn$>y;S8?nGq)%8p8Ko_-1Qc-U{7L;lF9}ZFrJQ>TvN`%?U4cC8o8rEJ@)i}W zIC(ei*LejH9@imkE{Jl4c}hHfEJdOM$er-tfRtT^{c^aU)F2J0gpY3;P8|{m8>FQf zvHyO4e~59&omOFKtSNeaDla_P8)0^h!!+vI;~!2Rkw>_Ci8I)XofAyo-P5HbPQG!b z=sam#IQ9Mhn1h3zuaCy3RGCQDwH4R?4D+J4w`+oF1|>__Umk8 ziZwpIM>f=2R!8;~Ni1-7Ysf%%u(d3&N1Mr+)t)Nbv??Wx5w^ZApA1Kt0=o-p>@XJ1 zLF61G0%kbLVUbY|HFUzF3tZExyGWxKZE13=SuK;@d}1fc%0yV#*VpNN5&GMWPj1Je zYXgV^hPW5R8r$ETs0%EYYQ1p*ma-=GK!W2lv6s9lrx3&|qpRW0#5H0?(42vK5eOC= zsS$uIZ5w41e+bA7Sy4f<$*=y4-nVbG& zqkBl{UHn!hgiJ}QUii9L5CpYW1`$SDnPIkw%DUf7I zb#eE!0aycOy6|c#W3{8WIp`GMoPz-{KGU<8pKI*kU$~zpJ51u>OaPqkhlohy{_zHV zmIMVdL0!RtzkTn$bL;qZs$lE7@p=liOswIBxGXR>He~MPac=8rOpCUB`{(R})S{$| z@O0Id75GHM;rwe!4%M2?Vhy9M`5!HH-p(i2X4RS*E{X)(DUmN!mYGs6V=9>{3nqE}4YUkntaG6dz+=~wUEe%Lm5d+VMLWO}F@ru8{i?Hh&l;$2dIH zjU(> z{WFH(?XXE5Z059o zE=rf7V+^40jKc5HYrFjcL`*f|xz%1_b6q!0EWy~=5tkOY53tQe_xR;^q1FD1mZDd{ zmPpM;q@Pah90@*tPD)M1kS2HQ<#8Rbi)V0>_OR*8`AdNoOS7(^ql}g(847+3kIT;E zqeO1)K)0v7P%$?xdQnr$Bpn?j{)cmqKiSpACxFj{`c*f+j-&Ng=8Sp|=~5psF{Rpv zxV*&*;4qUB8%Gc?N{hv<(=l|zZ^

Z|8)We1+TGdDCnhZ*ghyL3;pEzNqF?{6Q2M zN~?Ux?S13#Uo^TV7-RFPuAG|`xQ3AL?pF0s_pe$7=#R{?v&1V^<0H;#QEQ@k3<;ZE z`&s=zRt9{&2tHzt3Fg3h+>^qxIOv}Ht_!{-C1^J#5c)lZsq^IPDgrzv8OzANu0MC< z;?#S^+&n%bgP{f-L$x*4)%^a(!&84+ITXg>x_0>J-ji(j!k$q>Vsf=DLLSx|MMO~A z;4s)s)!ox0;k!aKm6}@QJ&)lFv``*5rAmehSi7r zf_{99bwxjC?$IkHmHpM*--WUs&tmVNDI-rw2b@yiDqd{kvnC28Hco3ku6>uKawU)n z$5aZbeyJ3JSd-YkUi|p{$;`plH-51Eal_VmQVlCpCj%wKZ{g=9C+RxixHbUUXxJcM z*9Ok=Y#vAd=PVESVj>BQTYMhla2I0milwS1v0lQYkkbo8UdMB`gfR7Uq1jlu=g1%R z?mSz_fGpj}30Fss#>Q+Si;);wvjqLX2$0 zZ17YxXJ_LC#1!-@3`Gbt zt(nyYpy^?rXF*fV2o}#$roskf%`g?Klv5Qh-TjwT0^LGcYyoP7=5PLk1S${)&)={i{N|*!(o|O}zv$y9b{PFuM$K5r^jwiS&VKaAgb1Htn3qWDtR=k&?wb(W1 z#$svyqM!@Ume`AZDd=)rg||>ez_}0w3B&W3F1Hha>#`&>&YE`!^Yb^kc=PH$M4(|| zP@v(cE%dB8rd+K^UNP`uTu`U_^{&{g$?o6j*sy$>B7rDhAyfgY~AE_~SNUrKS6LP*ffd zplOkM;cg4570RcssW?#14or^fYIOQ zyZ#@ehv;NyqV3^ftRCYm)V^G+c(Qs5()w%RLXa>KxX=oDG=hijb3&R0sYOqK@_OhAqQ0gwZEMGp@#BZ*gPK%R9Hob$#VTmSLG zezupbEa_74jEtnaOZ5e|yLs2YXAlQOnuza10;ycuX!52pGM|s8AZ@ZwYc=+?g&R9*(oljg!NLDQ4clvza-BT0wmx`ef^n84Q z$~BP{&UlMOOe`L-%SzsYX4q=n)8bG|4&))4!)dN8k2@<=d%SQkdfeyT;xQxnSDT=D9xB=G* z3{|sWd{KHCf;3TVJ-S}p)k3vUY(mgQhO)9%zz6g^#{02Gg_Vt#6{t7vQP-_1mz})e zcaCi6%`NZr%meMim0s4Loa%z?_Lz?t_uhz4xA`&#lrwRkKlbo}DI-BAvSU(($QpWJ zU27OUpx#N@MgvH3sf}X&vZ8<{7HyqLE$>^G3VW!uV~$4=sa4h=``%$Ey{F&<3&Ot% z967NG*l8f1rTrOW3DM6k1I&B!^zt;s&BPxd7K@Tr*MEQTFOz%8rqSW75~)}|1f5P> z{c&y2Dt$K7*P%ApuqA5YZd;QkuNR)}_V-q?a-XKUmOZ|(5~IHF&Wm4r`q*Vav(r8=z~NIQ3o%)z@`OS{eLT^pXXlo09uoP|7mtzqxNKbL;~l8 z`x0J9B-K+_bf44NUWNjeU$ZyGjSrtf%({R+Ku~R)02Xjs*3>q1{8V@*Q-<%VTZ})rtO-^L$8=xRdyaFBO>>1XH^( z5Fl%8$0tSZomlii2;u@Lboy6Q8(ut+@mPXJfOZEU@JR(heVWb?KST+kxjjbM{ccu^ zXuVgzDYQIjhQf(rj8RY7(N-7uqo>SP=o9>J>()!YK_&zd^xnt(oUx?hF-!pLZ54>G z6w*s#2w0oh1?$wSYV3-f*!DtUKWxsat7ztQkxK7y@8T|c_=j0N>H{b0eh29u z3@Kpwjm%=s@IfcrrbaM{@?JE7u(%hMz;_4dm6?DOgySMguUJob0v&2_kzv*m5SHsMzRrgUW2 zBCy2e8l$XTtb89e+2WCP|**@AKjb-2OJUF&5^*uVGN!?b_Lcf&y37ZRz`+o1!RFP zD7R8P-z2c}8_9_UH@V8ih)KrOEl#D(`@Q@5NL|RZ9$d)dtN(f_#qh3Rn^2j|yh#uV z{`se7-OtwJmo&p?mGo2J8l7(R&A%bdMrwgUp~1CEdY!%o8C*-N7V2%D`nL?(BH*eT zG~~|sL(>5Jp992r%ZQH{?#EP=!_s)3`X?D)d9eIlyebW|Z~*&rzBhxhn0nC`A8$3> zr?5f^w>8K`FZUS}b)f??I|BxAK}=TmHf_#pq=LW@V4jd=U3GR~dk7Z&*{=Pp(Pbm1 zxYwm?TAeL%0y|r8wCP2zSz-*60EedAWi4u>iG00Ga+$ipjURwZ9^yZLzFlKn*9z@b zkp^xQ5wX{kgBe?VnbZRavZy1;bYVdoUv2B&n4$rF%rN`irsmi1G^6KJkn;QtoR&xr;|aV1Q&`n$81<*&f?Zr@r5lY;Xtk!0=Hs>YAdc(T_eJ0( zwXGrPDvyA1B#)=T=u=&Cf0R8(#+>pU2SFs`LvzP<;;PdbD(A9*ce~FnI!cTkEvBPq z%N@;`Z?)bNW|cuph0>FsrsT}M!57DZ5ks>T*DQx#{rA^;sY5J2N>=k?DH5(cqW{}P zOnP)#m7R-xC-_6Da<1Vi0h;ldjWymfut`t{Xw>d~^#AKNl*fgbQ4t&sRbKQN_y2It zn^*gkFJ=-=O(VW|=seA%{iflih)}wkg=*HUBP1+=o!uiF4xEGnsD^5%h|4Oo6}yJL zzX@~(f3CGN^)+XYq~ve+ZRj+Sy%Z+>ci1+79;J`!{^WB>E%Xvo)x1`AA-PJXJ(M~P zlqzdqv0@w=h{IuRP228aB>|8TMMu|~qIX{!RATPo!_W|4|=A_pP3Th> z^`jpzubArEjrsO_k`&)wkkhEJW%zzik;ge=6I3v|GBXhw#Hm^c%Nvjln#EE9hpQax zy?X5r7~(Xx)}vP^%B?Bn=4ztFo;*SMFR|)C9b3viw$+51DJ(LBU98b!fOj{apVc7P%lt8KF z>A7jrH(GKSfWrKAf&>e*+?{-E2rOvCo}^V7%*k$TmYC)zKcB00D${>(cAju}u`i@E zcB^wc!%@i7pM|G+6-IMCMgO(%!fYw$u-FiZC=puCJlXNfnfSM?;VDz8mf2+jEP9}s z{USrOgyiq3&t()kVFS&0h#YJREdhJN>-3+IO;ul2uL2a0O4%ZhK}P_JO<{s3t7hgK zQfAO|l|ZuPu-Ybo1d;{N{KbdHlHq{$oX0->U+aa+`}xU)$I`DBpMCIpN|#I2oR zWDL-;BIrcNAz|3V1%f|>J&1N-A+%bhy08YuSOzPTt?93)abB)M>9P!X!oZ1fem)9( z5oq@PuE7bRb0dn!cgn+b#t$5GXk}2=*h?Is-#;B&MVbXPw$;scI%^%XvxM6rHG6B< zLYMG>LEkzk7Q^vjfRMsx3*!F_oRhi$CzNDFyvgMXC@t8xxPg3(tKtT)M4sr|iz*R5 zEKEYkXlTUU1k%ZG!l_prDEL0}G=k`kaCDqp_5qSv%Y@zra;4F|cyGQan7qS2j4 z-FK1h8o!SGjNB<^USVy(KR+t$=_+ou^cFElCBKV@?s7jpKAqa`0j48?iDl094T+>w zf{UG7*_MPG&o-d!N5|@=2_H64`qWn*$ z;^N5;_fM2%Y;580v`tPtUd7f17&8nPke?+m&3n00XsPjQJ)($k57#{%LPr^YziVTZ z=U}l`$}=U#KDacW(djhjrt+2Lo7|@Z<^scZEV>}EYQ!!uMf;abK=8=dsI}G(>q1li zJG$SR4~p6M2sP1xR`DlyMG#RX|24&0g*;o85EfNQVi==wvr&sYB+Q7y<~P~-l{hW)MOx8{${n^VrWyG%!lWYg3!mC9RV7{s+oZus<2a)^pv=79DP=moJ!mwM)l zz0PP&*UGYyZJO*oZ~ zQxDnwep_~XyCnxDo(8VC`GFV7j;RbT0;aeWZUV7Ber`nK$zA`A#T$CrDeL=Tp)onw z!>yOo+`qHrS4!m@V=8Kio|A69U znr+P{AFmCNYcZ~k$wJKbrA#@%0_OZ6VK_aY*sgPV@67@KPWrN>32*NgmX-(B*`^1x zO`Es)R{-1}#+AbZn(l+U_0xVrTGxNHf6`aFJc{k@ehv@9mhswdm2vNC_G<)q%3iE= z(CYpaCL~k&Ldyp|7m0~$a`qBn7@biS!NkcIMw?z#t6|kq(G$H@r-n;&82GxF2gg>+ zSgG{B!!)y$fH_nT;i+Ks`PTUSV0ccwtx>Mg?@_T!8-xYQi*#fJ0s6WLh-fdJ3Dht~ z`6u2mwOj8IrKr?6>Z(*=68%(Z7v{g4Anqhq@b0RWQosc3#)m&f0%lwX2U})Sukh^; z*#nG(I`Y-j(%NZ|JBzqL?+$B9?^Dl)GZF|3CxhRnCWgVnotutt(%folf8Qu=p_1_s zxYUj$oRtm0?iRmK$6+`%h;e8IA(gn9u8#3Bx$hDyONvr3kpQIoAt3$a5z~DII$7_b zSB0z>+A(S(GH;DJ>e{_LFeG3gv60;&^W|udPZ~o*j!&+03<3*#LPJrTl};-}y(yT$ zBB$JsO6it-zs9k`prAzX&W$CVWoF_(Y*7y-ug8jD_i{{G}< zU$`!^4zsjH7Dc?5tAy)tY_c)vmBlDS0I(CFl_iQFC@z9PVZ?NzYX?TUPhoUZwNHU2 z?swLYQe+uiTyguGH`YzY_`ML-@~!ZisZA5jX=p9A{+<+v8sGDMSTm%OsiaC91Sm6K zp$;x6Ra>xh`^m76Xes`>_SZgc%1)Wfy75Zp>XjajXXc8)fn;W~8R@sG&Na6W zCxz@?T%O{Wrzb-xx@Bd%SUE1tKf6?-nfI!=CF=cF@qX z07~wI9$mUh!&}Lxti;tK!r6Tz&OLbb-SxDboE$3>6?FK${jkJU2`=;ONmf(R*A#QG z%O%}48~W$d`2|8Oh^xV+6zob3#{qWv`%b%*$|h5-u?u=~QuRDW?xfJIx=ln;yHeB3 z3M7M0vZ|589AMliXHdI;^RB5#)6@R=VS)2#0XzEEt@z&0m#&#O$*Ox#x8SwUH!vO# z4eS$tnVhVO&3f@6y{@a(zi_BT`slpFw7q@RGmIK;x_E$j+$?a2N~(oT`d+2`SIV$Q zrnjm6KzF(6ORSUxs7D!4-+HW(v=)Dj7?1gbn(zqDUYqW^(95n_?^x*_#KLWL1CsfNaD>eBCz(l z6-ayS4u5DQ!zb%n<~s|0dNOUGF;KV7&HTpml-D-O=0b*^$CYlrENI3zvHbbt2o(-qfL-K6%ojPdv?ix>Lee>YAHGB8>NlRRw!0@j8oZWpQa^gV8mK zLN>Wj<66%OxPNAL)*KM4X3pc7MY72oe}r}db9XCRIle|2HP8vNr|%NqA4^e zG~WC=$w7%iTf9+UQO3OY#BwFZ6V^(KnE#2mCT5uei>UyWOx-q;QJFVum27rzp5lk2g0t7!Z(Fj^Mive#d1f+^a6j95xA_X$NIa(uoT3g zV=vuaJ%x^o^G$qTk@ZdMQJ1|gd*1&^b$dG3SsnG4UKkvf=qB@BN#1 zHV0N8Qs)Zr-?(XO^^gW*Zz4YO)LA*Gf5W)6wS2>iQks~f_p@pLpaq1QpAxL0gIhNI zqybi2IByOPq=l@MwaaizpZoNJs)nX!BhJuI?ArC~rmbxOdq^2yDcdAru#wxxXV@J% zws-iXv~*=Wvf}W&3h&j0n_u_lD`xXV_Uouxk#;0>`(GYG07RsrR6^dmJzNfxN=9iE zzPHSj&Y(HJ2$DM~RMstUjOmz3OS!^?|Ub?5_8dsC*< z1KrpD7*MsGxT>oS^@LLc1?j34zwtIgsLiWVRbyo`otOno>+;X{=RE*tA&zI5{hCSr zvN@=GHE~iWu3Wvk+9DSCK61IbVfDDsLL$_$uTW1l#`Fzpf47&{rT=Y72(itDRL#gH z%#O`YPa=b8eBxy=(~KEwus^5w^uyHSFT{*C?Tx2=Bo1+|hW^amKg!<;QTAss-KU5HdRN3HYF654Pqeg?@H6=&y+*>DBTmcP?wU zr9VL(-qCA$biUHw7MxucuM;EM5U)#0m8IYBKcuOf-Fmrg!}DNig{phVZiq;Svo*=< zTpzwfk#|qw`xEcpAdC?!wC`$<+pqd7j%&23_xVjOrfcF{&~JTb9j%40Ta`M<>}r42f-RMJGGnWp5_A_dRcm}>3>m_nLzz^>AXH}p;y&ufg- zu^hLX@v}ObtNsBJ;7bcFvhLpAVuvAlGn3-5+gGnj9Sn_(8CR9KcVt#FPb)0bd>a_K z@4hYmV0>KA)hXw3_25B-=KSRQE2$moH@FX~6~RH2FZ>s27{hNuDBr)gP!@N%(=$Y% zadtli!5U7jp--Rl^oDLarGW$L*{fP6mm{u1riQvY=O~SnGntHB&a+(w?%|o%R$x3*~EQ%{Qdi^FN=*T_H;ch50P$e3mw4;DL}gxO&uOKidy)BnV3pi zbPZ_oUkO;7RDFhTQMgGS#W7M@gZJ0)U$KF}*)VW?(9!tV6%}z8hQB9$I+mnG)(JG= z=fH~HF^2v{N-LciYb*!YG6ix}$rviq@LV1In;Rs@j!`a{8eAJkdWQ5J?iy%HIZe9W z84)ks%Kl94i}numoxVnTNZiTxpc$pt$d*9nvW25!hVKeJga0Zod<8CkwEw}Od~-eP zzLjSLUh&nm|1z{U@3%$BQdPMd7CO|$U($FhK9p(}oT$gI58LYE6 zXS!J%u|j_K0tAlddUfo_`>mY^vEe6&{6F4rGg-2#1~>sFcCcCg{YERoGdHJWeH62O zsN&}ZVe2&=q4=&4xfvkU&u1LTcP7zGVRcEES5M3ATqYMG#NLcz(Vm?!<)V=tN5SI6 zC2a~3YIajQdks2HVRV{P41H74L_pllk7d@2d$nRb_B~#Aw&r3qQ%k)yQ$G2-wkvtr zcqAPjx+n1WZ7Gb@_~k0&PArlG;n+uVL?z`KwlWQ+ca%&*LxbKuR$e)wOQ~$QUQicP zXkdOuTNhq0uW-txI4ifDk-n@_U1z~!0AjV&Q`SOuqDJ66Ro@8!$WXVf7MlNq_O0hEG*WP>9lJBRd2 zO5$nAdmYOM(w@p!FmDc=gi+HCaile>X_Dtbr}xp0)@edIz8MRXSnmL{jscpV$07ws z4cp&6r2YK^s|8|pQ5k7UkxLlT zQ@$&lCd|x1W-319;Tq0b*sml$sO#74Z>$X3axt2;C{Ij?D;_Gg2uv) z`83ppSsFIGIUu=egy0z@B!wAi;nWbU)=`~(oOqJ<%`h~f^r(11!j4@Q)LCeRhD!}5 zT1$&`BhFf`#^lfo6rK{*gGmuLbPf;4%!NTs&Yx2oSS)YY*`82UCpf&BH$=6*)v(eT z$UV7yh={Eb4;y^LhDQm>HF465a}x7U%kx&Pea2$UYNv`+uV-Uftr2OzHElJu58fc6X11+k#e;ZVpmP}(I3K!f{or!76FyEV;Q#|qe@4#W{o;FmT8dUf7 z^XD+f$>p(WLl?e|%txJ)eVJXe7Yz(Z?HxzQO@V+`_5Azd|1vI_17U6#EVVUk1S~cm z%$N3}+Qx7l6R`~kW7K(;B#&G=n`W+LGBX)jJ5i;Yq}!18i&5q1i5 z<%OJzM`6z5)PkuxM}ZI+ImPFTn4V$IjOf^QClt1@Vf`yKzf~;-!rQ?a`0TOs)NP$8 zYFqZxxrtw+G{R~2hyAoOEvKLA8j5WRlO^u%`gX5xO=z32LYL~y;ZnqF607ZrtF8x- zund)06=zn=DPgR@+ai67RmfO`K`?x^S(CL#=eku~s8%v#;AQq-N509p2^m?7rG#{x zuQI7S(%eP8_<64uJxUwVWMrpCl7CBWxQSEAn+B=>_nLn=B|O}o5yQk5`sxK;Sb=inU?KI&a|5RXDfyUC z$Q>@4;AUnuQkb$kd}UEGoLR<9Are;0i?q2f3fgZB}i#xAtxP--E%x zTGujydOTO~vt8bx{fWw{WnbJHq0aOF7)*@Fd2UI<&>(gP-3PR+!Isj*IQG#a`16po zT03;u>_FC-r56TMB4ei({;AKf6pzoYRP)Keiu>WzjEHS0kWtaCl(JfVTx9IcTm1zM zJKs9$_RBikE{e;9DZTOHIVsWUn7h?Wf7{C|`}J!&Fj(jSTR6ShvGoZ_(*+HW0!`>d z5zOd=6=QM#4Y|RMv-y2{FRczHD!^4;aScwybIBAo#R2xmSRLt~FDGaOhP1d^Pu_o0 zEtD&EYi&oof8S-0mFBmH*3x1Ro#(&2&a6q))DZp040sXFMT)hp19uTRPwZ1a(E~A@ zD&}y6CkFfPS@UC=s;cBjR;ucQHihk8^8-2q9sZJ$0NFGJulk!3gvG=#fBE-gmQ3dU zw9lJjv+eB2=3l?YCMK3;o^LyjnpvDr?H}$Kpn%EuNlNBIStkkIVMr~khNBY`^F#lk zkpd{IVk*mIO^K9_t1EVEyy>PV8u;br(i<)1TM*;Rmr;8$Y-(J5fn)}sxCoO9n<{w7qQW?h;X*gdTQzs<%Ho!%o_*O>0%#AX8V|!my zGm?87XO@;8R{?yMX~ldgVWs``uHjnYc90;p(Lrnzvd&j8HjuO35x-3J+qKYB$2!z< zLl{aDK~U5{jwiVbRx|uIE3gXz>}MV^H8mw@74#1O08qlPU)w)QOGmjX=mH5Z8ERwq z_V>+J+119?2|*x{*Y1ypCs*N z%ny7(>TfM93GqSUqr}xGQLE!;7AnrI zp!PNwD^O#>1_kdQfVf^ukE)NM^%(YG(`3o9#|Mj!z(Z_*D`Vo8N$TT9U5t|v7J}=0 zMeafWyu$+lPV?`H4<1NPTr9L2f@SeEFjCzQUg~x_MwpsUe zRE(az>&)!zB?z^K?|!!hh5?|fG-ekpwxOe=41)e z1no?&RSb1uSr(z6=c2ls+uDod{#O1|;>d{3`QA&9;zPnjjDz-;i0(xa`3(bo0|RZ# z?YX2P_=Q2&s^^Nf@b1NMR>}3-PtjU$z*7WY63t zJ;ob?D#isbd<^~Lg5Ko3oTN6#TJ20C>gNu>$sh0^$q|4Eb`W-LWf<~EWeoICD+t%JTQ1ZtG@Hd^Gy%wx)x4hma(vn>==SKfSaFnYvkM?KVWZ4aDfY$ zvo?}CtE&-FQ6cz9IH@}cYn1?k#d@G?Ag@ereFOjSfu!WU3Bcdkymn@81MGvF(gSrzQecIl<7-3 zHTE+Tj+*FWO$i8xxpmN1Vog>5d@y!8=B zwUv3Css_!Vwcf4k#4bH4;`_GOC`CRdd(-|l4@i^KE^=lP zf2EMp>dOLr;mohcUSe)$av3fwPV4^X%d=o6S@2W{3lCo%kR8TR)NPY!5A=&CW>EL; zZlES7aSxMnLs-(zom1vWcvVbaC1eoPl}mf|I!xb7_O+9YHJ<>FoZNMoG+298E$9`> zlTG>pIg)UJNqL;ZU>ICx7S9~^F`3ZW2nwem+?v}n5Fo7(hJ_J)aR7j%Qq50nq^}^9 zr6d#M#J63DNZj-U1UZ_mgFP*|K=vb7cF}8dNdBTbE$&h}zW(I=vxunE(|Anbc@03* zM=QC)*l&BPA12sZzVbeP!TdGJra#gb=m_LOpdoE`eps525H1@>G(m-#l-*pmLrE(#Zh>8-X2>Br9k>Du{szVf9m*z4l9!})Zypr&IG?>zL0#stb1bk z)4koyH~!4D)9pN2PoeMk_q8MuaV`?zK>sC}DqMnBl@`qaJfiFyWYX6Fz_2=qqU# znYpA+$>32R_9-EQ;Os9!mQ36W#t3!t`$g=XuQO#to((YN6zo>I2mi5a5G3!sYCmI7 zzOn3d4&d9Fn$}eD*J#@|s5YFeDN6e%k^hLLfyZZ-m(SYT3QXencM}=5PU4|HV#fB4 z$?Ptu$*&M7#_Q>n8)0_#2U-05i@Yo`kTgc8CYCFYZiCy4$ zeArU#0Zr^dH+no)Y&z6O$@>NYnu%e`C27 zn?S!p$tldAoEgfPR#-4N>T~nA#|w^f(S(<38*p_a1OM|VjY~8 z;V)ji_$)DWRf!skxVEu4HTfsv{!B~T89|EAROIFF6&0P@l2=xa89ulprRAvMC^UC7 z0R{f(7hxy`x2p}{^35^=q~@{{8kbD7_^v}6+G}s zPQvh&l@%b^4U@6UOA5;gVJ^9dVerIm4Jj$<53um3u%_+o1Q8=#-Z)FlTr?!>TLkTi z-96hd7T!r3dPzSVmrReb{p<-}ms?JR!G~+YGSU~{hEfPJvp3=Z ziNDN|vG7h!MvO;X!)})f$-x-MN`fe7XLYkxr2?=8`Zxob+S_<6CWNh?R$)R?gdi)F z>nSPE^EZStDY9UY}_!D{i{Qluzw#JKElo};iU_uZjSWLCc z^4#TM_!1UVB3Dv&gHzbap~8}Ta#UMqo$5*J(-3A(LelF(CkbH4D^~=wpfD+&5k$16 zS0>(IENm7|wRXqJpH$)NtyFNAv<0A3chWYY(7$ z6%6528Zt;SuKiY4N|>?7D)D9nXWK43a?^+J=(jo$_%3HlsnMyZTaj+bbdXl3fBWnkz^6^2P@t!q~CWUr4Lcud63}=z0>F@bUC8O1hPfLFG61KW3Sr2#n z$U8Hdf3pmQDUqd&je15Hezyne?0EOyWg;r0LN&9GL@PGmx`P^;BX;kgP!gk=BrLo$ zoX%uM6>4QhI4;R9V}0ZAKHBHA6g?OER1VVI1^M0batZvYW*sZ1jSF##B5*Jpnx^=(f@G|xMch_ENd!l`7a;#C$^Q)LY66_pv+WEhEa_H)g@$8ZXMbjm%iP@M z0hYD3(dM>mWgq6#SkE2vZYn6f>Wu18r<$75?&EUsxB^G=@^jmB4{{b{XJ-!)k}?PN zjE+9SKeJs0qMQ#mYYXZ|*j!d9Nc(@CZ=RS2^N1wNZS4t#Co;6 zQ%1vq97nyjw>)PHzgX9&54}m6{~+YXR$2Z!t;U;n*{qtZNw$`-35YhqU_qZMxUJUa z&eR~U0`->;-X-DDa4K#h4NNEa4;O8o7a7UrsCB`nurjK_&X0pna=VSY2m zjOQv>Rkpr6o!ArWt+cLwtw#;(6DKEaJT>5HlZh*fs$;G`_Sft|{4~)e%(@hv6`UFF zzr~F)Lit?3xd1;g1Oxw1zmT0=-mKiN0qNmRU?ftNoVXTeelTSYJ>W$W{rP}Z3F~OE z;TwydZ~Sf}SwGBwTD?UX6>|f3<5JH-9PLyMpVYBex98)bq+hCXD%E*w$97MmXvm;OJ~ARosh2ub@@oP;TC!RPm zo@?(jrih2wrb7OS;@{6@mX|Xgkr5Q9u{!+p2iviSeHmfZ3syUgvb9AEy(S+>nC%Sj zA!5Nt!@xJX7+%b9`__`qKmSV_WKDOYQzkP%D{F4PM9N}Fo>L{zO{idMV6mnsD*A*o z9NPokc}faHHqXyFcsU;Bfvf6N>Cy1oZCBg&O=x>>ww0CsQAbZZwE^odR>a^WD46Uo zf)5!RdzcqO4gj$h4qse}|5jR_LX2QZP}Nu%aOK%wyE#}Hs3K9#d~LOHIV7o_E1K`o z&=Au9J2GXtibBs`3j37ORT}HMdT5uv@9__)_M{`pOmeKCz6%JVW8Xfc-Bt`zw+JtEr~bl7)n#!&EEIv+|HY zOmK|UH%XAN@C$zpR5%C$t&cS`b*e94K%bJ%d!?s*=%dCyon11Sj9`J#Nt*u8(x5OV zX1#wO%Lyl?k1RM)@b$&1Il40;*snq0UB;}9EKYh7Xo@J_-3*tMHE3?T-5v8MqsI&h#F}XK+v+NhgXn49BsSk~rqsxlZ zt>%y4(#`d|KqtL(6typZgOw_oo<89sCWPhw&D8jiXU_zeP5ojd?FmUm`Z8;lXXo`B z;PkEVnt%Z9QM@RcSfmd%;5_H}_WXo8NeO;evP_0=BSMlM%Ns@hJRayshn1qJR3 zjJh5`QAkLjUK$~YaOkVTsP+_L|M4=&%e&E)v%*$gU2)h)n7$U_=6Raf4$E^sa+`{) z59MM9QCNB$)2cg@SDtroO8scx@{8_;M z&S^)9$>I)}U3`@tX9u_iOD5hy!z-K81rYVGIt+c%LYx33c1IVi^9}A%W+zbV+uIMP z+MfyS9OcY{K6y8`d;6yJySD%^0pk&~-M>%6J+Zbbq14B@>@1V|rbZ1WrxU`qtEoA9 zQVd=)<`yZD{qMmXS~-sf?65dD^?9Zaz9)rZQDsW`475KDt~9HE`8MfZ|` zGPhJ|+2fYk)B0+J3xJ7eGWTM%A3DihN5uC;RH25^oG5;EdJOCQKR%<5wBiHULrw~Dgq4{vYC zzu0ByS;3|LnU`e>A9jEp&ofwLTE6#C{HLjG!ABgW2_{`N@3?rZ zUgOp3!LK>SPdzW)`H+F6EYWjzP)bcQpZ%E+%_odF2yKGN2Wrn8F( zoENdaYA}I2*w;FjzDM}+Nz2Gc%=2e2)Hg;sU$odz4hP7xUQir!)iCMz&UrM}$tT@$ z@p8RtL+3G{AE`BiT=CMCi1uTQtv=D+t*LRfH(7W)3b9ilnxs!BscJad!}`U{)4#nI zGZAV!KPAf`A-tsVH)Q=khPrxWs22n8-vdLHa|6%KpIJ5h>#OMFjLGay9mCU8x-v++ zG3XcHyfazF?lyiJXGpkrcd_wliU1l}hFA0%X6OUwY)4_L*_l|cK;TNiJB@Ibil=B_ zJ>~|iT#yJq^M_X}R^;5aEQ6BnB;J8Zd&|f+`-NNC;IhgY!#*Y@c!qH&od>Bk!LL|5 zDJzaPK0YB!MwANBE^)U<0#HMD{6^b*X2EHnZ+Yg=(P4PCjXS?ei#nR-h?qvn0U4|F zZk;bD-uKlKU03kpQdGWkX=3AArrMhs!$6gkwsf_R?gMY2+3Q(bfV$A<{;*8UC*gXoWrIHq3C}R%5vide*=8JN4K`EZFBhT z+#Ejyvf=YtG4cfDV4`h-q89@-9ocSoiZ-=w%yh;phfOd2WcawUZ& zZN3LzY6CZU{ygaO3oxs|d$wm{q@?Zg;r-X@f%xKwh$tnch^kvesqXGYUhV9sL&Ep` z+k|eTLBk-e8b$bMZ!3GbO#%H#0bNp(fQZ?8$~u_QtPa)PIA||Co%BocKPd;?N%D$ZJ0uRU_ZO$_Dt}N&kC$>^ROZMHwUL#=HKVfZPoGfliS_{2(dI!{x3z`}`PftMws&Lgjz!as8C)4n975_D!XghwBi^SIk5wh6qYa(BEB$`oC>A@#Oi=I-$^lNiU8)M&M73Kr%dK*alatm!#manrUT)hL zWxm(n>mL9sNHd=%kDm!Oc>3|dznSFc|KVb4;qT9CWo5N=)o-MGm}-ZAKdk54Rv8e; zO?-QL3LkLRL~2vWXfeIDDL!$HhaMg4k_xYZ674?DK4m9k#Vbj_84R&#MR4+wM8sS( z7PpRDX>=kaedz8gw%*!GHb0~4@27A%JUs3=drbGFbu%kp_vk!l6Sr1kN#1vt_q$7X z=_?S&Nt(>}6FO0Z#XjezzrDd|YGx_~91V8E2bQ1X_5*FV-f+389zDrmUCw#i`M6bW ze3ZQa<8hut^d2o8tf9N7>M) zk8#50EgOArrbgYk>8Se5OB7f9pT^9)JlbCh$aR)WVxw^x0NUq&s4OTucdDbXe@Srq ze**8vlcOH;3E>+`8dPh(Z*N>uhc5*+oNmr4$|h<{OJg2`!sIMYh>#mSQ?tphad8Bt z^YP=_IJGj+l%laOdbW5}@EA37X+nsV&2q--9ZKtO6ba(P(0H}=jjinS!SJFYCLO&- zJ3T6=R2h8fZ6RzjaxbE>>2nZ9N=B>C(&GxugGtO(y=7xwyu6g_oy%Dp9m-CCu{jv0 zCm!x>u0Jw0wVR!*|MKFb$FLX2Lf|T+gJgq)oh=GU5J|F|lpa3jXx^BuQk1n)Cl^5R zq4>v}#p#mt99R=|niY zammXgd~1f2^uNtjo^5Kpc-=JG=ndPH42u&`;b>}7ehM}Cy0$V$=I{UdF6!Qx>mefS z@Vl&{u|muWt}SDmDJu6Us*D<=rNtO{_CJ3=!T4z&F6cX%t##j%Q%v+DvmMsb>*|%v z@8xyquGwUX$e!@Lj_uipa4NI3lNZkX$^F54s-z9^IM4@F3zs|a7nq4hTK-M*;M;I4 zkZ&Xi-UZauhvTj$_oi2hKonPoex3aXRsJYAIV(tV5-iGsH2l2E>5e3UjUH$ivq0+` zxSZi_)rzI>j@o__4;iRWP}hQ4-M|M&p9p{M4p4}C;j*gw*<3CnSa}Dr$B zMxO?H!((2FdU$wbX1`&nArQWP9R)5aHudDAjvpg<{#;e3Wl)#FQ^8|nqr%W=k}2T_pfvA#a461X>)Hmxg}y6Q(A_%^SX&CcQUmx4Pad(Uou@L^H8&6dxR zzdl#$E%C>&G?ZXY(`sjgT?u9m#ft~D#r>@vKrCJ%LW4DFr~VTAwm9*QQBqlZv<9eE z(H94!|Kt0P9AXqs2$OALK-oDt>IcK&{hr)2;^`^!JcD3VVsQHHcvyC+jMg)}`{KO5 zI=t$GcIFH6-Mh|)wgM$R&~|6_G}k)y5irLue#0W7q-0la^yxVB-C=1*@z*|*X{oYA zv$HsVD{STFx~jn?bm6yYpoked`ARg0uvy|EHvK*%`xDutj55{;G_j?q>6HhRP0s@~hON)t3*Uh8YdNtx zExbK36wFYADPheUJ$&Bme~kPyYM-b3IT-kuBqlaHsA%Uy!enP?=4$r;Sn{a$VB+8a z`#9-b;ebq2T4~AMomq;M+FI8E^}7fa{lJ-G-!d5_t3$I|S$@8Dg_^-t>B{^U>LsmD z%Vcy)j+(KT;^HD}*ITJj@{c|=d~axI0ORd5ezpQB>%JaM?<~a?SYmWjNBhfkolhp` z-BkO^uX{{MNmYYr-QX1tHFxZ>>!9l6p_uqS!<^h)p=dZbentj^tnm8RGj2pb#O&gTm>y9Fco39%@PR?+aos92t(4jT1z` zy#HMY(o90uTE7>Qu=?)q0#wi7)RDqkwcx2`jNy?raK3faO>L8!5`P$j>2X;<;CtD*O~ zM$8`={76h_W=LwSn=JSI(=xGhk{aVx->>F>);E13CG9Pmm_}%_v-#<&lB-_K9}kXD zWDM{Fm`FadXG8 zs0Js(@SZlkqZx`^N$H7#n{4-Dt`WiMTvqH*D3Q(7{nE{_yB9H?gPilt5eP~w7UPtc zmj&)^Wfjrdz+{qJ9}tp0fPtm3fD#(bgCr_T8 z*L~Lkbd1i~S?z5aH+;*@ej=xlOC)L*GB$YbboIXEWFSOQUAX@fs0HeP`DWBUb)0G796ghduok<#~9h^WqYK*hY>RVzzZ@X)+F` zi(r)E*YH+Gl;7r7@1wGEDMLeHhLZB~Y#R%L=&`Yxk1cPv6Gi4QhoPakRs=V12Pbv6 zmlqM;hYEk@xF=7voLs`bxSaKM5(biAaq-C!5i2Xki1{1TWeTiz_ReSAZ3RRJE6`cs zszJ{Me~6YIlz~O-`og;;tH8XgHL{;St6n{hS{GEG|3LEvMeB9PlE7HS$~flI3gU+w zigRI6r;dk?^h>|v2^f$$rnq8pk@+gSFMU2ApZ-_>iT3tPS3kdta;Vq8y_UF4RajyO zP=Hs|iFMFQr()9oJl~&YSA=xd7T%ukk=wcf&RpFI{r~w+531f;rG}2m4|Q9<8kopl?h9#!rOd{YIzXm}qO^*xZuI z6i%N$Ej-sxHwPdh6Fa-6t!qKQ-X-HmD(3b_UiG(@Yfvr&(3jVVPHVo978Pv-*g?+F%bhnOElFWA!8%w`> z8`GrXO=aV&8BxL^_kQM|pd?}mvlFU4?L8Od1`-97qqj@Xlgato>j?Rz9EADC*RGGp zb4dlP$r~wOtGwSZUi#bAWH-=E)|@0P*qji?djjf|@5s)0(By&a`x{~W#KSh^CRHA= zfyw2o(}qXydIa(RGq3=-2N#AgYapo^$;&^LLfYw4@pO`7lcuS_FqYInrzN=H`NE7F zSVeGtL?&xtr{(Mdh|{n0^DssEy5Q@2I6b&wwY}|A05ZN_E?7KJva@s1eAhuEf5YmO z$ra*-FGRhK(Woc6MBhmGtXn$QIzACzG2qF`AugJl(gK{XdtG;iJm2u}!Ngs1@Y;03OZ0$4oko<_U7m3xO^@WSGn2zgkm$;|_*Rux! zTco8IKP$LqPkr|(M+ivoqqgH6a96?LaxmXGAue}(BYB{v! zR%SjUQt7CE|Ivo5x{J;9C57-K7!`#)vitDJf7eF9I| zxUR4>wL#WcS8s5C=z|~arz0e%0HM`Nldhn-ORy_Jw0vE!CwQ()fUxhZ4yk_vv*_o>M}tO1cUjqEOOIo% z_V!GDpwM`;6zn)8zk%Ni74>{WR{?mgYUW1wI#^^a=4REZhGL{ooY2zKR(Em|u5SQ) z%}z9aU{j<2DZfeHD@_9QoHqMoznfVufK>bSculMv9WNpv|~^Oa^`GU(7IFw-Glgv+f5@)hm_u{%GE zg`$8oW?fv^9wZ9VSXTa6LVKv|vn|+kskBz+m%I*32to*yHt4mN) z(2OoZtowqx2(azfH#V{=OON-?&vm@&wc=G^Y4ckSo!=Z7yPtTsukZa+^p2)5I&#Tn z=9SqQ?{l#6yu7%d0wJFId4G2oaHFdeq2w?PYwKr(L^}@+waK_e zskAN_7<2H3aH7d76GONrP2%EIH82QG?9PY1x2J)qJMey$Bvi;tXJ=LW=f2VP>e9qq z)A18v3J+)Lp63(Lm@d>{WFVh#y#ot)ce~>L{V@rI#e!p_GxIby0SL1n2Gp|PGJeD% zfI21am`1$JV642r$iNallo8lyoNIo3T5cb+Y~_!_DJ4C<5T8Be<@)ko`5R!b(8mV+gd21cV}%-hVFPdPC$QE}}Oy6WJL2QUB0McNoK ze>FJoppzn?W8~uH%VOH=)&o>+=Gc>yxypt*9cw^>2hY(AXM4e4xDQ0G@Tzf zqY-o#SUG9gJT($#SM}iC%9i36+VBg_-aW6bHt|nC%O@G1K#Lf6&ua;)zY=R@q`QIj z;}e0?S!12TKaxy1)}fasNl|8^7-f0#DqcyCh5)S=L?hU^Z0?r`jv8QeqpzU;F(CEU zu$VtYMijQa50srA`o?9w*uNO9Uy$N1^++x{Whr9ZtQ;A1F5>Urad9iM?qe_&p9Ufup9!uXXQ;1r7f2f@J3&1n=5VVr)6p61 zI+4rUpAbBuW_b1Z4N}s$q{J`)ev<(^^zBvOd@Li_>5?iM8_;xzm+j3F%ibHLP{bI;TuoNgjt%#GM`rqq{mtASIp^5Dr} zdNUj1wSHule7Q8{=J$$(uFeQKhRyR(Yh)BNG*Sq})m73C1m?ouvjjamGaP(oNbDCW z#RVPm&0g^Prrwrc4L(B2+?S!T@Zw1yvc9H#@O&@M}_K;H==+fQD8ERTNoGz{NC zQKwAZ*Ju+!e47QTizJ3FFiR1J?mLk^~mlP%Enswjuv|sbZX4UM@5+`z`YodXSD!@ z?<7}vMWOhUe6F_^LAU)`127mSu#qMrNguPf9PYksR*|#FdE#8aO5mx;5D|HWgtD-R z*Al!^GTgVlnXYGLHEZi>f&@qjC93lC`=lTq_tpVcEJU>;QCfxQ*-sCd%M-7;+mOql1*4Td+9B; zdKg^@mY-BE*Pp*Pkw!!NUVl$!^qD)aN-y=j3_3*|)+IpWHmi6;sGaBex09W$(a%m6 zKmME!*<;KIt<9yj6swKMJzU}GJFq}Tohh~J$!H`%Fz~bo{BRcw7-VN;0R5K!;Sx_* zxr+uqoWrF4;k84q1lO9oJ?HtB?rttPYJO%EdwFozJ?y8c(VVne^}f7WOz-i{Bx+A-*fQ=>MFjtVIRKt!F953b4`oHPz|*8;HFCQw{XLFd zdqmX+&e?7*py%0OdH z>vsnYvJQ7X8t(NwZZ|Falag*OYE(-p5ZJx*ks3v&ptP@tf2x&YVgES^D5gMq^zA$x zLAS|#i7(lZyudB$2!Cfo%Vg*9_6g&i@q@cUZ|@e1RYRFf)*t_J7S15z7C|>s2Hv;W zs2hCExW9`*Kd>rTWQ_f}0+goY=eeQdeY`yc9d^~e?#h^-FfyP&h#?ZT{5fC4 zZ?&dSdHd37|9Rtzk=eH@`}-q2JW8hag~`rw7d41tvSY z1&y(CuPOm{c8*xn3xUepoD8QXBvrl>Hs&na-KbnmD4uy!<4kKi`s#OF5l#v!5z;cm zFVGrc2{2R-EZe3K6b1i-@jnWoz`2`+LAjmjk*Je;Fyi&s#59a{U=a>>&bPx^=8TOxItS*dWCa)DK0Xeq8ZJxY38hCLgk2snYk&Xf zi|3b&j)Q)O=>=+!OP5eeJG>^bN@d&gIx6)y&`TeV&$K_n=+!P}moc>MEn&XtXFzUP zq2Hb^Jz;sunWkL%WI?)G?-xQ-eI9kOjI-YF&%N!Azu{^rz}_btv3^B?J3A=wpjmP@`o=P02HnF*-~bs?tZ*P{i-ACS4E9JeoQ;zU|dhm zHARs$wVeNNSQ+F>k`rK=qQ{GTcsd9iZd$sJmM`lEibj)x46rp1fHv4AC^}U^PJs>% ze)q_$tY*pxa0dJoR{oEzs|<^B>!L7p3=G{cbVv%)F*Fu}NQ0z;fV6ZC-L0TBC?Y5! z-5rV&N_U7L-5~iLjC;T9z5je3XL#N@?>;-$UVH7Mm8M=_0u~mOPiL_SXryGQG$N1( z4=R1$EJ(M`z*#;R*SS!2l(G{UI?(IifL2*}@(GhhnjO1f9eE&gHfXj8r=g0y3BLZb zJXo1U`EnlG6mNUd+qKi(F$rZ3XX2ID{pGT4P89O<)NQhTONA?+c*{}y?((G~_ z`agmv@Ug#%9=6h2U<#wR{>zR3kFGzRFe+e*JEi)PT0C}e76l&@Y@B+ix;ezO_=G$(f&v+i3zWz?I8n`CuMDH5 zh!p7KsH>nU-bt)1Ts_@U+03cL3a+7E;x&>R2r|>LsEtNbq#H?<@ju?EWM-nZv>KWn z;FOxGeiAfX^tJiuyG2$Aeb)KeMwN^VgX{f!v&@82fvM%z^}jc;G+$T4G^df4a&C<5*VH;ka?_VzZp0Lph3~7q$ ztA_nF!s5#iw$~ahxc6iF{Og99&F^8h75rJOA)0Vhj$76zYZqxNK?*7DEk5&=ED{X_ zGs+F|#s4GX{tjk>s7c)zZ%Sk<(hJb3m)Ri%AO)GL_x?!jS|y7o*5%UQjE*C^wAVmV zq6g&vW{w`sENkvPauVzt#v-La`~DqqH+^gdULd(y^!dB3B%W01M@)RE-0%dx;V4;P zhD31W`t6Ch(a1NW^=_-`G%d_1?rcNrC{u2&enxfFK{VC`*^DMMHm*L{S#}IcUnMqX zB5p~CosL)LR8>(jGB$XMwudvi2FOcIDN9_V5Z7P7KrxIpaoY^9D)paF&8O?%u;QvX zKeNzYFsPS$6(Muxihp(fQ`_w`nOi2t8ZRsPT6cai1GMV>aNGsu@Q6+MnQR7o(@6eB zH=4%%G56g1O5>%M1a|u5rHet#pg8v5>HAMy?}s%ur2s&>mCkC@2GH%PZ>P|(4D@~S zANzWLKu9>-!sZ5!h|bQo@pKtZk6|sCK5Gx5sS^wPw&+-mQfmkmRH*_JY?cpD#l`*B zZ4o}aNPOMW(hE%BH8)&rG%4qqyDg5J4mSe0%!Oeh$7M?5{2r5nSL7)P`djaAjU{G> z1)`TvWS44$q}$G5ol_&HwO)4~E~X>R25?%d$X;3W7$>s+cVbUZlnyvIg8H>q zo&bwqnjkU~1r4oflOH~P#$7;e6Z;kOyROaau_1U?@UAnQS>BtDLS$O=$=Oa=$v3V` zCX${Iq8Be6QW_wNS%ZfkUOrU0ihB97AwTutb(Q_uE+RB(jt$N4 zY-|U^!mGDbJ3=ZRwzAWElZvOQ>S{YuDb*?mw5soBd$5MIT3>{K&1ytXj4<qv5wfy8FVD1%|M5m(t^moRbkgYD45b`pV08kI= zy#MBg|ED8VGk*80lGy(8jx{3#i#G$1C%P>@Uiv?-%dc#SV}=!3SjY?JrRN4lOF8O& z=qOf})gF{IeUFQ2s(wIX(B5tp)MQGHT84>HfAH3l3@mLd7O*J;<&$F*7LgWdnV1{0@JrMAV}v-8$n&;kSG~MNiPO zZ{rzYLor%fP$>M)q%%uoLl{n#v3YeWv)LBqDQ~HS2(qFP$(#w$>(!F`Zgw$ub-$BM zFH=37z3j&Zt~Hu8g5mJvxQ|3A z&z33HaR_a`DSS67ekSSWgZ4{dBvgqyzNEQ6KMIcq7S1vE`#gU6H{fhf_V*iF?mW%Gg}i&^ zfz;1Sz<9a21={BTw9D+eU#S}dMQwxuuyj;#ug^#_rtE7ezcy_rNd{*4_M4Ha{;)2v z9AfS%nb-^a`m(kvW9b$ zJ7?j%?2r7s{swIbK`GvOF)nYch5Xn%84%i`bI^O?D2WoD)y(O!E-Z}fv{`(m?X1XV zO7-{_L`Ju$<|)B@b~rt0MrkM*+CA-Vr`XvR@hi#kVuYb4T$JW`dZDt?i~l4JUYz-+ z1(@#}skEC;l}{{g4I^PcamS?{4+I8#qWO2i^E*XVgBznSFR!R;=tofao?6q^xIlBT z2u;n`^h7J{u;Swf$kE(Yj9%)Gq_Wh(Z!L<5$Q#{;oJP^~ErQYNIMiBn=I8N<0@heI zbX{g9a+h`e(d%Qx&z}OofSGxj3yC#)Ee{9~v5deU61;f>IIk68CItNF$`I-{bmB4= z4!4T2oE&t_piMa*CoQdS@Q%Fi3sQ$+Ri^F9;mt7iy%7U`|22tJepZwc2Mu<|y?pwG z!K}mYmxwq7ZRC%irP=4+gDco6?5-5ew+01)HN|UH-kk(5p2}{l@OQlt<(nB1PP~C5 zx|`*Ks_Z~<0m7Xz7Oy!G!pnT$zO(2RG*Ym<@gba$7Y2b2Wih56ogGYQ4IK(3o-Fl+ zk2|3Ja`+pH+&ALQa>|M_5VY z63{&Fv#oynR{Y{c^Rs8T%3gI~;00e;^w1*?-nv;#Z568tAtY{#%?0^>StS~1 zxZQ-R-7Spflre%{QK^!ZBOrEBxvnvO>F5YxNXYf0D+-CJfm@Z0ZLJI?X4hR9T-F?! z1V3XqeHyS)G0P!%Nas=K`yq5^FiccC1Gl?bng9M>G(%0YPgo(b_Ggj}ColMB3ny#i zQd1*~7mByaPs?@)bL4SEh2|qAmSzGUK2>h+{t?=eo9Hsm=$1O6>uCq)-!htE#BYlO zysNa~=+v~rG}4F1jZT+DTWLiP=B%af%)a_n?o1K&wenlf%Sk%cIiaTit0d)^xd7;j zeb3Ltl$qC{3|^bajL0XgRZlOh{Pe%99FDG}th_bX>lTN_B?S|oi0Yj+Fw^x0+UA~f*+1Ozm&*d z;>`rk=Q5GwlKiA8!D7RO5qq%}@05gOIo+%vpWGX4)NzZ5>s7))m&=qrJDxjjJe9G< zNa_hHZFCz9;gY=aD>80D!Z@5Oc>!L-If5b>PVUR}TYl>Qju;#9laV3nbK-{5!+jVG z)CD#toqCf0YJvQY1h7~LV4#XRAM)Sj{u+*t7+Ly0WAtLUPR3`AX4(V4P| zwpWbIoD68gQ6=~LV@$hqZ>n6o=C3O9eRK8pOR}y`XwKy16d>*4NQjyce&KXj1&Ng( z?&{GYvxbt-@bK9uzWc;5Bqqv+?+%SdUC+sOrO#}q?2j`7C_@`F4Y7_&M=&QUCYn}* zJLlm#rp3RCg)=6=D#9Y5O?DE+7dq@td*(}vFZ98#P3q7348-x}m6iU!KEHD7VI~QQ zWAdIh`2fSrq9VfK?(QvDnPVz~kie!Rc3+6L)=-NMOBcT=wxOqlT%iGSb|FbUH8F6m zOJxEmy@%uBmAHRq6HV*UO~E+A!c43Hj;2ei1^NgIT>?T&_<(tIt=L3}5p~|dK`;O+ zAYj$hJRC8=1^N$=l$(YU;+ZnvQ6od{%BvgTIb!n7uA_mj*H?rO60ZYx1x-L0cXxL= z5z#sx5>@3UMauLbG(7P=3_1-GT-cdY~L9S9jUY+1at&r zA!=`_RzFGKOFfsGgYVyy3h)`g`XVW633{x>=q^5UCQGyljHMFiCk1`qDEh6w#^qz+2;&pT8TmkihkXLd&B#=WB*MHUI!mlW$l7TP zuf+x4s4bO$Nh)47(~@ErG}BVfQMMx3XZ1nJRfX%d=SHv~J40}{Hf(etF!_2?@g;UF z{nEFahZ|?S#3aOry|YXk^Za8MB81{92>~P|JTwuK6s{LdZ2qLCwZ;P&{*!lhwo?bI zNhbJ&Mh?XYY@w0P4*R*<^O*`qg)#fH?;=_g(P%$B4RVkXh78oDp&6!K)zslBZAPeSB}nwW zckEn^5aXlGhumpeF$+nLGL6GWF!`Uc#2q1=A|lfy_ADJ!Op-q4T}wq?^W;jb-pL{- zL!){cs~DR#Nig4^(`9Md6j&iV;W=!WEcJ+soSdxLm>;o^aka&jDl&z+JS!h)TB6gn zRnK445XN~Br*n6*_@3ND5u?KZtXRnhpVV9#%Ga_P`}*|Mk#?2>OQ8r(tp;^3gfs6U<6je|-ZZc*nYm_irwx*Pf(O+~QXVc%;T=WL$P zx9L?OZy6aW;+Zfs_`{90`#!zR0sQ3^OwFdUwsMf$-Q5D7UvF^hmSH4swU}V_>Vf z;>%{p@R)Vhvjo&6yc&&{#*WoQzK8tWSFR+_Y#Fyc8a5gF@=mAB81*$dUZj$l4xM|k zEfRNir*JZjR!?1(`oiWYl|YnxKo*7 zHh@l|*lAI9WYy&c7ndCPi(Tbm z?M*fZzrS`zOWWG|(L)|R6rPbjtIJt~mI@Kgeov}IMTtpJ3(7sonuE)P;LK<$*NzIW zRnlxf)d&Ua-vf@mQ*7QDWa8l?;!H?@Wjv0os8JQVYbigc**)_i-CtOlb|RO>Ew>l) zgd5e$8X2tA1=w}P<8dczl`60ETfX3s*e`4^BtK1wXvZUmUlP<qZ34aKM0W?TggVulSlTE|Gg8Y@gGnK0v(S9o&#(h!=1?B%Jn~b{}(x16FaV1R58clTkJOQW9E#Y`M!G>oyhc zeqJ_qUM?`|e^2IgG&#T!n0C?m@%f&<@?96m$fm)QVtlHlg3pgzWzr9g{?rC z;G3-sXZ&+7tE~pPLMt8{aKLy``yXXjRFFRc$7E%r;G{uf0|w$$*`H~WMX9n=*VL#@ zPeng_LJm9zPua}7p5XWl!YiCO4sYJ5?QevPO+^O=qTjf7Rn{L{B{9*sKU?FG%zGIKQ*=CT`c!M@|K+Gq zqyH1bIr`R6qQgD@iFYm)LT2Y1zKhd0qcn=od&fg0@GE~#_44C(h1Rl^#YW4m3DRW? zZqh4B)Bi)@>Bs$rJ%#}EvI7i-9=}OL1}}-d!532Ktu}q}$L%)No9WAv*Qxg?cPVvY z;Z;;r)Jtx*DpxXffBhg8TS!DCM;)E!SxWizLr`1>0-5Uxu{03=NY-9hkzyBjQZTnWoI;l$3&pqGY+5+Th{>{9XL2ym>yk zqk&F&ieVK)ZbtfQ;tlGep12AnO|Ol3Ll!K9eK7@#YEehq+tnp=`uXaQ`WRC^Ht5cg zHcl%Jb0xjX=S`B3A8{L>%UJGO#w7XezEfA~|C*kUWB@tVY<@xEvTF;|>Sn((Lli?S zM>;1ORNZS^NBp0`AE`qE#$MV%I0u|mVs(vD9d5nktYndM#Q}G!jrPz@B(^ZvN@UfH zSvyIP)cpd3*oKbIvSPGvq|eVShbV#lrd)rW`_k&NfA?B2s~8oh)}=_LoC+xlTzs}Z zjB!>*EF!nfrYj?bCxD|&X@(55`=GFXsq{qCoRr+O=RhRdK{L+#&`jS*`Se}F8B_O$ zB=WufEk&39*B2-rA`*v%xw3agj_IwbO>Qc|Kc5}A5I+d>g;Rd+7+1-F290x7)gk)l zXOIp&eV;!0D>HbL^3`q1wTae!|C*xL=Z}ZMq>BioQpf`ueO8P?z@S;!*sNq+U0keW zB6{$|(|F@wHjicB$fWP|basR>h6vwL9_7~I#W2-}Z`t5}J>B6tXJOUtc<+12-gUB* z*-KL7CV99ka!XE=^!z|M{g871!N(HsEPIy=)9X+`Y=@A4Qd{!PKS$KYxq`ymrui6|Xrr_3B(uA7U@^}N z4DKp5_!!8+?i~bKN<0v_T}1Z?cqS_c7Nz^057gk|7~#GZ1i8;PZ1K|`&EM>LCL$xw zF8E$^m|iTB#Ln)3;f1w7UC3F&d8>8esF)=1G4o)dxH4`o6P;jOw64lQFvTZ+!48X_ zZ~xI(;eQ4Rz@SzbFse%-1ykd@vl6Y)p0L_y5Wfzw)Px zD9>~eg}nC$Pi@-~^1B9d|Lrn5UNmLNhZLK%Vj9%B3B2CnB4n_EHCG)E)9;LhJ--I@}pAkwmNS>rf zEhS$Tp4CgIy|CptmducM40o0;Rl#K`t}eX&F{Jg!@pT}ZjFFf`E{8J#gdIqQ-CJ?M z&&h=R5XSj&A%1=ynM{#aRMhE@fv2XcOZB8$kDEO4$rCWM9=zZtiT&e_c(KpOg~&{( z#h6((aSF|mDjXv5K=JR09BtH#{=!UkhWa)lLSUzcMoHQjf8Bk#-c^kbX8ABpJ7)g; z$Q{2YQR9N5)K`g+{N&-R4VxtQnhi3)!9w%T3;6SyLOFmWhU?rj>%wo9Y?#zc%g#_8 zAOiPa;obpc1s5~9IK5H_w9isfS}*$&-3Lu6zVL{MR!2$tz#kY+Fx!k$61mML1}(%W z&5~veJ`oO?*MYA^ge9L1%+W)x(;o>Cf4bdS^4?Wr!_uY&d9!iD#Nq3rQPx)YCc2e7 z@kKr!c)clHQb)bd!oC?j_^9;}z1xr1@W+Y!Q@|!E3hVdBe6Wa3Lg*x1(0$?2{L2?5 ztGEE+MI!UJF@b-!l7Z$<2Dz!*Y!F3ot##kH-BcYFq2wl_Z{8l|$7iuK5EA*v_~JtI z28ZD@aU3uV$jEcr@d*eu(F<^J^E5Hx9Ph|e~PyA zBT<#(&I}>SE|ufT-KR2$%_7_)5~KaEW2dA6%0(R=-a^su5v`VajyL{zR#M8iCLoVm z4sQ)%@Da^E4Ve5^(n;S6+zS0F|3t=*lV(ytAZemRCoL>ORD~2(9&-mkW=Xn61gSK9 z8;d(pDJBlkbR5}3ibAm^x+Wbli?|q2wMf;h1x?!y5DU+xkjE-hN`u? z-Bm~iMWk1Rx1M0M6y9dBPx zoh~itoVa!NS-Q+XOORJe^Z`iJy#U?z1Q|q1YCvodOGMFN>IRy{|FF&ZILw4x}xX=G*&oB}Q5P1LWkAD$46+U#DmRw{_$(Qe4Qy6Gv`teD) zBSuYMHU`bJ!~{z<)l8z7eeg7;oONzVdnMc1*O8EV^xRVyqE9j(*S5a3V9_f$s`ga9 zwR)4^QmLQ5A+Q+yctP~|U^?;=mg*Cb9?&6K%$p;xs;rxlrBNtgVg6Tk1AY!O1toVM zyah;99UcxC8~o=7loJ(y4ve##l=;IAG1zbfRVXQDrU zZloEiref(LH?>q}e_py=jx#lMn~G-Rd{v~)tFVoO52R8^X#TZ?aYmDxZg@dDM9G;gxohjpwWV%V&XYA6X2D& zPKh!9@qiaEgX#KA{lQf0-muZMojQ0KL*J?M!2DbGqCv^+KR&L`KI2kbZi~;p=ll!43tQ{vAm<|?CR2& z7I3rB@22+XDVKH=k65TOQh-QhT7v4cPi1juN$J;~c7S9=UX_}aUJ6?qR~uiMzSVp7 zMPKMOFPBt7_DCXoBAH1Dnv#7hB0>F(=g1)ey#T&Ji8sYTr^!E7aV6tnW5+K98R{A8u6`0lmP&IOXk#B&FmKxnb{PJafi&lwmddqpG!+oHe_On zP{fPEId3Hs3K}j8M5Ems;afm-O*vl0a`?t?Sc{s#ST##ak~Sl#E3U!YyIE^xOP5P1u< zOg5(K8DGT({JO|W+%s!)DANVlV!L{h_77%*wMNGWo5v?*k4KNEI7gKYAg<4wQhjxC zc3zdy!+`Jy(50ygg$G~@q4Pczq;Xgs&ghtP7GuYaq(P;sSud8`$n?M5fBtl-4pwq~ zV@BTiCD!!uR1uK`75Q&E;y>I%3p2=&TnXcLt3|yJ~g8F zE|IFQs(br@wIT`%afPcLiy043MalUG*-U#H3l$6!UWK#_TpDIN*uE#gs?o49c*xa+Wda{_mKu~Py7!;`!9i;S=t4|=d6(R1Nt8=L&cw$@2nwLLy&?twMs3>i{FWN* zKi?GDlaRP@Q*D9(x>*c={6{$xijCafcDxADxw*NS)_T>BFUZX=u5O6r(DGox)>bD2 zp}XgFuqPn)k0gP-^TJ=jtuT~E+D(eTi$53U*)?8a--SzSXW+`vCI*+=h-fM znf4tNI=a4Zdn!F$h--K0*?8|pa_%fL`;G~H`SO)XiW!Y90p~3rHu1fkd)0s3XfUU2 zN%}KH+12l938_Au82o@}t&&(s<^M;3MIhsFR;L?{@B}WJjpk^(V=EWezeeD-Zt4Az z`6!?*2+%}HfbX_Sle_-9R0?$n6>vYKyM?Q3l$Ww3PSnC&sxj9brB-iCO~jjRBC8bJ zaG!e#q6(%P;9h;~F<|+zyESren33@ckE!)WL2-1hQmW6nRGC5D$h@`YZHJ?b{Tz4o zn|D5jwBI&W{w=cXpdT_SyGlm)?l=-`EvO zd{*^w6P;UGkpEPMTz-0JC-_Evzu&i&LdBtz@2xcUkrjnfUX&Kn6R4G~qdAbu(J;aD zol7HMhho(4NpfQ_$v0)PxwxvU3DySSqB-ADQM=8YW2q(Jg8`8zJjH+qsv28hPam7) zKXP$txnDYaezL5cH&H`IC@gGRF&@Q@GIuNSK1z9fAf7ng`$(lbENm?r29b&F5hXV5 zxF4QL(Nrg}6Yk_q{6oI)r@SocY!^6Yvm-@0YW8R_uN(0q-;5DLE zlamGAgQwyh5xBQpEwG3@V(W_PeF#pbnD^=gyd%3~zO}L^vYL(AQ83PCFT}gw?@5pH zzoOk@UZV6|Ht7w<;=!uYuBRSCS8I)^II2kMWiuCjRc$dp#&QX7u8vY zVhF~TxBs)ONBW@}^8r${2QLwzowI(@r;U*Np!7st+bE`VvB#wQ{IpTcb+xG|P1QV~ z%VVDxatGxxO2cE8x}xEEQ(NBfp`y6rXL#Gc(V^Ca zY_jM`hZbcF)gYFIHaw=&^Xb#BhB;gVhe1u9Qd>GlHp3$e%S8U-f7OSXh&vZHRypB# zy|Fxe9SUOk{W~A-)ls}dw7NAyME_c7@XKIO_BW=B9+{2QxjU&y+BTlLyrF4*cEwum z^4$&D?VTNUJw5T65uo?$d9beN;INf9&?NiI83=H~Mw(^oVm4#teHWY1lE{6QV3Q0A z*mC(R>*%wF63>q|YUI11n|_lFN2MQpEU35dCXX);W0q1?MlLyQx$pq&#BlewUEXG`?9^S|w zoHmjDv2qE!s7c$%H!A6_I|h!CPuSDNp4nr1!gwssW(uoAHD{}??f~m`gV#07T--WU zFu~kg!{RcTMTM|A!Rf_0%7!&aC3IugUFeU*9RQhka6pSg^QCo@DV1etn$x?df0SjE z6@G5iNbJjAo6T6QQPNi7|n`zu>|)n5Z(NH}^MNthvT z)9^>xy8W%)V|X--sMh7GFc>z+LmY}DM4t-SzDEeHBHfvdCNc>Al1mqePs(? z!fvdVP!oX7WRvNPMdE=@T$h1?NernZ+ZesVxL=6Z!%>0JaJYT_6m!v+E4Ko^dYm%zgt)+~d`WO|%EzxvCH{)(r@ zZIHQizYX8>Gde2n>$+N?G+1@C$-!Gsq#BXT~MrjX2hB(w!J@2_LM_3;K zBN&}BquHv*Rz|mF?+DvvT?z2|a#jvI(lTp&@yv;hDW@3rK;tE&K+XnAo66#Yq9Wz_ z>e4(JcjAYdk538aRb4Vq_7n2zzqY6lwx60JK#cGi#xO}nqW52w4J3UoYiAOT%ApE! zz$HetyP$nfNY_%!SBJ6?!MDkrgeQ21>_LF&D-?yiS%2;v7G45|`{oEEgGg5GyI~t| zbigvVlajdoM@X15;VMdht)PO@^zlBF*39O9bIu=$7|0rqekUV!TbO&<2ry;KA$pbj zpHg_42oCi3-QB0M!7FmvSiiXd9UUE+AqFL;LFA@Yi|L;J^ww2q_@tIq=V!+y_qw0V z61-dc9m}zm;QU`^R+eBN+~)0#`oA?(*e`9n_$|?SES;9}Q4;kO61|lV3DdWLFRp!y zH9(Uo8Z$3xiBG|EauNQZOA;IVB)F=rjWNwIX)-#xL#b?dFuOb-w_@ATc@%TKEVF|% zuVxFMtI?M_Twq_q0tnY!6aG|yxnvx8_sWscyhq)wP1kFiu2(mM3Cg0e8+dW&2FI_+ z2J>FK-+LLLIx56VOREYIAA>)Fnc2?_KA|n2UzU^=;3-b2LLCA~FPWx8;{!$J=j?4- z(91yl+L-pZ#M^k{Xb#T(WyGAXFa{>Af~XufvS`k8+5+w2$~bSls-*S5O4dA5fEC)- z?+y7_U*s{WV0FuXVVp!bw4(Nil@5^JeI;6(_Ix>R*Jy}$8Kiw|Eb~$3v1bq{=t*6G zp0Bl5RDu_zf8U6}+fBpm;Aml4SiB}gl-Gu_lLjzizW8IQa>VO<4r)z%zQe#Mq#v)U z9}ivY&u!Y4<+?5XKCt0l@wh}|O2w3Mpui};w-;nr3C&!$$omzCZ55qrm4w8M<->sS zZYVh)Oed%pWow|-4@Fml1*0v2r~9bYFVy;o*7VB)n2o7Q!s) zEjvkJ6gwLH!<$}`LzB)VLx!F_LtY!6p(0O%`Q;+*J{fJw-teq4WHC(*|NLhOf<$5{ z90Wzti0s$KVN2AV9j%y0LIBK}J;PF>@Q34NCIVSe3c2|OSg!QeGsgP{TLM64m$E|C zbaW_p-I@vdv@@H*TDP*YM3Z1+hw2|&QvlmW2t%Rk;+Qw694T+E6-ODCpI^VjFcK3y z-x=)vp>+>BCcPv0DWtwg+=%dij5zg@f-fFX$02WERuj~r*5@E1l0-h=bIp)e~H zBhYcp@uea!uadOUaqz!~R19g20Foxhdk%)M))-~v{S@fS-t_j)44?4e(_<59Z)y<^ z-0(YO3H4baX9jHySaY|sNZv+DiPJ^jNW<;kUZ`3utc}e`3L%vaWOPnSEFuY{bf_{3 zZQ>;!W0=Js4q9)s{}U{ny-?ql?3on>o%va{uL6I#=fJCoi7rMtd{e25d{UW*gJTnm zDn21(o3@Jy42E;#L>e<`gK6?^LRb@J_^dVV{L`+xr?7<=Z2<&hMQ*5T=sG)&E0?T&V zGv&;OTx6ASH%+vVrF%@+^zpGr(E_IVlC${Io=02Q72e<$2P9)ilPWR95S^`Ni_Z|P zal^XS{%)1zA8W>t4lEb=iOcxI(;m>|b6YDP?ub*_RecQFI8v^!|48%wj54#cDxF z{9de@HZ+gflP7P|4Dy#g2#+vLG_6$l@LgZJ#olzq>t@V1=Du1<>q=Sb6WG7(4utR^HHRvA2?Docj6d#!T15QD0)Zu`9&z6h7uE`gBbb{DhT(YKe%3p%vF z7xN*piLmj-4#mY4R331fxj}mNg+=xBXWx!He2(#r>?M3`iN?*x+p<4>PVW#F#?Qvy z8f#8J)ieQU$e|BViOgZQ-pg$64U6vV4O<>9UwVE;2tH{$oF3nckiU^})|H%^FL#^t zi-%-#PJS19tZ3W&HZyir6=IhaXZwzJS$1*iLpf38t>XiiyK3!Ks2SFVWFBvrQZsqt z(M#(0OI>LOkEsuJjmE<^yvMCXIwSf5@@^JkIoGUfZ+LRf)bBs-#~wBJ7vRLXN{*L% zkUZO5=;NevmGNllV@OC>OWc^YR1n2mg`^DnboKWI@K#i z=i;ActBojuG!izmFyY_2$3I*K{0?Ni;^F5Sfz^=`<|W3PKb-L4Y>4^~C!8aNFwUF> zb$xL0U)!XbL`kt%XW&y2eZY8$MvlKP>Xe$u$9Nprj0X>PCn#Ba>x-;UyMO{XYmV_mSl#4+yd#q-~cDVE!hrlUDu_=J-1x7tAn9h1l86*;ZL?4K=kH!pkh| z>{wEFt1ve)E{b*dl>VC`d%9&<7qzbmWb{Y*T)rBYIFrRIDc2B;rvv~vFDm~ zO4h1KyhFP*G7G1_S{Bd1&4}!(TsgWI8yaVRpaGc*Rv&8SwI>c-f+P!^oR)8O`0b`7 zxd9{SIt3pXdlA2(WG0l#G(?F5@pfizwhZKAGAVrh&xRUy*afKAN$0vNK@La*CIsDZ ze4)Ugr&zy#*)MDuG^fMEaeuS~pin3?Ls#wM_Chyki5yIM+Vz=5wW9zn*XEoU>2P^a zf4ooRG*gGf{FW|7lwpU`WJ1sgn7(9&j_*`OzCajFQhDtaUvJe(r=m}R#4*DC@tOL3 zv&u+WLkMPf(j-h|yePljyQeenV%Crihx+keet(aQl#&9H9ngwH<)%(pC55PgeEEhF zfx9G$NV^+zO}7IBrQ?-`$5Ff=<2H6P@$yIN;MC}!zYb}A;YJp z56(tK>YFwdH+q9hZw5M*NdABFqEK^jB8zFR`}(;c%h`T^DNY(X#7?i59e&Q$^)I-Z zNp%LeF91<|U(6u9`ml1+1!O%{;9K&Sr*xp(hx0LJd&`4k@BjWHzCHq-TA`TH{$7{K zNM!SBpSCOJwA<<@SS0ts3xv%@B_*1wYU90gvu=O8JNDZ3lKdAKgkov1UU!RFM&TYO zQ40aBb3w@`H6fxXUOZ^GD3JlSneWiPw4)_)HgRDU8(_S>lL>87c5oPZ^LdsgjX?2| z)=USDZPURMzRtE)8xT8H=9KI~j}KAlw{g%+5xaD%>nnq`4s7jcJY(_iM+H${{i4N} zm{yGX9<(Z5dRQ&~Iak>h+62(AGI(n=orHgST)*W2$VzxFw3g~rC;>SWL#yBl@ii0Z z?*ybR+|O-!ly|j6CxCgocFU9-!-COIP8?&nvMwu&{ zCa-NDD#o=U!*?F-xL&IG^Ct*HXel&;-dvxr^L~g7WK&)?d@NwNVfKM!aM0X zXlNAhnvSp@Ktb#>^DDP&^1H=lH)_5?_hLrVzc*t>68i*dp5kY-b?-{-6z+#DlvlS8 z?3NX;wzRL>4BU7MSpj%_r6tkO>$_3AWkN32l&PuuYJflt2~hT~-FtRb7zcE6f zlvYIo6R8YU3&0kyGMKJsaD`>1Z6d(cQZ`Kr?gL6+xC#+|mR!F36JlQFb_`R#3uHPy z8OrL{@rJ4=lV9iSB{SY8caX0Qt$ze5j?j$nBgiz2pSi8MCNX_EaUF$uO6f%R$_KN( zO7EDI-D5ZZGke>^4exYb92B=s297{@2PL=Yj0nAHJz5mIZ6Vq8fh#X2u2U5mhOK5$ zRd72~P3ZHh#JR7yzAC?0r12M@n6f@Il-g8GrKrfE*GRu}zgJ1tM;dGvD2s;v*e)GejWBA)G*Xcx9o9C^cI`)w zA2+PjPus@`POKgK)2>T)oR}B?q_A@hjy^724NO-)VhU+DdPdjVYUi>%Ls`*(Bq;x7aEq9_57 zltVKE4xe_%q6dFUYZigk3gL$((x}7lqqjxPFfE;jd`v0vT+vGIO>3>G5H{FwX?>pG zr#x~)(O4FpiVHOr!(Q)+gVGa+Yft)L=NDt4Lox9oZk2cwxd+g_vEI{%!?!YFF>*e~eDfbT!FmSb1&i3_0#GjTL~hR1`982a*q`9V*g2KLBGG1_8@v`vn1@=$)%uE^zsA+dMlHB&e* zJxch-uM{zQGvwkWxVt+@FzM9jk!e%M89;&%%nTxrz8+70-!dv9fSD1M?%lg3{*+n%lq^bowY`8lL%q-)J(vmh zY=946j-NN0-OO+WgZadDyR8lBYepFd)enpK1ByD36>D}U^ce>fmP+A56psYpqW zVNtb@^p!M#FwOJvWAPP{obp#Vsv&5YNq7mQ7}fdVlA7%|uF4VlDGD5Jpv@f=-G#V( z^NYWV7^O9C7l(^5s7WH+In^HFTb|;p6k%+yHn9-)5m2!|5+C@Oiqkq#om_8>`h;88 zUpFX7?`7~=594{s@5p;`onocv^2fs*+Ffipq+8MINw=_&ypkKbxpqNrwwEX5uIq zieayY^CJ%Yrgo_EJ~tsc2_Ij79m8CBtE6Vq7U+0ZrKvi*xMb(l)4kEu1XY)ReLk+z zOOmIyB40Uizvgk>f5qj9!Vp$fK}gI!ni~Ie1XLp@})8 z-~KiGdKk3HQ+(!D7-Dv>Dcc&UsqHFKTw{+pa;BYmgbmY1eQk}B>k4_twOP^Zm!oy* z3#Uf$er`(f{Ymi~$^5b_LrrS(ug|p{erl!u#!OK#;EoUc#B4+_%-Q+QVh!1?8{0Bk`W?m2RT|7Yr`Gr}RzIbInfcC2aZJERN- zajoA#cqOhCLbvFt=Y&Bab4pvxoiS#;>yvJ43rP;1@@R#n;bp7i;{vb2jZc zi?eE4cvuAaY=h@|^MF5O?I7$|*ZcqYSzyYGuklQL{j|1m#dXJ1*tYHZ`JRzH9j|bu zStg@!?rDl6~>u=eN-F7I9M_QcE{z&zc6%;$YDNil(#NclUW!yVBTx@6I5yb6kP zPn9F@I{duk( zJ)h<3O7y0K0WCqw$Gms%<@7uy9QF11OLNeiCTu@wX_}*qK^L;_y1ctA4H``8k@(MV zWJGgnykuf!Ra|Lfb=$tgXd96sFYIGq$z#1B(1_ zKZkMVhkI!%BJ-K({M<=V6)dwz{Fc-li4j*&C{SLyl5HqfHBs0u6_Cgq(NTN2-ru~L zFUp1+Y6N&wIT(}fT-WyC+daQ;?!T|=9MDL~+UU)Z8 z*3D1zRfpa^AKU9duW*j+lKp75V(1QLfKptd{J;2nkzng1e;^5Hdck6={?I2wQj-1% z6!6xaUKxh?(T5XN>HygVV;QlLowC0jA8=aP2n0GUnCmoZl0Bh)(XCP=c$oX17pm^@ zNmm#n7~VHD6%8m8Cr7^Lc6pu$bG~A3s(M|1B~`5JsWcr4 zyDI*D(RCVB2vgmRz9Ktj`#chRv<&Qx%qk>^dhx*)f^{Oh zA#L)x?6$9gLw7ew3P^XiASx*!APv$;cOSaD^8gBnQqtX_ zG)Ol{NFz!}eVey__r7<0W1!>wp(xL@_gZt!HP>8pifg*PM}^uwr0al~u@rzi*@;o6 zI(~p`beYqkS&tCKiNZF0ctEiWT@nqD6oY*G3ZKRgsTU3CPQ><(ks?|o1w_{Wr6TY#5Z`03tRC1UJ!}CT4e1zqH)0h}!uz7zc>1Hxe_>oWB+$emu|vfa z3CG64YeAd@37#D!_*H_T31-~jj!xOI}d-|{64MOutI~@kdNd~{5Ar;EO;#I;(9F>JZZcnAjjMB`b1E|M_0iGu zqvJqSityh)`MJwSzz@ntpTehtPGNk;0@{gE6;m=r5`eo9wJ}QY>v=~SPo*TzjyA%g z*8{G4)PWKBY;0H)x{x!%#Xc5n3&Ti;NcAftt@@O4+UMZZ?~@5lE-ZE{4S1(pBO%I6 z=3W0))&220#@c~$OtwJ;&>#r-g8wS`aW@gxt^5k^wN=T<$%x`vEb2v;KtT42ZQcLB zhao%Q5a_<)lDgpLP|`7f!&L;;?8mux&~|vjaCZ2(eu(!Il;xEwNJZNP9dWK`n3MPk+YQ@w%ii?>N!=-m!YK-FBk*_O(Tax z%xp>73vW?24w6r1WFgcz=FI3t2)L~X2o=LdMVvAi1q;%m0WY5hq8`*- z8UVu9(b1BJbj*?`UqXT!>*U08YHw|P53hK#Q&Tr8FqPPLXIG}GfM&(pH|%uUAI||- zpT0-0=fj20H3{3vBR~610c0t*1MaPi@R)Py#qJHA78IH8PJZRXryHj6rHz>zL#opk;bGg zuCh_{(a7NI=i~^v?-D*6&6d8rJk>sO+YpiKe5ENDd2aQKK4+R(r!N=WBqAc(C}?N` zPpGRTp2^Pcu8gj37O_`VZ4Iop9Gg8R#?sm@w0~13u>hv3srKyzHoMWOr`a1EfQ<>I z!j{qWAqcRB+irp8sDFy)Eg*mdJd}fic{niZlvw@A=&8z+XRpXVzJDJc7Z=9%^kTPq z)Ce?!c{8&d(-vY}O-W5K_whC{Fe64sAQu`a*AmpsO;`=5(niy^G>o;nYS(+8zi)Kx zaYCM)Axz+{Zezni24VB>2n)z0sq>eo_>ishxZOsnp2^TSK_doCWFENBs@TeQxj zCUP9qu43@l0O#HJRd`tU+u~YKot3a2y1AJ|EX4Fi7P#7wem)onic}H4*{xyOm(uW` zs;j#{61RpCY(Jcpi(cESqiJ%wXyORhs@JB%e&g!mYDF8Wd{TW;J+c9P8f=!W%;4@u zS6c`H3z!&0bGTU16I+eb_%!93N@W&-9W&5NJRsD^Acy}7DM?|_82ohhsOXYF}hE9B{a{ywC}n<64A5q3s)Wn^sV zwCn%HK~m(shdnK6E! zAT+Y`IKgJRWF3LX;TMIV$!&}0Kn@>^#yiLV87&FthLRZi5}kv!U^gR?z;OnXuV+?s z^!tBgwEz8RqSQg+go-H|49k*bZsxrhn0rS%%^@*jA%-5FHN=^mx-OaPh2F>6-UFr- z*!yCLO6-{A4HlVlWJ|>CPP`Dx%&Z(R z?|#;-?@iv`!2fEoqdcN`bM|j70EPTaXxeKsQFh|w?d@(JN4gi26QM7jdDNjv8yVGL zV2OMM2Z|bpFzxx?N0<<$YWB!s?FS5NEfTOpMdb;Kp2@*}@JD8@@Qy$>dIG7~0;5j_ zMv3R-xN9LjG!Hq-HJJi9;Brh-7}!6Ky)U&y8KaTGbaX65WemxYA{ycHs8- z$h3YyeW;IEsgL86jLg=K({TN2_0u5y$%p-63)nZ^)u^QoCVTivW%wBZguFg7RdHdQ z2%v5#%ChhK^zOMaA1Sg6n(GbazZf!r=ww$zve|L-Dpl%R!YnYOCb9iE6pXPL{+0ZgF+iq~4+5hx3;0JQGRjZ)YRGwxjtG}b5h=!|m5{C7gEWO}dB2Kt-vJSi6y1^f@CbUH5D#~wx}Ws!k=a^oWGZ&}fY zmOBFN4O>g;u#YRc(Q1B{s|-ES`%nN0YOre8NOUkrbyO~veOFqbrio|IL%VDu?emI! z9W337&n!hERYXI3CG>=8Fy6K4P&2jG=2;7NUHG0ZqT6Gp#7PuvDgS*^zr&MN9?hvh ziiA%WBAS$G0i3@&u5_dhT|4eP5C?Kmwb_^XK?y>53jq z{6s9y+XW8GVhjunQb*p|S6o*5%1pLpWhE75a?YAWV6~Zoy`@y!aA-(rqz+(Yj)s3g zuzY0_9nd>;;9{k%Q86F=bf@=c?#Aq9Aagh!N97GJkXU0xK$U+w@sa>82^9;mysZ)f z3nA+f=v=<#5a9}6l_3a_x1R|Cf5OiWGL}D?Klob4`vv~KiIQS4J(!^$5BCUyFS_sm z-UMA>5!yvC;=M*+a1)0xoGdb}e*_Gs_g@Y7Hi~LGvU)2t!h+X zg^mR;SSc=-KAN60y=o2aJ;vxZwnvFgh0C*rwD}NeuON~(zxLtSi?1@r+R}5zvTM5a zdi$>E)AMds4qUr`cNHnoY&|!Lt{nofv2YeWnFOk3Wi|Bh63JcSMoZF}qW(4A{(mIK zAMeSC4-w4sZvF_Pn%46de_UeBM+|NgmS*fz=rNkD|G9p+(TlD$LlaNHH=KqR^h_=; z!QGZju0cK!#eSdUuBycKL_(rvQC@^wHm={;|D43k$u1`g95umC-bcj*&xw$THK&>$ zW8V5)$0v77gTc7P3(k>7)ZFl?P5qq2x2^Tw&0NWQF3gkPRjs*T8Wm4Ml*5#t27=Cd zu6hObX4m45SfV_(wy{=qycOf1775PE%seJ2CMY<8R%|>q9BONf zoN)*N0?3_k#Qm=je*yUVJ3?)53@%gR_;@%4d>C`bNIf*oALSc0ijy_eR<3LLt42dA zN3Z1VhNQ{v*Y~fsG5(X4`6~$B8>7lL5YOftqbe-^IZFAjGyYG`fu`f#E091X#9Ml5 zoEECKxw%S6$`5}MU2Bo&jeT@;64&sdj(Cs~TT!don>4(5bq4OD%pi`_$w{@wnuzC9 zbwYYFVWL-0m0U^wq+M9qJ0vA6EK6}u{H9%N#e3|!5F;ZeT~JRTrGWiKn$AGV#aH1t zl&lFZ`8oa<1~d{^5smkcUNN9W8sPZ8z+eCPa)588`E|1pMc%tr#ws*--J5_B97>@>BsvG4bnxMGt4!=rcea}jbth1wb>%JlR?A+eHG zoNDUwQroGQNTE)fW-$LKgT}gQ;h?0&1MioaS!GI!v55`qkESLrx7#~m+j95b!<3NT9h%^O7#m6!xbn8h;wec|*bFX=5IXEaC z1E8*tw-cO;mGe)(J!Qxf4MPFF^`cV1@GeK~1Wur?*6gIiN%e&E9Kp1QTbH9?VLL{& z)2g7T8hP5`22quOq8OJ=)De~hQm0svRT{dHO)oiN z*y**mUHL@RVgJ!z`OgPsw1|O8Z0T`)*nH9t#%NZQ!Q}1H>FC@)G!1kOebJ#C%j0~> z{ic~p*a^{jdxYwc>&CAA&4R$9(;)lp(F4zKcw#p{Cuu4CE1`a1U;FB3ro5l_XY)1{ z#v6SxK?i+DLAZbTj3{;(4lVnfD%s9f(uU*F`_H5qc%gysoYy|qPwkBvCwc4fjfA=Y z{X=Q#@mF<~`?)3||64H;QPJAF&k|-|2=6C4uJR6m&&DGtm=-nyL#?-Kem|1(R_848 zu%?bF|6V=?WhO*@;*R_PqnYpV8d6tcf31{_F2#spOL$tIKQ)t~Kb49QW%`Hk?K;T% z`x9?7vb%@5wvyfg6Bff=$=5!lPcDxt3v6Uv%^1&oPmp$5S;5LwLa)46lI1GXLK!~1 zfZR^`6n)Y2_^mEmrTOcQ#N62ApDu5KOR24Z%^f>qqJ6FwArf{NB&_`snMvY?P|{h% zF{Zyzf3Vg5l0={Rak?>Uz}=Z!F%X|Ts3e9PK&o+w3%3bZNZ{=ol?EEX)V zJnw(7(QhaCg9wQljtI_e_m{`CWzW~mK{YP>+_Q776T-7`1MAWcC&N&PWxEI792S-b zZb#3!1ap5JD*Sl3|P{qO>g0!n! zKU`Ei52cADmQLIdF)D_)%*D}eL$PfkVNS;;#q0=i?&x2DN{XW`nnH?LMXo;^NgdYC zm`s(`o17HL4TL9VaR(Z$m;W1gav?$`+pc+Tx5l4bE&X@`0-I#;iE)K2v+#A+3M2O_MnPBaTGNv{fy>)RzP)iY zx~7N(5ME2 zmFIg#cDreK+w0!~B&_Sjk~dbfBORQ6Cm3Rv-;!=OfX#pnF24hrIMgD~m$;(+w&@P8 z{q|Qyl}T@;1kOb-iJ=kb1kbyxfX&i9myvy&@6rsq0N=mO>D%IB+2Cj$-P*Q?BT5LnByC z7pJ(KETXju^dP>z8(q!_SkS1mzn19d&PjTlQLKofM)oX`HuxDCxuymkqZ*zZYKl(i zGntTrf<%d_ZCMBze#W+NM9|RbMf+h&?VSy$xAs+b>-pT({#9eSv*Vdx|H@Ulds+3l zv!sfLVqoa8Lu`)$PbLhiL#|9I87n7w6Ko^!rt9WOENs3vig^tpA%}HsyoG$5epfse zKC_jVns)$qQ4Nt=e;1AQ8SX-TYeGc=F5`_3ZHwz@+X%u13w(MGm9{=^!vP-5^$AS` zU6^Y}vI?}}0kp*?;LG+p7pphjRtj5$w0&!cwdRLi=W>OXO1_79xbXk=g~|(c1bWnbEbj%uecZrpv?kNX`qUz#eJwbdd_170&wp0lc)^~AVH1Y{=B%gE1*8{jN z-zR#R8Kh-jSELk=`+`w6%daH~du71QCm z+&x4nW`&pAgJ2!PJAFf(E=MqrLsA|=oX>;z8_7oEMJJNUA~EcF!*5fdoj?aaqS!0< z_apk}S@Dp=qmfg7EJ4J=rgnpTpu5IuGMZLlEIyYtp{Y&s zYM)o^_fBE?7yV{8*TL|_rk9$}5q${aVbY?H|9%Y}4EGOksBP&JAL1v5++b`Hj_a)N z(hm{na5WJ6V;}U7I&ZIU9xjcWpWC?z`7ejBD>Hppa&+9uW2bOSV~=XWqM!qUGvk;h z4ry7{G?7yB!SFz2b1NZ_W16}O!#K^;?TuRX;^U4+=LQ5RE+@Ai*iWmv4d9yLY$26I z9mH^=oUQ$ASiNwBtv@+?pEtsrVh-)c56dEl1vz%?D|TE{b~MR!1dYO{*xa&Olg>Su z6(QSk#ndLrBfA^Sp&-iSm;Hr|<={P>saCtqr~O}N@&0H+R|!b3J~LS^yib}5&9j@s zH(mAc_@$kY(@Z{BM^~gW|^)7;=rM%27xR^EtpUcuz7mq=^LY=o4 zc|{d=a8cz_h~NbgbivGCpy%oF?SlQr=VZbfVduVZ()LFj*v>p=U89$$8@7#3B`?az z@$vC-Nk}ZkF26$3V6?yX3tG+P3HgBO4&G4sC*R43z?bxin9~Ipd5%cP9{g*Zi9ofl zM&@QhzAWmHYJN(j4i(~h$SnNo=<|ZG5AY0-1~e&8xObdr`t=r7uG+w8aMKk>@*{QR3?4IdRz@`Pu1L`Wk^8eqaGa~( zTxmVWlRVo-Re!h=7sjC{RgOEkt?5hJv62>yIkei5mz2gM_!=o5k#vLEiNzbjE39gn z;9zB|y8(Td5nx!3F!B<)ln-)t0Kxva358F-MPbIxBQyLq8s~Jr5|>-iO1!S~-t&JC zp8^w?`TAqA$;Rp#<7Z=VQh}igD}Cg7fB(4DP;~$Yvh3SBhcbApJWfpZ7wU1su&HFg zKBxpH6>5!gJu>$tSCUMDH<51{{H~7{)9rqLsA%h&0RwvPo~N0N=86kBZ()+A+@$K- zb>3TH$;Xg4lG{#|67|JBIQo5a)P5%qML@cCYXBWS#Vi3VXW({uuayUip4FZRf`J@S z!Sco}@PsrS z&DSMhEZ-MR29eKMY;t9deIOZ2DeOdg^R+|`@@Ao~H%4%Ir~1KRnfY*LE(}r$ zpN5sH90}j~^lkSQ-!R7KsYbvFLdff9NfqaJL_^>Z>d>Cdsx@MvThaFW5i&OA&Ldve zU5)rgNsLX`wF-OtBi|zq%q1K@$)4dpK zZN~7DzruZke^i{u{ZJ2>WG+}rf^mNN2cJKGww$fZcU(Gsh4s~=Trpb+PxAU0;&!-b zl^q2pp5!_Mkz(9D{W1chRfW$Mbev-KD(IiYt_};X@QoaTl8JPCSM;bQXgkk;d5Eu>6sMpeS4C(*TIX}64X7I`b$=eph_ukdcAbm>EaW~s%JZ&Nsw4?NR z^J9L?U_)Zd@58IwN11~5vEE0mf~%JKHZ$eDX<)JwXo<+Kf-R79TxRXS8;%xu;CEsC zdiYDld5&)7oY2wbO5%GWzIb@g;}#lhWdKox>+&=T%opx=VQ6V&Ym_Z*%L4rC&DI8C@k1egfiEq^XVinxRHLAAI~E?K%i z(XoXw?1es!1-8*4lT=Q7z`VuAxFk2;J8C~t+27|l7rdD@4x0M^d-(_Gk2^uEI@?TZ z#oo_g%I(;pm8G*^U84liZ|!Ya+h56@<~Q2dIH+9=c(Yw^$f!71y!P0~GNvNNb>fww zF7oGQgwK6$FSqZN%vjrB$au{gBCni+&1gmFC!Qvs!a6$g#v`i1!?rq{93nFD6drU9d+J88MjG8-80q>~#|qk#z$w%SaABNYWe3+H$+>sLJ}R z4(5IlRIbBQ6g`%uy59 zu|~woZ{fIB9*~8P6m1~x4#nclwg*2(%9B{ih~25nU)dHmlSNn(*T=FmS@(8kK)xyN zuhiXU==F04DhPIal^F;jV!7a&OSa#fWvy^ea%Y=)|JpSZ;t=H?i5OxbJT_lEUA!Y4 z@;RHcupBQ4`LMGG3|E13l<4;_7GzhqW-l>v$y}NYYOPar^$i0S`N@e zQ6o)W;B^eK>2Pgl+F(k{5by%Ww{>}?<2vn;uaxU_S!2e ze|SId@VLp{nvhAGicHua9d5r4a3u84`#|;PI_DjIHuUS8*IZ0&>CiVLbG>6ej^-ed z5CWI=8u{6C!3U8-%v;B=q3GnZoV}RJk15Rk!A=Cht?w)ot~7z6s)i)DLS9~Z$|H*; z?cirHv*+azI{)1ngu=P7-4gr#wf~Cmx#xZ=-eh_Et=BaeL+HC|d6;1Z9bauFtCrQS z*5wlI2MO74j(_+0ScmVcvRC|t7$Y${x{8H`ZBsf~UC~dI9_kBZ1Azw&v?$YZRI(v^ zyw)QA`|?i;?|=ckK{ZnP=0U>G;Tccj3=8^p7=KL0vmM(J=HEp~&&Q;U6EsOXs{@qh z?7>wsJ3VEvMD5KzoG!~s5DzhzU*<)Td5gO2tkynbo)e-f*5SaF zhJ+;4T2FNW$(^`cccXXnN<2Mphle+|aga|DcU}s)pq*_v_FSGMcd;;OuCCZhhH-yd z$nQlA7c32fzb?f@k`#lP1()z!U4Z#Wx`uX)NW>85W4}a6CF7C`d2qSi{3Ni`Ys8-d zy}Zlk8@Yh8#fykw)-EIe!Nf!Xh4|d$5Ji4}BrD5YBL5_-n#FP;lSp#=b5NINDa?te z>8l0i#>&if#^~s|R{7(-?l84q*Petb+uu*rWg7!^S=>)mVwLb+M{M~ zqId6Gp6`#REs`E!nws093=^xW^)|EhuS+Au*s-$_{nCz{YWGzw@cXf<(0HGC!bsij zV}$4+k8_Voj9pjX@v`TPh?DJ&v&`=fJt?*^4}=jo0i)p<>u6;q6umknixH6Sje%

oCvGdN9}P3Wd4}gnrLEw@O_#;;a5sfm9rQay|w-@Nmppbt1J7eOym6v zSVI>dPoY$I#Q5Bz3#R!cXZ!U8Y5P=qNMP*tOGky1^e{kR&*oQ!9jU<}X6uNjmBrlFog4_H3jvsU&h#9BS#HX_;l02a!U|nc z*_Y+(lrvdmO8tJwa~%&Ge*lwVroIVY@3P`*F)CwG|s{e&R)n%lw&|CP{ghi zvZWg`@a$n0&Q%ZJT%9*(e&g@Pq*=Dz8p;S&{bGHcV}aEBd~0r?+IlFRdsXUiBmZwL zz^|^Vdm9DdcwF$|RV5-8ptyNQlqWr61Z}2=aDz`W8KMB#geouKi2ocj+kR4V{w%cK=EoD`o%KeY5AU#gU|a5JZCDBs zt3@CqzlSe3pU~w6^UHe#*4AYa>AE*fwz=$kt}h5B<*n7OkiK&8pvpv0`m}MALB=`D zQ7v>LVOa1OZ6kZtH*p(hl<`B!DX1$Pz0a!7@phd#Rc{}0{#7i0SE5P$#GB4W$MIYi z7WJA)h${&af`iSYi!>htu5JTb%a7d;vw{}bnfvo0krt!m*n>5ryk=cvZy5+H45*M2 zlVTL#11iVc)udiheT+-c-hi<51yaf*tq}*V>5tk_0<(TV9)=ju4EGg9^~a0Qu((ffhCPtyqj2>GaMr#3YsDYuRJTS%$J^AI z2w7hsYB4Z|c+FZH{>^#(!>-WCpec;48W}TKI>0@Z`x}q-p>aLp%h}$!P%uqJkawz= zH>jsCkaaDTkI_>L|6bCsur_1hePG6Spo6lruWTV^pRmFNvcHhUbY_6#grS`ZJ6RGIZd53>+96p2P;JeZN}D(+A~&t=fDcmWY4sAb5jiNs_RI{G z+w$@GR5dz%>rMNyXM|=+a@tyjsVmv2a_iohzPR*{Nf-fJ&ZOf|Gh73=1Fc*_bGeKI zwU!BK#erpED07dOfv`Br^+6PvF>Zo(b@KiWB>ciKc&I1=1mtXcnIJdhGirL zv&X81!qySqYC8D78Tcj8*Iz0yXUsJ(8T{p-(TFx8}*QYcJeFNKa}A=A7m6) zZve1#PCdFiSgN&|LN7$dLO)@qYw<)Qr}KgGwZQOT&MF|{EzO%I8;J;f`SWl35LAi| z@J>kP060&N&Wqk;<>F98U$sOkoQa)WBy5#;!)qG2B!))L>;ZFt;-x478^o0s^oJkc zNSw`@!UDSZL}YbC@NP*xyzPW_0i2R1fv7?Zn%s9JDBdFEFLl0;XoMtLf8I z0o_5rfN=NAjF2IjU3WTV3VN<6AKKQ}-CdwR*5URfnsjYT;plw@JOml0TW?ohKVM^I z`uIbAmb!G%(%d;fTkg&^zxa@wdHH!Uwds?pW7VZ)ODZt@uR3ofcni3)(BwFZgk9sS z41=OkM}`n{qsQ02_t=}0HLgdp0;&2dtyF?(oi?AwlW5mmWwwBX6KKW*F*B#tD{$&( zb4pn>V3U=S#gN#Pgd-(WVseqIg_t>(k8^CyJSGqE?MGJ4ebGbHt@^Ax@%gy+Iv~i<5{WV#v zLUAt7>x^~Y4>%gN5>?uYVdv$RTh9l)F%|;VBzMQwi`8{mr+Iw?j)6Ek|fv4K_Wr4svd8aty5=5exq0SK4HzO|=g zTwXsdYiwplG|K^1WQTxmNRUt93|JC9IU$bNxDCaq@dUqK^oJ$4Gt(7@M}nsiDtQ39 zb+xEO%BD*-2j7sM?OYP3j7hIV%+deyCSaLG!qP(#>HKXfW1%AAo7q?8jP2(9$kM0? zQ@%tX2Je@+8C+GJ|Br7^P3<$*iA54`fg7%Tvh8FxC}n;1g>*Q*Gr*?lCbMEdE79)s z?DddB7n{<6uh>@VX7@7k;N<02*E>rqr7VHo`zC;iPmBqi$j-zL!|>jKR%*B^xTeGf zv!Dzn@{xO0KT>Vb>UDAQ#E<{7;>64B4E@7gb(s*}RHa0<)aMnb$x`u?lp;h(?6gJhL~tfihE8NSYtBbI?p(VW7M>xR-r8Bil;?y0!2h~x zg+9nc=0iyp7(pi$c6$54Kxp=Y>TOwox-2P2>ojNn>59Tel@p%DL|pb7ej|Cn8Twq zb@nTE$>&Ud$31=TQN)TA4Z;Vu_C; zuue!F;0_@cw9i9hfTs>FH|V2!$%aaPvD9q{!t$B>%G&!Nl<|{mPcC-`Ijn@&B=G5E z6xi_Eh(;0to|robt1sbF)^DlKI~#xFxj_)g~vgGxbk0%h*)1@x~$fVY9({% z&pY(-#f+~<30)WT-CauW`RvbTaU*&JQJW+ zE~)h*|3vmDY2ibxSa zpjZ&9JbQ+4p3Rx?tXMf`@l#5=@@Y$3I<$jNB-;IOac-MShSn115gGVs@>w$T+LuRb z!JnIt+Au_{v-&XUr)^RzRvi1Ok?;|c@@Co&9PkKssX384iO8Y!5_?Jh^5JEZIF1nNmH_IN>$n8KlcVhsnGV|ohS3)D={u^Jf{^}v& zK1DsIMqulZCi`io)2ob!I!OTrs-z&n77`Tfg&Xbc_ zojSIW=?`H{54z)tbtrqI-V%$+MQ8#hv+7F_c zEsfq9$_o^X=ZBBTd>VMzfm6DJ`q{F;r6ylpw^9iZZv>j&;QLj{zyJm50el5l^idVH?G+jXx3r5hcUTpz)lExoA z$KgQ*ez4A+zzn?$%#rAaiUcYj)CxlrLb?slVpUPe_q}_p2wjp$fE8y7Yx6O`{W4{= zrF|_Z2b%Qh7e{XkwzGa6jC=!U_V_xJ+cb3L4Q}~g7-62n(%}oMcwZmC$v1x{H{djE z{C(nGc>y7fYPJRc6{QEeI%>j843sRXeo|}c?u(O+@ls9JnM!8A0@N=_a{&0dZ+}S{ zJWBSU(mkquGhfp=TV=Ym8?v!@DymBKSH~WTN{g%DhO8ok>X`e>ehm(-2#k-PDI621boI?8{5Sq>EXyexBf>Z6r*$%{+^ zQLmrOz~AUueSw>FQ1NMA?5}94qpze$p5F!%%Gd3IRUqJ~*J_$(obE}k7EeWmn+on~ zgkBO*gVC+FCh4GktTXCFxHqyYPb<}`uoFr`F#&Gnt^_Z+K3(zGp~zopr>g~J@L$h? z+#N6O?WV;&GL@;+<>0h`~20VHj#|vIJ^Bf`XvyW;i%7TmA zKEv-_0aMRDFIb())g8%skFcY~pQt@z2LTf1%n>s)8%f04a%g4KoR7;ld#+G#w=`C7 zZ&)nUaT;>U9Wz=wWMY!(E14v0==>$yg6h1?3LH08RrAr;8)!2B&h5H1=l#}GrO=sT zE5dOd-qd4P^OvBz7`-=y`ugs7Q#^=@Cm}xXjjWNtHb|CqN&hxlV$(B7E=GUcgMK7= z)H+fmda)x#fNECBlvs^v(Qg&h1UmqD?Y?8Xgi> zw7g;%LM9^Ccoi+#K^ERaE6~jD&$LRuk9o2IvAfSx+0f>L@0)1%{hIPKW(QJ!>*T$2 z9El4!(B5=iG&C`xBV}3UYlf}m`QJJ^4~(X=XX$z}QT;kxqVWCAm2lNA-+u(oukicb zYRqcjORJ7aDTE8Ud#xX_3zxPB(?&NvzMx*@PJaW55Ymg>Sp%MM{zrDFWc@LzC!^>@ zk1h@b(gTs5$i+M=Kd6+W%rKIIB#pbfM>pm<)|qNpgfhA8f9ET9wO{R*^;We*o#6+t z4Z;C^ne3I{Y`EyskaI}RRFGK<^7;PUhIOn-UW?~xlV5Q_5FLJTpL5)H-u(d*at*|p z$#r{Vi8_;8he4iw{H&siTXzD?{vKIIT@vtR3psWv&GvhAc!y5>f-?;5wWf@J60}n_sO1*;o26A zPa1qgCC8=`3;$&^O*0yb)nL4>EatF=5Gg;(v$pz{{H z7%7ilMi-D-mHcmF>|~&k4uWKoDUC_dLXfbEo&x5G;IR~*eA+c|w~tN$g$O)G0qq|h zkq{{-Cmw+}^Mrg4@B8;{cembJ-YyLHWZ|CsZ95?MW3Q^w$#gy+Dpmr0ZZfl4*OURx zNRTVK%RWG{-!Uq%M0^>(nadbK$^c6TAdkPSHS) z%U0Iy^kEcrWoX{0Rsok!>~x5il-E4kMtkVDu`9L;2I8NI3>tfPF9yh$2|*~^s%{a4 z#jM@@2`%hFn|x{83U*D!8lH#`w&mbs*E`sZLelwtwnF2s68 zC-C;8Nx2a~gZiiFM~4F|0Fl7&pg2IQ_(`tIg@grm&&h+{w*D2}*v;M>*^sE16|6U` zxZyBk00Kg#Mux-)EDhQ63_xkh?~)@kelc7f&#hQK+c8PEj8IG$$@g)#)v3I$Wg}a z3&+p?7RChDN?)uB$XJL`#8nz9;Z$II95^3iw@rY&BSmA#Qjv z?v{s-YXKF>wFt2J_uJhaoEm?#5pW1VvA@2Dbx!&wci}_^TF;cf5mSlR1WqW6p++Rs zML@&!6*T@AHUH`P1O*iDW4_1ZNjJqQf_2(XW>re-kWZNQ3++!5il)y|eY}%@UtQLn z(XYpiMs8yFxzMDmiq6uA*c{nNsM1H+>7#y>)@Y6_Qf|AN>g*3DGr?3hrtzsTzUd*!&82)Bq>RC#{n^uK>$$ZL%+$jc9o9Zx*xgsMd;CBbNa zoNs{@XHwfQCgC*$LkA3bV^jgNP=~q*x{E;8kYF>BOLtZr5-vU=k>j&aW3|!n8Aw=G z0lX^z;U?V;dVw)l(N+L%^n#2}Sw9-+!dEBacIBjjSz-)#_7NR)<^(RpOv$MfPq#;p zzN{OKIv5|=1MaQibVO92^YRhJj!@YqJplLou(6(++ncK(nP8)If_o|}N^0Bj_fM%s!?{W{V`tf^+s>5L+}ePZbY&4RNeyK!Z|Jgj23WvlZyF1NjOp;}fNvvsrPJV% zkvpo2qGHdndaLj3_woDBD6Sj>qfP8LKV57F7%kdd-m$6E71u+585BB%o4gj$q9cK1nVA^839;rg`bq0|YFS;wgU zbq-D^_2sg-cctxT{OsjAtas-JvJc?i1uaF)M=2nHGq7rbe$D2;m&n-hV{^y-kn)k- zdl-}=!qb2RAw4BI_{eFy52a8(->cRdud$zx`F|_$F#=LyH#UQvdtMI-7;ST{u@c@N=3*NoA9G^*^c{y^d3V?SJ8`k8)92!@9U?B}7iSChRem>K zZ{NNp9f^&e)oXMz69cBa_fEX=@$p6)?I1Jl^mraF3TrvLB)$%Q$|N7gKLXWDl~8ghpQoMOaPI>3Rm>;lgAft}2ZB9R^6(n+ z+g}yz1}&t5x-Vj#>?cobKs;Yf)7wuPY8(MB_!x)HM-qH?i$YTma;qf|-R0GaPO)cF zyv0>=#rl?uoOOW)WE>_9F})iA8Qmlfj=q8yq1o#0YUK_=r27VM@9TR4uxoSckpR%0 z9P=~vT`{&x)no#amp3~h+4BKkjD^tAcjYqhGvDK<4<11E?pc1SC`gs>X;>*S;{zB8 zI|Ll_>iba@aqOIP{^cme>iSKWw%ad%1jn(ZAFv0}7D&#^e}d}kGHCJnrJ~b1V*8`3 znF~gkc%+B*{4dRI5EJ_WV`W0PMsi8Gp_*(;&Wo$fYvp0XN*EXlu5uwzN|kdo8s19_ zV6?0JHbgcKw_-`zJoQmd6S`xdTszPh>j**b&%M7t6a9TB0Q^*9<{exv+Gn=6C*>H3 zt!WDun{p2dgl$iV`=Mm05+_P+A%+1XCI97lAZB8sX%@q-6(sqDJs*rq@a@h{Vt%JZtA5P|M6NQD`R3}l>v(@cKeW|XmXSq^9m`EO24<|3@xgI-P# znYGHZ7laQr#?0#my#ks$lH_8~{%p%jz;hXLrFMG?yB3bWgK%urG3P_%tm9I+?O_iF35&; z_UJ!A`GvSR%0pvjEI2gh%DRbE07B#yEsOep6>lnoEx&K`n?~uUSF; zu6n%ke>L$F&!hs8Q4kp|FG%pIuD%mm#7G^$<$XY<-<-r-()uYcuWK%VHhJMMe`7I? zEHb<>oCV|vE*tjQ(R#yY&r=?SfCtkUc{)gHQ)8`iF!nxIIVy^n{m0C(*%5D(B-O8s z;V!#zI!lk!VZm`AunX88K_7Z`0?t-o0luO6ds3@`zqJ5{{^dkS9DpR?;RzP1UGI&e zz`@%XEmh!IP9wtS%_}S zc7{3nZ8qqVXIj)wi3t;^T3S$@f?(Yleybc!M(v?e9Z3bs{)ny+4AJ+8CDGzh1agjG z>01r0{Ogr1&tc08v2I^7s#yRV_a1e9l<`4EE&3xKs@7Pl&D88@E9YB)!I*31l#Gav z$}Nj4jL(uCrkv?O1ae(-$EQZ0<&B7@5}jsmequfU^JUnKEVz7?-sg6Os7OMK?u1`e z3PfX&Q}XCEdppSILpo(EWgR+m2yJEiTl!RtB%5WVjU zQ`#>)F?ZW561UNLjH=ppM7Z~Ol5#s&lG^LbIT~SY1AwHf0VriRF!G>J}ezdDR~6xZs`V*?vU;-5fqSy0}7~wbayw>9ikxJ zAV?$K(*3`Wqw|}0=AHLj-&(U~;aW3t&hy;&-q*hNwXdC>W-Q`stzB+3h^J}vF_1JP z=Ccx+Y;LykFSPT2Ll~%85v_Z`QdmyN-L?2?kz>Fpt`CJJT3_N>RWO-VnmArEsuh>* z_$ScS)4%;F@H1F7`t>Ok$fjP#Q%26XLGjk&zzXRXK<_>25Fjfp&6crp1G1A*03yGw zcCo}e{Ep38yRHc8T0q_FKhw-t{p^64Uh&4->0`tBMxi5U8;ut05(Ep|aq-WypSO&i zW}|;54CdD@H$+$W? zD(d?emAQ#%X-j1fZgfMO`ds<==aaMPyss3)a5D$3sex#?<8q={7bV89-YNeZcI^Y( z@gnwNEDw&7Was2{)D!SMmjI~bC~z2HL+AZQ5eRfRrl4yYU|O!_!`v=0 zp0ub#sGVzh)&!B`d4@j)5)q(U$bkfEStCVJHh7Tb9vn^(2E5?QILFRLOE$S%1E|-V zpW>iFt9ZMlDZ#tC$zAlAS(G9JG=?2_9yPXn9iUV4LvBELx;<4Dk{75L9B=2U#9a*1 zj1lg!5rk3+k50MOwLfitwzXFPmsN|BqaUR3ZG#=_JB zn$Z%a(%B^lx|Q1!9v4yXHXdNcJ^jq-W0C|I&j$CeG zm?;`a;px-SqUK7v=i(LUAJW1;HK!Dk2E|E9bzMYj(N_^1uYRgq^L!o9x}9~a1VQM( z)SaTpl%PX~tUDOYNrLv^QF(#^60l-gix+A@#2`;Ek-WkQ!V~lFGHzpSF`8&}BXrs! zwr_BNyKb*Nql^>YO+{&KEK%bCE1~Ts_s(9S)izo59TEk*Qg|r>!C3qwhT(-fFvA}%5gSu0- z*iAlc7aQc1EXj_deTBWv${0L6cQ5pHBnS;_JgU{Lq1NDAcs zRK--#*oE&jf+TO9)$?S20h=;}9TE+1uCIo&*}No6I|Q~)TW9v5cmqDZqU$dC#{(erh&GEPSwdAmZ1Yt%l^n1@X4A*E3D|eZbN8; zoI7y*XpXz=CI$NMO=FgXO94NfNXd#s1EhL2nzTl5y=q13YKku24-L`B?U_wef+>wg za=S9fM5SUff13eK6)j*K(h*%jr;NK8pi@F#hqTP0AHt%m`utl5-k&|*=@%)N=<(HD zBt~BFT;wj*!2}wvb2-ZUgXG??_e$C2BDh{e)O0D|`EoE<2{7&waE*20JP}3L-fhq{ zaLXpQPtywjC<5smC_=n`_9niNSW^wvsPD(;rs-No)3B%fc$|A~ue5XIH^&MI zKqy*r_7;3r^iiAN?Z9np&iNBEJ=@y1no{!FMGh>IxyZ=Kne&VCM6Cat0;>tg8N?kq1Z|W9<0J$YrV#15BSvO1O^}7 z%?3ixy9ehHGrJMvMT^iN_&4W_E(57yJHT!Lxq=oY-m*5K;g;{2ZHu&YtF3m0N%yBW zd1{3kwe^}J|Ho_mZrXx4l49h$Pn{ZhIQZk1!3{W_1!X%Nzeu76z(Pz~WvyR?7y7pPL)?CR zXHS~D5~9qq&>X~>gYcz<4m&}3lBwu3(&9e83CGyI$r*yCo!Xo4rgQ?e1&9A#h-_AG{w+0 zAWz&CG`>(!=m1;>q?Lm=LYeW-#Gd0N%ISWITF2|TsU2%WnO<)puFXT_@vDR( z2d3OaZ{HMm)TtcW;DztiXR{@&M$WhjtI$27br*gIWEE3Ss6f7gsqRoAsI;R%l>~4Z zY2rOGgjG>7Y>usL!SXNoPBsM->})gU?O#wC zy(KRCh;lu5DTKW5c8{}>lpyfIn>SX2c{sAM^h;ckrgY)kGZiR3F-&diProU<&k3_N zimxlXFgE*jO23@ASur&rO?T&Z7Jcpk0if=W0* zIs5O`1DQCumu+p&`S(m+24%mz`=o!kl57QNQ6dP?c5<~_`(t`ure`M7TFNO^WM$@X z{h%O`!e`N2!}$V8l8`&MU0&QpigbqQRrqhkgV7SFFFjH8k#k5!-}P*{(KPm`tAdWn7D-w|dUJGwgug0< z!fmU8R5B1wDb;9ku}5V!-|P;`hRYJhp+iFU5D!*q%j{BbX)HH@=L*$3NF6{mAX z_I>AATtFSyM?Dq*7@a(NV{AwCT zbm2GI8u~!U#_aAq2bP4?c+(?$&lIkT0PRjOcDT*Bj#VLa#73gj3OABO$qyk_&1dyM zKq%CXoT@;tVX}gPj!MW3@JWI_(cL)mfPs^7OETeaszG{S214AZE$D}ts4-S5T%BRj z%4Yl`Re_;Qe^&*AtNVAD0hrG{_Qxd3Vo~0mEvv+zWDM%=5qMTO&GG zz*x~rFVRv_eV5)G)Nc;oMr1GH^WPtK`T_){;jTk~F_J3-%hvZx5R@*RJ zs)H;LAs$Tk(&pPVV*>Ad=}1gl(6>13O(6+Moq0 z9Vrs;1~>MMM|nN)cg|EZEw`zxf>Nr6rT=lEh!JPKZ@iqU5f`gYCiC?L?reYKAr^l# zElg!q>-qGQ`c(@nL$8k0VmW^p#}r3$yI?%fD}hDmM!bQ%?2<#4>Utw_%xxQFD}@*h z2LwIt_c&djN05qm3#I^YO54uaJ=oO_L5mCZ3w~?o{DbZOyT<^3WI(sx01pWWsg-Vs zirhN_)}8QFS}}xgbox`;b|m~{?3n@9!DZd3EiM&OG`SW1p#CD+b*`4OOkN+!ZAjP| zOh=FmC0=(m%u55xE2n$&+FzL9g1vXU)^53NjM9rETJZ4i_QkQcGb2Eo?z~2GimB!& zNi^^6g~t_+lgxekc6lvr8(($6b2I8QMg=*xM%F84cycHD&TjmX45^?1nN z2vb~bsybjPtG8R~joL^)2U!>T$}@0}7GdnpYOq2{ZUh;f`3vJ@IT2KIE0yn+t8~cZt3u6z$R2Cbl{?`{A#hNvVf z^n_Ce;)Kjax&dWxIVVZq70e_=FFdoaT#-W{Zkb4bWaDyKVX)O|(8-rQ#Bi$Y26WBO z@8@iKd55=unHslhapE`6L2i)nPix!%1lO+pnPoaHE$jJm_k+X_w;^$E?Hh-yrOz7F ztbq`Y&1r40rvUUB_3gtuk}aTR+@FFz7g<6oIN0R;<$pG#Kzk9*squ(rzGB44%*i6m zkz&*&=9Xkc4LZTr_I~rHpgmmmeFKYu{_g|vzE5B7&XNForx!i^OHc9E)1-41`YA^( z2oMvlhKy590!2gO(Fk9s=n0`oY;CLXezd&DpLhOzDu@$6fi}yB{BLf6wA!0}=$s!3#Ls{C4fFLvkqIlnaJZ=i~gEa{Jtn{WYmV znZY=kHrsuY0p*ggmJ7PqM!m|dy>!=1>UNh$wmx&9O>`6|^V%|kiz7Mr+Ld)-PHH7y z#yCg6=(GEAOG7(2KY)o}gXA^-7Md~w%Z&`@WzL--GNXZ=*12L4+((~2OMFu969X7V zr6;{jj{@7)FQCfj5*jt$N@yyDG;~p$dn3$s5HZdus=xn zV!mw*+)v8I4u$7VVHdt?`aL&VXAXyOzHCZNLhL8}V|&^+wr_x4jh_dW!W zRzRo5{^?^+o{&duF_~v?1)q^3Y!0%!gC@CT2ZY})RmfwUP$Y9?B2T5=!EEKKHx)sg z?BGB%MsW#X6=%Fm1kT;F*S86dHODqDHYZ9uVUlLL;Uu2bZqzHM0<(tRTWxg@&xH*S zEW_!*A&AHD)kcJgER^NHG(AqY2KEUmfcm0@co%9E-|6%;jDdip0J8*mrqI}=L~H(V zK{)po)K-b6QG<>S@chKUEYOs9LG^N@Z)@Ow@7)eNW5tk(Z7EW(?+mk9GWYiQrYga) zFXHexw!1^fcFVJa-*FMK1nfZGi;spM1{EhXzORvpL(?IQO}w*2zaf|-V3KGps@Lly zH>^3hlrVop5Cl5yy$-0Wr*w1_w&?n9$@@$T2fP<)>A6cFjE!%T`u}qW z`Azu*al(rO1(Lq|$uWOX?6;auBhp=|DbGg_AD}^4I_u54?zTfs#|i-Z=*dqpWPJhp z7O{9akyvva%*tX2BqSwZuB63QjvSsOO}+;V3old>1Vu*c=KV?R;(*d}a~a5HdL8!4bvaQXYo9*W4dT34%n9D+!Dn5r_MbfSS(sX?OdIB81{ z2WTM`2t#kQ01p3MnE&+$Yihuz>7W%fqas3YAz>W%VuIMn;Eno7GX)I7%UYo3+fPJzgmN0tlw1Q1*N3}IgC-3RxS{riHdaqe}m1+F5m961YJ>#{4!XK z&GNg2WY#Nc3dy8~k=^-LGEe@l$NNK-*P0A;@>4hz*b<0a@g#J9MmZ>(o8IL@V5Wiq z>}_HL20Epd1EC!Xi4@u(@J`_pndW_L{7o?awjQr{fsGc7ErV?wfi0SM+C8yFn|{f3efdo$b7R=2l@UO6}0#} zzl265B?W_t(laDc_C;9r#Xw*cbH9Zo?=M}5Uwkd>Aokt`ypu(&!M%Ymh+7mW92f0p z2elV%D312Wc5L4@#cnxC3!@py>k-ca&&$jl1(kaFc&GHtI~ePJLKOTVTw?7jN1Ng0 zfD@Vot~sOv0sJ^0(4km*l2|v`4SeCGlT>`t*3uxzG!A*sR8j;y1HFkdq2~@EK22Z{cM& z@*P57AbG0m#$(YV6nMFF2z$K8Ta$T)EzO(Mp!*&8z#SDxQ84nJ(!Oqz=nH);)_yYQ z69#NfCa@c{LP9T?bt*-HQmKs#v@=l3&AJvfRzQL@LdJkG<;H;br!#DBj5J5D?FC_F zsMc}GcQfA)b~Lrn4tM8B0lC!6d|MP`pMT0YIO`Ug6fvu0Y(|lo{bg_UEo3fIfC02PMS2Fsl2 z6`#$#9lkh*?qAAE5g3GUMv$sjD?ZrBWrn` zz~>TVEyj7C+Ofq0<#77Bmo6jZ|Q^2jd#mZ1^y|pz!?NBstLJS zL=4b%nCU0JtMO=>_R~oNSZ`6W#|aefCAdzs$ zRn^*GxsL)*)Q}9jrlR(2y0=7zQyrfdT7b_&Gw|?gOn}t?{VisNw6=y*?iYL>=$oBl zBoQzX9Z0d>q?)qrtWQe^I#yU$Sigr52o=T(H3jZ+ltt)MVHe!NfZ2oq@Usn}B>{pM zvkcu;ZqTBsd^R`xq%AQmT`rb|@S#~yA#nu`lYafEn-pA3FsE3165k8h>d)Ff*v%FN zi(*Oon5d~ge_1oGI_w{GxIEqOc?ca;iPNStgJlwIdPE4Pl`oK))y?Dr3xU_PDX#F@ zveA!#w9pYiJ0_h7%W9{6dGMn?;hQ50)h04qG)UBFtc z#YVl7T#rjPo||pbs&7cnirE>%XfH#LDdY{H~ut(ked;P7ujxC5qlkIal#jsA~J&KjZE1A5ghqK>|C} zSxg*2-VY87j|lR?xiSS*KjxP!T{E!I(-qLk`pe>gPCIamq*0jesCv0;0GOlBeXUe5 zH6KjG(eY#!q$G2#@yby%e+NOjTj4ZTYqL!PFjI>Jc%mCHNcSaz`dy~=6;NR1X%r{u zP9EZOIn2l_0x-uK3`4 z=KCwlJ%PZrP`w~3T^nW<^0mSk0lifJojVHFBJ?&vhI=zmmmmGG-uo+Z`1$TR;SnT* zMS0}*ygb@VoA=<)Pu6fMuQSTiwFo$InRReMq;x9QpKJDNE5c9=3BM#7nyUoke_%|} zM|&I z`>8nZ{}($B?25kXe@g> zo)a46$EsAiZ1ls%G^p5$D)%$VooGhKPAGz_I`~^^a=FO={!4-+exjTs@KnA7u_}1O z&%;ez{D23;6da$?OuciSaymSVmasHXyDoqX3%s8{fw@sV(@X?Q(9eeytF44avy!-4aVZvM)M;xo8g&pt^EQ3R|s=(b5!tGEC&blIVW?;z1Nh%4@_WU z?5`DX*bX}8d~UXR4_;B;`h$KDqiDUr-^Bs~P!tI-fFTeEz803$cYje-ud;cftbRHu zjQvb&t0#@(fQ?5M4j0|Klj3n96Gk77Z-FX68Ov7}CF z;$DnYID70%9C~b5eU*$GLc)M`&tdds>AT({1d!nzfL3Z3z?t(IT&MF={RVD)Carl5 zZZOrr>vdk)d0q%Cg}`0fJ$@j80COOlyVgq6DAtMNd6rUW*O$P>4jj;=oOLU$9OKoR zdBhOz!wj4D+fYbrr&xe?6x4nQhaVWj-BJA1MN0RBgi)pxB>rv>~`u$qgQNS=d_vhyJXxY6A*^g4>(6nd*p zr{QSRm&n6I5ue!cWn~w5VVaMDXh0H+aX92S*jvfEYso@sVgNuwSU5?}Q6}7bbO+MKwKB%Pt#Df6p)F ziYNaL#x;@o=w0B1+3ZQDUiUm;V6b&J=)~@;??>B-jM+ASS5YF!!;SIr#=iq5vK&;H z6Ga^daCG&9Lr0On&t`PX0PF!MrP=|EVQ&)O$Pt*6J;KO+YUr}RDB-mAb;toSkSZbq z0MU}hCC~}M^r@`26vY5b%DA2_$IeV;x2A*gP`DE|Hk1LZg<_-ksjYw%42eObXib9_ zTk7KFtXrp%nGTrgyt5EQyZVyiR37x3X=eoa;zn!=ZEa#4O->KU^u_Tkxi~0cuHWT`-=!T z%-;gtg8-nOt9$!A8L0K#e4hL{()-^tJPDjns>(qFJOEgt9pv+JgM(n-PROvzVA-=> zgCf1^JDmU*0T<0ixHP8@vC{ZcGGO~vZt;2A^GrF;FQ7Y`gR>Nje3=fMAJJ90FmC`) z1{xLb(ksGS;;j8i50Nl7M!N=WbGu;i>p%Z-r5${B>d?4CDK35jj9GQN2eI*V>2@;O zpMlA;wuCC*{_D$`ZvnBM)F)5mUr z#IO}hXgfv&_$A%zjdEE0gr+$H#8n?b*iosr(+<0R1};`6mu zWthMN%%Rt~(C4`>h48#**5wYnN*40K?|nX0sL84o8@z~Rfw^ZU0z8s7#)~(P@g=Bn zV-ZI{&k?qU6lRiBya{W_0fbdO!FK}2jDWa?XQj6nX4KYxezd8-T-S+=0r~#Hn->WK z#^JnTzzvS;V4?D9Z+a~$XwGVCrQ$Z^ge@T|(2Q5H;T34`3$k%QJwr{@>Y=%$hKZ_?-x+4TSH;K zt)o}tEwn+*=O<}wL|niUw`?xxTkYt0x*J8G=X0^0z9GB)_CMbjczus~p)~;*;$hxb zjiEoPfFE??OoP-Z(<8yg;F$CUAdYSYCBRJHSdsQfP-rSxqn49jqytj7Qxh zb8GlrX{o3PCy^ci3lm&m7!Xw1;QBR@IcO!!B$L|rCp631IgRl0F;>r(Y?i`_X9H)Mfwf+z`qfVt|X291ro`R zVhUiMiu{&r?dw2wk)+fypqX$1ij->hJOdU>NR<9t6X;R^mlf(*LCc6V~qpi4v|-i;p&fyC+sXg5Mc zfH+VT{DNRFMHS=;d(gM+;7^of$C99}+4QgB+?ILr_Zs>)rUR%lNDsXJ$2(J2W)#@y z@Hos?UtwKbme1DckmGH@tmED%d-N@sPpmyhL0Y>Bn1sy+^Gk(gh`lO#*J8Y{JEnF^ z_{}@kNH9Pa=yxp zqO#lSWnIJ&=I#T{b$IjwsFQ^WIKhAcAutn|s(!l3Py>u*fuGpt=(@Hk(K67RO;kMY zz0($qG+u<9g4}^&KPCG>au?);QyL;GonC=u2Sy+sRr^*U;RM`oLlXW zLf*b>-vsoV<4BG)i!OI`ac(hCpIa{x^i`RHlH9rvk_FtUbOc^z9PcmX;bgy)5<_TT z@k*h;XV8^IWT=qvioeQ6V%?6@?(cvU8(IlFv2bl*l77B2o*f!`=|q<+F8mr52yUc+ zSMEL-j!%;e=@Ge3TRI1V4tC3aV!P>D9GD?6V3opI4TWJVK46nV`=Hak(9Kxd7`z42 z>K-tQG6kg{@AL1dCC%qH>Uqj=AeKskLOkS0+m}J3ZCCKu#{rSy!uw|12^Pvkc#;j! zEVb_~1=7;mqj6pRC*Id*mZSLxH;zoaVSqIi_)2|)zt9*5H3GOTfa4OFXa)279Kh8bhqwME#w*v2(qugcjje+M_mAq9-%+=oT-OT&L*T>r>b zA4CC+)6z2UQ$f5=1@F7{qUDhtt1zH!7W6c0%Q!e5Vmi{Q@Tg zif_?wG6~6GLa>IWM{3!1@VmJcH3I@(AvQ+vaWsP^ilg~Y7-cOp|C@q3T6B(FeDAy! zYLK{o^rL6(pqtTpo2Gsfj1A0e5`0+$l?4=l*t&vB`xyvmXx`331E%W#^HD%)NICv2!N7zH{> z6Em>9bdP0O0~T6$aQ4}rfFogf#bZAm1lTa#%UBUG6aN*ceakKSHeTNC3?&fQ9k)?k7)hxQqlC z*YnqZpm%8m#C$NknI}XVKf=%7noVQsCo> zA3Rorw<;|9o?|4CCOjN@1SUA<*L$Ktah(Ya7S_fJW4}EH#qAo6Ll6r(r1C1)V5@f?a{RcwBq{6l)RRDxnDUc^J0}}i#aWHm$vr6cN%H zrQ}B;2dm*cKR>?mpaX6zXnwge+iJ+i^Wr$$jG-6d{Nww;;e26(8C;Y_0nxKBu9yS} zwf?&Hbx5GO^78(Zy64MxRK&q=3*w&``rd<}` zGmgG(9o)i%i%a0+a0ktm0Z+tUjQGb`mgts?9Rb0^L2+Kk#mB8zu?$bpIV^fb!5N1y zDMbHYbp?n+*o?3{5*Y|OP{d!S{c|5yXLpOFuCx2|J z{xYq4)TU~xpla%~Mse||SH4yFmMzG{8*X?Oag<@ybg#Eab__tqB+3{a9nHH(GTmZm zt5F=`ap8i&!aO!WjS=dOr&mUa7(qQae{iO5Xjob^>nfgobCLR>l1ZVQX_6ma2!4VS z8gLbnqNFq-#K-4;`i7R1nm3&sel={39uh#(`$imzCgEIr$@KmMaU+V1o=;uaqPO4> zfBlQB8R>d=qGgV|is{+4g4CgO@|Ns3a*iS+C;NUSF%ax7V0%PVytV}khhcqW1lua8(&{paRU2$?4U+=D%YC=F#%XK2 z=E$Q|^WNeq^weEOfclD-Lk-JiBTM9JiIm^%{P47HpW=!2i%9ZES4^i~Y6y|k6jgVV zQ2zX;;P>-uk?Ex^5QtpF+czIiVV0Epvnr*f`xE%~Q2yInBl8vQMSJC8H2HQ3h1nD{ z(GNQa4)*$5c!}$|D8(aN_K=Q9A3k1RUq?SVAs^oU%V)Q*(KRJ1PVCJ5 z(Dw2sEOq(3a+pEpCbE)>QSPQ|U_v}hxF9lD;a$6;N#pm95o!nunfzHui)Dq^wTA-9 z#GVIxzo^?^PZahAe9g2=qW9Uixd5gpQGY6Uj1NAPYUKa@*!?_@k2T4r5qc0I84VBg zFrdfysCZVVh3)Bv7G_q9Taz2Q>RG+L^6(hjO@v7|YEUyYPH-Hp0B6l#?owRNV>hTI z^dKZ?M6_K+rh!U`a(yO=czbQ?iO=b#A(z{R`p%Xso)w|VQyZIC>xI%4e zjP?IKH2-;;C>TZ4$jeibFrZolWP{k7j8REP)N*MHVCH|S*{fk|bE5DhhWR{nqOi@8 zA8lP+ric1Ue;C@IJeIA=I&;-2Vzc->dg1Q~=%#fk%u9ok}h(y|GCC{zR$fLXHBY$~LzDodC%<6dyH!sGE^N z{c@`U5yI~-RxA9+V|Ju+82R}6d`#%%Rgvq00?&Gf+reU9rVCxPsJKAdbJ^b!;Jpn*YtYD!OB=NKrx9+&g72<;d^hPSV2`GNp1; zEcvRc;Z(XU-cv&MNhK}I_#uQs{FwY1j}cAuT3-?Sfh{TdAqeciK!63Xe zcwwT8*#F~uOEW+nu$Xi)NL^$Zh!P~o*kND(fiv&nX0JR(s<3_&`0|N~a%tr3&!BNz z3?M#bUmROY$h^tfnaq3<`XJivutiP2J&oB*(sE7H4ulkOLCH;@4MsvX3z|m6<}Q6;-thBy}sjDsFCP zxnp`Sj>hU&OBzhl_+@`x2dFD{Em$P%^liH)km*RX<@B|;OFPE?pzOt1T*R>VYUq6Y zQ~a9&QA9pIy#EmyIB7-Gpce?x?{`5=aP3_fB#DoQ@IOs($HSv%WepP*e?9{tnR@yV z5z=dV>%wJM1B?PDcwmmKt4NS!x%c-?5Em8a-&rPSpT`=G zr!x24uvIY+wuum9UeR!% zDphPN(u>ssmwl5N70q1lnCwH*3z|U(OUVFar9{az@;duBackT}@EFU>%To{M%_o{xWj!kl|7N9ny+6Ft-uw^>74pd zA(OR99UymAzyO(M<8AyrW>!$q7sdheJ$+H++`pfC8a2Gd`A5*hc<@7+qiG@FzP(jf zK5vdc5-O+D9=wCw@Bi+faV0{=S5*9AF?SOMnf}>P>E;?ZN}2{Gkh#|^gj-F*TzL*?9>s#6Q(eij2L(8IBAS+CEQD`cNKRxsqvzS3IfQXL3SuVkWe z;7UVitP`@p78RkuL#4#;??=b%Cl;cdFye)zEDfEbJ3>hcf&FZ!q?$Su77(yC(x{D* zUqpZjU@KrFZ#>Wm_h)*A27IbRLFJ_C*BM6p_gllx3Ubg&Y!Ez7P+lvBrhfMD=XXch zVIt#k=k7-sNmquLfjiy3>Nk-}8YdYP%d4x5({q7A_%!SD*H=0fHqq1HYHS^>^SxQR z8Yu;J7jILErx{;)?B=^)xra=B5YKIxNq`{ix;&kI_HB!6a0m4@hFl={UZU`*m7Kjs zI?OCA<3P%EFU?lxcLX`cXB#2dsa*drG1)(A$U{Jq)y}@Olq)5!eLa`e1Ix@~js_)uD=1tMb+{7{-9)H*75ehQ@ z^THT)8tde&BM@Ms7|wF54(z7BHEdMLDi5la zG$Mqtt>RlplthZLVwqIdBb7FKDW#kWCN_N*)Gz}@29<#eJ^H)1U_ibmPb5x0E#2HU zE=Yq{5d7xw&xqec}X|$;^v$&rZXilHtNPf>EFS1f* z*hc1=%+y^}t~hPNNGgTs(I=|aS-3KoGF1`R(G*v#O6Rq)oGvj@iOfy=d7QR2oSCyF zhUOMFgWz%Wd+dgstH-{old(dC6(td^bJxc_`Yw~^#m!S7BboVO{}IMvPl^}ro(7EL z6@Osy5pzQSrGD+m-T@&tfSw5NMA7~X9RGMORPSKrp0@S*#6x&7WVKoDhQktZcOj($5f#YG5_NZF{&EA=59&@@8}>>=E$)YdW$#$WnQs$R zztBv20L#*8%3P<9BHq+m`p7STG zcy&6%W8mm-)beXnAVZjXA|^J+LYZ|dGitRA=~*YVtEwQ>^g@1xrW7(Xt@D`j>TGIw z@^K4kSz*-MsGgkZ0sRrkau3yrB&8W5E+Z*==X~c^*h_0IenZ~Uam@A+LW{D zeJZYBXBk#<>>f=4?l*p-LW`o@NOQWlbGLOaJu|a{OM}}qA3wOBYrLI{Pwuk+l6JPr9B6QYtCudcbRzlmhs6h;U;)mCQ75n#0J zJyH-eDlBH+cZa=es0((`T=tIb(IR;Uu#w7ezlnWD(q1F&Kw;~2)Lc4BToIlbw5~0XvV2f{)w?S33 zWg|yANc^U+TG~3R_9Kv9uTRe*RzYVs3g1$C=Ywi0-*CR+B~@>kadPE%^86LNb(Evw z&3tS3bR|-Kw|0z#haT1E$6VoPKTiWx>u!*GT-%|#o?cNrhh>MV$Ee@0dV`(LD2Mg( zxTXa|J3fBaVY_Og!)Q5bRLfTs;RNyDPYCK`1ptsn^XjnS*(u9xKBF@?o>_z#)F{5d zd@w34!v{sl+PM{Jxbi%~IIa-@gvb3C8aF9xbw1XP}hTMwB=Y;)!JpbYb-DwJASSf9No zKR#33ed5n6SIp{2d!Fb{c@wa-$hd_RC+9!U_uFB0kyYE^<)o zo2Ap;`}Yv?7)06ksD;v4sFjLFO92?}-%EX>z1CGR^lB6>U7I#6v}98`x+^Ue`RzS8$)8VeWfh zeH?3HNE4DsjzL0x);N4$E?WR!+R`pIAog2TSA2#zrBpYcX+X2vXFSN=&n@?u?cTJ* zu1ywxkW*ZnQGcq4A=sTHZKIhW^#`Vc?g2RMhxRC7s`oH}^lD9NLFp3?35#f2dV8!d z{O@r3&xa)a0Mx1sx-rp$gidcoBT&J%OI>QYSevU1i61Q58M|W>g)IZCK9;Trn0q(Q z{Las83Xm1zGvFwt7#JBD8FrhSeddIlF8T!urt8#Zutrx9_>WqO zn4IYuhRf2$mu2PDWNixcEMC?{MMT_k0JDofX@Iy7)n(Yibr$c@wrsf_fB}g9~Fn%o1)~uT~nb z`S%8nGI*5PiX+(vEi4#>Om%w0p~b3Q2g8&#a)zbvkuQkdnV1!t`uU_dnvc0cQh8PM z>*I)U{z%au$Oa#PLUQ6)A$glw72($f`&8zO#t0CO5ILjShT0uggUn$NqX%?U=>Po& zI>LbcPV9SRY^y3?x06#a1+-4;bL!76bX{v-SUl!X>ehH3iIOX~<#IK=uHKDCn`iWu z?Pzn(FyGp`xLMKGz~}+uT!SSzXa@?>JCl^r(biV;#@pjbfu>7pt@5Q9wY~+S*zrk?^@-1Wm89re^NRoR{YP80L{N`x?a~cP?PM z-Imm#0f-YNId^4MNwTs*LsbV-vV0}7Mk9C}i$%ZUH&?DU7|knO4V9m$n*b>g)#29Ejpp=W%wojnDK~T9z{E8i0_Vc_$mqyK#)cU|MUu(BZI{A=0$C52 zE#>tReg1meSoa4)1<*`e4>~P#{T=PV(#@ib?Xys>r=O3nTo7%Q|d^= z=MCAz2*aeiF%0-}xx4R=wH3Fwho4B%Dvjq8=x0^598%wm20Pp^xRv^>K~++4Y6M&ztHokU*Jm313y8{5$(veNxK(4$@XtiM|$EP>GZbl-! zuUiGTT6!!Fb_GZ zOJZqqf1aR&;i}8U?y~cpS>wa!PZ~OXin}7YRSNt&z>vrxhh+__L`1GxXn*`9uowLmwsRA7BUNR$0R9e zzPgZl-1ds7fPwL9*Q}*S-r{S8RPOk=jii1u&6#I+71NDbz?T94AnCKDED|L7Jn~v3 z(&N&K$xEzjO&NYV>zeijEWRy=y2_FDLm&O8Gy+*U1!^wU&(YDNB2!DJ8wGDtl9NfI zmD{0L7gd(uxVN<%Gz zW!X%z#Wx(H@N#h z&uk$2W5!;i1g1Z@1A$6Ime5}i=L0hg;(##~EbXlL*}ZnsYqsjdH2#)bP-J_={}mk) zKy=7cc|ne7qG)tg@9e%=HBtFJJ<#a~xQ`x3N7rvq+sN9!aVN&) zQw&{#NhH${kvsMeaKkzf7BOrwPI!)7r%krGR<0es+C87NyPlUx$a3mA-(u}NTMdaC(JYN2DUUl%H3W}JXSeWNCaHu)2um8x-VVGI| zA>x@D6Tdz;!twCZutAT7kN9aKf(bl7=>Nb-{<8oKNX@g#I)Iix82 zg>_dw&w9F9>4Lhyztd{C$%l2ff~cWZ0Yvh1z#+G+`K<3*$6dIpUqy##FdFDbeL%7n z=R<@{`F6_vduL8G%^6TS%~ebX(rn<}Q)T#~5fp*lz|6J#k|737IwJWc*S!MWnzHT_ z79)=W#Z!#iM{N(SoOg%BV(g!J7QAS1-da=Ho~r=PDbF(&b4i$=6Zi13VxJwH<0@lNZF-{({b zchK-Q8Ruqgb0=0$Zl8Zy7&Pbsq)D~3oSM6R$^Rqmz2kap-~aJjLpvpfG_`1n_Kugd z)7FyGUbJcVN-ELT-g{BBhc?<pYM1IFIo> z*16TSh{U9V2Z{*~W1_N(9}s3_X0{rXwJqAX0Xnnm+UiDF7PC{8S*Z;uvoyTjxVFHzh`nAr!(W=KO{>Or0> zmwp(8(MJ(j4hExyIL6Kp!2ln}_RaHXd9!yk|LkgivklRw@O@mDBPCErj^2@@Cow({ z+?2MUQ#M;xHk$cr@Y>*M;ae8o#yL{S#0BZqVUf`?L=_d=$*#8olSH&eA*p$#v3+A> zBR4;Ppj08wLBEN(KPt*nSMqM=74@9v!dI%R;>$N^%x=!0HiL&2TzL7fRN)XRDF)Nb z#wWeys}R7wAvtl=R?fZAU>n7%SMY3OW3|8Ez0!5`26*gA^Sr#P8tN^oS07gnYY(}L zWoSnVy;+!L1=*7|W>Ut!5%%gd$!*+Q3rgbro4GOXl*mS``TC@!|g1Vk!P@$0H>QY5TMQdm0E>C&iNNxDk?pT>=uttGqN~-$~ zPe$s6YwMrCY&z<&s8AJ1sutu$8a2>##c`o(cs353_s;Zg$*5T59-*pS-L;tMxIVKn zoqqmAMjx?Uo2u^cpr==FmO@_?=QAai%L%iG&^|j$e$oS772m9KF}7|}gM+H|Q8nvK zNDeSN&c0nqq5@&&dLL?}ARTK`!V8bc_K7qS?fHYok$@)iu5@P)AL?NaAa|z=@yGC! zmD^~q-FqCY=cddn7y0poUV*2bH+T0VXA+mF^rKY7)$s|BAB8gX8+X%f%=b0z5r0zn zN_5tf|CwGvP-N6x^LXRA!6!H0=FflK>8~o)U~#UFeYcjQq%v%qyxVbOu-6+y{Q*@@ zKIXw}*UiNy+sG|vnMYr#i4{k=4z0zFVi|fT4G#9V7&?{dEXGn+jNVYM8eMe}2^-9F z2$s^iQD$dh*`HIXonQe2HJsSmk0jw3UJ#v^X3(l&9qgC|7A2W`{d zSPh#t5b?#yD!i^Y34b&5@C=)rKTXl`6cxT#m(D1nkrK(6eGk1!p!D=3fdDPr4%wHEHcv`l9bM= zYMQ5FM7nzH%y*=Ebzb!PW~hA9&bbnERrI}@twD+k^W}k=qt_mtWl78)gAy84MEqgo z>Lh1iP?MW*Z9rcc6cZB@2S>!@53h?354(N+F1WB~jHba^oz4VAOWaa2;}6FO=li@G zv|IVL3zQPc3K%6NCBqf=S&6sTmA}qy)()PruyBZNn)IZr8W-N)>jDEfUNOSR=#=%A zO#+X5r7jw$>I4M|A@{3+S7vjW3d2v0?>pUmli4>n=jdx}9%Ov_a#%HyI(YlG=g~od zG>`K!adM@C-^t(Oi+>nZnkRAfYC?OphL%=NKmdM3RK(23`a7)RZkkf9t?$=vKb%}M zk52E=D|mTZM5w;-6$c41*Jf&kX?v5jLM#^%EuK965UY97Xg(lLrLPx;4LzpTPM;Ch zNmyNd*jJLb3ZgSEsQ}s@o)#4yrTwT?;Z`vM5R|-DOy|aJo{mB>)oYBFM4Tab=5ABB z^6y0u2*nsG+-#%nr9GEHR(sNYLDt+R^r5K-DO3NToDQG#WpU2xn~BO-Svu_HGJ=kX zhKHs+R8Hd=pD)^2$je{d?C?ddOE-*9J#MnK{x(G*+N$4{?Rmrx4OShLuuG_iE*>&03x6p?2YoC=iWZO|+J8gQ#2C z&s^C9m?b;ATfa@kvrXlSOg^93!`&y1<4N60f))=eNzDXm?gp>sxrrrtT1eT%-oX=i zH8_wvCU2LWr<(BQ@%F5R7CE^cl^FZ&%su0U+Y%1sEr*?&f!&$~GjcwOs{L#n3NoMJND zW76mweciXKXg<90Yx@QVN(bEKx})W<8AtV^<6F!P4&^Bm_|~NZX&n6|W@h(k3MBs{ zru54{(Hda4n2{gFVF-DGk$2^BZ{C?_$<$qp<(=2#6=0rq(vct#{}9t=@71^h`OiW}Z5jcV^426;DK;8n3QaC?N@p z^3nsP&GUDnyGig~5sUd%c;@EieMLtHp!^)xmklDQg_)%k0#|3}c(-1k-6+V{NU9Vf z2fZaXYo)d8%EN|XfPT3Ur|*S_KOgm_kMh&7)v$Hh&gLDlBv#N}!c@5{F8xDu{kPjz z2MrnsO!#a0>w`Nbnv=(U?!Cjh`);#+ql4$}loOd5mt)K*87^ORFwrf0J+jnjBSo|D zUDI%lPvI6UveQ>j1|H*ZTw0L{F?dTelNQ)};(j{jUbxFb)TMIk)-ozq#miSdcc;wq zIOcLb+qxb|C918MHRJOw*q+RQb)5;q&}V*_@7`$3AGbq-3O9O&z;mmS_JW2*CchgL z;RWAOJQWJ~<7^$R0UQ3N+DWnko;qr3IvZMoT3$rfu8j*rugovLUY zg-SSBq-IBTSRPR4-ErNtSSq#76?2dd&&}m2%U5Jzmm9@6q=`fOE(pt8ygMYRAg$3a zujySql19d;*d{2XRQK#n(NG5?PTTaFCr=+$5VdG73g^)5a%X~2;jMz!ASz|gq|0fH z3ZHKCv=*uz!6htq#JDi|Nuj*X2Z!D@GhkomA0@#`&lzL;5XeT_->!DEjW6*zEmtKzeej!I4Xapni(A&WAh znR<*Jg4bfXWLi6R(%TyS(lhR7i0>)Rx=X|=F(*t%4!llq0mMFTb&dCfH-W=v^(&`q zlO@19roMg4#vC*aT?O{_)9v~i6EUWVJ&mH2xl5bL=;|8YgX6Gk4O1EgrAR8 z3T+gzZCiFN@mlN`cSR8-#EM8C%V?!6XcU*~Ao-%b+utbyWL z5^MbY{e&Rfli7PcIEA-iJy1gZbaO{anu0nes2ji!0N|A(y2Y zS&22~UQ-=A$~vPEr?6)upf*@mUfate(5o*s$PYj0KAfNOcyxsbDZ0-uOVM3Xb>9{1C4 zlHS2bg5CG{gGTF~u;I;^2wJ*6kI+l#NPg8%L3zd3*wL%56>_&eEg5D2I(`554DS2M( zJug!cw#xJYYfQAJ!mr>>uK5^st=j74d$+kouPzxGnO&9*n2(8>jgQKDxGP1np9}B^ zpaqA;N6(#kUFvG7Mf9)DXE=|j~(O*@}fGHqeG*Yd^1J~&qC&XB01V{T5qhPrV^ z5X2C2t6jgkYF|yLye&d$u0=V%W}a=FD|JG_+|1%SO4Tt| z|Ki>BJ%My7?u>E!jFl|8J`*`d$KFzo-nGlpIAS5XuIXACy~!4*b$aDab3R@g(bCx4 zjdkDs9P9pRXm%jYZ|@e%h$lmF+3{(FEyL95G#Uv_L`~YGQ^F3DnH!__)utE%UE40= zBhlGNhy6&@f5{I>XC?4))eMzDwV$EKK1pJWhK@#N8@cMNdd1RGva$|Sp$wEdSF+Gz zZ>KL1O(lGo!(3urdT^U5<+3IVL?|y+T|HsNw-D*@>O+_?1FBz8Ft?>MQkYFnEJ`l2 z=w7Q;3d7N)m*teyhI%~{{#UZs`0cOuS=*lv$@KVCv4q|Ec56o=vFtntN97GN8imIp zd%6ni$Mb!azVZ*IHBE-TS|u~nn|5L=sTmX3dM@b*{->-dM@BX@(2Wi<4 zi=2z5s6=zQXXhdev;s_QQkbqfGpWn&Dm79Ry;(?FG>**3twYTdy(JgFJ?5M8_@($B z&oh0kB)oHOi{;ETVf;-zZq<7(1`UL}C@A?Va-W*(s@C!JU-qt0oHUG!KiPx3**C~T ze#wkExqEA*L*bFx>uceAyFC5&{w^1=se>v;b93{;2dCEx&c~*YJ5|-N&s2$#)yu?p zI2dL|JX;D`>)GE`}}Z?p50<(=c6d*&*>g~aT>!5tS!yma)N@} z6BX05ueiHj70>iRbT&pn;2YCDPmy43AT;sz#-oOi%q18q(FeI8)V6pRmPlDX_v~|-x1S-!KG{u=F?GHqnD6F5t8v@NK28AoQn`~k15Re+KFwH2k27G?kNi+kgf9irD5X0Wr?FZen-%`JlNS2ht7Ws|i% zjL-oNb(sAe$De&55;nwqFlNfeM877>&dcj-f^3qE>BPQB{;?3(1?>)ilMO8`c^OG8 zwnnPnH|d?QRaOq~W1v(Y8#&8?cgRO5vm)f8&K!QJjYx@9E~kBPC8M!)Yta2Fdbd!M zbBzb$*7L8rv~otI%iI-BUz|}n6#j0Ag`6tF*I7Qg@p-V-utAxnX)w*OxW1R&&gNjY zOgPWZdS8Eqy(u%d56d(z;*ej(rt~{*XK(-Yz}=SycQY>#q~O1SG-+r<(`Pk${P=M| zsctyl#G=$zcuDYGl}N+H5%fV&Gy`Qd5j-?2Bd5^5xAjCV{za2_BGG^$Z)HvlWr}48 zTvm;`IQ5(q-6*SV8Gfe4O-wsbHaGj_(7iQ}MPxO+!xY~{3#qi)DW z4BSp<(95}1$uq{%VI$Yao)ZU`*@c5iQZ7O9v7Hd_^_PSRytndA;_U)lHWoRu`f_ac zsJm$_>jl3_nB7_l2)!&qSGUV7>=!Lo>z6z>g`sK28OD;&{QA(XGnU6(B`?YlMxkjx z(LbMet?9>RCFoWVTmngpr9Z(0ki;h3rY$Wt)<1hxbc@&xqRnPn)EghoNBVmI!oZ`~ z-#xhHCbsapRDt%9-s8a}cMbKtD|!0UiU|`dX6b`@7~Vv9PX~BN#W7598~vPSNVC+I zBJkZ*#Qh!`$|x2%oMMu6U2w9FdJpD+GlNua(>)f8Iy@G$cgg2x$I|>fSyAPC2mNVD zzpu)SUEiA&`gFNSM-y(n$JQETo^sd41MVQr64g6WNR((<+tM8F9^`{#vLmNGCq)$?jkdlc5eYY%{4_VRxfDUl!yU6p5L>j zxwetDF=UnGHui2(FRplm^Me-OM(O)Q6zX!rb2eu7gZaZ(m692porMh6%@m>ql*6+W z)z1Uaq^fG@Y@Yo+-x&h~%H5P;c14_MpZMPA%U2zGBzFz9Pgo$G4`pR#Pb!_x+Rw+l zNCx>10&KGXhXk5-+}qW9>gpO6ZBrfE71!@ZvTLV9M|4M7_i7X8YRb8_&zM9$l-EsK zPBHpOJWf9+vncU|{umAJLEQExr6e3ok`C%Vu2Vf>_Ix5Q;J$bqa`v^0;66*{qPT>Wy-z>Nc@-m@Te0z6xcTeL@?GnwW)C?{k z+p}D7+Owpr-Q}Lfr|Db%f?mQ7<|aG#W%^uIBfVh4?x=|cp_{c>nRilLQk8CDMrLbd zV*aanD`UsmbPqu0-g+IF9jvWwN98d$*L?%CLPRk7G8Ot@m;#E=ikUkak0`Kgz=tyW zeU!*1S;BXj-TghsJz&8QkLUTPZ6)eIVa9NU5j-U>em3KiA9I^sS@i;A~41?chM* z33aD;UcK{9kSlfd?)!@9u4z?BEoBX+R=uhoVK+C+GdkBlq*oBY=tzt*$fS$T!MXXy z3Q_9>cke5?pT&?ap&I@qMWo-EHyl z@tx)qzqwrfu7XN2E1ok-MMX8@x>)R}&zX3|y{32IbU;Q!YkNBs$0g$9<9`wUuI*Ow zt=^O>VB!#4QRw%iN>;w}CWsZu%t-P5k&)d(pfLTz!0Jv%j~7YdCY@rFp~by;t!{E9JGW2;=hM>Q*l3kwcCi{?+aAq^74Ah{ zBn{8?(|pg|ixJiq$NUXD;10B$c3hC?P3%7eG#plx zy$u5*QG5!?^d5_l;=fX)p%$=jEB_bFAu&P#KH?5jI&!ph2H1}zG{?U}Lb&DqqjTds zi+%B!I1cCCt9|8K&CgHk$&iQX*;K5@K_1KJl7bn6>G(ABzO1%qa=hR8>@SRaC!ZL% zQIM09^SaA2?x2+WB{#RxXx~30t zr~91E4tHoa>9aq5TKjELR_mn)-PlpOsWN?;IZvJ_5&JRV9WnpL&U9K>H)_8+eO=EI zCmOn;p%DqQ6LM|#PCOaMyKtBCo7Wc>W|Wd~85WML-Yf-_BgKUm^#=dLoxt7Xl3N~q zN|teL``a)3)1t4^dOqsU)0oK+-&L;RAM5_$=*U{gPVQq~AND@97$Qa5QF3xsP7(HC zy9zJxbVT#YVd4-4&|>{CHj?jRK$o@NH#cjkS3k;eR$L4gS(PT}`m}e*lJymrN&B(K zT1A=t(-YV~?sLd%q47V0v9mNbkK5rl(ADyDoE3T@tzVu9FLvV&M!LC!V^4-M! z4|Wyr9fZQk9_D|uy$);WL(2m2p)`xWio%5MSm@Gcdz^>dg6@ll?!#xe-_9HDLxJey zHmLXdUyA{Nu^AuNwUV=~zka)$`2YwS(h;{|TyRCufJZ*WpsFKtPbgvdtiIPsnv~^$ zmZ|yt^Lwn6LOkXi=2YK!@hSF=ss+ALXfH({*WS{iEGa1&M?&dG2~|Y-&~U6|CjQy6 zAIx|dxm;#9PCf*=IFk{@tkH)zOax@SsyY0fvG;G`uV@P$1;Vuxxk_Y+V(}u~vS~b6 z4FHzY*PXYsyNgwo4U@`=#=Q3?iRF#C417ywX0|U6=Fjpu7czInqz&0mWlMD>CV$se zfX$OJ%XdS^lMA0r$2dMihpij-dqgOr7cXAK3fh~*b+zFA_%@v_Rs%Mr{Oj>BIZl~) zU$SyC3?jT|<;CCh;y(s#pp`X9f)er+8ido)$#pOsYoiAWJKs>>k}i0bdhJzz&VA#S z0srQURG*}^t&3)ivs8s$HwQj)cXq!LwC6EzJz_llzWIaQf&1UYjl>0ftJhD?Lo=0| zrDfBJu8Py~_KFv`5BX9e?O+kR`{eX{#(g$DhOj9#$E7TUx~i3;PPkpBkF$^bApNft z{Z3_cIg;+aDJP8yZ;)ufN6NWVQ!m`w{W3kg)6QM_W!WI%-AeZTbRikzFk*-mEZUfv zTI4zz8#N1?JP^7ZpWULGW$_yF32!Bd;mx58zc1t%`r7VlRON?AoeS3;W?#uj1yS8Q z6^X|?{~CaI3U>dG&Vt8(SP0L{B+4c3;0e2Zox2vi#2lXPfByI%$hIWM$L)n0_&K6~JkD7CpPW^&M^|H0H z5_9#cUCu_J-{61a+|yXl(=QA9X8Fx;1hD0ILl^pKf1PLv6ilE!>7l2%AO2opvq4Jc zpEl7D41M!kbpCHjVH{hdKs%#M&t3fm6i(-gx*Fx>M>fu=Il=Jy&4s)~GUn{A=1@u{ zwe-Yl*SzE>N??LOb_d=~)SYiMZQ*!wV^k=Rk~de&2ii9%nZo0S(wr7|cudy#5i>$S=LAN=u8EZdC_&pfW1Q2ItqV$xG=Y<=5~bL(Hi zFI#NZxaa2PDChR&GAAo^ox|=$RqIp7h0`pz*qz8(pYGH zrUlJDT^^{(AOG=G$VZHE3?k-k#%!Q^i3jJbl2kA29swW#8|x8^W={j;X&F zFDIweK`EEx+~YFei!;3$_lcY)HO&UpD>Y zhBA;1vA(eVZ4DChxDP0KWdYM7(CWTbyK_|(A_z}axgz${tr`d*sY&^p%y{7rM4b)DXAb;XcnE;GO2R@Q8T0$+B=n&TFZ5&6EutxSwi=))x}ny-FM80~ zhG_l88Ix2jFK!fg97}j=b+dV82GzK12uq##n#<^DI*3a*4wG-2OtpEeuV8Pe?1K z3mrajo!60gJq#~#=MXvJ_brBiyekwT!SNqbr?evh~@1u#gsnb_te$vgJDg?C<){ zn}AcGvuLf*435A*lW*`}G;<4bw?7j}?EFnks8zj!f$}4U5|_9O18&fJ8S+T>+;ulD zKK=1f$Tvk*yZ3b|qyxT?OkG_-IB_WF|H9<-`%IvLEU@%)fh|!q3AHFYJBz zWncCdAL>r=y)T-qG1?d4GQJ!52cqqt)(;-#J^K5uhZ&)58vjQaRD|msB<8+t2K{}l zD-WLeX=?{v@semKmV}b>5G13aeBEeOdj5C-~3$(g9BB;$U3f zPp19$!X}1gxJeeR4^Ma0tV3hHL4YZPr`Mky+-DiHBG7YuWG~zCU_0$9O1OXC&OIcE zvoaV>{Hw5~+r>u4Y9KR+=ugbNt*tG!enYVr*n8l|d!9c=P6zt8`#pLKC26ZswNzza znN-KID8tN4X2|!K@m~jpCI?ca3r&GbNG0%OsICDC-;Fv?CvXUm`TZpO z0s{#rAOpl;LfzQWjW4>S2B7mr!Jl@>&j){D;~z~1ep`vZH5v}c96;R;iV8PKt&Taz zRC*#s=*L}@HbVpu1j_M-7!Y*R-EDS5PyV*l9g*C9SB^x(bAz6k@n2Seyl6B!9k zIcrh1UyQ5b`FmLa+%;E59PcDD+|3}%klz{a7Xtqi(SQ6*;yo67Tfj)m@QOUBJ<=#u z2Cq66&~D{qzh0T2i~cVz`Tfumft5dM*)u`fu`QT8XKN%L?#I;sx8)#|3{isbAGQ!Q zhbuA+`XYtH35(!(~hZ${6W7x?K7T%?xtF#_(Ux&nL!xua81O4#?1}J1;p3Xjj)16-l6g9l`>y*x z?VQ9CW1P8i)l=vBaDei+GMD|WG2W4YL9`AqG9cvfm|Yu3C78A0Xm6T*OI8u9X6wb7 z*^DSXe65B1XKJ#GI)&I2D`ghX;qfqTZujlm~Ye{=P&*JffT)>}qxsz2r76jF{6G^h{o5D`=xYTyJR*e*u;FO0rTjaq zL-R21Q8O+BKM3iHM#^SJk|2VF_cy-$eG_yR@I>mRj=R4-gMNa6jO+o|w$?}F1~{|Y z)h>>&*KGEghmOP=&D|-0f~Kg%&d_D2M=x};mIm!RSvDE*FJh)!7O46dYtrU7nk7?X zudb~*zHbf)Xj%^%e#fI4NKaWsA3{f=^SM=~cUng@CSSaobT6+JC^=GQjABBYYS4`rbh7&p-AGO(;PtWXb(n~Hg! zz@HTUc`trkFo`Bu)yHGE@_z?sc_^CO+Ef9Bl8%M}aI-KC28(!qHU2W+gRarsri$_d zipoiFFYBoP?7hLwMMN#H1*gw%%kVjJ8%7g2LL`)rt=ORPAT(4Yl-xf;I%Xu+33y>G zy(RQT2yYuOQvN@IG2cE_w`aH{QkR+CS?hk-m0iCeTT|(*6H_V%#dBZm^GeF0{^Sv6 zJfHGkle^x3$%!9*N;Xwr>PTQUdh|J`rV{DStD@*8nUv6lo{Qa{QcxGnV!x?er?~|7CL_b&pt*Qw#QB~J`!*RP6b!e}vf zmlnlN!RdIL_n}e)dyF)vf4(vn{a61{=tW;2W}52K2=@LMA;ZcMBBtb&loTvcy+0k@ zw=JPZ;QZcSGDiIe83GmcpZk-h+) zEW2ZI61E(R`)Ks{)7huUJ_~ViA0Q%H#Q%@a6$RD7kQot}Wu~NHvwNd{Kbmih^*4VMQy>S?CM$gTw=X7V zkZwV@OcXN624E*y;sr2r5Bbr0+?G30IT`x%7`RD+bwHfyh7p?h!HfenJ9P;O6pEZZ z47Jb1e}8L#i?HHX_^`{8!mv)%Z`9A`!vKMM2zIG6WKav{PYR6L?C0Zcg88A}H_65b zr{+X)6@^-Ol)?S?LjIGC@Qr;Q6O{OEYrn0BBN1T@=l7vulj$xfFnYAVh)_XOd&&{) ze|Y0B8{jzs8|d&ICX@N?eZT%vwib}q!ql9X=T)b+5ZRv>0cUp~?orB%GohG&rdsy| z$e{5aDOwIe#aw;|n5grjtMPz#O1h zWTY0a(9UpdBsryprD#InAAbXmBUus=H>pug_5VTwe1s<<$S516jzX!k8}djK5%m{o z1gZUY?Ek@`N*i$J)V>}T`gw!@gK6O$isB`hP?*4Td_zW&!F>nRn1O)j7<7I)qJQ{n zw=}$&=dg6upBbk+0MB8jm+1kmcnu>Qaet8@tffm^P~~6GuODckv?2HLUkKK2htLAL zw#x-!7Bzx07HMmm`HL0##h6fz|K8!RhiJwKtVD^IKKgS{Xbp*Xw0m1p(3SbhxjyJL z?E~{`OT1&cDo^juUE9NdV^ySZ&I{r$esX839R`S+x%u(YpQqx^xWNP)y9sxu>zQC@c1nuiDc2wiIwb-VFZc}aJb4qS z05zNgxn~en@m@b?>`Bk16Y5Py+MiGH@)WNUy<7h&>3+WT7ZP>IfY`C`{iOTzXUUa_ z(%9YT>+b&29yj>_gzufg>Fk3TCHe=m?+U6l>e)VkwK|ey8=2M3cf-7@*=Tt-+6-S` zjhX}THTx_7`MzK7d9on#YQ^D1xu0yT#*YSj&TleUTrB2dl9+n~8exv5|)JHBNBF79) z$ml|KC5kqB9l&e=lTd?VHVOJm+w@2tWwI9A{+RaU`C&O9;FG(EJNadjb`KW`O~ET@ z8B4vyzNXaA&h{%_p)TMa?aPfbclJrxKGhw z%z2t)xT{Nik1A5nWoEgBC5f>>913#{5*!C|`ldeiWnDhTYoTV>4s+ybh@tx9wZsHUcBKOPyhEW@Ub3%*=Jk1*w9~uDdqjY+0 z;HNwJ&1{3gAMx>JI%PM;VdeP(#FX(c$7>wm75QNe?GuzWFbHfMW*r6>b|}X3oJRQ5 z08r1CEn$a`B%pf2|Ehw~rJ{oZt9-cyDd=i`yZ6n@FssiOD!+M$Ro{B-So2H)ez4ZLYnn7Rbq5?xv=(;8fhF!O z%E8u6Z%@UTp41!B8B#TJ9s~Hb!Rd{46c?3%jehy=_FTB9ebP0%7ACeEq>D-Mey%I< z1jXYsuAZTi6nKxw1_h^QAZsvtU8{1UC4fhNbaTvg={@;W9j`1GU%uc=KIhf(vD(`2y?#-tOUdA5AvHt-_i4^eLkFNt&MKsVqt_l~bI)q1QRP~|4I z*(y?>2!o`D(lUQ4EUK3q+-_UTAKw-ugC@@R;zs&YhQ#$e8f#n*C+72ici| zb%AqeQ{UU-Zjj<=u={yB_!FBOA50tTuJzn|QinnC@OfiV3nXhr63}i|!z@dvB4Gfz zyK(rPdyK1U4hSz%SJeL`deE{bA6)bNS~5HRw>e;zfHk0L7`P1Hzf`zXT_7&?fm5lM zFFJql{)D?>NN@hM6h=!q2mr%}N0E4+EWD(--79y7oJvKJCm8n&bonHJD3K={=PMOC z4srx1!>G61PDULPU+g5fR%9{Mt=QL1d_Ft}M}#8AyF8PmJ?J=h=KNFKAec8Z{IOgF9ZlOu zl3FHv{%x`7%5yTd&J>kv8G3u*Juom3Vys1<&nb;&dyP5&K_!%rhrMdPFjNqO`$)r= zs>RB@9?gLUkGhKu)yEFps;FDPOG2~4hw;UAv4X`sNSbykV`68iHu!*F4g7XC zNC2>XZI%|u%KNx)F8Varr5E)(Brners^2+Cg#XC2;9unD zvc8P~EFY7(_m@ z4F=&pkSDZ#)!!Xrd}Onc`{M-yjw2+bN69{3KS;;s2{Xn6h^qw&iHtC$%G)XeuqQln zuOGQjuAxbPc!J+ICxz4Z;Keudw&!Aw5|l@sW4~GPA(C`Wa4I_Oy;I7p#53BKfliNc zw+NppTfb-)#E&}F=3W8pD%=2T66_nBzWs@4@Z4V8L3Ocao@#^%^Kb1Z~nSFf)W~BIb@V#N*{CfIOoA&EN{tHzOGb&2X%u_8MJ}9fYi6z`# zTF);lb=7QFOYXYsSlsjk@u}?k$%HT4%gf*(O81k?w3x!iU-I&SOJ({CR#O>(!}JidvES|rmwG^9U*mRYmN@0FAIaWR z+;-4 zx>+4zA*ea>_{c{yMkl1OXz$+#uA;oxO{x=?Ax3=e0fP&N3BDOIs*%QZo)k22q>+e? zC;(k2djyZypKYPD^8j_-2xGF3!@RB8>{v-EkP31V(Qmu6@28;Kr_{dq-)SF-HX*TO zh?UZOKQ|~J${%I7FOr-qMr9lm**~b9qS2m6y~7trF1Z9L=JZu zded=>9$z8tDQb!)BR3GZLKUH@vE%V>7iXu~;Go#NGT|AuQaXszQ>kZ;)3nqGLjFnG zhU^meuHJmnnQ0hOCUp$bMd}?JOFBipEEDQT&KflM*noJJTq3unYxSJC$3n@`#}lDg z3XRp%_b`bC=!U09SSoynZh>)bz;lbxV5Me~CYD(Kz({xi_Mo_H(B$Mh%CuIzXU=a= zW-Hw}?PJNF@AUkwbJz1Hhy#-P)pV(AesA3|RP>akS@QKdz?3LRmQ)w8>@nSyQgAV; zn2-8wsM$*6SUN$zWB-R$&Y@DKPP8bDYiRP`ytP=bCNZJ+Jn@}7IRm474qaHjN`uk3 zcBj(I>IIm+?O(q9CA{V>55A@_xZB#;;M+aquDb4|32I#j`@Tg|y05RrwewA9{>_=p zMo_a{v!_(K`^L88Nw1IL?4NDvd@i{OInBR5wPycRg0aKa+(0OGpjcW&jM(<if>$ue&a>;MUw972Fx5TE$!1G439rEAFtJGqvw(NSYVvV>9CWz~SB^@AB#=M0 zb5lJ*N#fIRk}rgg-L!*3Qy(2RIUNlqgr8}mGqXjbJzs-PkhS!CULO7H^l?sBSo)Xg z^^C=%@ClE8-QJMXyOjLEU$A;=#?TOj<%wFCC%^9m({^DZFP;9@DT?_wR(!V#%NaU5 z4_-HJ=QlSbIBD4~oFP`$O%dJ#>FD7OP0zR<@?5gvuvK`0UU>)hFF~|q0QO7b=Nq>A z%lb98eA`<~z^R$k=kgg|Pwf`Z=H^i>?4S5ZpbzNWv*!2la2ZZyR$fQn!y|RmUGeApusBV` zi)pj;VXVP1Ff{8`$xGKaIa!IZgfVk06qEc8)Y=nNT()1JL$7?M?~pHVy}k-7m-O}Z zdxl^k2FYt=TmW0_R!|f8rzBvS3GaYk_5T0}&dSgMrVz*myMRvqbl)yfOC-@#EU&rY` zd?}DpeP!f96b$W-7G{eLz9x5n`SS^k8}g{R{Hhy6YjpC=eXdl{x7z;W+uA+(CZiW0 zsG4rGx|`6Wb}yZ2vW`8zM9uoa(v(F9>MIL3n<=lca@9X78PHZHe;`nP zBRecK=sJ7OsVCr4L{M{j8xfL6AQoD4CvTVgIX1gsL2_=MCmOn0$I2$&4QCye&S(w_ z+$4H%fGBW&L($W}y@LPxDOU3K;Og*vMlfiyj;I}&&>VhoFt+?muE?XOFDZ@vf^ZXe zZc|;YbifN1+cxVlq_jAgtonTWL0y1xU?HznrtHU%L!F%?S#hA0^8( zAtG9jk$SZaaIECX;c_9&p@Du6x=C1B`IjD z563Vj1R&oTEZz@OXo1*S?1;powI|66dMM24y96;EpJ}xw`%dnuOt-~eZjJFMJo!a* zbEJr_&o#&1D32;cf##_rA6HR`x)|{T{12@1>A`QopKkyG9sT9r*F$%Fv5v1mip^&F zeEn^u1(GJS3rJ5L1+jWYSs#3u#;SD$b|tmAx{jBl~M;vtN5Ji{*!1*!U~g zZ@J9wy!x@lw}4G>m}$)0FZh!(T!7(2;Z8c%CF%~~1GmHuu;eDI;pg%wogSY~@(hYqL7(E=HVU>TOPC1UgkA+$Bb3vsQKU3_1#iA}Tg8BT4xwQRU0KqX!Hf-{o+lPYEMyi!jD5lsN z&I5Swzgz1mVaNHpoUQuS5eQh+uTq)( z9b1Exw0!2atS!h&3N@o+=ZvJ2y(NUWrqW+juswS6&C6zWOnBx2l?N0?Y~pi|itv5* zDuiWu-w(^5I0iK=pD+%%<%qR-1vy)Q;~2CnrLk^hqy-oTpTp8v^#oT11)u_D=~vH2 zk_(^iOU{_bDcrj?H^6ax1~6nLC7JXQs$hW$|7;;yp#b;%4E&C3kXV~O1OUh}u9^3E z+l}SVMU#?UFgAO9#~1>RQ<6NLCe1IJ1}`XzkalehMwaTVh@S3pGjDVw?IUvw_8KyR zC|caivTy8x>~>WDT@mJ5#QxEB>{o9&#+8=A#{MBer}QdEJAESAQp&9nTd8v|>@p7# z5p9f~MXc|1h@GV9X0RiG{yTvP!;8XSvAz5G3{4Q#tB^*7jOa>S)%llgAoxC z(Bo=3cw(%dJRt_>3*|J7=6<#q;|^oxAOIQxT}tGs1vH6(@ULfHe^IDjV4uji-UuCz zudE)yb#5V{ZGx=&6V16vfg--XaW^VY&jWk4q^Rj8+ewby1}F;!W_8#UwU7gDILl>D zfoC~HL@?^l-=|(RQ(mU?O_6Dr*=Qu#GtX4bA36b}B(q9vSJLf>n|NIhB_9t@NswQN z@SeL4@c-pla_*x@ZeR+y0y1&W`e`RHU%#EPs(q0^BsH4JT4o>jnmhK?GO;=K z3Icm#tf?i61(f966@0#y+WUftet|3pb0`v<`@x#MA6jQCyk2T5SMzF zQt-l07wI1^wL}MEA#lshT-=YbG?TzZZhle=*;3OJJTPe7i$pvK0!fS_pI#ecH-T)A zCM?vdzn}0(DwqasHE&C&KMEq#F7W;(+*sF**@$9VfKTXz-T5FlOPk9CE0!%E@PswG zfm*=3!UwYppA1{%b-dyWP8s(hQ^ZyC@yD#6fm-o6R}X(%(ho1szaTh=&Psz5jAx5m zNvaKXPk6NApHT+!@+U7TEqMeOT$#8wczN6a^&Veoq7BCStR}t%vpmwQ7HYq&%GIB4 zncYRSif0>`FSCEW3>FDZXcXI-R}DFyB<4#@t*s>aKH4w{4^UT&#Kkne_A}Ktvk$KV z`ZO(8qluc@f{^XSGbM^jo9uC zkZuY*aplw3yF2wrvM!{veO?AUPBMb@-O;6;_0P@o!T0EcGSBhYcq-J=M#R}WCFy6s z0SAQDAa~0J1#zOYIPI**{;KFQs4*PX44>DV-tBZ3BPJpuk9vC$;x?Fg`toe1=>y%} z5_KK7%YA)Kd=_%{Pxv2I{o@1(UJTS=#@Bv#C6b-+;NE_~`l^MG7$1zf!D*Uz?>tJO zFL>v4hlmdsff!E^xgk-4O+%=EH^>P_OTDN2DsyiObCWJImBJjsHGCS7jvL+pra z>Dd}{)8Gq-km+=D6w0tjKB-oF6Z6tz#2<}mRljnT9FXf;5wkSDM_07nlB#_xvYs3a zJpL`l@y-jA@|E!??ep=$(&9I*;Np#gM<5$(-<275k*@~yjtwMJV3l9LoqL%lA_XnW z0n<_2dD9~;%*@12UBRC{-LUk1iD8 zk9VUEJ$~&8Su6;ir~LHl*g+)Nc?^W1d(UaZc%Lm(q%jR9(`z{C( z5J0Hlw97Wg*L}xCa2IOY@Nj6|Y{q6TE|7#VoC=`$W6S(vVvx7tFX_g)Vo~ls`tq>>)bfUrI!~djoRd~uH6do^Z zJ~<9XN}eS@(;I%jl$6*_)F-h9QDYE%?H#oc`@zR&Pjm zcQ=U(4P;8Z2g1@H%9u4vOGyzLXi@&xgcA#IxD~OQmssfc?Hp1JEmR{*lG|Yl9jm9h zj}qYv-H;QNzQCII=rFTFteTA#B$!+&e+wu8a;HB~N+n)GOn9}2rzo^+=UkVnk4C~k z9`DR!CrNq^t6ieg;U8MKFG+)H1YJOVqkP=={W4^Y3MiGNaE5l|D`tLOkB;r@CJBy{ zFES!RWN0H0SgFtgbAeRv8Vq$oA~^YN#rI1)Km`N1h|w?9i>9LuC+fd6Ty~RI{UL&R z6AT*>aTK+7BZd(6xe^{Mw5#twHYE$pCMvHVvi%OM^P zQ%b(tuYub9fVo*EQ0VImL8RjM?wp%4=ZJDX+Rf%<4QwudET7--c!$QJP|MAJ^%+c` zEBZDJaeI*1A4}zX%H!+CVDO^B%xlo73{Srx;mhNDTv#g}Awle_L_~XOeN?`_R{e)N z6(yNI;dZgLu@}ilgFI}UFY3~Ja${%{q)4F9nC- z`d)P0mqk{a84UUq_!VMLQns6XEGS4xfuYpn5Mh(wP86`cj&?rTwY6GW0oj!V7weAd z+MGuqzpzG9GX}k{pnTG5BXU2H(1tX1OE}^HmK+b5n)2N{&(O;PY!|xlO;21m69BlZ z5fO|=0?vV_W>&&;l3Iz7vErL=Jw3OUJokkA)=6-KDS26!isec{Tz(4^0>r2p66yhl zQ{XvgL*mm%IbL*27~e;7iH}OI`kzZ7a|nh*|5mN(|%zqQTx~M`hN<%?qOWD?G<6RFJ{(m@df)3R=*tBl1ScU zqtM)=aLWrwg~MyxChG7~|BJMcr{--qXKB`K(tU}f7ViEO<&~=^+>x{m3cKATB;wHk z;k-l#dvHJ~{C!&d6(bi_LYum6z*@lZiL}*Eu9FVs=ORdFGgngnYsFTG5>5zWF^%R~ z36Tz0Xi+F9PN@C$-~Rttd+$Ij|F(ZTdtPQ_&&<$e@4ZLaLdf3AEHZLg*_%*il7#G# z%DBwPXh_K{G72eV)bBX^+@I&U@B4Y4zQ6DD`~6qaHO}*WzK`R0t#|S%TkHe3UTg?s z`MZyz63Nis!xiF|^#+m`wE@OjO>sOT=iRO9s=arNVTJnVT(o2yt zz$_+>0lTTS@>BriTy^XefS3Bh#K2n(Ozt7lIP}qyldkaZv|Wbfh=OUzu)wc)&;mUe z@TAW>>+#GLU}6V+)1_bAUU|O>5ERdd=yK5Kw~{}0K_J7@dZD)~=n9rv`@^b|7frod z&#yYk=F)kD4g+J=nX>}{SQvG)yxuqD6jYC;lif^#`$I_88TlQ+?%Z|ED$1+2%@yzY zT8^sf!0+3?cc(ylZAI`Sch?A1LJdGw*+x#kJmVv=MNnxDr^~fCuS=;3V*#WUmctca1Ja5;*V^;mr&;HZeMYJrbw7dF z8A_bnW?(`ltvY~gc)6>SHZ!BqHr@?`yn|cuWk|ae#rPB+NryW*7J5Im4*J;#6krT)>R+gSh=`E zZ8WfdfE{O8XX-9=YGjOKZYRkE>On{5K^VjU+3!I&nYCk73W`C+GYE%w`_={xiMh+($k}E$w`~6 zL&ojjgl3d0^wb=_8}A-onm7mhe$R;X?6h;<;6eu|4f&3cN`qsptY#s|c?gEAaj($N z&F7$4F%PA3r{*{ij zHy;SrtdQ{CqB;v|*eF-HgA{BEGB!}tbmhPNfK9UMWq8(;qQ^7KFcYAIR$rdPU4mpoLQP9uo{~QTA+gl{FcPW`P#PLm?1I}$TISGlwG%dg;(JdW2Z@mUde!xHG zMD1!OTdhFnmr(Ek;8zq+XTT3w`DP8wC=`lkI;p{(2rU z1w7FDz2tfEo%B>S6;iokP*cBNnB&2rZgFt}rWG1xrq~bo-LClihu4biZHOzV$v!3k z8z?$dox-1sh~SW8{Dj`+jhBBGemG52DV9NzjOSrTCRC@gw|f79;ErL%Hj;Ef@EPEVPh^~*ppRpA z>2g*6kOEt>2+aa5P;Zp5!YAWiwqW8&B$qtXdzfQ{Q zSFH%&Q7^JLO!v9Am?BLP-^t8f>76+f%Iwo*Y^GXnG7T+LsoQ9gZlj}X=@P&bixG25 zH=cZn*nKps$y*J~d!x`#MsZh-SLZ=i6CHKAmmCEcp~!&$sA6KM`HTuSRp6MZk(1`m z)w{DDuVOEDZ1qL0MI;Hg5JMH#kIR*m5Q4dpU?bqpQluZo;BDTkiPF;fYZ3+T#x|j| zB%JXQB#0Y4f9Y{^Nq$_M-pepsTpD-&zl2{?%Uf|pFBWgcL7!ML@A=@*JLqxfJ-dAV zqnE5fFta?qSELAM)nNJrs!BKT3x!Rpb$Ux{-mw_iJU<147ncllzlP7Zz&*!(-dg(k0Ya!?<@0j=Er|z))ZgHU${1mg6W6k%KM;m-=xI`egPXLG#1nqe7wW(lf!_)gWWQh~ABUoCySSM2&#v-mUA31+_w5lF1kj!yw8fN}|42 z0J1dWZX+Umq7Z-bh2UCL%r`$Ho=8uek5P&I(_Ram4E0bH=vgMRg}hvptKk9=(4B>p zz^8P1b%`}NyT&`$q+nH6mPb_rbvkQU5OD1c43&akZbH>n5Ib8Z&A_*W{<4Tl0j%|l z*YvEQCb)Eaz_6Gv@d*54c;@^IB}|lkR0bEZ(1Wt2Jk89%2(LtGwlhfhigkjHePOcE z{3?JOOpo1i5-X(e%oZ%xzvoI_hYho%)4NA${^+TVGs?>Ee39b*_qB81jD}^mzIR^H zT+e|oSEEF%s0Hh%7a!gA`0(p99z=InGy-D#tFMPL{y2cPi znLG9darxk_3qn-)e$G=~ z8rJ$>q1-LMZ(E@f``Zym7<~QLk?};yi;1Rw0CB5oIpdkV8BonxN*@+A@uXbX_dNpU!cRW_nYTSraZhLxmb%DQJNsWooV-#J zeY;H{a;^Vl?R-W9reqsSsKLzbHHb;W-332*v_#Mvj*qDWg7Kl4;44{Mz;oL!rv9-7 zH_AcOJ|3jISkIYK$MNxktrlNiJ9Y0Or52^{}k@K1I+68b?`(_ zf3ECSv45+R>K=o@uUMB{E8bzzeikV45%I6DKN++ylEM{g|5P>)1Z9e#l*CEc z#HhYLsOu&j-1k@7QC9n4nRkZyHKW5C0@0_is*@8k_AwEyb;~;Br&JuD?_X9sc}B`# zW7?0S647py4H3uR9;{BA+XF@;wMy5>oQHKCMJ}I0?Q4DM@psbN$1o)F(R6J<>x@ZW zYU(P-*ROpQI1T-4#@=IDtJgyjbNenA?rxCfF}0raeUOZjpKfeZ_AeCQMHJM@45C~H zMGCTAc0*&Gvu&?msD%r5v%p|fdhOTGjPzo!qqPT5DGGY)$g& zV;(@C-?CV`VV|x@F6A$QjFl{}g1E>DiFS?DJ^h5w|IB7YEJm23hyX2%h)2YICcT3g zXOz*8?Qwetq6b~F&PaKDlG+W1{4pP2>GKE%w=QVyc>I(F-3VS6Zso2dfY2ZaU8f7kd!4eN2^|@a8A+MOw^I7HOWx= z)xK8CJVLqUe@|ue`5~0pVz*Dm9|^G!8OYIQSXHg?zC0*9S%J(&xAhast=MDM&E(zP zf#vk2z#s4!_YAYc$FB2KnUtTwH7kWDiHOTshA@4dt@DG*0W^9iO%c45?-8IpT-(HP zMc%$6T-NliviPqWrNKQWF&ImpEak%KeCjNd}cjG$v{i>{qF9? zVR5Mfhp_nQP=y?8DpTkHeWyWp1l#=id_~X0?B^f+*2pY$uEBJ76`ZL#O#( zNaeOIjq_At(4D|c;bc+o8o}av1IxSz=za_TeTEFQF_rN6SZ6D&6!gp;6pyIQ3||{x z#VM{WrdK}bw_8_s+-$nyCf}&DTxYz#TP5QTz~8|Qn}-k>7CYZ_eKP3$yMJtcv)wPx z|5lI1LG!KX^-<@Kh6r;*SR1cSm(u=?g_q!Cs!K7|FXCkfkJ}ow7JMOeSVm~My7!mg z<$QQ&q^>@_g|x!v$sArmMI51uRxL1IepDFAl5$>7Yy5tfQUTgRe-#OKzdFWapAna7sm@7G!!9%eJ0`A3T3~eEV2MflPsQOflOr^V4WN zGwXMI47Eh$640RrIoTKAqtxhP;6d1;Os(8KjxX%a!){M=5|`|)P94l6@)bee@)R5pfq>&5Rv ziI%dzxChYrvz_kdk%JzXY%esthpm*s95qO6+Z!$`19M zLg>9ZKFL&djg3t#b+WmnnL6CHsrz;BdDm6!?5>e0oBz|c&NfXpyr@q2oAbzo#}R=1foBAWiPL|(JH z_}j7?j2mNme`^8utS;xJ4M_chzD;9Nu6cs3^IXs1){gUA z?9&VrmFrA8AacC4!(1USEc>yn%@V0l?LR@mN&j9O^e;8;>>Sf}4zYB&yk#(+@Ku8Z zfaEI(ss%i?v+viX+j76o(h~vSPD<^S8R^!U6(?{Cq~Yh8*>xRzS!?@9Yxd&Q8Y_1{ zVvQ)ge!#2s2sxPwnW~K?3BHs%zrAaH1`vtcUJ8c3hD(a+2fTfR!89LXw<(+2UZC#-O-n-_hMCbf+kU?odgX#vk4s* z^d$j-51e<(zEW%$cTm<#BLw4sdsaBR%VVHVm@dL3{OL)r^`=t1YLpir>-z4Cv+~02 z6qRRb&&|&rWh(+B9r|I)u?3OuiQ;@Y(P5ZF`oFit{btZrD%%IRk_P@VPI=xsw!3dx zo;Fuph5w2wND^({bBpEnZ|2^KS2sc;?U;395#`o{=3Z+ zgCDf=AO*BZ3D*oS{{9yFAn3IfUzM5>3WgCTi$T%f!-$G3u32(E)XPC$#8veRnO6Q6 z+T6%E!iRD2*)gkpn*f_%N9Mu6Ph*^j|ALNB0*oODh`l!7-nu z{P&H>{!2ZBlT|kU6#;F2czq!LW8slhhr%-=bcgnDk0l5EAo{!-+&q=AdD8yp5j z2KI<8=Qr{VE^+;{t1w59-z~gs{dK?LnFurT%%P#)oFgCxCs(}z#b27NAu6!JLGx$V z5R2I0l#m zLFCgS?$1=YwUUVeeYnR27re^#9!uq47m4GyA;95d&bizRbW~8E36efg{qZt2tHEWe zsV?9CyFPR1!(|HneVKx2_W*!IJfgpGD>=gt0HvO;d~LK$;o616#N>(-X!w`CJw>ks zMu&Om+WDvM#>Hv%zArEIaCbN9xD3Llzd_Q!hv|Q^C#V#_a@~#o{o&!)n)Q$mQ(L{A z2~RpLjv$&G0K{o%gyx}+*T{T_ZA%O>Mmd0a=E0kmJCd+&CoHgAf2~_vq;<8wTr!mT z|HBgbOce~W{vKf5dtek`1HSP%LNjc_U*ZrW6|7tdNYfMmA(G;^&+nv%0Ua}!^@Byy z=1uXBLC`1**$X~2$O-)M8azY15bc&Hwab zMi^v^j{n20{=)-z*aCqC~;Q-1(Qc#9Dx2{y&R0B+oIVkM%jxz2q$ShTRVD~sv znVeDVBqH-&r3U})zgc(xTdZ|3Cx_=^Aa7fM=4nk3YF0BN8F+^9NpOj1JPbHvNBv8J%kfFS?p`ue~9 z<4Imdoeib--I z;IQZhf28FDifh|YWPVyd;8xW6|MEQwVpIYcn7&ekfoBx4xSlE4o`nutw`;Z`9011O zM$_b4-bBh4%tyTh ztOcxG6@A{{&8YmBR_-dhO<=-eATUuV3?wTK0Ax_YHzGmAi-;$u2SFtPMowxl9gLWr zesJL_8Zp-9AvD`Gh+dFXh)$0zTm$ zL?pZT1j)We1UAjHFa-AOZ7l{g`y^{gPy4FB0m>_@Hjg=sxJt(cuI)VHTLED!1%iTp z3sa9J>6?0ZX%@*xcoo6`C~C;J$A_(ci)9<%5RDhG()SV9ZcHq_HGh?F9qba<;enDB zY8)1$I~avX9z>4f3oRz^Q8>7&9YAT9_;W*YA@y!agVe+*WDg3XhC+Qo3aSjDYt} zObv(ja-8zK)(fhE13c3gx8B?ROCiIwBjq{&HSnj$rQQd=h?IF?xyg9E^zk^NQa?-+ zO<<<-=p&@G%LjoI-ol6`y;Zqg5@sv_Agqz_bvShBk^2UBm@PPSxJtjCmH%v(p09Al zjfaUV@@QH47h}RT>fR@yry6h8;R56a{3O?$h16K!K&Ht$fQw&;{*3pWKR1~NHhivn zsRU^Y;J|el-rY4Ut^1}H^yEG8!Z<#PY~y%Ua9(HECs z2^ba~r{qH{MK3NEbSR@GKl88uYxx>LW*Qegv%OFxheGNl+%pHK=CQF&cGwN9dAjol(TF|B;(U~CBs)5X^spexWg@wF4TMh$*EM|5C+w>@^ricv z+BL#as5{Rw=-eTRJjFy9YTBz)ea;Kwe0^qmk8WF~zC;d>Yu8aV=r-a9^9FcE{PC@$ zCyb)|8QN@&=BSdd>P00crzcpT=yuuFRYD#z(K>ApiOHDlwuku600!81wKZBnS&K zxC7FiG(kCps1|Q_VD}Yr?QpC(LGH(LZb%|y_rNuo8lVDi|DWKll>+ja*#RisXNu

H7g6^DA1pY5Feqj0J;V{;WI&k_@O;{}mpENA zgZ<+o2i_aVWl?x$&ly?rQW`W-hA|*8_svb|r3ER&f0R^6zkoa|y^8NcLZ6g`?^%sn-_M9;OC9`7 zZsy)ECPZsp1J)Z3|YRn7}HVUYx~gSs@reX`c}E1w`9NVa-- zZty;HwzxK{06Qas2lFf{f4kSq3l5R>^tRhgCLn|rPItG zMztHaq<7l@n3W7+rNtXHFq57w3Qd@R@_QIev#WM-%N;j;D^7Baqk&RE)8`j>o|62#_rMtk1Xp=a8v% z6?1AJ4b<&84v8~G3`eeAgNM{b-(q`FN;!(Uai6H7W4p;V0#`9~$3QGv@&i%DpkYVJjR}LMH1&yf1=+MLDj7&zk=Wn1f`&ED_p+KiY^(_J(UR|P-O!2hRA2uX4 zxS&>JeYP zWM&)RSZK-`Yw-E>(?kE0fg-uznWKri&BWZ#B?3N=PZA$~ia?7crptG(2;(cyYL=ps z{A`zYC2|DuirhQU3DoaRkf9Hn!dbHrLfY|>qbwxFz7=oC%xT{g$ z(Er(cfw%~!+rtU2Z|X1UiMZN;@_*#Is~%vOEHviq!wd0#chgpmZL6{X5t|ru&u<-k zaK;s1+qGVgsq6&A)P>;st@oa|z+(RR5W1f%b)-*-9BVe=;C~OIB5o%&Idq5bdk7GS za43zX7o0*Zk&2~qyH+&l$qiJe&Rqp0__Ta-b!n;6EGPO3ew(ubpH~=*b2idZ^dKc% zkKgsG;!Rei(Poq7tl&ueRn^F&R2jA`TyUC$%Fk?l1uhbq%_ZWgHYv2Y@8=5cgK+T& z4h9S1(SlTWaHFZYc3>@ud2~x+LmI}dQ7GTYU*)=4L%cW(q2|fX9*eI8?%tv?A0H&- zm8;_DSG^M>gE4ADVd`TKLRqSHMQ@+8Q&*SsGoI#~J=#{X5~&ntYeM}>MT2^d*7XSOi|{7SY=DJCC?o6*gAsi$7jPC6+?r=6$?`5aopIXP4(Q9^8)rowMEoVm&?<77*r*1$p9cgs|0Qim7F-eEr7SQ z2(x7vQJ*is6jBFv0(utf3+i}ujOZ)}BmNW9_d|-isnmU0oKEc&!9AI%+He2oE$rXn z9eaA}N>}wB*q6;WqvPV@teO%EJ~d@mvjZhF@hC2i7uVIeS?C_3|zcoaHJrlK*Vgh9T8ao1tIK^D!Viw{w@D4(t07P zEx|o`x|3-6?8H6^;E5Yjv%(cpVWw+WaW1^#$i(zDv*CR;2asAp-072N%4enGtl3E4)@Nmydi2X=(CO3eO^$Geu#2K}Dy1FTRQ((>?dyEuK{zW13c=8)<+#lR~@=saD)*!x=oOu zyr=5;&qG!Ae7r&8q5De!0?_uIk)3H5K9)^W8X#OM0|YQVNw`jR#4!VbMK+%WZYV|^ z?%DV--yVk!#wgt*xvlGZNg@_-5LW1lo}iJWCG8GSQc72$yJWz)%!~->;oF|GA zBpc3AY=Ey2ivS9s*p~E$=V;t+h%gj2uU;erLTTJ7Zq#2-I0U|_G)Y6eo3kgw(ZrOb z{s`lEKUl$XI+A74!hNTLST^n>B5u1S*+z)p(!9BS7!2%#)^b9z7c%Nb5_>|XR6-GL z$j`a_n%b#5%-gaLOAi*1sRN-c85FMue!CT$pX+w<=W}uCDV>m|rM9@`FaB1y7wb2t zpNTuNAQJZ9{NObNK^_->iJS?wC-2BDHY)-xQYpCmaOQnwRRzL3U`BEPeUsrnADKwL z6^U5x42<`fWyR;cZp3}V;%^aC2T3p0NzOpQ6W8`%6n6t?k}biRBs1Cs;@PC4kx#{b z&__`sXJq~M6AgZ$8sRiiC)aoNFLHr-icPV<;f53-hy2`^;90osw(QuoTq3&_B zo(s9iYoc!3BA3OXOHCorQ;{{ia!qp@hEH{=$qqfonCE5}(@9(v+~PJ}eZdw_1h^%q zleaYM`nDz3una3#Abd$L`TZH5H(-LW)P9|%!Vx!?;&x?6a9evg^_c(d6sg3bs88VnLLF37LbSnK zL@3r~lxb!cX>;3!bYEJis~2X3Kq%_m zBikak1xwh`Zf~51sG*4xV`z|;6c0huH~4CqTAPI$IV`1IcvPawEP_xRzP05C0f$oF6VFT2SA zpD$fwMhq|RtmqQ%;lyaSZ=kT1oopMD9AaW}RGoqX#zgW=6ek;ORnv`MNynzh81AEe z%}BAY5l97-uMlqF#K6Q9n%1}Y4o=m{dK?{pgvkE`!yT0d#Drbk=N=u~8Hhb$$G})D zNN~WI#p0UP7vCo)fsHbld9=qCwLv#TFiE@g1SU4&Nr{4e>k-L#1MXzcY3R-CCQ+_`xOh*`@&f%0bTleI(x&jV=8q?vQcg^GDGII?%wL^ zErR@7vR_7mB#D7X{B(A6ui|9qZg&Tf%Tu>L`&f??rYsw_A;nG$^-z0f02L%lrv12- z9sc?QBj-^yE&DrYKl2`=$(K@^GE$v%60;({^mb&PB}S%pjktl1E;p2t8&-Ap7B?#( zIM11wR!vf5kCJ=a^v&y$3=bEdzhlY&Tlkq@^_ZV2FeQ3F2SzFHuds)_c)xj@R+;|< zE!z2-y_&BU?@4^!c$u&GR;yI!(^1Wq*$0>ec17qn@;;&ais`L5Emc0GQ$)PsFg<}u zS1uf<<}|nF7^Rdl3v{pL2t7R&vZ&(RO&NJuseZXj0U!`BjeOLgf~DXe%Drk2%ukT1_ev0595#o`AvoCONeOVU#kKCuBKsAfdX^L-g2!IMxK8kuzVL zCC_a_xr7bmZUp)Fw>O*r0e6%X5O1;^PYOK;3`U}3;LPG+LjkIRWV^%S%TyWANXAm$ zQOo(&b;m`y7c`P7dZTu?O&r6puROS&clIi-KCjuZ=I-V-^_X!h*i&Fov5fXt+lK`- znjtGofmJtqr1Pt0qLuomSf68*9{%`B6$5cmi(b%?59qXubB1?1~)aRJgnS)I0t0tx?iDRmZTO8_mZiLX*6*Jqfmgm`1bKGD+S2 zz)XyTM?hyUb53^g%+)W%B|p4--slsA``LCXFq@GjEZYvxbuD)XzG~eI-oY&vCs8si z7a!Tqm-N{$MHRbDFwWj|OzU$}?>tMu66MFibeBfAzWNmyBEkq~z(PmXFy9~UWV6h~ zMHaBLkKtLm(KLr1Ju0zeR$9&!z8PtLsEEIN(%{QViJF1+dQt6Ib@ zp=Z9qnSd9UFVp%Z#MQlePM%P(8;jY@9g;yrUQWgji(hL+E=Lqy(#xmQ&FsE1q_Fta zDtbfYl;+NXYn4R?_M{=C+m~lc=5q}!A8}vWtj?>w+;iorfQ@DJqK!d??T@G; zui(>Z(aQyay(&M8b`O?dqBLoK_>BQ9RJNk;{(z5wuT+QQphrTD2cL!bITeb-Mnxgo zGFnK7*neQ@1d;MO7t?}vWgt92T<;dZf=_>R?2MJ`Fp79|FiJNTM`JCXWc_k->|)Gb@HMfQAK9c0Ozx8u{CF{ z6g<@vQxVh;jRm;rA99MQHbwp55Uv)?6*%?f)CQ#ia*}7Zt_%gfaJ={c)lk~4~i&u@Dt)MX48t<3#s z$UfG5uP9)x(cMhoc7xShhPO56AL>k>eTA!0ghg!737H|!^~fTrnxWZ!hhwTzKS26g zG#(^%5}t{l3f=ex12)%DhOHT~%Hb4m9pAnO^{1O0!D!furwwt!k6V$dI4@4E>9yF3 z^>CYf+{PKrF-y@QD`CVNt+HA?#^>DOJduW%LD#ni?Wzb(Y$M-X3_k^}2yTlE1A8%Q zBIh&}!oX}9%lBz=l!pTyaeGuEPkI9Ps$i^f4JWH}8!#pxvo7ad`C${Y*JgsgM6O() ze{=POjr^8%fB!biv*`(~6FY=n18;jBFBs^A5!zqkAWyxWXUwlCRTbr2ob*FFz=hT6 z1y%9ZUUj5#Z2cx>3gPU_x?+g{TG@MJ^ zt98f*e$+a^$v`fT&N4GuUf7X3h&wpGt1QSS=2ojevrRSSPie55G|+Ghr|jN?SNjc% z2ghq~SfYmy@OK54*obz+cT^QFC>c8G89WrY^0N;u;jFy2ZD%TCj6bXDd(`iTL>udp zu09hCw`qx@*wCMTki>Y02|CE;Tq%JDscLQ89#T{gkL!VzYNVT5k!jn8h1mDZj@ad6 zf?PROOmN!5mW8O7``p1KAf{rwBl8D zJ!&$HM!gDubRIuNL|&R^z|;;vdFe+O5@T9N8mtvDiPb|#Oe7JfA+}xTFM~o&bUj|YqSFX8f>uMdn8PhYz|EX<8bA0+55S8kcS2?O$|Hw*E4=u;RH&c-}FA zC(*G~?=|AlH`+ou2vrn#bBMUI`PK1-y#5&6(3^W-BCboiFoE4cp#r6(pG}J0uhwT7 zCfO1S&?8#g1ip*!8W*iko7;z0hu34K-VeAmw2)WSk%qp zrJFWg*s+n0f3ZmZtI6dwr{`%p8=_>++BcB`$9gE^avhD&sjHiQG46W^FfG24G|li8 zP{k#RS#0N1ZR?5B8Y`S`INtwieUG`gs}dWJbI;5f#qB(Lmr0{-JA1u)fD9!nVN@Db zrEK%d=KB5GcF%Fs0AVLyy?zihu<@V6rfDMtKFZ*0X zIvRRB{-o?638I24yUQ1XQ_=KIF@BAyQO}9Msp~^ltfQcJ$5#?5I*OfW47Fi+LJFJtp9`BSHBJL97e|7) z^OloRcdT9)<Q5l;yZFh-o zIbnRlyxCMKwNhky>g4s|zsYnSjf2d!fsG@Vo1l2gC^xOoN+p3T(x$7<{R7d;@ z#_gvbu4%(GC9{;!3Z>)){jEg(s`#pLr$mm4YfdK7{OJJcphM4cy@_jF>*Z6gh5(KaW=zYX=yPi&;4g4ICI>{vqd zfo%7BUwj+`lZWXiwNdl+fh(1KfsXdu7A*uTnQqijsvqc_lDz&%X`B?b8BpgGqSmXJ6 zEOPt?scT5|^6Nl^=+T+Ud%T5w4B{L5enyfh zyRqI9OS>aae@ObQJQLSL5~crV44~@Pv4sbLgf{r5D<o<|GeSG1MF-}{uRGs!J`Eo&? z{?-xkC)M5LR^jn*6v3XkBPQLqtkNU{ap*jb3aL)sz4(+VKk!WNJYHY>>yu$}^*DqV z&Vx|nw!w$qC_&sjvILnPh0)0RAK7kkz>b7fs8iqIR#`a8OOFDMDDy| zSzi1jh!eY{j?&^JGoZ?+hOh(0wPEU-WSPgDZ$s14Vbky#$$r2!Wu&`MS#BwmuH}E) z^#Zo*3eHrOL~kmPp{w$CJ7l{h>$?O~KL_^CEN#fNvfsHs@pAWYYO&Hpw|Ph=_;l}^ z>=b|r5F9#V<+`4ZUz69Qh+bdh_~NhTD{OWCX3Mih*Ep!siCL++Ow~3<@RQLb__+Av zNnQ9XXhjuV!WSewEdpYMxD3%~d;C0Cd>l7?ljqk27u2erS zl7A%r=*sTQT4?b(wSWRN&^-LB>y8a#TJjh+t)o*(n3EcjM zCru|ikjs$dKT+KXTl$de^IKMJ&j1uIG`3K{zPx8DzK>45tc<2}ne}XPa^6h2FUH|) zAl_DA9Tzub>!to1=Vrj-BdH7PKvE5-Q8`HAZUai#(obCs+><0u;6U6H5EH$`e}F_1 zBE;c$%T(|C#Lv_@7^cA?Ca0F&M*0plK5+Q9Cgh?vMcIO0-VLWH;-i-Xb@?CyHovbY zT}axPB*=f9k%`Gg?6jQ34pF^ze3>BCy;4jF%VI+YMy{GnR4VGOYrwc`>pcoIoIY=z zg`7Td9#lB1^tz}?L!}?iarG6(>CJ3-M#N$tX93y{8lfKQCuEE16TRKQsm8n2T1K)Q zAT;b6(oo+|x5uP-j?U*)`0LdQWLD>mX_#Z=zu4c1TDtcJYrsRkbii538&6&4xei1_ z(5v}@ucP9+Qz0*s4KE~*zZ~m)I+$%k@4=G+5?E&#%Y3ICe{2wcXw&j5qA{a91R?z@ zxoVDu*;wU6u&1l~Nk(ZMbOmgH9>ns1(dmqhaUA>pf{o7&T2~Qran2zc_FM2o1ijKb z3r^y7z}E%dhru~QW-HE0U7@(OZ7vxzH<-*z1;hN*NQ zaXqdOqPG6ZuADt@;H`w)^ILjr9~S#Q3}$)xFeluJt188zrYtM2QnfI_9&t_xC4--6 zq{6V+?%=Tje#XTclqQS)X%CJND|)qf`KJ0K_B<-Z^gA_rNI2-l%D{YGTB@Tm>wfd}<8LM{p!1oGsAxE5 z^<|M?Od{RkYV#|L`+@vsKU56ZadEyFYqOd^^oEX7eiu>-F0}td(vd~p1-%+N?$GOf z-FuGnBE)0JVZ^T)_BNZnL5`#930K!JywgMl1lV&#ThPAK=sGe4LdD{@vs4+}ybqX= zQ$qU0Er{_W>j(3mnx5hMqCfo9C1|JP?nPFl= zTcp>O3bpoOUF8KMZ6IqRJfb%Dv)lMaUPvWdPd&}Fm*@o~Qv-Ew7wER7NgqKX>iF1@ zi>_0yv zM-+ss6_ZdebIh2iySA#UpI^h1lS;cGMds~Mr-a8udGeMK55rxAo~iM;El3ZJnX#t7 zpilD4xXvgohGdRRl}=`6y&ue04+o!|p}(l{&Fq~ug#0yvu#oE=OmW*E^Thic-*lq3 z=7G{L{6)L90I?t@iN`tDk@JYARkk3=%o!1l#zhu??nh3MSi&8qN+CzRFIdiH)6vC? zDF+WvSW$hx=P}=pmMd8j=%P*z4LFXjvclNq!j#lh<05k8$!f#QU9e6sZagvG;@r`J{eNL3yfR8up6g-5O|vjlG^n^iJ9Tzy$e=#B93& z-_kZ-{%P-Cnd&=xel6eOV9fz$ZEy004YMm-Ab_ zGa@N_-(E4C0qe{C1vDE&Bfe8iyP5)Q$=HuU^Z-Z z(tTs6&Dupd=`BZ`+ckCjbc8a}J9ndq+k9V0QUc_#^i$ByP5YjoUT)Rm)aaAw56NM= z(fZtf-SWvZAibFx3z)h{Q$jlLzdXmoL|$y6Dv4z$Ins!kBhmOrWFQsaitGmyW04vYBLnms>_IZ_V%pl zBkTpa&5m}z0i_*gz-AszdA&X!J<`eIX6IVytcD1X?$;`X!cZk1qr*uh%`uVWR2N}i zMLrn!kFFO-#~u*P!8|uA&D~4*!bq2Jt-o{gjZ@mkU+ftZP>k|_omRs_d?-I?TR(bg z$A1b1rEyh)^E2{9=NxT@gwCgh?#}M^w(s+nTN=|a%>A;^k1HfymN$Mi7P%)u-=6D} zWH8R@B<&+=HP+8*;um(`>N|A}*B*tj**u4&M0N`EYfbv8;B|+N1Qdr$|HuYp3|~aj z)Ls>Ejfv2#n&2SkQ$1+z(K!GGLtQ^_!mdm8__z@@YTSJD- zfhTOZSwstURer!SFVk771wI=?LjvwPXmjtipKs%Dm}-OrTZ%O0>1^HwO+ku!egWr?Mw@0LAtj)Xk3 znD%u!RJjrw=H&Xm3tIiDvXtJ_D!zJ(r=2(3xd# zx;iT0L>0l8plw6)3G!(~Byxkg!9gD*&p4!OGM)h5Gm^yG+sycAQ4S@(;N|#wOq**? z{F!l~o&Zhnrt|5u(s${|kfUJRW!>qN3cXF8-TANb3cYo;)?EZFOz2pM5 zc~tX4ecruKbpzNW;)LXo6eS(u0rtF!wD0Cvv-j&izu~=rnwVn?Nklo)`HAPL$T?X^ z>%r*h>^wrMn(MOP>Y1)9OCL}J`sgXdt#nU`}SwW2w?A z;Cy^OE)LOA^H31KMW@8*6#E3z=gVKY_^L<9=la&E89U38s?yR2eeV0i+B`Q?q~2Dp zY>gBvD<6Q|=fY4)4&e#gK;!p6UJf<*y~8-Wf7)q#OTk@5hn=J&*Y9|CkBgx%xfL+% z$tv88@B6^f4h5ecYs`= zuRwye+LIR@SfTs=@d7kxrdK2U!pSnt1h0=>f^)mC=GfkUsRgKkfz&DyE|3TQwjZUF zFFIqFLvC9k=_f(v5jxf4p*!pCn)DxbNA8s-hwyCZADo)l9hs)w<5jt1GZQOKDtOa) zoELwT8roLZ!VIay9hg;@U+s4{rw@55Jd(U$r1|Q?QfTQ_R>G^9D>0;)tq4^4?#Nc7 z_`$&As13f)un%9ZY)k%wK8#!rH~z*zpMGvTaxmX$$2)%HEHsxrLfaKSoXJDDa-o83eU-gMSiA0`1KF!vT{`r zTc7PY%xt4@)y0oNqVOrVOa&QEi%Z0OzU*1_Znd?uRTL~K(ZeIfCb zEAfP>sHdFaeNT54bTdc{&dr!>lsR{zREz5kL4?y2lc-4hw-x{j-n&d$Zb{T}#z0eb zyzYmPG*Y`FntpUcsFM>(JLvFKKcy-e2U4Zx7UDAbhT*%IV<&iv!*{HH(rS@n&--z7 zlnJU0sHE!3&_C<*NrQu~yFWKIYU;>ZKs(0bXMy&`EJccCk{rY_VC)4 zp|~9z<_D1Dc$r?rfJ6#;)vxBt+Tc7>q6Zl9G~jNEDSCDP>J$UqWSTEFoLT zT1i=o$RT^&@9*iHbD!(nzx&+3>v8{gT~~ii!(+yL=llJ9-|zS5^?JU9wtg^)v7~!$ z6E3-cYpFpvkrSH;xvLbK-35(H$>C!T#iO9QyM?11kWr^exb}6S3o{hwhs~RrvN_s$ zacHK*Bf&7y7q>M7872fb;R>_O<bnaGkNgU7m@Z-$F$?69^XMBckXTA!K4AT z>1AlY6E4gKzt7{}GU06#l@Z6q@JK1o<1sr&zS_{Y;rjW*F$)9EkYs+kQ#c;g>eOtv z7!0McU3_;SJI5aB<&HBoCl0+XYdy>p;kBWb09Cb`#mTXjAD3AV78_Ugp3eLl&B1%q z?o|X%{KvEF6bif_eh5Ckdx}`@x0b6I-iMQD;na+U#j{pw`Jz!_+lhSssdCVqlR`y4 z5N-Ik;Cwu|r(PC=)PzIz)>j4kcY9|66n-XpZ35!BZq^tyTuYYJh{Ad=RD5GAu9h#GWwxO`QF_2fZ`@_W~I&PTm z(X&oa$8!V#*loYIkC|iXONF*lnoM+>$^BDeaeboMrWT?)Kv1Juo8y!eqV~E~g|On&bT`(1PdhXWk+c-rRj9Eo?42 zRGeGGgg@*@9@Z@@0XDCk5J1C+QEDWCEgE6zlz_bJ^+tSHG~rlXqPQ!I{bk{N>%@Y* zFB^)dqJzTNCvcO;R*REIB%$2nq($PYom?juN)4^=O69A(I$2=9l1rh~U^C$4R=Qbs zkj>i`<^PeC-v2u(cQa>IvuE z0nJ;p3iRxqreo@ULCPX+Q74^bExS`g|Kx&sB=VwxpGX866mr&m#M54f*QD*>Wx?i4 zzbrcTBp1|$>K3-A&9ZE>ScgPYJdV2`WvYN0xc5K`7P~wLGTT-pi9~;>A7DzqvghIu zRMTyH(e-?OB4e9yoQ@E0c-%W6eioM5$qj;PXFfIn2Y$&^51185+N2sZAfBTGr8D3j zupLs+@@YEA%oVQBfKa@j{}4(!FuI0@@73FD=L|WslivI3oGvo$F&{*Y{$d#kW1zHN z7hZ8cnpPz&ZtKf)Rc>N5NI12!z-9H+TezC`c6C`eme~@Cx0&vJQ6{_0%wqK5L{zdk z`62#ALT)Tf%pN=XP*sBb?p9ryT7a6G^-R`v3Ue;;c-np%L}=c)0JBBaTw?p(Ly8}< zye>Z8OO~%9MyuUH@tG|b9`FZ_e_6*4vXBj1qC^|g`4-=mUhvLKPHSP zXAqh*&utZTO;yIPkR1A9BI~~c@!uvKfCZi7jHhPEdp^$Cpnbh{BV6qx)H`~55y=6t zLQGvRI3gj(2h-#M#5r<)NHApCzN!3P?m?>L*}}N3+x-WwhAdPsksM^UHPwRPhZmekWqjPv@|Hby z7uH(9TIyerL;jTI5tHj6>!}1Be-)Gw81QwP+xRvP*6#ka&4BT3mxgWwLef9Z{Agu< zqR(kV#N8Zi71bd;{|2Chzf2uM*%Y6B=y7KjgmVK>7hAZS?=k*)2fpz=r}j6QPo1%F zs3nuVKAIgtNb>ArLUTU@1&%T+P0Ey{FVdlLggJzk=sU)wtqe>2e%hrN9$$l)+yT84 zbE<7;db;XXTgR*NpL5jn-X|hAW7zTOFa)SLl=EG*zOCq_o8oj`a~wb2OccA#K;l*=?aL zvEyCH`dssAXF*gcA~(N#>AytzH-Et*?QxOPwd9Fu?{XBA+eE*ZKKdl zwK8oZ?-Z%|p6~4hzIP)9ppjPVz(^!<;rHpL#wM50A$48)@JII%Lm|?mjBo0W=!w2e z527ECe<6M>VQdYSl{O?iY8vtdTQ}e2lrYw2!ROnCNZa?LXfI;uK8kIBbH+dQWc78E zh}T_oeWaak6#{W=NT}u_Oa|Y`Lt{ZQS_D{JMu*R^Yj8Awpk?554#n3YHDG=IlIuN3 zOiW8VwTor^w(oo4r#f{;ItfZp<777YmE1$%;7Qe=q27EL%$$CXo;k`{)9hM*oG;i7 zT#&rKRNM~${j~44h2fiDqHnUEdVybq-?ZYI-QEpoC?=9G5QOYm#bRMrQe#Bbb*g|P zQyuUf`VPxQ$Qi3Fu!U;QBeGS@=1eQY#|6aCfNw z&c|R^9pWn7UG?IX77k75^o~^Bo2Xw{Dg5$l{2<33BI8>BSO0Qx=>mCNutFP2tv<5H zD>KQm1rq|m!S^ZVLUITf)b}Bl>b0-fPP#txx5xK@V%VtIzYIk4*_aq zDkPh=8IYGfXh+zqd9(~;oDPJV{-#2cc@eOJS$33gsbt7m@kl#`R`|`EFQ{>GM%P;Ib?YDbofk+Fz#e`)3Q)!^a>iV&F+CftypqB z2$jdf&`|^oSb=~MOUlB2w$Y@b?Mh=ePRIa;oN`1)SfoSrw$tj>##NTw6~$fwbnT9q zbnrY6X?bAW9J@U-#L;sN@c)wvFkBOuN>TQARyg%Kr@9u-v!PZcjmRn}#rmA;yvXQF zeZj9y4m*KW-t(#II+|J0VjH+hFmn5N5O2@XW1N6!jWcbF_v=HP99M4p@*~ z>!_h0(p@i(MiDB6u5pBIrAV&2l>ycGQ*n>JgcD#6YER{z2cn6ezo8XK@i+&NM$nyE zx-zK|mZlVl>vj*4)h>!@_@J>%K76jFQt~ovlR6uba(Bt4)c@|iuqE}u{gF|7P(-H`XF?HBW$U9c-_w3{<(A!{3WuqHMf8@ zoBWbOo9L=H^@nIMsJ!m`)>RSFTgMgeNKbs2cY?xP@bZo$E}3EI8LSdA?0)g1;5%y- zHJ}!){qJ-iPDErPRe$6uyc4ACG^A%XDNO%W(h zM?1#AZpY&4imCjlL402Km3PVD9~2zb+M!pg0Buo_&rjfhO?%pqErk3301BqDV$)nZ@f5mANw>9C`wME*Y3N=QdnW-*Kh$0Gdv`{Djx(iaON!U&aaX z28s5;Kmq7vy4oJm(siX$4%KvmJ;yfyPUut7iH6v2w;1R2AnhmZM_bZs>zR2!?c%2T zN4b)>9|1$^Xe}Uo9vD5s&K{aqW0!3IN{rO!{Y=QFQ1F5}dRLc~^DEFdn?sK_hLQX} z%*NAtzJifypY!lpc2ZB>dBf}t-7p@y#E=+-eWJJ@p?qZ7@=0H|XR`NH@opMvqe`)% z`WO81$*(pb5xr$1_oV>`rYI|p8n zd>NtNWb_<~@d6Mwg=NUlP?@0KajBpBc6xvkD~qX94q>>7C;Ge>BfXFp?Fg)e@%#9M zu}PVO>*Qs^AoLX%jt)4mjMQj2uj|gi=Bf+$LQnpZypM(qx0cqe6gEfQY?K)dnfI~0XmeA2jkAIdqqOzS8tmQQQ%H?Yp`Qv-YUU`3@l zvforSS7=f+4f~9#_BAmPPI$5a6o5RvoLHt=i5YM!KmFC%IxIR^V5wJksi>&K2!pk> zI3@GZ8)$8IAyVZ#u-L)0aT%b&0Qk;+Y@BR+bZ>gD zEmtt%jygU*kP9=$qxjivNrH`2q zH;p27?9!ezr6XEi`k-KXO$&dyC_!=)hjw)6(8lnjr~Ed#@fT%J!r_BR`c55&NsJ8h zTbdZgeOOFiupAS0N8KlP-38j8tN|JI)1CF_x=NMT-Nvj2i$ zYz7NNTAge0p7`voy6)(sF;rgPQ{qY2cjrEl*(YYc?2W#=0 zG@dptFGtP>r4HXN7kpN1J;+(6#Pf;;nozn?=_EePYO34^>uMw_65xR)osO{{#oAHmsbsA%)J z22uf@Hf)(i;Y0AEM0_^pP`rVMSw~(a2g7XTuY%*O?Ih|)$&T_<^HsFv|`+%9adS{Lw#$_YeM)`CrpKTNGnt~ctRTK=1_?DCnSWR2^vvrs) zN+^s(IaL<=a%3N8O7g>J5zKk^4IitTI1f8ustRGat5a$d=d1#NG#=Q)D$^d+f2^Pp z%zhN}O9KF2jsXB2Ec2TG#xk!**UjJ%rsRI=X;lKDv|GvsP#IMi(RikTu27OIBv|CP zk#7qK3aiL$U(x{y2%blX4hiRSPkC@}neGZ&tRoYPO(1Y<3a5wZhKWVSHOsnmOn0N~ zS(9%PYH1F6T|VH#t;)$t40VFDzeV`%qgk{jP|>$s=q~pn{=5U>Ni0Ind;NX*VgRhs zd2!r7R5#4^?g|l0UcaKVuG5BC2~Iow=whBz9_Zl`X$lJ(g(myuW(^b#y(O<+QL4~w zxZJ%%gl-Td<=xc{oCF;k`Qpa>y(w;|ciPSu#w}u`i9#JTm2>dM69XT(?3?S)b0!{2 z;%mu1293kbC$OVj0=uDE6=FYLoKFPv#eR7?B|v$~if`MgbIP@juU<{KD4v52BiFyV ze70c~?Ri`tr;th;`hqmfqy~Gw=JbW44XE5C?`>&Lu7B?Bqlvdu0Hr=g43EjIuWX|B z=o=Hl=5t&Ht`^;yPs{1-XC7{f=k4?HkLd;dmaS5=cNuyr;~>503_9i(Ve5iIjx$$E z^uwYCYF*@x^c|fFe2U{Sx)k>&)W?GgMENHvSTJW7(jBU&@$@tO~V28o>-||Y$d)Ys?5f;mitGq}; z*J<<))!mOG9Js@_AfNq+WbF6@bTf~KXxcuI$ZMWU-civQ%#thNS9nT}J8ydTCEiMx zl2qr}!=tB9L)-d<`Q2gKl88aH?`f)dvnIsqm>n5FlC6b*TfN!-jn!L*UM5+X`z#=d zB)l(u;UFtCvYYH=D@hCch?{@Eu{LWb_HJTnLrxBr`1*UF-8~EA7#*_Cg|N^|?R76{ zG4@qL+o^baEh&;D8*P*94m%u!Q1bgdgnxD5{jb27QBKNuN5LVnG#dO`4@7N&67ZgOB)A zcDWH#uYZmPSGYUdEWZ{kNugX3^Y;ilatY<<*zdFrOXsMa2z(aP7atUMM#Sc$wV_e> z5m+8+7m|Yv_>kdP+mbK`NB$Lop`#?yjye*hs%WVGsXJVPE3!L!-)s5U#!5Ut9jtD1 z(GeOhKK}o^>Ua-K0fbU;4*+L0V?kN3{2W?G1h3uuh3EOFi>=hVY5X^ zs$>;m=P7Sfk}Q9HeC6;GLYT>b1m?B_efu0mp{DJMmMr=09>-Q804vroS(9QX^YL05 zH7oqb*+LG@h@Hl@jmLT?@)eH=c>VAYkuEN7ZpK=+TOY)F7$#SPYOUHN*C`gj# z61flpgC-@D{H^EQ^1l%BXIM|8;w81d8FV+(G5e{PUzE z#Kq*e*8psE@$x{>yz|`c`RF%}8l;(<9r;LyKV0-JT74a7NBP3OuuIqzRjUnqk(03_ zNy}4qo44&FbsnvP4s2}Rdb!6thMH5Rb5H*A>#icCOrF}i%;BpzuiC`5*5=P3YLdzi zdXCz4b#a{BWvJvDRtc~1x3a#lbjr6oJ=CpemudUtxYY|okFP^rH^}>;f74UDz;_JQ zB;?=r4mH7;)H^9HQ}k-WBVvLuo~v^Cn@ZD$qlW8VuO+G*(>{8_2%|m{9PIc*ir#9qcSOtf( zbfDD51!HuUGHP|px0QPTeFf}lt`AVerOnb|sQS3c6*?#T_c`H2L7xqhO}ZUMf;=qwC1^4ZlENT2)IMxR?F>|vf1Rgl7y}JSCaH=zS_%BD`KmYK54$eP(^Z#>j{yQF=O~IGcgPyJQhxX9H Nzau(;xzr+s|1YX%!Lk4V diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort_computation.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort_computation.png new file mode 100644 index 0000000000000000000000000000000000000000..47d4ba81b335450a24f95dd83ebbf080fc32f49a GIT binary patch literal 19345 zcmcG$Wk8f`)GmyOQYturh%^i>ARsw3DBUe3B}g-rw3G-)cXxL)q|zbXE!{(RooC$J z{qA$lKHtCZkK)WQ&wa1F)>_xnUtU)1F~$oFBqXHA65^tYNJuCSz|V$YC?oBZ^tNA`&f#&VH7lqpO4n;#`NcYeLk&v-JBcc53N03)h>`m zMhA<zSrt?7YefPf)D9#Tkab=I30dc2LwtMK1-RY`|hmT*Vm*_O^+>T2?zrT+EqjY#9GHVaj6y1`>=0yyl5PMP`%Zc6I8om6tQkKB1+Qg9|2$(of{k zMoId&Ws!XWl&N1!Cyfp$Q;-gg_vUzHyx!5Oem&X6{MUC+dyY&@aeF@5B*xFd|F&an z1Hg1x=83W&0;ZEHk4yrM%1gmyZWzR+$hzjKla*Q2*z9X|IcUc(ayf&m6c0H%(}3LeXy zAy^B#);}K5DTqzXI&T-H37iOc+`4L(z8Avwcs+2n*PN0RMCa+Mt;J(D?U>{}lp)q> zXTJ(zl>6d-xtZe^D)!=!KBC?r>E)E4CX5LqAsYz`S`zY!xs^+8>3jp&#HU zOzeKXNT<*)5J)Y{zg<|d({u%w@)t1Z3}#1%3}NTz_KICNfpINr<{X4-hdx2qwA?RN z^_Y@rPqx3#_uqQyjHOBE_xXCeQdVjIifF^mv%3`G} z>_@v_ZFFTsyX)WP;`>x^lI|O+Bf{!()sW$l){emfhGL|}+TUPH0St>;rVNC?9B!7n|&vPJ#`0vfXVnaxT9c0bc7^lz!gL?nBn!UEsEW2d@{kRi6D^+IPGLpw-3t+c&Y{gvynWWjF5k~uzDd%Hu7Gkzvq~e9o9Qh(TOLemov~SNzvurG z@(ksG{OF>pg^q|I^JuyHW1XZP=0|IN6&*o@GjH&x`YHusKY?tv|%lqB|CkI3j=mgqLS|5#jQ+?w|1>6UC< zZwEQpx$C;@R=sk=VpHNLhdGSq+vZ0(Hx3=Jsx%Y~T)g@xk=X+m$$=BFAtM5>7uu&! zQMZ`afHxEN_)Gm7y03*0QmghT0i^;(3aE?!tq`VoS05-93>7a7#gWvHgtphlt|E)u z|HLW(d6K<}?pe?q5&2O&ZkESA$#!_}B+4vDy(M@&J^R*1YQ+G5LQJY=Pow@z#M2Qv#-RCJs>CJY{M-6z zP?0XMEM-@{cL?jjb?axsh!=bFI;h<9C|H2k!T7@f$eADVp%kn zk^6414U4JWlV3w(e7?iS!zR^i~k+0N`lz2#F;J9L^JkSME!6GM!%#Cf3k358l^26RBthNhcrhSMe1Ev|!1% z1>x$Ic`GM{8Ws8kUd!b2ppWU~hEr$|7+3QO@ZjftMG^dOi;Ibq9Q~j6v_@KVrJkl| zb3j+RzNghu%T8guzdg%lFMw*faV)IIx4pstocm2B1=2qGm$iEiBcdR&*;_9}YG=QP zb<>4QvCI^x)oNT$!rO~kfsWo?UZAeMX6eT^z&pZJzf(?cJ0fzzF=Jjaziy*0INBFh z^lKeiy1FG;O{<3*7qHX3U1x#4DV{Vi3J?`@-|j$}=x__`#v7cD=<(+B>zU{k$Et%B z6YtxMxp$+hXxkpp%-G5YII%talcVg#5OzB`%!aVr2K3t6&`r-7(&=)y=L0Sv_Sp?? zcRL9p5{E!oM|?Q?b{Y@9ngq+bil#0IvZC0XWf}u%E${P<2-56a-=qk2FDdd!a%AV0 z4j2j`2*As^=F!hM($G{i9VqiIRr)p}O8U1X&T)X?b4S7=0(d<#@X%CA_06oRk)!QT zO!4L->H)q=SQpOkOA5jVrfONsHKdrjUGU~9ZA2O8_$b!DG+phtVzE8hj*8$v|8*a- z7Hhz|mU6&)m~Tm~$D}mIf=J#mtxR6MI<6P-ye?EGt~A`%PCtU)A!W@)A9X z9}!d>?Wl)?Q_=oP7l@R?rNdJ7#u%%^lk`DN){DYdtIQq*qj=4RuC=z3mNtNk{5G%<}mYgYbde}L>)8UVw6f@4+yil$He4AE!3 z!9P0&5D~{rB7J*XzSF1?s|MfTmWuch>W2B%{xwe=NVQjmB8>4e6@Ie?;j@z}odR;c z7gA1@y!cOug`77eVq*UM)hB`N_wkbSC8jb zjYVqGxS6l#4U7x~j6;lia5c;H->Bz|7d3F+T%9qi|D?|@UG}gVa%HD{`>hnnWW{PW zeeKM?66}_31lcaQw^>zNk4*Nc3_tEw?M)jqXTgd16sr1@P{@Mv zs>Y~WV9Qu~G!xAai~q)D;0OShv7QBK0BPPx_B-j%VG*Y5<~A4iq-ia%y>B<^h-Ji(IEUQJey}w~3kme}SodlbEo@nc$!|*w7lf+{98bq2 z)Q8|?H4S{JO)h%1TccZLiH^mt_-U|@bAc!kwaV8A{J0Sl`7t4fG|ZM-Cf*Q-MpkRU zGo$K)pU$vf#K`WZX2G3s@>B1MWw_FZyPGpC3F`tJHSojSlC75JfFBdKU8BlE-Ro)_ zpT@Y;My<*Yw{uH?yKeQic2}l^@E(fi22ke&X>rYK*&SqdfY8S5o>ekArfj+-`5u=R zA0Iu%8%|FPo~m8Z68-rWiQY~CM*0T{e8L8tv6KH5CL(5TKMgf`1%zN_l4pFl^k5OJ zAm`_2*DvEpzGjdUfvn#Ky@-N_cA=-DDrsl<37lkLQ)uUehDsM>%u%vPP(+ZJueO9r zQ8p5N;x^Ct^oW>eG+Qo(M6?1>Wh}j+QBTfN`d1W8Dn`rU%x-6HeO6dPq}l3WFEdtp z@M&rt>Zv)&3Z@Z!Nx5zk8;>z^BI~)#qN##f04Bv)P|{v(JFdfM%y`LJv3C7*sb1?i zW~XgV3{;lRFSy^c?Z@%(M$^2>*DOqyA=h{CTYsL@Yoak#=v+jBanC>$vmD&}ukt~V zY#vbXQlr4nCx8e9`%!rB#9rfy2M6NFa*=}};{zZo@C)(UuWMdI#+$_$+9jxpSW(?n zVDNf3&CWwu?lWec2A$%l4c2QR2z~5@NFBdYF)_O7rk+I>hNJCMQQ1QMx)0@3lK7(O z`fsv*hNq748na_tWH}7#<<&It@}-T*FXKY+9?Knx4!b8EZjZLnjx2a^nEiV3Cu@dF z0jLP(()kksp9{sv=k=mI}YoFk$X~ZXljN0)*z1~FE?S4hH=qgzWO^g zMCJz^iHiFzlYCbF9Ixw81O-EL|8SPnL~m!N#FmafCrNw^omGUNvr|*@ar?!>E6b#C zbBOof30_|WI4Xzc4^c$$!vJ!bKSQK_sk^5afqBV7tLU7S8V8NRt zlj?0PM6y{*+U0miObOXnz?`A*ttBl>6gGCBCkW5RuJKfOg7%n^FEQu5;JjFj%9Q`0 z4M(I_H!q$BEjl;N^|fghQFH8e>y{ z>(ST1es58AU*R6T95!;*I8lZ>!t58SERNAlf5+(q0Gr_4@#%j-B&Bld&|PosY)Mfj zF3|!Ur=`i<8PVeVtC9-tN%}s0hK;qcIvcRiwoITjBiB`Mo-(z8E-v*lHy4KMiuE4u zAwc3jQVB0()-$ehK1loQLwrWCXtm{Bouu%Rey~zNQ)P7P6UfVze8mxs=d6a}QHCoR za}nQZXks{hZRo6`v?QV1=T4!eIpJsdiP?%9&?&lg)w+nzs{@~2unbeX<)4&Irh_ov zD$<`15ymTok`B{MUwrAj5&8ZXRwVR^Ax7)rz^re2kBsw1aWQL%Uoh_LO^kY29bdrx zhxpg&7ja9knAhYX_e$c`ws<9~2EH*Q3Rd#GQ2tve?O*_~Nyi^Q0024JLzI>BA&-l* zeJrf){eg6h(KzKjlf@R_G@m+QqYpscEiAl(#Xj0I6zrLig7LpbRVTG z&PyG3zIv60y1&+!5cBd*s`wQcUZ`G1u_M4pfYM-!pDx>Q)@#cGgD~)ka?Dp4JN(85 z*v0^QwV5YgL-Z8Lu#k10XxGs5ijS41F9rIL_?4K z>rx?U|H5Y4`NWCF`v7^>;kWaN0}yTT)!(+g_4TtFd4&4mRzb;X(tJKp)1quknMv%DaG+1P*p4I0O6+!2<$A5Qg zUIAkEJy^Cx!qy-y(#-wGE;(F+Rv%YXw{h=>mW-Y|-*c*N|FxF#X3q}=>M704Bge@XCH zdcw9seuLf)#b;`fZQx9pLgZ*#7T}Jc`^H>oU%$ubx_=ztJ4*~|hV!_b%{h99j^rw2 zAc=W}v?aN|8_AaO?iHhulko}-6iTqH`^evFjrB)U+@LO%$?oUQzNHbA_Dl!}^G|th z^bHND0Xnj!lg%fzU5ea*4pwzHb%J`#oMR1TFjvcTwV5#xHPI`gYL70~Q~a=t9+0}5 zkh&c!M5U+|y))AFI0|w*I++l9)KkT7KKY6Y*$Cu)U9sUvXj!XQ+-lAD=L{dBi%OLY zn23RvF6j4bhKPP<*=Ip?bf6tQp6s?pK*(+y>2^D1JZ?H;u^TSMT*Y@fN$I1#=~88W zw6x)jE~x8v66JOT;0%8O%xA7NNSkgyy!NMn0N#35r@D7h*~c;Svw9NR`%OP=@_f0>3z(A)T=WUATZS5d~-TO2H!Z@%t?t~qr6AkP;#Zw-1}g~D=bh3 z7CK{+5#&Wk%XcUDS}e3JHJ5=l<`(wsFAayjMjk_lXrS{nsrw{lT0o9`5vl+ob2&(Q z#R-wU|3Sxg!0b^**b!0_^n$b6pL4;y9$sfAnW~UX?ECR%;O;tv?_?$7bXwr{X&dnz z4QGfbaig781hq^dptDH;Y)z_aS{MOEl+34?^NN#k&6#oF-!kzWRc}F_FWAdng>!M| z?T7toroR!e6#`uwho1e#A2-XgslMCpx905uk?P<@+LY*I+&T`ST$|;Ni$|?|f4hM* zWhm3m3V4HTXLP2C#o7S{yG`bI%O+U~&S(#9XfPA>U zzHsOpQ=8d|(S6d~8$~Jf)+>ZYIa;bycj3;XVNc*_PYY$ZzKt}9l12Op0lEO=yUKI8 zTM~BW!W??$ECl|L=XhP9#&O<#CYWc77IJodWHyV6buv5~!=#}Pa>vDZ=9B7+>CIpQ zv_$EiichRAKb-!w95m7UcmyQKz& zCM9;7*lZ9skp&o}5=PIrd-p2HCW!G2XgKpA5?S-=7xQ*Bo8=@96xxL zwn($4+5i=+n%H6TM?AaPv-3RMIwIaceC8)hgR{+dbI&}k%Zjd-Fpsbqv}wvjnemO& z_Z0NH1Y%Nggc|@&1g$?MreOJReg7Rg?b?B5R07ulh& zd{tnC;(Hgb@f{<<@62NEcj1V5&?=bxK-Mfbl)z52D;m$aa5!JY+Kn$W@D3Df9{D@t z_#;}o8@mRF2$S3j07@|Juq<7)%%`=>r!%|Zfy_^2V`DxHJXt7KFKc;7YAcP_YC2V( zrEN2&0$4%43QWnUk7m{`g70`xq}p|=96P@1fI1--C2Fid^}#{=8$!1jI%O&1w*oO; zi~50q9PkGJ0KpWuQ;pcbKzRjD`OyavaFoM^*5}*M`xfN~9Sgob>=veoXxoK3>h4Ee z2tcOl5iF1A!X2;uglE|q)QTU;X1nacI+HzaFXS1e^)&Er4??Q1NL+l_|G5-mcr#gK zu=M*<;fPBOXIY_%qJ1NTj9WG=KAdp?!eMt#$`i}Dk0aSr+!=3u3z%y6g(1iI&Eo#F zm(s%RxfT5wKUN)3x;^T{!p>jS2Xn@!B>le@U;ncOLjD) zE=k8RcK)%=aBB;P`Q+dWtIDvdk0Twj{HwUzrz0s}RtA~CtInTad&mjj04U-i&1h#J zKI(dZ${n*!)gi_z4o~zpZ|&brYIzy}*=?aPBmv_BY;hhS$z|@59mzfN#C#j_L^ho7 zY<2`*yIqXU`g$ib!pmgDprmo9r=YkTz*jlr8G9uSO99p)KEXgB9+2hRtt5kswg$|; z$siOliGuEkLU+&4Kz6*D5=$XEpkP(k%RILRS)}mu<@CXFqh2qhl{6WC7JOsgYbkC| zW%ljb<&c`{87oqz5jSXWu6aF?m~(d$ZX0z_8C+XW`GweoY5!ckW6g*xq|ae0`^_3&xFlDKn``@0q^qy+Mv z!e>E$w8X=!g&7Zl+gc!a=y9wa_Iei>HP1J;UQL>nRHfYP80X28qf^=fhOANvmM3!U zB6pa-SoeEXES!MJ2lSpWMUqEoq9#7{#Yb{cl8dK*Ly4~e;^XZFygqF>3OXYmc{ztp zGnuM;$FqW(Z$ZTU1$T>muaDDW*rH~tFh&RCPE5t@dIV1mrL16ZkPcmnbJp5>j@Krg z4tM8=AL*0eJmHo`jMaggzaxJG`mf1uLSjyYvS<;Yb+w`1sd#sbU}SffD$t@=CjP^Y zUN7~wNAhmfl+OD7b!WF^ppRuCMrt3~cs(rTaJc6|ssruZsW_V#GK@VsYgWsf&)iZM zd5Bf*IPcV1x6|Z;Myco?uZRiST$0B2_$gc)(U!xkR#Huq;@pG#;S@-<@4W9YNg)O+ zU1adC?g)#BugB-hAv3X3Oz2U~xU5v<+jqP5RzK2|;wMUg;scz+Z?ho}0b0MX}ESu6sOi!hg$gT3`DCMrwVRvRGD-9*w(Yog_}oLO+fB6A6T8s;5mET-IRghwwl`L~e~_@U+v*=1HTT<5toX zSA-qrm)Mi>5bY zwZE>}H*u7TiD040u1o%<#R*n0DrU!Tpx1XxgCgFT8@1#jJEKo2q0hdi+q(SnL^U6c zGk)jygm@>clZ4?b4JTq8`IXHxmng}fgM{gQuBaQ_K!X|BHydvaSoON`Eo zL~+Lj7b|O;)e$Dx`O@G7mg97{CG2F}>u`y-Ql_NX1^&@--d>G=WRV16-BdK8-EVO4 zKCs?s9ZImimjH$xk+_`Rh$2b+5s*LH%vCn214@;&#FjI1xd8@e<8Fq zaeKnkHSe*{tfX*Z zA{$1OVpNgMgtqZqojpTsVXd6Jo^na^={s?ZqVm-c{?pj1Nz;PFb!OwCiUD4ORyl5} zukUMS9TMz!CRx_quOGtfSEjqc>8o>ezXNBNx1fD+d~QAU+{cK{SF?)QfWUj~3^bl0 zfHX329bB|hA}g^;I(YHvtR9WoYY!pu`GQ223SB3vM}s#x0#$ens*|ww6e}@edu3C3 zm`>eJof-Cfl27|WS3@E0k!L>2kGB^6NXlh6XI@5<@6FZMNbGR0?^IX-#i)9{!>%yv zx@%j^7Il^D1$3ss<&2D?@qAdyiQ59q+js@9=ScOq8yslUw4|dQ=(h^ypVo00JIBDE9=7U1Wy1ryPsm`_U3Od;x;`${?Q5;!aliS-+=_%Bv)t~{=Ga8L-MY+{zF zC#XC7*Hb(!uXd``tnnp&O@GWug6>k=-wZgPl!x$Nc1@qo&rFk+TAgbd!E4NiUpGi? z3=N?1J5jE^MT=y=hi}9RGsQOVao#ql;qpnEv_Qu}%&o970e3E&{PIZ#Sudydisk)8 z%5-l8Y2}P%7)Sy|5L_!^9(wi{%@RmN4i1bDwNPn?#QH!mz7G zsW5x6B+NMRX}(?~ud(d>+%u(L;rAt@emHO+##EmaCqd&QAkNs%(3XyN?5}v9cAbw~ zWD2YOx>o=S84aqs76K=wdI46WJov%5UfCzfT*An4j*btj)U2O?IQ(8gOBB6!-cl63 zZeCVB6qhb;@bW(Ew`A;AhI5(5Wp~2- zH%Yc|n8UG^J5Ijx&Gj#D5tGO^!qujO(}^p1#n5^RX})B4U&W7yge&aizWPN#yXBTw z&uh+pJ?RHk=Bt+{H29&=@!YL(RVU@5{ExztAh$c+JJTeHV|BO3m8OpEgiJfAw&{Ec zbH+A=uZ8!N>w;^>Zf1#E_U%TuOCaniGB=L6Ur)MMXy1#%X z1XG=nH{pc%me|%@?AWhFCKqvmfDaU`)PVmb2GRq8GQfq5!*p_xX?iavO>#7zx%rWB zA7U~IUDbN!Y}X}{(W5qm(i#HHUwXnAaJT21Z^z!%SZdEo#KobIR_O=wY#n_EjNij; zUnsYQ{SeEe%LP86WgjII`-;5q&L5zf)u(XIe`<9fD@n1K%njRhgXdKXJ#FnTkBd}W zIQ03cJm2%>#e_2Qy;;tv(%!Ki4$+S-WiQF8=z$n6!*#8+ZkDd7ALc`{qkmq`cSu?TY?2u*C ziRz4gAY%ZejAu(Gs#f`(7G5s(^(u4qUenbY-*A{1ksbmMH*YO0FcGs+@3~vTR-avs z7{yFwTfCbhp?Tb2pHf$+AS@T+K&(hLzHORVzBSQ`I>9~AV`_n}`-myg$BJwugbxtx zq}5X#9|S^S21LH~z{M4H%tNBlx#Rd;_LUyn_H238?qy2QPE9ANZk8)7U!V9WVPVqc z?%Eiesh^auPLgYUXR5;DoG!=5rxP&>w{AAC9C~XH;!$~-na^|5v0XCroigN+t=s!8 zWwV)L?fJRAiV2-+yG=#N#aS~}iR%m%zOK3Btb4r$>?rtj*&z65O+xtWx+Mv|vm~nt z2vum(zrFa)8zL>PvPlrN!ad-a^zS1yC=d~Y7YJ`F_lgp&gn+ybcQC8Zs8T=9yU|+_ zH=C`s5sxfv;K-M?hjXt_wqo(&<}1$edgF{n+)_A=MF-(0Sa$kdAU=jJ54 z4g=#sgY8e}X-;QKTZ9?pnjmMBr+{Bk2|W4AMJ3k%8M{jyLFxUgryU2J*P1CGh;wvs z&qf`bdf!j%k?cw%YyLP-q2(#5K&>cn< z+K3}yYcZa&Xl~TDJ7_02mkNF!C8;KmmK`-e(b#lVRU1`onn97a1%TV~kcl!#ML*;RQ!O2!ODW8;#WR#P9y^hAV>7%l&jeyke7+QL_=+=+3I0uxr2d za-?eUNQI!I=asuGCc|R;4bPrsAHOzU_?cv;d{bh762y;ymbCB2dcmY}A3v&DiKHcr*5)stod$NASj*s+YL0;9fP${$FObP3w4ej(0 z6ud?t)wf3e!ohRbx|XtE=G5ea(;Dj>YgT(>W}cv)RPUbM6z@0!FDzhUxkTBh2iy|s0@Dys21&xEmmoF2XXH1r11bzHBy zg5JK=Y2aERy);=A-d<>KPI808e(XkCZP#7F$urH?b&1W3>fq5Zt?mgq>GhkI0EUkAX*g zKiaKX$kut$>r3+Zmw;5LzkBiC3PyNrMj0?kc`%1gS-Ya zZ|CDV2ePH(^bzfymTp9T3?&y4_P6chOF3Ny7^d#mpXyiF61-z=&l=CBWg)wfjxfiv z&GPMHz5b*S{@HieCONLzQL!%R6d@#^lw})V5@K;^SQTJS(6h^WEf<#A=#ikX`cuQu z*v94y;|H3@#HK)xGj4aJ!kBh} zab3F74d8A&OlUj$iZ%ms!PJ+jW1yiQKX;^al<|H@*BKnh;XENF`}_nS&kO8e2)#9V zq+PNG%$;PIQ1aybxk2&Z)5>{=8F^SiFT8$zw|M9pUUwu*$mwAI{O&7dNTooc(}!4( zCYhrdx0*dIp8Ax1!kNO|Gp~0|Zq%Di@^~ z4D_u82Yb2%mh@5xgf7noD6)lM_&$m$RcZqZ=RDBH;{O<4#EwbzbAW$6@t4arUwF0!w$pl2ILT1Q*rZ3+v}%~@U> z{VuA}Dl;`gh-D(X*?fa)HM=$$dC^R=%NMD-B!_g1S^Yq-OR2-Y+t1?}7N}AU34W*v z*0|k45i8AIbqOvqOPDRvb2iKx1J_q-tfP-m5DJq3@=185=1=w^6fkR|$Gp>zFv_Pn zN;$HpGdQxPOxkrmE8m&+N2|rr89~C}t-|viHlT~{?{;|5xyX0jAd40*m@!D*DD^T7 zDKo|g7vDWSIMvQZyty7b6XtYF(pS~zFf)~`UH`8BbXR0UReW}~GS8xt>0^ax`r}4Z zwMzYocir!vwK0j*KK;oy5GyA8&+6jv1C~NE|NoHsYfX$OWi`vn2a?(#p$U!DCw_c7sOVO=UU-tS2*&Y^2?MZl8 z(CaVw;QA^C2aD-9XZ7#(8BY*S=*)*TOy)@yH64N;A1V1TBqi+#vku!C@z+z?M!oWq z4Kmx~)kX7E534MR^L1concGJn<7b}Ue+clV8}v{~>_Um{M-}K;x{?HY?kMp?F@-=z zD`>-wo0epNsSYls%PYS!J@+P6udlY)js4+WB$vWZ-o~JLrYK`J+R&lv(Ri~u;8Cp# zfxq{=UW`=UkmNU~-%Q?U%@R$X^tFr{@|IElK14wI!>0Uh7~4F&(ZfI1jo{`g25nv% zgvcqv08{`QX2gDQdKzl>CQZYt;kK?3s3)rdN?}BT7|cSo&}9M`d4V;Nq0{0>;a!w| z-#~;6cJyC`pbvmcB?<-E_q`>2Fhslc5K$R~He5t5w(e%?wdND6>MM600CQeMtB%aq zM*`_xxm_Nkb~%{K_BaVs$gJs_wNRoZc&*l|M5kJ8qL|w+!>Cm_I8%=%2{+&I=G3vd zBEsYD$~r+nd|Ml9h~Buw@m(LvwdWWyAIN2^PbIVzHDM#}=x8m)1|BX#7LoAKPX>Bg zV*Vk%)Z?z_3k1^>QU2Qkp^{~REL#nR0^X^e#BtYYYUtSmc`7b2>yotOKrNshnOgkY z`I-_Y;a6*FH&>b|O>W-LGaGp7`j2*2c!Jv!L-98ftb}Q!eMqQ+$E9wbwWi@DMRe5b zU4KeAk7@orux(4QswTbJ5F3-7krI~rbx=MCD=t$kDZzJ?lO{D!*Vn7V$x$2-3m;En z8YY_te>|f%DQ3AjEAevpoP}t}f29Iqpt>bygqNTtO4IdWZ)6t^O3G@l_f-y$kho=< zYrNV(_{>|CQm^|a+B#&7^$cAiom;|ylh1?fBQ=fN_7};uc4BTWr*bO>s)1I^sDs(o zRqo)jzT7yctsWV+8|{Tsk(lp)DybLA=p^yukP>O3oZ8dW{>&Q})oN5PPtC~jM6+vrcP zPp8c+a*_ZRi9#8nu$-l+05B5abN#Vey{XDrI8jQzjm`@@b{P5mWAPAYubDk&rnXud zEfZpeZPjCFpz+oL2>RvAZ7K*s(tiW0d0z{zUSC0Nko;|;U0KdMM_`a8^eR7(Lfzgr zs-n~Ow(D`F!g2@sW+f2>1Ahi)Aco*l*aNdhOow|$y$tlnpA^^3_lkVBwI&a$o>A-r zU6&UB3;smrt)_z%25+PSAHj!!1c-hUBeA=V1+dJH=<4rFB8tT~WcwG!DJp%Bar4lk z=`<>#Ynhz*P8?H)5x<5vUG{&FA5;i8Y*j37PtuA05}M2#h|s<+Tm6n+oFGm@ zjgq)zo88F@%v6-93A7&5=q% z^{Z-P{JJ?JaVYzraP^ho+UChlc8dXDPuCud=kW+DZEL7lWJ7D|F|zCd_lQ9pV!nO! z_=6KdYKOqIErOI2{+oc#c@LdWM^#%-GiuNj#{v5E6F@8T&`+26HiGk_)8q6f_U~!| zaV~HmAnfwfz$w5ejNX11sn*({t60s7jwmXP2>R|_ic_KldYskbi&N65$MM_DfnQR7 z2)JO+q_HZn+5!G7$i2SWtumP>fsjLUE0O&I+0y6&|0`CYAOsRR!exPm-6F4Gsx*2V z;{X5!KWI=BwPmMT$foN61<%b9-*RpNnvL*#!%BLoQr3dk-3ld;%W5YaFLn^eS_ z76B$=`bIet6TCtTW1)~$upUPL=Lxjvz=^`&fB3x`(M}oK7Ro4G7Ep87zU5zec3j2CUP!(PUk)eMdx+5cU*awU=Ib~!MSA+!UpYO` z7CZ!`OMykf@d7nw7hqX%%dSOD$0@7IWT+(=pd0ZJ=Y;bxXAMRGR2Rw(<@8c-!kqA1 z3Jr!o--g{40$kmFwiXi^`xTo%1mwU}`wN+n&)F`C<-kUk??kzNE#7R)JW+CQ5{IR? zJ41~{n~!M+mtrHbpp^39tqeSYG2!*&y<3;86p3-He>6-6@DzQL{*s#fV^4ss(Dx9F zglLurx;v`k0sx^R$Gv%>(Xd((2F82n{2-^<#fXq!lzL(oGqS{($*zhKG-5a}>aCY4 zWPiwS{AD%21(2!_%odb)#w)DR48;U3;~aLUjT+8dFqvQbLwZUm58g}|)s44S>$o1g zA>^`tAJuf6q{H+mDOr0*|5VY}f&d}1i2BY4srtvdN~AW=9MaR2 zzH-{Tfj0i|tAX1H0_Mbpik(n&}Wq{>nUP{ zDcUY(XQwQ~*nVRCg04E234SYqhi~ERXFr?(23jz=U$q7emBKcKzvOWCQ~_jA}(4 zv40Za$`o{7$;y3tc_5ai()#6bg-U^{FUx3+!1*@6KP34Zut{md$5%BVWh`}-1MH#_ z)-MM`0wMzQguM42>eg4EN?8Ao&jL}WClN69IICB^-hwhHvyU^(z#X(dyW0uSnRMRG zMu5d4@Wqa{&!01$0t7w|E?c_=pmS*kthvgWzPN>jtha-+D*~0UTKMhfSt9maqGl+5-z#PV?;bwB+|tDy?`h zG4hW1ju%F7OxAfde3BBwZ0`S$hy^bYlaqx;BO~nGsLz4)L!}J91LC1^+_oRKZh^Jq z{yN7!5@@FQ%20jr46vjkj1FbTT09(Na4X4{XS8AhziF+hv)cq+c1L1Q5x<$w>8J$& zutc)fcK`U^gH7)E*{CdyEWh(rb|s&rhEf}xe?8g>@#q0JBNgnffX|7z^g<*uiG_aF zzRED~_00{53?w8>HpKr6P*~Al4sfq|c|)-XSiw|<;<&?&pwHm%U7I*~KEqcwVZhP> zKZnKinS|Ad?U^VI{7f7zyg=MQ%Wmk6ig11TJ6imx$j|lmyc*@FL)wsOvDIn+FYBwk z-2Y#~5EhgO)b+TrPvErDK}+LV^uZBcWndq0%t+yLI*{R8F-Tst|oj4?7S3_>ju@fiI)!cw+&N)ZGef;Wu0kAE4dDs{=ud?{~=?g0B#ktn5 z+|0Vgv{6QC#bg6Cw!n6}ABO%=cIF6!YT;KSBW7l^6gjVDll1NQLoz2;OP2078sdia zFZqh>kM(HQkGdcK0Y!lDRuQBV*R$v-6|Q?!#LGKg7j=EU8@J zw;>Ia<`tFd511xtGfPMjr9c;*`tovYTsM1<{q1al-kWu8?dQ?OLrp8hUXfT0MDQUe z0&b{bze;_%{kCX3BP@Ot*b6lPItsm9QhSb#^1?nzL=I6>e{(7k_v%Rk0wQeh)pmh6 zvVxjuHWAO}g}q(lyW*v9^cYuF7~WOhY6 z3$LY2lZdK=&dq3j>Q0Mv?>DV)wpwW7aJxLVo&wlVA7iu~G`5}<835cTy&}_hC5Zp1 z;b@K>4N|qZ>hiBEU{C;85K8D%WC;B1r=PX%bihlWtSctmrlO{eNV+`)p(GpIb@|a9 zUCLt&>)p{C4+nH3N!F_sXsX) zR|Ux=1)pH8+9^b&F138+_t*yrTi-{j%qC8Nr5$H<1`tN%hT4RLdM&VkqNpc&sgv&0 zMqXu-8xqI?BCspbBHofpdktOK;9m_>s0~FycdXgqM<>MM-51=j-55+G*Po@T3fdufbh=*xL#Qova1^C#xc%gaa3$`3UK7C6}i_Ciy@W6NJeJO|4yi z>-7^@6duQ1?7?MSNpWJ;L+9I)N{<-6`%Jmi_b*7?0=giMm*4AIiT%G7%e=dF;4{?M$ z<7K5At!TITt4@WJWy)7`F1WHq>59SgO*GEI>$(2aYvWEs1U)oZ%KR=ZfAjMHf{WrH z;L+gSXSTk;KE)@rsP$!k>iehHe4G9eeE8DGNAb|CQSj`!+bT)GGPxLZUYzR)x`rWi z#Jb%toTiR3bvRgUvdV}~PST&bz4|LGLJY4gU0)78L|#ZlLjCxaP?1`H8Mruu3~lz& zKll{Li!Xs{)bO6a6q&pP3K)a-(ORna6G@KA0m~JxZ11ekDtC+OfxAn20@YVapWK5~Jih|9SLZ6HF#x;q4$JoF z%u~4D%2eK?@xN28;2y+u%?M+R(oKZ;Gja1{Y(ep-|xyrkRGxZWYrb9-o!9=HjjT z`}O+jmXjy$F5U)gRNs2sZ!dSM)_IKQmS-(a*IsihkzwOkL$IhtUM*bi)a=DyKzX}VM$Jp6M=PNQ{|@5crbOtB6076 z0J#~b^>*j%wfi#n*Mt>|_ZSv^TCqN(VxnDeM%c1_R~Mdl>})me4b+T&-Z^<{wui6M z^r(=G)goeRK>GpU9b|!s`M@dDVIFu5*EpsuSv7>cX@=#$o9X%ZH@uQWkT z^8Cb^86(XF!REFYK_;Vl*9E6-(jceNg;)=i>*RBm%U7;kA-sx(PwRp4?=NCgI4qdeCzTe;v1IY|6K=|&rPw-nI_HT&Odj?gBa5bLM1)s z_2;k$4?U)u5JmUn|Ho)lSU6C=z;fLGY#I2tnT%17fEf9U(*O4mFtGT*PMg!(5dFCg zQ&M0W&<;ws`+v^f9G?_5B=+sfzfT7}@<#-i20VuM=-r>QA0nkaDDeEu_WP1a%{@PT zk{GUbDniZVlsy|RG}vBBk8dgU!s^bm6TJFCIn|Ha{S!e?h6>Z++Tns+IJ<6&X@6!1 zYZ49?{#`b)O)_3O^52ciBOZ5eb(lV{_9*imL`dxdjqpwA=|M6Ih3tGK`cU5VH6i(3 zD2rP5O-iiT7vFrh7xfV`qoo$9%Bivs`{W*+`1dWQ<-`(tz8)gwO%hJd zs`fQe(kI1vcR6UFqDbdO_r0E4Hy1M4qCpO-TaUL5zeZMz{8?!4G0)weRzk__Lah!K zDwvT#{>0Ucj-6I^ZqNR&O_1g8Nh!pjCBI3&Lw~@9U$G)WH(`%wR--pSw z3!fw^4!*r@Hx1E8hzu0PnI0s1%8QG8qVjE$%_j=)!8M^fD+aN&&-Pc;n!9WziwfIJ zQ?)H?R7Z+U^d)Z9NUWR}$+%gavw4TX+~GaEE(LzYJx2mJL$xT4M@Au(Q6Wm&pOQCV zsAIQR3EI36@6PT{edp0YjxMV|6@SS4oqbYX<0#0Td1qcI4ll5%v~Prq+ZrZSG<;?Q(?RH0D88{eHibFt?-wl!`Z3r zeEZk6MsbCjlwn5{*pJ4{Z_ zU(O>dyhSRp(%jEZdkPKYGSur%ALj9pOfElieN!Cw9yx=Uccpfl(SXC^1UaPCTVFx? zvW>`>2JPRfE)qt6ICoi1qe;2QP$5G*FV23kOZ;eOiM~AmI`Im6$J+uIx6pF@4mW&! zAoYoAZ<>O^Sg=w{MtYnU^(BjmYRw~EhtSobT3woJw(q2xIz6b2J%{%Vv3z z{Q}+8T-i^WycXiaZS))b9mY`oADmr;SAT^olYFcPW*8b{rcGO zJMov0aYLz1vUU|IO`KKWriRMCDgHiN{5Kxz^@wwH`x9}*7Ja4Fbl%PtQV&qe- zctPZRb2C%yjZi<>bgq8XZMVupU`@&r#Yc|rE0@Bj-&_ofc-N~8+$UJ-33{| zb$nqrDSGqo9{VY+wef~0y{Sm~#@9*h$@6u22P?;LL88=(i;(`X(P@YuXIjv5 zw2gsVS^I;IG_g^>{YatY@#Wnkv%Kc6>|1t2TdNgzx>i)Jot^xcJsq(^23^;lfA!}d zpFMD;jh5VB<Q6d)C&)x?o#2RHcl*HH>=o##<}RnHvYpayO4QT*y(V(+QV3|GLwXgObe>(|%hJN$uvp z2G2A_+quDXilr%ejHfc=UR>?5^EGUbVGd?g2%4ef54#F;eMrfBwCf(SHdG+lp(w{a zezX{@)W*6Xsg43s&*h6T2L+f(kj+3VC3n4&ri3fh7ybFgHpLw*0`>>WQ%~L4gcAyC zX=oM&G~WkJQP*zJ)GMu~cV$g2BoVO(5>xSgwRm~1IYIoTjs>!(dpR>PT+dmiLv(>U zlFK1;_|n{5st@;y)7?r!Dd-^EGv}_txC)hmr}qXGOmxi#vfs0^*NvI)J1>Q*`{|A6 zhF(IIr=`+j#SxIAUfich@WY2=@kE|)Gz0ls-n|SGOdJVZ3GB!q396GQ@`1$#9Nv02 zI6nL-v~ z_i(b>;B8-)_F(mOSmzDDy<2o5tqX06vGVzsYaIfnns({M#c_nmXb-mDafy*%MBx~7 zQTPo4>xaEnhG5l`;p-_N<;0LHhup9D>!Xnx@7_!?UCERhi2P9B$q)`>(f<;#dtOWu z;wBdn*MJ;5`% zcO&?4uiJ=s*BQZpx1Xdc<6MH#x-tZi&ys$-f$BRfeTf4th_8G`0Jmoii@TO$gukSg zy^>o8JJNM4sXm;K4iYg55|lskBI4kA5)7YgzqdJa-=7Qrvy#UY6MW#*#CIxvY+<=8 zQBoOgO&fUE1hl|!4&w;jw0%ck-U(J})uS&Zn_nF+Y|wj|ROX3J%uXIL%55ea9qm+Z zN_3ZbkJ}^LZC5PHB9Sk59?Ubmz1pfze_y)Bd3UzG?yTm(LPv3z03PFK0|kpRA1zf_ z9z>w{q{&dlrri=Ln~UDN`FVM@Ctp+%-edejDDiJQ%itn$oxR3Yd>eV}V!y`d8c5;{>{G1TEx7iydC$LLuELhR`-uO@X517>WsrgpgRMAntZz^M2wLpY#kpGc?l#vwTM1*^YgHo!3HkcS(e_)8XEXa$Yh|kTM&r)ADZLc2)Zx8Y8@0#)>Y)vk zKO37?Y2Xz$?K_rs$9rqr-FT2Y?CH22Ya@+&n0|@%os;2gWGB|n{aM;dr`BhW(;M4P zxZ|DFfX`nkH&0hIl0FJm7hq4%ozZ3I9~|tejBF)=q8`}lpiUBBx~y(BT|+!1YKz~G zaXm~ufnwV`q29cw*DVPxdg1GOFpU?`T58;_Y*~HCh~ATf+xiB_7Z%(DR^kOMPscRN z9CO-S_cYbrP8z1_b5E&B&YZF}OT10$p2RvU7cFz(r7REbNY;IMEtZ5%fZ^Uj%m+*M zM@zPgQ{s_lC}dBfzLXtC$vKHi+|@D>XX)2|B&h|fD!pm4d6OsXPiq(tOvaN^7biM5<@Q~3HIH+$6fdGeI___h4Krza#Un&f z(xq0ThGz?Jr_vv>dd2rZ7{C`d!**1#>&le7Jt-<=onmFGNh_nsr8VGNkzMVvVeIOy zA-a-GRsQJ2M6Zk^Fl)TjglceKrr@i!^$6RBU2922vk0 z_meEA{>tdLQ%!MNkFQ<;vDXE|Z{3y(rSsgv`!IfmLATTkB2_axKSh+^pEb6iaYphk zw|quc7_-!wVIt;prIZiJwICMrns>a&i@Vwj^BO+aA%`vttOPS7PLz@#>48T>(8^^n zYI;FLW)_Ci;xr^P&(3%94R6FlpaFTxi%%X;+F^-|Onns+^NUyowNcp37t0`k1io(HpC^T0IB3O^@q$)ScS4^5{2yXq^d)1o`r z8g%U*EeAgEb7=Gz*Xs$G2#1M)Lx&Aa!D0lPrf8&SWn=;vx*$H{E;0OXr+!tHluSmc z%5561U3xHgT`lkG50cpFMZG=pyAZc+-{An;UVr|Uma<7c zqYEW84pn2c5FyjJ99TekIRz%&!89G(75b!OdA-R$Jwwe zJCfU=Cq>3qXXeZHr?(uk$@l$%O>jEx+%^Hm5oDNo?R>~o6XumN#%PRsrNZ_Xn@w4C zO7+jF+Ql5AuV5-|F2r0sk_0hf4>_y4i3E9)Z|*>bN_v3c4MF?p;NXX|3k$8h>UtIz zp3>MiU9+80;AcQ-!yHD3CTd*fygjk!Kq(t)xe&`l#-tDw#cLLoxDss&JznKr8Z65@ z9I4uPcgEUO=`x3$@qjLUU4JGstEYeogrH_^Ccw?%PFfej}QE`pCm zy$I9P#W=fSH!Qq+hmMb$qDRfxDBQZ@S z1a+hm+JaYr1sf~zTTR?j-(6$H)h=sk2K6*|9DF2u#D;QU(Mizibj@me3Y+9jZdf-G z&Lb~4^Nt&hO&P9)?_OaiR?9xh;dfZt$jS3L&2&3o!;h*hthE}?^Xx?UkhFTf#GA`l zH9wq8l~aI5^INea=R3nI9af?OW%FL*k+fvx)v}O?93*IB@;V&ZFO5|cQDC#epPsq) zVqqnsFCB>#h)A1{Xh{Ji=;K3w5l5pv7{5piLi#2L7^}Hk$zG`i-b&$Rr`?jlwhCcI z$*3-xWlcV`v;5+J&8(xOJHhZ1F#fjNO#-6nQrN-dt>LZM?xjp_AgML!ABL zfr;C@G+0X|*`n=wMPW{Y*nI>AJ;1aa9oUtOTYWBE3o=njZ|MaX5y#4*@IEoktp&%W zZvv?9so5C>G|U&2^LQI|9F;wc@7al8?r^T4`y!}8HIbe-}k)%Fwav~;DWUEOr^fVr5{5*yhS$L_KC$2tRjR? z45XBBjl_GJ)ABL~*Ks*<=wR)acgru9?}lkVn;W&dTIXHkxR(6#KGW{9>=oS{?iD3> zu4x23msRJE{p!t=<9+@tzvccst5WmVuxVERYzytz(6d`U?x=^h>N#B6Y1_!{HmYKK z@<0cKYG<5?OWUAn--nA19^@u%cdoc`tD_S$NuLWn=}Hh2N7Pp10*T3+QZ&SJ+6g_= z*;!3aQ;2RUXNm{)yGY3kq6o{ky>{-7=9BD*fWPS6*egC0aPMFD@E`&K`Ks~dA9(gh zP;k)X-3!jEmG*qQyW17mxIP%9^!_4K@W&(o3Km?XZ+p_v*%8B>9t(HwYZwIh*6DYA zE4mlpTle@4OsFVh7JW2EiwTL`O_barM-}k)qnbAa4|XKgdlm=Z%3kYMH@g?;aH`aY z&76uQ(vWT&%A#DMocfJZ%4+a*$tOUsAxA|~@ZJ~T+W|Ppav{0T2vu&w^}K`H4&MC} zWB8*lTE}e$8HWLV_54sQe+H)$mg_jMuOMLYgYQvKH?!s;E!{wUIH~m7E@M z!rxTyB|3QLUM93+tya|4wC}r8oD?masj`vt3uTR9Gct5g=}z?ww>;}neXuf+8~Vkc zsx`!z8k9s84b<+t2if>o`rf!kz{e& z2rOs5j(j{CPOHowHudpJ$51M(N*S#ZOAEC;jXWi#o$mOFf@HyCsj_T`wE;G|%B;lj z+`FJW--$_DZ4Nd#IoeguQe$&^+VqGzIWt`q89i*UQQzDmv|SA}qA<6wIX4SY1Y9?Ssy{EYcO#u-a2aK$<|;XA>kM zh)KhDr`OTT56Kc+eA1S^%v_g&ubYuv9{_uGXO16I{7#G%9o5wR&wgvE_|+!GY&MOr znhx2a2$-bP6=P@17UDT{EA0iBRrl6S(=G!`1ZbrV%a@byu(=G=82x?uaYV*l$woVinj+PP z0lDw=`v8;7T8Y)&8!~{ovG)*#nyGwo}j}B)-AEF8CP4$GIL$m zZIcexgn$0bLo5Nk|Gcs1&w=M}mU)oxyrOAa-MH9TyRX*OU>Y~14HAW)&y>O>L+vaM zC=e2z47vU2%#mKkBz7r}AxP=VT+7CI{tKVRQG7hK=`&l$UQYY1Tz<1R)9LL;;uy@o zkNxKfp(iVTwft~E``Op7#8f<}NM$V3>syBeM@1hGz!~XcNK-jGY7M% z_V-SP5^}!@=3Drf>s7%@-I1}YleG}QdsKoFQLcaRGVda--7i}613Ag6i_8mj+{msHW&8v)=rI#U??f;!CiSb${lP9|wuPCU-&7NfxW890GGUuE~a$ zpMEIV`_N0z{H2rjB7Ty`Idp>HPZ5>7+)cv1fMq^uYk8mG=e5D`JV4iYgQNU8IYTuP zJ2UV75qDSZkeTiG8sb+}a{22jYj`xAXOE?xsUbBjvl6I*L%9CYlxBm5gxJ}h0g=00 zaWLCkofQ%F!~VWEpx(R($>F=lHR_YFpIm?wjhu6wMP(iAysN%E?5sG;u=J|)@)X8q z2b8zknIq_nhzz5Ti8^lS(pLI)6G`9Xfd{+RkX4otLLP0V zxF^yD!fBi}N59Bw$=uzXA%KS7h{VWps*bk?n^eQh``v+k->Hyz@SlgnOggRay&%L^ zQR+lQ))#WG65CW)Tro0I4HjrQ-}scRac+#851YjYCohT%ZF36({qv0e!mM7MX@IcJwyH|Fx1 z{?^-0a79045Spk(LIRJ$xea?IrZ^&ZQ{c`^u@J1p(Gm$LqEO4v2j5!pw`SRc%8x3; z!}Hz%YYvK!w-PN6xGb%pz^f;{GIkiQ*V{9@y|eSm==y=o0kfYTUNQk(!i9noE41%; zy`-x3<2mfq#&ouT1HO7C)O=J}ixREyY(c3-s2;*=m`hxVb0PHM-}laAAB*zfR(mtu zqK!<}lR$6ib3?<*Y`VQhfa_YVMqjBWgs)x@m{=QLySh&|6^en!;liNlC_?>Jr}X0U ze+)7atFq9@SWV4l%1(e+)iEu-^|YABZnQQ@mF>d`%Y#&7@<;7sI>^TRf`ZC6yQWB| z>v&?I)M#wP+Pd)c+c=GizgRYo0D?)a@cjzIqHmob+uz41W{qPXiYO_O!;bfAlP5c} z7Q8CJ$0QZd-26W39%f)JN~X9UiUaLf;LT_FcJ1@$s+y0A)YxyM#SRXI%t}$TNA=_` zo?Y0Hoq~y>PS{s}@kKoBJiEG#%nZ{A+^VaU{W=JHRBu;Ge9>Zf1CH;!+Lm3i+b+YIHe(eNYLE%xb+-RRjgsHgH~JDh z8}|b5_Le1wOxpV=cSvccY&^(kv_Yp(J!?gl23A0$Z=U(10zms6fjT24yR=S{WGNw7 z_ay=a^*!UEi_DvXydt`avI?QWz(7K7b`V!)Dp2*ler+~T9#zM7cvvXNp;W6;qop=C z-{PH=qp4;@(FA+$8c>=x3ofzRz9iBN*;K4Dujfy?aDn zvVC=mbACG>+xbU2fq~V`_Bdy6%k-_f@nW(kg8b+ei`nM3lVz@^h<;8fbEjs$7Y$Pu z;);RMTlk^@KdM{xK|44(t0UQ0s^G}y4*M81M!#Dr%*&?tS~S)GRS|IJ%%akQuDFQy z%yPB>EF2M=&uPp*9c;pR%slmDje2iBA=e4vQSI_i>a)g9#IH|7qs`Q27fUmZJManF z^3eIrSD7xAOR2f1ky`eSh;a+sb}p{A=-T;?XeN_~<~GQ0(~JjO61Qm`eykHSGVLSr z%g0QAshHx5#B`FqJA8Ke??_B~3v>Ki>NH}!D=E9XY<0L7hv(&e1mD89yDlOz@1J1N za;VWSIY~NyEmU_a`eFzOCDtZ6{zWd?NcVCdF_$w5vUg?pm4XZi-X9D8q-v$IJ z{oZ2asUe8C{r_<)x5@H5_Paw_DxWe$t@Oo-%vr;0li6SfB@5wGQk|^M&pu-4YYb#U zbT6i|CSRJ4fq2Ci#(lhT1PETe$%=?KiHJg;yb+x!bu;#Hv*+QS#OI|Cv#R*dhq27=neh|_@2)$8>{cI?Bwax5{`4d zZ8U}CjB?Z?_I42z6!Qvt1{QKfUhyG)kDQvm4CHHwh68xCZ&!1CTKrw_y4hy0q0&{8 zs`RWr!LfwCZ&g|5p{qw_5Sva2KO4)bn+)CS-cxHRh^}m;M_LXY3(TW$g?2 zp^unBNvO4kJ-#Q-cj=q9bVb zM;kIM&Cz;UqHtGSX`_p8f<4X&JID4`haQF&Ieo)X;{N+mcz7s*$Xgv-o@GuG*6s(f z8qa9Q_B8g2@0!mcHP-jflU-F^Yao`@m6@%7;HuY{DB_Z8x~5eN!NYz7quo(mekI)P zQkn4tu(*`#;BNf)m|tRG(GYDS7jNI}rz3rh0YyBV3YC251+nTTV>@78S?JC_FzHWv zEj`^$8p@&?gl@5gb_E`vYYl3Ado6tJ?;cw~tBEI#Zj}rS7B^G)eB2H(=FmAF&^ni^ z#V`mPpR^HV%YQmI+EZ+z(qzD-6muh(NzqOX3AA1IyTXJ<&LdZyczDu&U=gwS2edux`G4)Hn+8zL~^^Ml$lZb&&Wd zK2_(F_2(BM=Rl9svRj#u2%!i^lkv<3;AY3rSCUqsogeEz#Z;&SdM}WU2&U0mnAzDv zmIUr$UIEE)9duR^G_;0W=npEM&0+^BXE|>1v5n^%EPR7R6&(7^I}93rt=g#8HzI5k zL7hl%CS#$5w~@xjB>sU^1fU6y+JW9bI4+o7=tmIY;lsyJzSk<`op7M3C&D9y@M?wx zzB{jvNRntHbxq8se2of9K5D|H#^z8_^|LV z6Ko>CCVPl|!{0b0XO0My_yy=UofDeQa&oaCkj$k~vNSdk((0eVSvzQNZP&2*fUU1p;eMjahY4F%-0p}7QvTAM; z7|Z6y&E4*!9uE8#STOHOp9(v=R{x}!OhceSr)V4@Sw3@-z5kz>gnys~oL;)2WiAgD zrx;~gT1yC5sh}VxQe{(rS5^IZF*Cl0z0_IIiLjg>{Unrt1}D#1XBT%-;W$ znxM|c%?10_PZN`aQi%`kkii#(B$(N^NnpKtO&Nk4)<7&m0UB$CYjhbVFYDzYN~RFyK%>Ibb-jDI96C ztrQl~y&r0GICij_ze2}JeHwyl zy3#KEIx(DTa*fz%)IqKXqL(zyg;}T_8y~2| zU1f#0s6gvS7!PFf34FV*vA!ZWag?!2BdqJ}5Yb9^fY1d%brQFSCUCTpbl_WmuMqO{KhJ=V>Y+2r?*T!^Cq_&&Rm-_^YA zQ<|~nQZlfG&YC%BxtMIh*kcM=BdJ&7bWhXuXAwSN7EbO`6}c?&4^r_xg^|96 zsk_T<|CJQ!$iYN+Uo*K&y?W(I=fIV$&13D<)aIp&pF#_lFPy+N0RhQDQ@f1^zvlsy z>+buKYx3^>s-kLvDcWCm`qz%{JZH}$K)SJ>mka3^#etTl`GcbU-(zjod6X=tE1PDT z%PJv`5{%^TN^*{vyNx6mHU6aD02wuQzPnc0)&zw4TR z{12@-PByTfm|FI7 zyAm&=$|H>ZetC)?-vQW7WK$EHRu?lR9?;IaJ}#gO_mL5DQ9>`s0#f!DEc5s3vFIP; ziXDC7sM*xhbg7dT|&L!IeY{Xk>76W_n~e?0k|Wn9slHi zhysK`2-w08GX3wq08f7xu&iW?DH5UoeI7tQrGN*c5mzSuV=UT0W3;2?qu;^%=g|JK zg-vv`mR>sZf6U{O0thADhObWlyG@{2qd|up92wp}=OLB^esyEyT^HmxpYr!o{-$zd zpwY_zn4>fgKqqHGQk9_)&8RiGNP;E992g(o)TyuBA^cMDE+(9Y%tmcdrH~MW*KF?2 zai5pl$yK=La(es7)A)$n^hfs9?>mOq>QsJQW|*^Lk#Qbt3c! zTjPB_PyU>Zqvu6>NHDVUIfuxBjN^?jh(C`I=b=YK>`Q^HcmE{9zm`OL(F;O@{l{a) zXwjSu%vcTY{~;y;ecbc^W2Z4ea3xs$%ysL}r-7EQ(LV?IYjFGzz_!Gg!k+vVMt|1V z0LQ`pA7>^8Qg5s~1?T^Psee5Uu+}MlefsA+ETE4d>+&_w`15Iiw%PgTcF~eP00_K? z;;n}NI6d?u0mJj}w%k7h00a4d)A@*PHgNx3)NfM&y_PAa1hUrr|JoOLt`{WkPrLiS zNAiD<p6K1}3>n`^Hu$YfhSoHTr85bNjXbPIXdmIKJ{$dQx{XLub`v zH|S>mpOMGa;RDy-lB-+wY<#3-`)DPvwF%;WOPkM%PjA7N{Xwd!s>yI+Di924R@$$b zisn7a2txYZL?;w?(dwM;-<=PpHrDa}MmW$5sMA0Ml}oKA+0hh|c=(YF{PfUBd#+;1 z*prZ)+K=nwRR$w{ z89_zQd{>8yq%zfVSkg7+@G}ilsRfyr#n(?;qu5u4I;6^rAI^&9Sx7NPB$iMh| zkrx`YULi}l=8oD5;ZyH{teCg5kV$NzO% zJU?IT3cXpwUfo5#=<1xV$R#MGy*!w=A%o{o^7h1irXz=qTHArjsy&LA8}uIjD$I31MaJ8XvXw=Iik;at5C=I8 z>ZWz-fV<>D1!5S#X~=K68m$Zt48Fubu{ZUSF(N`#-#f)&oqBhfj98CnN3#xIBYfMr zSaU8ZOShQ#B>#f2qeOO=X|WIjT3k-cfOXF<&wrD=!#}jAX7m z-ZpdqC67iJc1F?@Q}S4&3^|GY zYf;~bD%J+H+Ycq7C#WJpm&M|MYwd@EiFpwuBGg*PYCWuTa(CK>E7jfE){YY=duy|G ztJGj_yQ*XnYom3O+3cpHY5wx=M@!!%3rgO_O(VZhS$$0=ftm}mSIk~=+9_yi+vDV| zJ4}n79e+OYeup(T@I3L50kxPKt6R|kaFr>l zS!!Gc%a71Z(13;;y2HtyUm-phLV-7p=A2u1*$B1k6d8O4tsHNmp3wQw#N4#sb0tSI ziyyTB<+57WIb6{@Ggae{br{g(ve|wHh_{McPdbkG*Mbj`3$33C$lB;SxsBR`E?m14 zu`y{s<8OEzbqbh<2G?9pPl+gd zSz>Jt`G-D|XyYJvA8_mLJzJd!z)886xQCm${>l)2~?3c@==SHNEOKFVrat4>xsVmv} zi>MbK=^-D=e{uno$nj}uL8X8rMfA>{1Wa`vM))88k3X-0Pc?aIU<1Ced`Yr3Y=M?bhcd*@1qSZ8#lYE6~< zwEzCX^+0KKG0Q{c+Y_#R7IRZ15rTgsM(i~O+C4M>aL=@9SQevW3o@JBJgjo3s20|F z>bNa3#t4sw_7dZ12{idxaBoO|4$WfLu18rfQ9yf7&*YOSded92;7BT`>Bg(6;@xHw zC1*#3M}QCC_CWM#HaHo)Fd*47oN87ddY*UQ?G}(0Oq?U8CA|SojkY~aT_3RWWrLit zfTo}9ql|&{clVNt?hNUSRh4C*>}exSx7(`Lx$rovfNFNrQ&BvAtG*`8^>Je_N>vz$G z+lvbUAj_D}5Ti{3r56bvIx!O~Bmm>4#5$!ptsN!P-~Xz5a#Ug1Rz6SZbat};T{Ka? zH6sFT)5MNA>=ZGAHN}O8GZ9nq1QKynN}tnt9;=x_);`_sJb<{fIFPHZ=d$*uEaf6< z$o&SITW-Sy4nY{30Zl%BM*FK46MHX~bPgJ>VxF3Y*cq*D$SvQN?Uu|~Xpd#B)LQ6iWe@g&IDPIP{kkI# zQjPg0LVDN`95wBV#uXB5KBie7_J4;rZ$58-|c{1ojHZV*WLbmGtNH~D35XBthCQ`kuCH0*b59ZtBInrYtqXa#)uoH8%%VhU0$5TN6X!{fo5+U~WyTom6 zk&B7%Y&5 zF`db5y@j-hF-IiZ_Wb0j+SB3mG=)%D-LdXxXNAq)%6oD}?!2g;-j%`ZlL6Iqe7LL; z{ejJ{#zTBhTc9ao-e*qu0YBJWkxoO)A~`}fkjS~TXsa-7tE%?u+p9omSNNj)I+F0P za(B78uU{|+I4s(ZYVe0i+gaw{}pJw%9#?z0ElHOE#wCw zE`%-+T*q~fA)s1t${Gax{ktz|S8`yLWJynw@1tL{Fi*aE2!?`E zmUS~11h+nuwXcki14@(ST)-`<%^83Ck{bvxt?jmwllPa<0_ctuG+bE8Z1fTB5qgMj zm~JNLX+wl8bsmY!%LHe!y6uP=o!mqn8rjLEwuH8ecUr0+X{;?eiN`7mwO0?EaOBll zs*z|823!-GT`lH8jv_=4Kbw!1FMXjh0DN`1BXV`=m4{`m#M?GKPy`|H1Nt5w+~DRK z!J2LO>y>QVxRdQcnmFUVhdJE~fS$ep-184OQ1-5yL4Du`$cUU= zJg2nTpyDZZ7Yt1Ey_4bjj0}v^T#Z!JJl(HreSKB;2KprrN9`J&qR4l`yL~D>2jw%f zhgV^NN4qP>Pi5^xJJHJfhX^P;V2}r0y~-9e6CecqY~w0Gip7$pm4TrT_a-ND&UB~8LpLV{E!)I|i zksHpFwQgLCd!uvlS?Y3H3mxbTC_^caz^M&3~bg@vhAk1NzcjrPnV z1)g{n8+S{D-O@G1qU|_fb_&CXe>>diQ6mMm>c#mMh5(M$?BOy|ATT=*#^A*7h5yhc zup@%52l-+k2mDrhOrrRj8zy$heek?bK9Bru|2jZYX<74R6wKVnu#=O8!a2d zktrqBnMgs~q<~2ffn&BA$n4SL@x#;Ojdt-45@HDZcVUn3 zl;Y;hwr7e)4?revto4O+S%a`ah;to$+_e5ar5n*`@qcBGX3>4izXTpQu8)~u1=`Fs zRoz*Ul1#ZrbhRadDUS3+ry(BChd4M`QFIuG(b*(nmhq9FBb;}&n`FE;HL=qU$nRG* zi=GYU>dwnU#^=*mL$di_Ee%7hY7f)SpEf|+1{vjJZjQU`aME32h0DefqnSF&ElfXj zW96}1;8s5T7Iyv;#aNmFWq-Vs5+K07SNXJ%MtoT6S zfn$K0Uh7(stz9)x+*NL)A9=?js@P&M_eC}(>C$p46m_~^=!7&}vj0M{ovvBr*TCup zC_x-FO3PwsPrHMxrM}O!$pQ4nS7Ag)V`7KjpOHQ@0oxy+-la(Q7AO7 zo7=hXre?MAdjhczVWd2T@Uu6XB{M0O#0vH$Z9vx>yt-|#G zX|SulvahDe8bVmdp*%j|2RTudWFt=YCV{Z;swn%Z9~tBC0fi73D$(az?|i#*nWb(d zuS;pM#puAJEX!UJBqpQ>x4Fb{s?mUxa&YBu zSv`J)hh=+DKkM0eRhjViVsdV&;p?EqD>sSVzXVXw%h}n=zervfN5dnwO|j3T%HaLk znkp=#0tcEilx*&g&)`M6ruAO9Kw0$h6=Nmg&7Gdj`*pcb-dW<=T{<7im#URFKvDTr zW@YeWx@1#;?a4<^+i$*1vOqST;`L^Av`(+oeE8`FTUczgS?SAb+GV)}108o(vcGMb ztqkPMbDGzvccQwB+{@8Z<_E6LvhU_^og=Xz{I+PJ!B;$#&(MlJMNsvAkg|LYwK|)D zq^2Bgoq{>SY&MVm2+FfYzk5{c(6LpDuJz>?W#bN{WNyW&9>z zF^5)Nz`dr2V0!dlk`mEAULNZ3?&wP1MS7_yawX?H*qwpMPEl46B;{i7ILtP_CQ6kt zHSJq}1n|RVW)Qt%kR2a>HM2?c8S>%dca}!W@>VASnM_G3oK90y87PLe4dkktM>13M zob(D@D{g6*%GVwqnH8}}m5IN$D)XzXPwE%f%Clrfnl>VO;U=T1S*qMw9_;0t5*3R{ zZ`%%`iKAn+AbqZ2r*EM4a%)ZvZ^`$e;i{)XGeoCA{nq49Y4F=YOJBkymQ7QNXXj2+ z;C|9vLP23Wx>hC!FfU=Ut^_H)_S`(~v%P4mStu3XWyn|aoC5-@Td0-9(VXj{Xx*bG zvHg-kxD0Z>{cYCy8fbCcCYz4dM@#qYmR-2+^s^l09t&OP0HrLooOg*dvKG3_oAGBT zDQ`e;Fp7t>0MI13d3e}%WGP)p6g5)RoOm5@^J_p-vXLH$`5QJ$s*S1ZWV-;~p3wwx zd*4_dpVHbI& z0%_9rD6*4(G;}21d6^?mfuurW@)h~1+N~8nq5W56QkktCZVL`;rX83qaa{NAJYP5W z8(Ml9>#|y`*E3V-vTvzb<6Lq}vs$C}0A<$;1+VGB)72ZVbMNypVd|!Dd2msT)(cc5 zh;!(Q4mkEZXNqnc54Wth|vk zTKt|y#5tlN#-UNk>6+-8<>e6Y605tQSdy6?PPF=MQa2JjyoCom+bVgN(l5bc<2=R{ zzp^ixLPR>#o&715Yn&Y>W5PoMBkT#mi=5C=xBg#H@el9#|BIGb#1xa!)>G!s|9ZjF z-*@k$I#z6lfTUKj@x_8p&=~0#-X^Z4WQ+YFY5P~FGDv!AUfb$Doup3~4G^V__=DVi z=K<%VA3OQmUB>tR2++}66ob0z&YNWK61jjh_m92ze1Li3`MlE~KL^^G{}0=gHGd5p zNv;^|4GeFOCvM1Q=eoqMb8#9ZTvhNb?XNbqQ(8{C^vC4?eq9efChMw`S*Ld4(|tcK z2cB#b*#FblmB&N9wr@F96gpXseL0eFP+7B$3X?6TWlV^iBul9n*<#R9lA^Np+QwF5 z>`S(?wJ5R-hEN$!*0PU%d+)C?>h$aV{bxQO^DOtX-OF`dlUZ__;PRZfoaium18Jl-gAqAy1(!iMR7A;&HiY)S(%sDnb{=eN)V+cQ={)k zo9%%E6)2f}DxrD{w+6XM^a(mn7~PtdXp$14!-R^TJi+(@?YO9t64_fU6E|=MZ)_M=*V6LWMx}TsLig)Q-Gdi$Rg`UyF=TXA`m2=Ai)cxu z^CAvx`m@@IQ)oRK@4pkNV*hcQd5zhi`4|bywJA{;t+qBfHgDGb3dVyk`c6~c#|j?U zEs1vIVb(643?!o(gf;*zG?g&G&C-zF-b#F~JkZE3e{K80d?kgJ04*ykDP23}p>$qL zF`LW>6M1aeUz*1aPI*hUI+5GwtlNhW3vSO}&|g1JSKjNP?u*ty$+ve}7E6)w2?+kziWx$F53CiW?P$Ti(@ zfW^z8x|NJN5!^7ETV|YPrgzh`rTv5F)GpcEvX^X+%BgI;(KIzsi8@)@T=L$D|ASEK z4l%n1N8LoZ9S+W;n$LW7V2nPPjE=!MCp{N#c(ZrYz2AuUsn5hT&vg*X&1~{bSL}-m z+Fo~Pw%y+IX`Fkc<)G*Ko*X{}bJ_OFul3h4(cPa$n9oJ?A|3+eNM#)$)Nv76NuKYM z^RENOb5AkZM150qp|rHDtZ~2B=g;=dB^%Z1t-!(Sao)poYmEo-&=I**_?R=Md|V&h z&N>y;uU2Shav+v4W*>|-8<~gP-qdYjzP**ak%hx(tjlfEcM8ZS3 zR?9(L{{epeg?3#e6SM}#QPvD85N9eESH%?=Z|%dp{tpf2>JCa4O6!s}ZhwS4OGRCJzq ziQ=8fjD$b=QJHfjY;$+wfMAE}Kp;i(Af926?)ByL2HH`u{tpmZpQ`{?e^W#3^#i{i z7F5aF2yw#Y00(Qs%(qSRQ>o7Q3(gJI*q5e|>Bya)#*AEQfK5EE!^!AStoZEhl^Q#y zdDf@~#IAk2Ai*TNgi+?GJO3)QXtb4%+Z}}~;zJj6R!R&-lB-I8>$%KbUd3-;_~XuL z!>Q8#9f7c^3qbzX>$m`Y6IdlwLmTv6U^g_*RGjEbZHT%z&3z8HjW7V_$+|{FouvTJ_*uVOf)3E(WoadnbmPc-JooMex zO4Z+aYARTMA@^7ad}nTrO-!9yDA+tQu&>$v<)ziw;QmHays%-sZV_&9W(<8@ zq{dew+`Q6ZT*1Cc2u%h6-4L$2J5*w^*yj>p-l+rinKHhp$!;Q~d?y5HVDJ~x2Wj#m>%G6a<%y*J~_py~+&KV3)e@@+Ezp`yxERVwM z>|m!cRbC~v-E#KBKhn2IIh0P~qPkPVhYFxXWHGX`>FhR%9V|9xJ6urToOPrsG~`&# zFtwRsEXdg=jzdeL$&rb>D?AdVs4B4P+O=$orxqkJckI9PcJRLa8h*zv&Kry0U|#EXWt7XPQ4X zhF-a*|!pon|po2|Dpm8@|(*`cM5fW~x` z;8Fzv(b1f}O1}TMh~>mTUs0aL>Q5L+Q0h7vHObq)vb^{RYAk&uMJG^qedyPX^!>~y zC2linb!JZ1{!_?n-@^Ij0g`VomDm3bLXmJ4y{F2!#!|rbzQdHv27vZmsvkS@FvLRw z)WgtVjbpHmEBxkC0jyjBU8*vMA@y(X!wX^DZR7ZY@~`$4Kq2_ z7a(>x3^~Z#^Y7>=ynJKCVZH^!ts!0u{kNUcQo>doZU6vx=N@|7O_xJcqCez?|BHj z>~Xa%6u5c19UVy`Zl;R?o6mu)qSuolp0D?zw5ReM=y>NnIJ-b&@b9fdfPZuZ9_ z9~4GE@^Vb4>YKQ`HszPI`+$cxn7xo|p<~t9AV++=zarcJjupSr&{gmV6&*WUm(q!0 zNuJ9~10^MsZ~Qhrwkpexy&QR8ObMHe&baYEOW+n#MF|1}L{P#q20WmdZo) z9)Tb~%g*=v>Levrgs9#oP;RizSMfcm>E*(7Fqx>yd$&wlaf!qsvwiq4g*&+o(6g&@wAbPh;xLt4l4=`dO#zglGZ8QwAd zbliW;&cEU0uN)lk8cG*@ZeS6C!^9}}#{+RUT=ghhR7Rcov6PDT94Qp=ciFeaW#H{& zI`JM|{HJW~Y~Maj@*26R)w!GKGxyiJP5~X&EmgAu%6#Hl#)u=kkE;oTIvlut-{o1C zooB0a=`dgIkYBg2_sCHDWWuFbR ze(4RPGat*daRYhLd%KIO_rmV#?cI3m!ysiJo3Pwu6l`K4NUFa&(mtQqMg0{qMr9wH zJ~RA+z}jyF-2697fT$0SEJJgX_;H4F$=6t}25;6<7vfJln4gsIx5k83evuTwuNp^> z7qlS>&*WmxhsZ0ytkBy|U7nLRGLB#jtkN@!H)S}PY;S=Xd8UzeGGt&OoZQ_scA+U* zq^(vs^)f0S)=F*c-8)4Q1pKsip0$%8{@7J()WkvCjlH7QH&C77H--3J28Ve-J)y_q z<5r(of#dY_#94VL#$U5Br=H~?=;aJ(f8oj<|eUE2tdXa+()ioiJLt~3wsr>(*F?OLP36%W}tyKdfZ zT`@3fAqn)J6q4Pb+5as?&qPZvOMVlnghFb?IOLT zAaiZku7kY0cI{y!-V3ihioJRj{5*(0{I+CP$(c=Z7zw!i6%f5qq4)_NsBHyXDdrhq*wZ)E1S&3LdYDOv^`%ml`nKm&uQ;rQH~ZoZ$U^*&M0|j*KUIU z;1AScqP@ht&(mz!|C4Y1qY1_%qrU#}VMffiga7$BcM~L& zz&Mp{rT&X?O2)rC{vTTwdV86g+?*|@_x^t{AHNK8NAe!ee>#`Qcb}hS#Hb3F?%)4k zm_1#RKYPojFBzZUbocaCdi}#bs%3X1r6)&NPW=}qBBY7_W#s>) z>3FBzDF2qvN(%pliHLax_x#Nou;I4vG6_$nbLmW&{4r&S6Q*+?d15oSV6xjZ+M$Nm z=>7fad7-hFCo7lRbq!tEnkeuXTGbf3M?>Aw{x{yZu%DQB#IdeNF`g;sxeuNWb?d@R zR!-Ti;(71a@18l0^1m5^l9YZED|hm*=2z8(ew1mnSN;0@Uw_I_>Kkewy+THIndQpJ zn_Bv)Lt;x91Nrr(R+U!H{4Y<%*S_5=*xr~*?XfMNQT(#eCc%usxRSQ(+Ewy;EKTsv z6tt#?5SvSowMn&n%*z!z>f*?CGeKw|2hR9w*GjeI~x+`*}rII*l#-C^bH9 zknnz8W%S-&AGav#GF2R|4WTwqvx}H{{MSY#CkY5hlb=O}{`IYYyn-nsh_Wftrs1=^ zUi4NJ<=?6-!Zm}&ZEO3Y{M)mpMzW_rv&LPiKU;3i|CpABMYDDBuf`%I<|Tx&5dG~~ zL>Iq2Gw|J7o}PnN5~LrbSY?;8OmSmW2ktqobeW}Au5@$s#7jzhPg$GcX`+q_!jx{W z7oNBNm_-y7ABj#H6?}%CzxhtQGoy1^X`ElLQ7MaeKE}PD)&wD}$ z$&rr`pNB<2OuP5j74wf*t}B1Lv*(aPYOIH)V_#0yhUKFuqM8tfxL{cMPFu?zsniB; zOx_EhStntgs9>k_RYE*BClW*Qwu=XRJUvF9$hSn0Wr)=&N~xwc z6eYQ24R2V$f@|W@PZc+=4OR-*yM3t)T)j1ryXs||^S8Gs3;0NV&DMN~Z|_0-kM$e# zEk21`8y#q6d3yH|>e&3LJ=BI?4&4^1F_8?0Fi94*bgo~vgQLzhip*6^Pm6)Ix;BO$ zS8E@d$|~w+*Bz&}2@zY-q7k}%%O#d}*k^61D@8Au|{Hb{(s%f^!fK;AQ9jkVT|2eQwdT0ll_M-yK5fT(&X%fe>Y5jn&sB-|)k~9!J@+#j zdi;gI$6C8`_{%JKcLYifPsEhm0s!#c&{$-r2wr$Za0w&bI$z5$(5upeu=J&Q>n9@LG4~PMfS&=~NI(c&+_V=1yH*`T}zr>9d?+nEXsdT*!NKzSf&G z#+!jV!q9EdZ?b1#+a+$x&}V%V@%&_nKMbpsRx!buzzZE-&9+>js@4RtudK5=|bEyq6UjcTu zJeBz1hy{gxfa82?+;&0FtSk}DUQ(LpM30&6k1{=_wJk~L7?rK$F8Ox1pn<<oUW^f)(C+>T_SlG|qd) z6!-4lzSMedv}pO&A&AAgEA<<`IP5^wKijUvgEOhod97v+R9HxEuDP34++Vh? zeHG=eW#`7HbDwj_KM>5viA49(?fu;OUoK2mVQ1@Y&riG#I?lt=^8vi2)h2xRp1n)Q zd>%%z-9+o_X7br)2T&y>)RYFj8RGW~o+0yHlh!eLp&rTLT#;b(rkYAoMST61j$;E~ zzV7jb0zr~D<82zcTq>^K_%dKx8UPnr60#tNJAkWd1+%qa7GX>8c(N^&!ppC!vyMZTZ65J`;pzhI|m3@W8{+y*FPqioFn}_sdX5I_e1fP??uSxGY{l*ERXL6Kn z+3QwS+_E9A&B~3jQMvcvVXnq8c?R#VRxu)bX@&-_cg8^k>{=gi9q`WA<)G5O^<=5b zEY4&wI?bZ@d9y?B3k{t!uDf1!RIfe70}D`Ll;q~-T`gM2@a0EjNnoByR;=~T%VKSc zx>)qxM_+UW4u>0fSmdB@;ns#jQr)hW&08%x7)y!La%-)AWp*Ps7O*`U5JfzcazDp+ zYwDS3-q0hC6zDQ9R@8vm7fFj?rH9O|FU3B*QS<4^$*4F; zw%@w~C&h@44vqfk>}U`e==EZeqMd*5<(h@wLpq1X`M8L@BjK*VL~lci{$$%85P#8? zYomr6D}mcwY{(h*f527To7c0AKpCn7<^{y;dS3I@VjDQfSXZPU9BQ!T4#4s0fF}~W zeGH-rqCy1;%3rM)bajv`v!W<@D0w-tnv2?Zz21FLMVTs@o1iMp_`Bx6%*w{Vn@P4Ym&e}RH)ugbPlnE1}8+& zQ%{iKi-hcFphEhbr_H;=9GKgo2DVp zB6p?RDiy#>d6(;#m**#S2R1ZP&B!D+fA9jL7&Aj)<|A@hLoQp?gh!8@?_L^a;v=Y+ zRXQC})E)i|g z{jVKQTlTX?haM6d2{lCv7E_F1@Fs{yh;{<~J*4xBoAb=BDn@tq){KT5 z#vV9DUapyi9q)8X4_o^ZaS7AGLvC5Us%3j*Z0D<7Uy# zlkKSCV3F+Bz`16#80Yp$r;{~lR}-)G8ib}o9JqZ(>Tpnd9QZoJ$o>-*OD&2qmM4mR zue>~$(Bv3vhHf^Sz$8pYT4h_fguGSgjcnGB>XrO3(VUpSvDB7b_B|cJIK1UZp)~ni zO?h(a{J;@>1@BcTG#^nl=Iy|ANQ#g+k@8v>G|R!n*nWR@3-Zd;Qs5SaX@IJ9|4RA5 z)>#C<*||uJM?1F6me2K1&NFO&+ZSVNqIL7(=@tO|;TneC%N4CxTIOP0`!6|uIWNDs zNPIyielW0r*n1NS^*VY$#_rd8HJS^T&EkzlK0QIwvYm42heIMsif2ntty0Ch4LvN_ zT&Neo+Clj~S;vtxy|n4I*wA5NNWr2FSlzLKVw}-d#=Kw~fF~)F!%3NbDgmF54Gcjm zUwE35aBCsBPgu8{Ef+{oPV?2&0$7<(r{ACLEBs8#`9|A2#aNf=H?=8X^~|n9Gy$oD;>B8?&W`TAWc1PWzMJ!=#enSc zn|Npw9w3=<(H$1}wN7uO>>2v_FeW9C_RJ7ffZSA$IE)tww()73j_Fa)y|9 z$>A&?zD)8R$s|o>-IVx3A^30F&uCZi*ayPsO6fSIh8C0TxA-)ErwNP`QY&8Qg(gCW z_TF`SQc=#2&>F<2Gs|bo&e%F>nMRm+=(j+Gi(cl)+gi@?RdVo@sYTrC-XUQ&*}g}X zj!j~&9y5g;X683urckv&7L_$D{K*zY?uN?j!gd{w zKKNe4c88&__eOJw&(|3M6V*su+6HGBr$-ytBI|I5nIiL3D# zC&%o-F`|knCTPqBm%pmD`e0`|#jrOUbBB> z|6x4Nw|^?s!SloJeJ4VZmCic~uHUlyh$CA8)}DU9$>{f0K*DCl{7%+e$IUx!iu+pD z$K&FxY}|#bZ4NSc{kWJvwb&#PM`hqPI5yybmAQXnp$H0S!9_d72-5)cC!-x3KbL26 zemaZ_lPd?GY%S`s?U`Ixk=WwJPIp`7G>F-{(hd{l)Lp!W?M%Bo- z;iSBod3EfQ02?f`^UHM)Y&afa@L4mWx>K^)DAEc+zV+pKW0nZpC$dzR5DFp^;B?eL zA1o7#d!+p4+kHI^?SZxYEmW zOshW}>g9W%Hk)rz{xj1)_tXde%d`wirKl}P&Nb8R{&JpB^0wsFpY55X3QY_aW~X!b zNMQl-qq6ZNCbayZFh24cqXO%Ei_l7IrwNb85ms5pCrst^4M3K+=yUFvLHn(ozun7D z&fQX*GgWJ|C&&fJ&Xi8$M6r#D#4hd`f$mTy>AW8LN4Btx1?N8=5g|Hu2-q_OZ@e!e zAM}F+`$ov1;tQ@>o*@}P9ZScF2PbYT2oK&r66uZQz~s)?(53<s&%2BI}XV( zrZ`{`xV=})2W+;*Abj#d7zHn=8Rica<+@8DFyQ5wpFvBrkcQ8l??^s@amrfK1mch_zAGtejZ>pLb1&1FOfNjI`#`;-Gp=@jgX0~tog8jF*M+FY?`WV4FA5ekf zT5(ZxZ5;CaQVp%$(W+UPQ>0)!V^CyQz*W@AtnWEf=r?PG(5!P+SX;+0=&cz$3n-}T z`D#t0Y{KM%XxgTGU@4yt*SjDFPF31|G^T8J5?He<2tly8o-H6Kqs1(B#JwAE^pjZc zl`d0Fl)tFu2EMqYngqb=Nn{Q4P7LH_inTnHzZ=RYBdf>~pwLW_B7%3%Sj}2JRoBoy z4J5U6gDt{LMnck$^yLOHImzw2uDCe&#<(^GAYMU^5gM}!^XdjDK#h=(hRdK1H!gwe zI%wmS;J1Pivdwn;@orz#z&27B0bA)FCk^Gnc!YE2o8}D;%sGgdslaB6H1M`w@y?zC zjCu)Tns2_LD38zPnsSq@}BNqr%Qd%qJ8Z@Ur$txgbXs zq|M{Qnh2^w`A{RnF7Ef>@VvMQq}k_om|vb0;zJ*O7YiURivvIE`4boy_epH84NrHh z#=(kPLTG?2NGR_94I9%X!@-kJ70+6%_zwC}w?GJs^hI+1+ihQ>*_T$?U)U^VsXlSLC#wzoP6$vnl3c&B1>o~WmtKBCkvx2p4 z_efWO#->SZ^$H+PjksZ?0H5?6z#63bfaeEXLLzFxXqfIwX|^Dl!&w>|h!x5}8knVy zm+hrN?41PlWLndklV2RGDK(wGvtlr;QHSt_`JTFm7TD7mfuBHUMf<>|u;D{6iqdpUL z0i>S<>7j6aJqPGcr>|G#mjyQ=8wmFup6{FU5m=mj?biXwta;M|!C}4|t#K_!)vh#m zQ04uoL0}c9SKe5pRf^yqNRn=;<8mSNF~|Ex#sNp8!F053e0zRlY)TlsGXs zOJWZxQg9+f`$n&0hpq^7<{OwZSC6ybyB%f_vdV?u(@N98-J~1fBJ1Q~+*$uablo$F zNM+$MnH-)sxA)+&(Cw``-&K#IL}d!8hy1lC9FvHTj9R?e{vWJGQP7Of@@fBjUG(gT z`7!W_N7Qx0e$(a%-|-0zTQ1AyE08TxkUfwX@U{kVWHSKSlSwu6LDtU+BFG%D&TnWR{sGYQK6Ss_ za8Ra7#p7)W+@b`+F|V9z((_(!vjCK7>$9E6u(c~Gd+FC%05*Nts1Xa^+L+2o1#&8N z-MgY>8^FhM$$;BCZ?KcCzxdF*xb3A>1g}i;eI;MsU!Nvj@RG;29$_Jbv$!nFe!M3U zFsumS764*;TJHX=CApD5aluFTNWe~Ny}3WrVZh=FASAPdr@+V+$@l!)d}^3G$wpcg>&B<)pmn>3zK~zRD z;9=Rd?u0ZRTdZ@6__E?Q8a8k_Zo26S|7Dd;@2j6KvzW^uBCZ{In0!jy}5oVzG1VKJA?IO2FK5?dD^syfpwnGtePT7!@UR00{b}6)NhD`&1xI@~=FRSrQ zB&Fr&BxMkv4UOQReiJFu#>5I5p4uJLz2k*AO7 zyVhJNi%SmENmm<)+ZUJbMXiHP(~>V?#iWWA&a#n zOLTh?L6lcZ}~dRhr~ zQ2NfA4S26AnZfq`seuN_1`#HNhlGntD2FQ+8|%eG-d-9W3!FG&^>Cb-a3K!29@kL& z3WsnICu=bY(jpNgyjNyF&x`&QX`@!ifk6%t?m7L}_kO;T_TufxUK*NX;f6l$EA^WW z&m?211V|u~2qDmFst^lg;rR6E9PAvPYRc7)E2(7i;gfhz?p+9>`*e9TqpjhDTkA!Y zCLm#~C!yqOvQ-YCZuhkMxv^!Lk>zos*eZT-&KKvYW8_EKf^3=0I!vhE4s?8`mV2IL9|L|2Ql_e#Lf*#ysH1 z#p&U@Bxe;UY+s%;lFCt&5j?qazV!;vawqo+Et4PcC`lb}m^lv@i+&8E4|2?ftdpAG zC~Wm~yxq`u>!_7o!ON4jHv)8d%B%=TpLt#rRl!rTiot$kcmAx4(qG^E`3gIi>h*Xg z@*&w71Y09Pe-fruIS0M%v2xp|*XbO1b}F)Ai^M4)=S{nE+I^o;aZe3E^zTyq2GB&0 zfA;6@RLeFHH_?8_hE8t~pNBLm+!bw@BnHvU;%nN~NuY->57z`K0v)8W!hxHgT0_9B z4%GX3yWYY^ORRTTaW&Twr1B}6)tZCvM|v=TPl2+TY+Sh&`%jTRgp0> z#Q9!}Q3F?|vde9|fnUp~Jq|t*WArhA;wM3ISL|xJ;37q6r%AZJ@G>bnF+^NA=!DRP z#Yc{!2vk4{0o|#U9=n0*Ie-7E^ifZIDM$)VYYE{Y4F8#wpsYij_~d(p%T&of9)`E< zX*wnk+p{&#-@$9O5In<&}ClJOOf{|}BRnNtIy;PSe_8{hYTm_WH*^*GWD9~$~K zyb*{7pHN98_=15A2O|bklw9n9&q#m#C~6x{eoWXI4dW$PO`vz|noZq15UhyRbaY_L zIl1200Uwa|ss{5II_$oJ#~*)rp{gM?veDk&h;NiHz2MEy0=xwHhWC#aQMTaNCl2Br z;}RhGZ%+7%!Cz}(f)!fuxy#3iuZ2P|Zkp_Io4a_|2fh*iv#INfU>BX`JRQ9K`sc^+ z{h>+%UDA2p%!1D%zvdm^7bWjV7Q&KASLe<+{cC)G`FueTa2|U+`ljFrOHa*vIlObL zDi2){)@X~}xeI)VZ7x#SpzzwJk{C|B(f^HwxPUpuJT-a4hSxqvS)c+tmWzQ_Kb&=_zueb!!${7LhQsIyv=__PQmpr7mDD07csr02`oBxU11Vd ze1?`h3(f0Y5&oOjpCeUyQOP>q5vpbbQ&HM)isy9QujW31{X&mi7QoxX>(`L#d`-k7Z+34Hc1qxLik}9LmxYh$6r2l_{pH8MI)*Gb)LmGH2k!D7 z-0}N&B;P=2sP>=zQO&`-|HG+ zp}gdLd%O*dK;-{aopj`Hy59xeHwlcwN0aU*7(D<7ji+q*@&5Qv&qcx6L{gyyC%iqB zM2yR>BUsP!uSWe-XTBmQZf7ZrB=9xSjl9{Xa%T%)Q2*m6b&wSzOJb~z*L~O&;9W+A z4?ny5r*{AO%2CKIs+p;HD|JSUC5$dhgJOzl#{rOkf+cc-5MTF+f4kpr_xtUBzuoU| zg2(Ud_dEOj&VIkaCm!_p8+`r-pTEK9@7ixi^zgg(`(69}re1ziFZcq){}^ureS`wpubtr-z+GeZGhh_=x-MEHw*fk1;qzb{-8a6?*aba1N{I09v~N!JzUc& z{wU13!!eBX)92vogaNfETzjyz`DBUzM8ng!=W9=>wOn~75G46wWZgY-7wQCo_tssF zU?!)(*`~y|!OWQY77kB1u54PC@8|U@+%{#!P{D?$%~jK=oy08gZnK(Gz%c=;Gxtr% z8Gp2aHkH>hU+&*X*8FuN7PUeFX944Mdd}=7@J3EtFyn0p-xz*wgV%w27h6;J6}XmL z0w)dvsXr~?0V4n0^Zm;omZxD8IOBFV?DIc6$%r{8krwa9l97`}KLKyk7v{dI#PzB38C2`H(K@mp)flbd^^s%&?y;KnSsXms$4nRy@@ zY2rH#0cKU_8Vvn({mrX*d&CAoF5%qeJ%4kUvLPYJ^bJFHsG{M8Tj7U%J(bsc=|6{4sRA<_viZJJ*t2# zYRNzte}TCXC;r=0M4-8Kl+fbXj^E#fx(Vk!9xe0I{MEye)u9B|X=A@BhIe>>`1a1i zN+=IxaOG7l_y+ff{n9dFhD{XB2JtrV34A;>@Dl6abUzQeUq>atfVcZ~Ab7#n(PNGG z$N%WP5Pbi()Fj>+Mm<6nSAl)lPRDlPl5IKkzmLP(7he+v$eZPHyRdlo%6=N408wNK zq^ilo>prTX@b1M>|G&u*Y{+3EEtN$4>$eR;oK6;VJDzK_zt&qQED=FseBCGi?S8-A z@3;H?cE4Yt;;+@<{|njgEzWpO{M$(S)D{kHW@?7D^_UYQKYW=cREmvhFEJxKV|>5_ z86_oADLeb&%6192QoU(|-P~-l#4_hl7!fA1B$asKn0 zfBq!nMfkvB!b<|gjCXbs?D)?^N=Ry2Djw2*wEpMcfY-XCcA@-NikKho`^#IudW^jB zmVy!U)^DeVoNRX!kj8j=N6_uu5n@J+5fL%3Q)jaAw;g&bnGXt(ynzp6{u8u4)C-@$VKm$Eg+)xFYSdAdstZu8|+oz?5?Zx5OO+l3XQ z0p>~7*J1JB!90SnJ}tTLdt+B7;l>jtj7#@>B`@4vrV)di)q4DYXO3M2myqF}GFQI0 z!;eRw0<#wW0Qty=VVv46-!71w3trM>OO@T(JgBoA;CS_C#g541{SfLbvt<0mmTdiU zL{UIkF*YV93%PF`dCusrrKRQ9Vmm{9xOAjHl6NEW?>hhXGc_Z|exc(I#ZLCKIfFEW z2xcPpW1XWlv-MuX)u{}wnMv9m*7P62Bc1|Atw+B@>yqPCj2OmAxDwR{*9nj7PtFh5 zTD7Jq#dwbXFOJy=j#;osbkl8zUw*qEd?mENeozWgRJmFQ`e>?fadlyT%Wc6OR@xs< z_4Xmuje-mr(c^MCvEsLw>p&^ZqNd^%+ugLzWhEi`s)`jqOM)L_BB<70j`-U zIF5a3-dtaF1|=%~1BllxgG`8QK!=`V5Tf0)H{{aD+D(;(m^m-`)jn6lr7YY=4z8uR zYME<%IYlYzL_H`7D(yRTBD85-4O%2^AG5Q%6=v0***y5+f%C{GiqVmgG}pO)xbppc ztT847MCz^>*F3f;dRB^v4m59ta~o#AR!fyL>?uP;Iy|72LaUCmFT%q`#-}@S;!;%N zvOy~JGF+)FjohexxUu(^V{tl-Vi>1G&5aIuBcp_t*4CIQFS&vSL>4 zoP8jc7Rhg;Q;B62#)MAHS0Cyg+scpI;@k)mL&M#?CAgX{GDu2t|6@@N0cp`3s0Gj> zYO@*+4i3-4Y>Rc{u)X8ai@GI>!oeDPxHGT8C=Vv@X zfsXgqr%;yFpy?Z1aIHC}yUf|@S*=!RwG^Y__Ck0RT{NO^xeS5@9s7fMQ{iTF?|BeF znu^R9!R{0(z*>@Uafhaa_g{kiKY+x~#f@s@!myzBVp+B$c+BKRr`JK&VD!38Zr!f= ztOQAEMsiFCdfRzxkj&S7o?UCyAC_!RBkB4)7w8if(HKs<&D6M&@X17q;X-h0WI+rP z2H2Gu5nEeQA{x%?Hz=w5eQ{ex+48FqEYHTEKC?J) zmnE_CCl#7G2I-lZUx}#o;^DOw!D4Q&L6SV$I^(E5Jv)JyO%Xiud-fhwRZ{W2t4FCUXhdYFLR#K z7_USuddb>a!<(^Xwq*Fw@@$_jMETXkx#ZMT5##)H67*U%_fnRfcSfUNeSLk5B_*wZ zZRX;3(xqoh>rK7}t*I)m?XQxOWTFJ@T-t}=`o5ZV#Mo?Kc|AMjV|uZ&cT?DBahtbd zoFRAPChzYB{U@UFW92L$I(s>YhVQbrwl+H(8)jj&ei_uF(+dg;l+pYuQJ%(J;?qXh z6-e(?p+cY>7%ilY&d|&WQ*UNtXHReK6R4Ue6$4#d(%APkwl7ZK)U~usH+K1aI{Xv+ zdACY~nE|vRNR<|CulnLNJy&P5@^K(Hn+_L%b5CwXyw#%k*A@Avm}?HVwrIK=uAL*_ zY2uU!yH8uDaaww9aRIZzh55 z5}xxO^ZA=WNcY>-;yhz;4 z)GbyH3>u_j&$U}Gj%uT|YHMqw5q2_lk zZf~-B&5(C zOh_oqz47Tw1kcp{z0=WDdTBY{Aj;xWbF_!^+&t*B38DOIBGo%`A5p)V0SyLMDUxMA z65I|RWcmaCul1WD$ths^aJ?W`h=~8g~bLa_we0#dne_P zvpB9+Vmkqn$Jw$RZ)4o{7S?3zYljYvxx&~QJ&3buGoCEc_IspX?(*8KDOSm&7bFms zo$o8;r|;p=%(lKjOwol4)3t3zbWbMc5eTd1oKU4<7(WP7>5)Fzo&kO#Ws--T!s;3t za;t@wBre-)MK(SB+PUz%s-}=^lw!w0q@!(Ie6@7KhpHr({pcGe+6CC5l|IS2_+^~e!HKrf#fViDxP)VQ{rxck4fPugM zQ&j^F^h|?htp<8=7-=%TDXpH*wx^2I$^HENnvH2PI591f(idtqVOXH^ld=uEtL2wM zHlzqZaWofEvt|i_OsT#n_ z{+?nxO*NePVNZjM_<6Y4FFRnFepw;^PUrp|T?uuT1@m=oOgcf8`iN244jD;u{IG&f z{NMwL&4g*W`4k;Sa@AtnzUu}C^nJ_ll!LEk;)@X}hq4yeLI3uo$k~?JibZ7vRAd*2 zgb~s_6|34HAO-lG$9cW^I`-Q=GUT}h@~-)Y8w`T>l7O0QzGEiFSIBm293KXyyyn$R zse9^{0e15!e~_iGPd~$3tnbog;+!tg3vvf#pnVW5;?-Z_o@dGMq#fkg8t7^PV-`A1 zwjBA6TSen4t@WOmwjIyByyyRZ{-=AsBfy^}s69(JwN*u;veCyyt)lP5z|)mL!%ZpI zK4;A(a;(O-NqtybkE|jA>1TRFZ(i2DXXyX;Ay8-qnq z-lG1s#)C}emt*If0=!Cy=1|kpND8p@I6S2X^dE^jrsz_(+X=RPmgCJQHQsoTV zSySN6V%c$Pk{=K}q@8?stO)d%G!Suer&U-ir%#_&CJO0n@6Em9SYu@L1Q0<-*D_>6 z?HGG0$Bi?boX_1q7PS*PMmnBd*_k1T&xbN@B9o)OVkb12i;NY!I;ROyEy@W|)L!!A z_DcA?rBf!Yp%GSBSNB~k6CR3kD}-AdbI!I`(5AnlRJ#=ova?G7ZUw9c!ls=-*QtHK zpiFQO8E-FWi~Q6k>~jVgo%Qu~8rYYN5eJ1x^*{8fRE$N&Mn^5yehluP!3sbTG~nKw3Vq_ulRDK0uPqwIAai(*G51pcHPc%+uQgLUe+dLk=v@^q5RguF=UL3^pP-n|6u0pfgBm1RL57W`P>D04!E^i z3EOAf{ld-j4x&3*K${3Gzy|)|;^Oiw7>(_la{>?JFEzAsF=xBp{A(4z6m`$j$kb}i zoP;TB^8kDnS!k!|V##*hA&-D`u3|A5akj843GciGYX9gFQYu8MK!^ zlGZ2p2EKGYF+rd~By^2bh~k}p(IH-$y9di%W^S{~^qkx=uraz5%$&vi=rj(Q^ry8A zIMCVPt)ZRp+E6QwSo>#m8h8lX@*uxEg{T`o9|Jw%4#0OF%-4hHqaI62`}kBXk{x&h zn9igOQqAEDIhCHPmOs9|bKdX(QEy()mFfFSDy%=}X-4I3Rka;>PTfGIZjbBiS6$tr ziJ2hULUfW0--{OuodeQ!^)ct}9kKrOMU=`q&6{q&sEoKB+b$z-t+!14BbeT|(wjau z>#m6_#g}93WQd4}Hq3|RwjAeg(s6NK*YGIYdywW-`Q(S9Cm;M@tIYLZR#CBQMelPJ z*EYTX=d5j?N0fQ_14tJirSsqNoqb418@WNJV8y}vaqn^Fd)}a}m)2;X$IaLn^5^gU zqC)kRK^cJtDKCCz8Y-kF5fT!zDH7z`&wI+#i}kQMB68{s;a0A%QFw|oORqGq;lwiv z^IUe?zH-+bo(BksE(2_PC{mpHkc^2*vd_Yl;Z*5N&kG5M zS6&eRZlHZ`(+MX%-t=1TMH?C)AaTCzQlw0GUdl`*;#KoWdEo@b_h({OyKk8O$tsd& zhXZn2$VH07_R=1vG&g7aM1GvM?YM9&2>CtsnCge@P6-XN6Xk= z0=j=#c?;PKvB+#t-V`h{`mke^7I9rB5Q4@10d>^j0EWEGn7oY& ztHs|Lpd@bY(A0DA%Vd{M>I40%JYTPbpZt>3q21_#oQl5k!kf#Mm2Yfg`Wx!id`wg7 zSd^a5Z7wFG_9RbF-&bi@*Pgsj_v!^b^PqostuQ4cvpVC=)f{hbvD3-QyO>2drb;Ab zQix7+PN*76zJE^^5wVbxbV73`p-K{2p58AQt#K)~>w&L{5h85EnxL%5Ao|Jp63NU6L^^LVZ z*>@L#zHEFIJLwxoJKNlZ*8^gm=pNqo$O9KT-&{AFVAnjoD1)EqUSY$)qj3CreYd^1 z^vig^BmAbYz)Mz|yq~FkPKJQg zqZeM}OoaGu8avG<$_2H+?o6cjBAU((^vi@O4>E^IPwU>FvVete-IX_5Vg=0J+C9+4 z4P(g(8Lbbu+E|)&Ug;@yOkE7BeNyB)XE5ILk^m*SREcQJm#vRQMNLcOeE{A1B;X$F z&jZnf;AK7cnZ4RHKZDGrBWdaBEw%3M8?Dl07S-EZ-7K%ChXU2zyDbg`({X5@o4vK~ zxX$b0`wVsU$t^9z_sHMO$-k#qF-O(D+;yKWZg5$+jrJyoXaUPEBV2446r z$TFjZ7kaGAxxSS@?ot5@ecHrCSkNkLQ`0~j=f>HY>zboC)xj}ZP0g2(rm!d%{MCfo zFq4N>DP2wfdy;a%vwx4gm;gyNh|pv1AcY9-F}D@j48B^eEK*S=KA_Vsc$( zbYdK8jysQegI?VP?6TOjzgR_NP&dW|(8v2+L2Rn7zCL4hZ1WZojrF;FvnE7imXZ#^ z(uKE2FGF0=-O zG>T)bZF)?L>-?jHe72?x?Y^su|J=JW-?JOLI8c;aA2!)W$+1*dWYaBntCIZ=MDtY!HydSz3z02jB9*63Eukgu(= zM8;f`bZ`a^eYoV?VQx%koZpkU{0*P&$VHw{4z-4MV?iWm-w-Hm9qjhqAGNr;y>VSA zdmGL4?Wt&ZIQ_Q5YJWkJEUv!a&MjNqwW&1HbC__v#624e8;aGcCG5+JA=a40)r!=6 z<(GAws(KhAGfE8w3sJ^v>sAwX$}^+mX>ZUWoxXNaSe)0J#lez|98W!ai_cBoBXi|k zTgOLAHgLV~iNb5PZy&)qQekmXT+?uFPOTtDZ6g=Uq3PwyvOV)2BpOy}|carI!y z@`Jpc#EAN%K0F!Ad9R4;tX`MERHxE1DPQ^izN$;;v^2J|z&>*vJhY3??TX?a($6Ob z9`2>F&NSTmu4zJf@MaGP?b2-lccJd#;Zb>3JWd6PpH2{aMFdcCkwN3Il(JS|-r7qe zzWGBs1{5xx)7juDBkxLWmBp6VeBId2oN-832grp><5_`CG-1l4Lp{NCBGHTr5q;mZ zd!~C5riCLfm|VWs(E^W!7`aaUrdA=}z7aN+o<~G(rs97>Z^6;?=f zxz87H&j~1{lXJ3*wwrF0z>ERM=HKFV$w|z0Wf3f;;sZveXN1RuO zYh&;a#jn|$BriGxD-yHg79Dj(o`h{{8`Zv`ynnqyB5gFpv%sY1#*4?In%nLqM@8q} z+vm`IlUsYX!Vr2xHGAR0>k7`ziR;d}?BwU?+Nv0Eu^E}X6=+B6(rY|-7gF|(HXJ;| zCw9tC4&%rE8vc~2z%&eTC!umQ02_k_`ba~2dCgEE-fF( zB=l;zL_~CvT{h0%8v`|QVPPqE?-FPe`2&lqzAS&lMc_ZX+NJ!JCjpBD;xul-}??5e0Sf)!{%5jq>3qc-k>Y{`H%b=wl{X) z@vjqM<-yz-&dc@lyKpnAW2y}}q?iMTil96nRW>0i=f5d^*5wQG%o{z-$s+FZm1&yC zHY+ntBvhRCMNdx3v$L|wCnqO&SGeaJFG3k568yw;*d4e4UbDvNm9@pVg7aL~KRow6 z<0n*xYDHi5?dM^?q)pep?xi{2(Q#7s!Q8+R>~#218bPgu*veos{;s$|mp!F@H~J+f zUXxto_pHlKznt14&AZEJa32Z3*2KHlv#MC_8P7(mRACt#g;y)hiIFewNVCzn*}o@^ z80>hn`{Be?cc{#%T~D5Ra87)?f4q0_oXqs1!Z~LCQx3g8``Ne2mmb)C(?YYU*-3oW zMCA-*f7>JiN%yB6JtdAN$$C-zY@=0i8Frt`Y4{2io@Fm*tacjv&Y7=By*c^sOW@K` zt;O6W>psIm*7@n6xbJljl6WGCuM|YRyYQ#Y55Y;;5>ehbd~Vl2P{u?O!Hh75oR|;+ z`_gFK)|_s&gmve+anl9R+UNK1vVwSV%#fLYlz;vGd#Q1jP1woJQ4gcmcS4>6plxDe z!sq4%qz8ZKocElk^67_R{3N$GXY72R)fyX4_1foqS1l!Te`ePxDA1Pmho{F~L6plC z$!46epr!AmSa+X%f}B9Ty5-5tSsU%J>@0>A&H1k?uPy8R4j2gL3^LwJW=u~%m66`s zSv*#pd?$!0PkT9_kp>={_sZyj0_NR*vFBkYNMt^0_y>p<*D5HyD!4xT{ZYvQvO?5@ zFUFKiLwm@Z&&lZRdet86W?ctk(~S%DErYkMOoDBh{R7 z8+8?MDVDXtbV}LIO|fDzQ}5Gxc#F0D_K_$f+tv+YA739fYFF~Ji0m`kH}C{b7#T|X zhe+-_O1zeIx8bbKcDOFXct|__z%3%%ts<$^SeE2e28qPG1f`nU&)c)q%yB*z8%`E2 zr~EjNMog=s2DsI)E9^U@u#c=xUyDui(!=Z8uR}XBROS4iKRePtJqK0$0om9dvzUTX zc8=)FhicV50yJC$ULT~`FD8>NE5k1J`~~~zYTu#V0bfEz&kTMiQ}Ux_Zlk}+aq;;~ z_)3n;BsVgtHmO2p+2VN z5_PP_zir<;9YC#UC8NF{j2UXVdH7#Sm{aNy{;rh@{o?7Im{5m+L0HbUBzBQ5Ro8O^ zy~1=7FD)OmVOLid$n=J?TzMG}I{Ry2bwY4kjlrXlT~! z>T%8`NZ+36N>nw7wLCzgZi6*7dvNbyVF=XuPwq%x`NnkEhq!GoBQv&my+Zj|$_u(R zuiNS3GVc#HE_T-)IzQ*P`kGYg<9+(;*s31Q*PWJ!l#?HP3DdlzaEZ+C9$8Uoa=Z$= z2;+=LPhyDc!488ap#$Cv>=xg7{Wi$VH$6!FMufc-Vg(GYjY;F;l!X?Jl}ZZqyjkx* z@6UQ+aN^(3fJq)E>{ffRH=XB{(K{ice+iW_sxalOPqZC*f1L%;yPookyqb}US0W&t zxoLWk01hSw0Wa^8fAkMWD0`gF^RiLH&Uhyra#u==+^!>jfy>(^Fio$Zbm)AokY zzZieWI^wXVq8G)11x{8;b1X<-x66MaEvx}8VjbR}@7V0Ju*R-Fz#AQ0v zvz{s$y%?-#)&8m2;#nE#i8Oj|Y`U3C(d`Qto)6A{qC4<;Zt-ip=Ejo?h@1sh9l`dpb>? zwev<)mh8-;Fe;$s+W6vH(<`Qj-A&gjw#~o2i=uF1zbLpn;PJONH)L!W-_IOKPiIT> z=1A(JE#p{=u%awmy6tBg$I547f(lZi9q}1DPs;9b)mYBD<#pV_w4Tt=Yb}TGOa0{p z=qasuF?EZ0Vd=Zn;j{n3v`jEV6fFBB#iR6(D5y{dHcooxC`DKni|m3Fk9|3YdUje> zjfK+M(W)BfQCQ2P=9kEQ)qdOLKoGsIt3pC(uU+No5TfH6*{d`aH0R+ zzQW>oNvt#zWn=W~NXI61^MzXwq@F}ZmP}GoU5*l{UtDUf^TBxsO*czd0_{6I|7mzx z*!YslrK=t~kr%-1k&*1KdW8Y1Y^QpFZBcm3v|;|v|7GaCO1pRa#^0o~p9sj6?`fJN zdq8(n`q25o2f~!}%yYF8a_rJTS$u1W2SbcYplDkB`igr6r${Tx0Tf4SKSBtG< zWoDsj>FMo$PnCNa8GL0b3`)lY8uydP5Ws^X>HiO5Zygtfw!IG@QBXiaQb9mkT9lAR zx_jtSx{+=ikuZ=3L1Ks@hVBLdC8fK&Q@Z)>@#?vrd++;w|2ZGea6BK~v-euhde*a^ zHE>wNpF347Nh=!IE@Tt;8k6WDherv(@}VcyTsGlmZFmRn+X7f4wK_(UAJwJ>y$5PN zT|u9DQaDM)013vv;hS-uR;db86j$H7HBt7&WQITx9*kSrqOl_8u^?7y|D@2fb=8H za)hWgJdigz&;gYRK}aH~l3biFB^nr@M{4C$pCj_->|{A|ui**FmallN9r)3vwOvdSpyTsZT9` zw^05@6ccAffzlHYmP2eOBNG$#>4lZFw6dth#oMQ=H9Qg7&JVdY#QQTkxJ}-P%r{F5 zc*k;KGO%t2%@8`4}cnBYHOE^2!qaP?IyHDzsx$W$z0B~O8wIHbq zN|jMct{vPf{mn~-;|4}yHH{9l%O8W}mIl?9Od@Znq9`}m@mva8CUpHbdds9f(Qvim zqG2j#B!3ZI@UAAB3$ei#dwlrgq|xk$TjQ{`YUkl}scc?Mbo<`&bQ>vSghte^hquBf zN|qzdf(CRB%^u1Ot_dYlC%_16QNm3FC~8YX4#y(Cyr7Yn_wW7#Dj|g>RUf~!<@5>u&e&ThK-4U@U4^CNB{e)d2q*kh7oXjTtM^Mv-CCoFDNUU;q!nZQP$dv&m5bX zpORCwxMljg)y?-m8F58L0g>l!&2dU!qL+#pHhGS6t*2G%7wE1>ZEySS!cRoE3P?{~ zH^$(d<7F1>Q?-as?9{qh&kwD^_Ohi(x2Z1}?)o0mtG-v&bkR{3*6Ps`AMa~zKMk+_ z^5a?1$R0OgNl@+@Zq}h;6xqk@bHn7ou>#TkVk!HSbO}mK)~{&yH{8?4L~SY>(1pcb zV~>uuh~NNtqy@n~`;I~-?~jZsKNmS4A8ylgQQK-)sbp-A@6>~^ zYQSww95ggqA&@QpDl00TN`5H9{y4cTMKmqk58o;14Jq?VC@tLdMpH;ErTdc?Wz21# z$@9oX{!@PsV}M3zA%ll}E_TwNSXS5w1nCOF-(ef<7X&BEmAC)yFBEp z-=~R^>Utc|Ta3A`EiasPO@d@NOFEVdp6#^pw$B{;!Dxl@^}SuEW{V7qo>$jooc+aE<-7aac+{n z@WUpuE%@Sx?+}E}JK|{I&tHd8=^a(7}NrXsk=XFB*2zp+Px zDEMGmQ_>VFT#b|$=fwmzQ1&p~*qwH?THdwQKASR+`hF6RVo*bS-gzEI+97nQ$*^6= z1Ug`rDz-utdxW-)LRl%SuTRAuYEXUaH|IL_=Y``btkwF^gvLHE0Lx zfW>-?K1r?I_ev)tCfZUiU!Mf*mdEs5;jPvw_=?V{roqHDphW0Srt^am@72zUn(A3) zaZ>m4{!3j*pj1J_P*0*xMKaeuuKSkShoB8J@RIZLM=-E|B%@)9iXB>Pu&X?q6N~9* z?^5~;cL@fM}VLf`A zV*ej~W?@f)r}utFYV!OW&A*Qrd^f@^$V^x`^uG63G8Jw?UhkJf@4~457!Pr}3tjY; z>x~YPu&~=cLBtjdH|()Kay4pQ~2xF_8x;_!>6%VqOAy_ulz!+8@T8K z#-;(HcS=K$u^T!-Y#-#?J)cGTI;iHOw~%sT7$bIAfv62qjBcH7tXLC=G{ycO@US^xs zL)M)$^svD96p zWFsCwZiLV=TZiSCCI^Dr<_9=kZp{(O!`?&cwIlf-*$+hCP1Nw8QQM|I zG5(M70%+a?aJo!6j~#!t+@KMZ!mwH6Oh<(qRi6N~W-XhMBZksosF6islvf|Du@y&6 zU-j=!USKlN(|a|Q`(NX-4)r{7FyY@1rK_5(GF*}aU=2<)BVnJREvglJcwaCF2>;FV z$8%GjHxbkvzwqyRDoVnh^71X9D=$wJD~Z|E*Fcd<%?XLUcdrEni@gC2lRGUP&O>=~ zxl&-L?&BK@YyCnNJX3SV8_x~`qYVmxk}`n8t8TstmmL}?wbH;tw^af2SAT(cI)Kh; zY|1!u(7ycRDfH%ecNR9g8`#=e!C|X=?CfdXVEFVLm((8AK9DHgC_;sb28b3IA!viB z&slHPBsh=>GM^yebE$m|eliS#Y1cB;Ex(I%k_a+o>Klpdruk#)_54n6ziupVpzvb^ zhf+eaqb}2TQ2hP=G4v35t^zqIM!)o~(5{EzgC}{6jv}xGbTGhWhS_M3yCQ~y`WZf% z-FMI+bTiZNlz8E4Ytq?t`J}@j@@(!siO+s!^TB$?52NO%ggAJR$_Kc&G6zJkz{W!twCK)OFA&y1Qe4WtG}CbE9>$BKV8);V=@;$SmQXER2lVUcA_NV~ya6cyQO z0;uWjyu6Rv;xgW6bY3;m z+m8ssvk@v=%SjPd!z~!tWZ)&z#fUg~*XWI&sb?!L${ef~DqcuN^CkyuHHoyZ+;c#1 z;@V1`zIzEacl{v~evpjPmWc#)Z&>do{6W$5z>y`%>Y~~1ujJVi0C2__ZcN@C;RhgS zK$*ZrACoa0S1B)J-OgqS>{cE<8D?}F9Gq1pB$f@tW;kfL$!R{wC{M;Ecm3=TqKJ97 zM45@-L2P_)w}e;7;9IR{w#T^}s_A#7);i^BgoGv}Xvvm+Hef^;Af`+#?)${A3V33o z1N`ok>L6P1v4q9^uzy5RyvP>(3h@nkLp5RRnt*$2kV0XD3d3KdsB`&Y@x zZ37>+Tmv?P{L9_=$Lb_JBG1Y-^3FpRwJtxFIQV7bhXfTLi35`6A9{M63_k2rLMTei4i;QrE>A&&;6U9kKVs~ zUut&cW5Z`Je5T796-=4|d_YvLE>$coCp!@|9NaTKBR=Y@$y{G%-cY9Jk7@Q&Lw?2a^E^Sels0;vyn1M-2kxmVNz@ zl>-F-T{ZbfnLRtR7{L_zGxy9uDJ`Q8NvqPvKx?{oS4TA@gI3gX`ixiTJH)|moT@wG zN~wMN65&&O(SCnKk26(K`FTA$<2_#G2B_a6qX6S@z<~psuZH()QVt(=XmeMta{XIM zM$VFLh^f;*@Uw6PijDHm8l|ZC`XBfFRtb{D!)zG&TQX~&4sx8SNFkUzEzt)*Ti<+& zckRX+alzVcN!QB#MsC$e?&IR!t7Bqhnes>&62%X6$sWwwX~luJdw1%*2g~iI)0Bsf zy-w{HWo*WZB|RCL2y4zA+H4i_GtE8T=g;+w4Ie<9%;g`ZAY>Fmlgm)v;JamF35iX= z&qq=27G!`5C;TO5eca%_budI48kBz-I`?A$J)MKV#oYEm3Ma8RO$i?9*Pwl)BnY7L zYHB9XA4RG|vJh3;mvJP66_boHPEQH?!roy-5fHX<+QUSQS{NVM#BrE@5UKU-AjDuW zwu*{nfM*2euXar_=R6lGx2s9nr@u^Z@SGlgHGr~sXm6!aCrNQL0O7C|h4DR+8jF;5 zb0qIW6kB#nfNz#-eiMm@M65*OwuZ}eXiaPa+53|}qA;jQ5>#O<|4M@TOy4p7NP-by zUUb%Y&C&K(JYV?^0yOX5+GFk;V{gI1yA%We9AQmt@b2c@MW*~+GKG?jf}`XujSZ?Bo;x_0c&(Tuvk#AK(7e+;032*V?G{Z45^VEW-p zh#H6P1*OVrg9vVE_qykY8ncyPfASoM*Z#OD&{unREnGf~&xf_lD_aLO0@lJy!92OW z5u+69j}R6H)PC~VC4x5U$~aZ7n4H55|8Q^q4Kd1mGlTh{*hba&R;5fG zZU%0R_O`HzEgHQndi%J$Oc})0UHHB4-Y;sEifA2OWpvr+4t>ueR8X)m(8`;d;+8nE zFmg7Y5kr*-iOS9qOANM(s&Y&~Te9tqbv(+vT7BkBiWg4rF0}Rb6Q}n-BhRe?44NXD z>x1_ya{f%DFcv^6mH0Dy|4j%Mu|b3DsnLnR_w%3-d^dRO(ss8VJRm!jYS#(NI-=Ol zm}9bwxMC{jVa^LCUG$j8I`H1)3}$5>s8r2hWO`EEReoAtY9MWqg>OFMvY&Zq3MwpO z8L(b;s{|_C48zTy!Q6kdv2=Ob2v9#G;K|^ zHGUeX+cH*D9O!hUYKlm zMU4#ru*)yG9b&M@`pl38`{a#MITFTHmp7(UagRe!IVTj$75}_?X_aq;u-M zb?^nvz(8xMZxX+3(r{+*drpC!kF1~cHgB68c;u_+zqC>vwI_@}vKahct46}3lE-bJ zdTP~;IExeKHGwKpFW(rr+7IQ|gB6IcUn)Em^>!@$7d!iO&izONc?K{(t4#IHa- zXe($Z|5qcUn3!!q`TVB4)pgv$ma*W&ur-|05F#gY#*LZ#_~>Ghk*#_*+$|Z5o$FXa zrl#$mW3wW^%egZjhbQKNJ|3(k6-Hz5DAO`YF$w@iMn;v+Flvmbm=2@oZ^8FM!mCD! z$-KXvFI;Ymkp^$e+5@0HDhh76J%yoV-+*BM6s$#4ed478iE>&9GBPK8q)TL9Xo+`N z{5%OLI(tqJ`g&7mmHceNV6XKsODVDGCkz_`T1`Ruv^jDXw&N#IZi#>Ip7ZeZX+dt5 zp{RVYni|b^lW*@U@%q8#eCC1pQNa#Y^F7m;Db3hy@ob4TrK^63pl#7Pb#rSey#YhV z^Z@SB840^>zC>4^ddTcExGN@Yj+5n-!;c-lm$~}#` zerqK3R6&9n)^#-v7FGesl_u(Q1Z5BHjj1b&kX@XR{-L$^1Ql!A{^?2c-}x420|!AP zynjHymLmm>VBdZ8V3qtP4q4wjPOJTwkSOd?y%8ewyF!Ai^X9v6T>3q{LX(qsM2#rX ztDg&Uo#O&Q9@aSvmbh3Wj?4Vn+c%U{Kzbk`hJyQY7A-1D+-}QNrxZFydXyk6>QVJt zOUuE`tiyzR+02Z|cw4LVTK2%q9?u|&^|X?Dw1_&ifst*0<6d2?P~F;V$fJVGafCPu z#kX&>e@VKZ6!yICppBVk(@+kZxQQdh@G^#8#o%v|z4ot#&oaHA00rnn}kH4r8glmarXsu8bm4@3XIgG|VME zAToNNB}vUtmRY{>$G84KG*&=*%mTY}>!C6Ckj|}!!&1xZE~#}k>Th9n_OJbktl#52 zp?N`>V?Y{$%8~O<{3CZOVD$ zx!;wfvN$<=E%CMn)J)RS8JSq*wPIu2+q%?UT*~;#LtK`Y*Mo5cm3p z?cJJQlMObjmezqnka=^8Ww^`+V{0;7*dnXX<511?XlpGx zVN*@J6~lj_wEeb=^`p#4K=x^wQ*uH^wX_rr8@Td^nPNKNhL18|L9}oA#}C_jnanT)|^Q$;kfVg z2&b5oT_jFWFEJx&U?%GQ{@Xexr?!(t-m?wZpXx(?mL+rt)@U8M+;!u3$VhuQxeiI+j0u~)L4@qQCnj#~lVSK1 z6uiSOO-9ZBVwemDv^Nb@v=QYoY{O*}x`YNUu_BJk0Zk%rZI|>(C+tP;bFt~DVzP@3 zb&+pg_*|sDoX@%M$A5JhQ$%qNx4m>q7TjYKOhn}uYq$~4hW|D0)n zY9jq`{+^N(9tXs>IjM$+_+QYw$e&=}dJrlFCF{^VJtHJXr8v$N8J>JF8a#0*zjt!7 zdpUEH#CPVE>4$r%V4#wZ+k?J3cf8=)y6cvj&!fzCQrpnFgIr@A=$`luX5k*Cie#Q` zN$`y{c{?J6MuJa=CT!gu92dLV!!uyQTVQ%)tWdNrfiL0nk*b4Z6sWNr932KaMKEp4 z`v58O`k9%d4jdJeMYGg@tmic|~jgfQn@01?$7k#_YCkxyn;R&U+)nxP;X-L9(yUg5+%ZBV2iP8lH6tXex{1UI#lzV)cG5s4;DF< ziD^JF&UVduFLemqLa*0;^PZ3fVY!#img|(#>F4e&-*29A9QDE(-tF||k`Dgp7XK*r zK~GE(3e<~FS^L*;3D@U2jyn*{OQlrh}0ptz5z!@o^tG@X=F4P#K z#xsAv&lf9_++7TeA+BUicEog?U2L!C>^sSm^Ymr)gj!A`lD?Ww$JM{+B(WK*)^JY_ zMJbO;LBoDgghmLn$Ff$Sac z;QN)L{g(#8RXDUg_K)+~yZ(Uu;Jix2U_3wXBA)W$pWabWe2@a|sXYFD;2g-l7NN#X zXn;EGrBn=(W`)NjwNZ!KLrtzIYxnYh%nCP^SoB^_=GRbdAJt_P-@M(kN-gme8W0&7 z`6j8p5IY-@jhq3q;c;rs>cKtj4M}6llUlp`bW|Fzz`iLvpV4tu<-lteHG$hGpgEY7 znCyc;QBG-KkBE^75J!)B&%BzNuF<+__Fd`QpazpuJA;btmh|gjp4@JFvZoKaJJ=Za zvLu~0wLUw2JCWq@_K><4tNu;o@e=p+?n))?Jr7#DoLxzShgTbWQ9rgNIbp|~3GVJt zG{wX0aa<8Bdf#XFuKjU?Ks+oFcKk^cSx6rKLGb?t{R-lr)CcO?zwg%%0JODV%7dtg zN)qT~0p6;f$4M+d3Occ-Q)-FJUI{2&&yUTow#*Wh+rd=J`IGJe3+kU*Zrkc6p0~L< zfG6Xy7H|;r?CVSO+{#iFr+OEux3K}Ke2!|q&08J(*M&{pYQ&(GX0_U(JkPO&&g`1DaLxxv5&#T-}6}jLRrEp+#|tYZq2uz`utyUqJ9PTS^qS`nRfYX7h*a04(u7d6$ibOel~}S+d|OP zXca`q<0$%SNQaPjlOszqWd1BSD-4WN&CTtY9X_#04k)w!_RYa&Iz94R_sV`#M~UGv ziT51-wcvZC;fp~VEr8IAA!3o~#biQTx!8T8=6G=6uxzI~L|s4hAwSCMeDNA+8c(#b z%=JYx?*H>)IcYvXoUSbQ5ZflnSP_f`|rDRJa24q6{P5Y z9cy&7_fnw#BG=*StlqhIAd7^@I0)Zd%7sr?X-3U_1gNI`L<8Pj$HJ$l^Sm3sZG3BE zbRI|$S+r6pNx7a9lAIoHdOntLXk5OH=C^y|<>C7c!{(O1T7e<-oLK*1f4e zclW-zZ+*?dpw-dWlRRtl<*&Be%oAXoh{#Dwtu-@EEH7k;>0s5@e8wtdEzmW3_4VHM zwP7LtukA7x-Q+QshuyjYr7udb4ZQpiOxI=H&rA|r+O-pS&q4#bF&@%hys2FIcisB) zR}aup4t^>q@n-%ZU%fSeMBu3Z#OCT1|Lcr8akGrKA2eW#tp;}ITD4ozf~G@uM*qopW(9zxXK_+b*gD6sd_ zy8_y@rT~8?emDNN?C8hvzQ^uUZt|6O%tQNNe9Q9i8jB`w=*3D#8c=oacW0>Xhs2y& zxgY9A-4>9SQG^Wj)mzM2tUF!eAQrQ7S3*BM>&5&>7X(Q0yQqQLAn`(D)c<&FimLE0!?qDy_4NwV4AWP2Xy@w&RV(q1956crcn1Ad_V6a! z4x!c1Lm|M;GpIHalJKsS@6&tD@_Gj9lz|wY2+oMz-(LX`Ww1%LH|<`^l0*@PEtjNfi|8;GXDNR5fSw-dLJhjD%HYCb7K zTx>&L_IvP*|9wR4AfElY)RgzTwF8*dd!Hex_& zLf?eGkqZw^h~KNPTmE!6R2VP3c-JS7iI}>3Z{q0aKmZ!ly*v??yC380s@`nk+Rp3q z8fB?I_1W`rj@czS=le9J*fxxuTfZBPzkyjiN@)hiql9E0cqR9r-_-zUl|hHmet*=% z5Ap)ZtPCvqj=64M3bKk>*);ociz7=|I&nV(J3P^|i~Rz2TA;lM{At#TU#7Bt7StmX z5hXO7qMd4!oC~8KE451!=m`~aOy{smB)Gq^!1{0*4=UiffPXKmhgO!OB&Ctu{MOEq zt2C25WWcnTft6iZ=Y^5;dCGe=hm*x3`J}D8zV_*f!!q|hj9?( zS;I%@ozGk+E5Y?=OfLIm?Ii4~(Fr<(wKOt*XB$I3Ryi1(!)h-k{=?=L#)E39Xko}J z>L}xA_xrvgLqMi1aNf)R_Z4;rSC|8Ng{gZg(!`OJWbb(Q+#Pcj=*H94+~jaDl<%?I zMzNKU#5QekA>%hU$FV&3evs~|rjN6L(_|W1f=996k00;ezE>@BclF$}J*4aT();*E znQheeJHoXRk5Y*nXqL?-7W#!-^IBRmQt}X|mxT^X-<1cOaQNsLK7}}vnOgcu6U0BA z{WN92pGm!9NXPwYIzJ~;yEL5F#p%s`1U>hg0MI;>GHsXfURy{CrKNlZm91B+KVGad zc~Qd}tDW<_Dd%wG8}z!Mc1f$od({?8gO*rC{8MpgHc_T$pNQVRF1+ePNqfe}56zX) zt;_#l`mWuGXEIFZ_%z>3vpfX%+1e7B_-tp15MPMH<@T?#6$yb_r5{LN1BgVjubpU*m^`oB?5+$^LTv6%WO!5 ze7rjIkI!o5KM0jmgD^eF1bD9k?pE;pTH`k1xx#t;9L$8lTgu)22A>V*cuI0)c|90o1 zEo*^KElM<-Mh2J}MyS%u$31H3B+WDM{Pyh|Z**94=88ESxM{X0xrtz)hmkz?ZnSiM zL%h42_ThHR0@{<(*_me+S3WJaE&Z(z@F*Nb=Nf({ku4S5TKzhxbc(!8T+7m-Zy5asp zSfPTaQdI{-ab?Vfg@?jTPo;~~6=Uk_>w#|zJ1}9fQwbO7QF0m9>${Fqfl21gQU0Yp z3PZP0WL8<3q(3{R`2)$|1Yv^9)&6%mad3r7q$8Ym>4n0YKZJcJ@Nd3PH=(3XM@T4r za-yOh9T~m!X~GZ%XUUOHcRVk_=!Iwqxk?P{M+R)V1SO3x4VF=~OtL=X+zdOPQRAju z0`tfdazbr5fC_1&@p?Voh) zf1nK*DpJYx>~p8euLt)9NsyB?Onwq>>R_wSSx)rKyEB-kkiffIy1;2N94g{?BXIM?wc^~9W0+-^=soHVD+F9KeV3Uyp#y%yR(~?_|lWXPEK01O2 z?!%J-Q}KI~GOvXFbZl;RKA7o68NZ@raj%P@?y+Bt;kJ*OzSq~ZNM?CKc~yo@q^MMRT4aW`1PA<0-ipfCLVc|aM;Eh`*5Vw zP2k?wHM8jmYuXLg&OXep?=im0^*BxT!n&sdZxneic=A<4w!g(f=U7+E^H9aGUEf*v zD3NYjCo@??qfI5`8LoV>`PS>dqtZWa_^%W>^A;Q}|I6W(-xJ*Y$QfK}m#k!H0MeHM zm^ul(y8Al18@IR@7NnLun^PspgxDCuyu9Iun{fTw zG(qqC4QNkjsUEhn_a>iaW`@%8$>s`v&L=;MwhX_*o^&zF3c$+kORN<<-5yIkeQZ&~ zxLu(Wyq?w-i%UM5UDp~QMMqiW~eRmby(%<_M{BA7Vx?I@3TzWDuikY6wfbTahk z7&IF8{mg}hg*cgu(*spwp0}M%*=&awiG;X zDlzY+@-&>2leDnNBKKIK^ejj|ECk6&~Dcm$pG2LUL+6N^;$-@ZD-WWJ0lG3t0I z346ZKN7)kdWticDk^ zh9~WtuukXRvnia^goK2s=jmGDFvo8m13ymZfmWitsOL0~kv;J$Tz@PTr z+qcRY3JG16dHwmdz;>;qg+H@-wiMip8W$_AyC@38nmhQb!dfi$|>)8CV9#f=QhVWQiB2z00lXl#J79IEIx4N*m_h8$$)-~a-w%f06sV?RDYB_Vg4xmJ5| zIKG?%JW11gdX&zpx78`Gz?ii2wD-})iuMzmM!DDm?Oe{Jv)v9h=Sk<`gyN4pv%uZ_ za6Q=Qpb*%Xf@oN$KkOL33?A%GjXV60Qa7=Z^ZE4RJ|T_+630nIFO*;>5M-LLds0{`=b>cAp?#<=Q*@%1xo_Kab8Lh6c3%J zJTm_nY4{)6X67X_$Jln5-~AP^_{ESph6_On4d}PCL%}*gfAVP^xI?BjWC%QTIo^4G zusMG8K`)7+$8d|?9<+~g9X3V^$4adZPDmd+d&?B&?x(JCJL+ zQ+4ID-Pm<3U}WbaeRi)U#7a``LwI|8q{S5bl$^P}az!KUUo4g8FH*p3e|h0?AmAdW zN=-FD$uW>ECbz;#%L(zs#3UreOF>AIhuI7~T+Zv2vjK7h42=7#Bp>gGeem|EGDg8^ zo{;dj|^YUbyklI?NzKHvP+EH!sCi5e9vEAECS=d-a(`>Kd{XP^NDq;4=kr!<#Hbl zLnusn{bKvR%qAcshogZOAxa*u8>bj!?WRVb(B^Iy*S05J*5)+WEFAR}$GO|Z(Fv(hzE>=E?g;*mLhc`= z>9rgDx&R6W+CA9(#hAYODFXO9^pvT`e(o!}f8ya*9q`f}u6Q}$HFB^D4Is6vQ3i%} zIY$_FRjYK~z`mAqS?GAi4}g<$A17~Qiv0XpXYXvg{;CeFI!N>wW~a9W=4N;9+~FL) zfrf@CC{Xe#owlid=DJ|)3Ml)Tu4+-cTW%kPO|teKtfUnMXlqXqsXq{mSv9)RffVXV z2kXw0fLo`b`AYkqH#|Nk!SnFpH`D&N4665`Xv7C|c(0;$Ip`#!;j)C}gmB8m#Y1$g zT<~@*_I;Kx_zTN-`v#x%qBxjM%SaJJo{-RG@d!uP}(}j_%(L3 z@0^(Amt+H>ldTa1Z1DYn^E5^jxty{@bP}V%xu3QAXXb7}c!xfJR^gH6;L|qm8!KzHyHd{K zb00mvr-p*Vp~6i7xwAb%Pp)eL-YY4nm_!5dKIy`K?q*Z{6a?OjQ5p*9^aC0C3JM?P z{z^T3o-X|<3-A6Ey)dld>@bp$as~r>POzF^OIv$hw10J(ly>VSW$85@W2IukCD165C z3emn@mPu1BRdwZ~C8N-8*Wl~4x~*tAGPsC=?HaP!gLDaqd>=3KTMO{NPV--%y*dLK z#J*l2nfg~++rj>s)>@ixki2;DVjmy_E8r(7gu%*@<_}UGaw|kFuoge4^Y%u;q6_T> zM$;bC#gz1kHa1w5ILlQ@AXpxa112%!P9Qw!ojz%}Y0MFI#A}CZ_4>vhS<wM>~d#N%wUk2<6xhZuuT z>%n7{TsheDCbZzKG06OPze{~LV60)O1Lz+Skx0urv(M~J?5GWsAH(q&s71$Ww8m<6 zcwOWkPuG7WrN_EQb;U;9>U&bIqFiX5drmNtr#5d!rZW8!b!{y{XW5odOz6Ln&cE}+ zD@i2gX|+kU_pP-I;x&c;$jjAb-KRucT{VfG7DOw9|_W``+A#zTo^jWGuPb zw7I$r&Z|_NakNQ!2_}W=?cp)>vJ*a~o#WYI*UK}nj`7#-^&YF}{(qUc|Du5=kqOPy zSL^q>t_lTYP}*20HGi~>MaHWJ>KaancBv&?QRqT#7$Owp9(}rX*Zir=#wUSS%4eGO zKDA&`%+xJuRtpC3ztV13C|0-;r!iA4B%M9IHVYC}+~PxZ&4(RhrMsTM7LCL3Rk}jl zK#lysOV>TuIuJY3;UJ_y6!|G9J+fszk~1SvLHi2?@0y=9g2jRqmh(~IIjOXonpzrg zc{i_5^AqsMTubycCgm*&b9L-9868!5ky2t25gAEya{M%%^V2Ka;k=?8gY3}j9UL6? zv1p1y$x~jk>uJHsxBt%w?T!Q!cHJv~gEizNF!f~<)7 z4J=g}{8kfTo!c~sPx9T*+GebT2c9ARo@g{f$^L;-47eHkq@YJjfWnj*%Ed-O=Y3v? z+YO#!WR~kh{R*C{W_K%*ZN~eRh3o)N~7hWgWKWmGihttXq zxExse+l{~&BIqoHuP#~5(@tcGfRU|$fL^b=`#ZpEev43S=W?^(BNm*-ASCR2i+||d zr(rNkU%k>N3m>98VHgE)n2y7E{`|QNV1tB(g=-PElU0xi1Ajt^u&r z160uKrF06GvB-O}R99?yBTjp!BT3p5kDdnw%MVQ&0yzwf^cFgkyR1J;Sn5j5#nj!m z{Xzf!9YL*YKDLP&)9A2<$10p6U5bPA#*rf%H2(gX-|pscj&jWAI436+n9ewG$S41t zNs2$w*4a6@^yUWHEgX$+9c&##<#za!wfF3dilylWLZj(`Y|Z;9K~38-sRuTcOQ=$y zA0{MGZ_pph=*30Gt8|9vj}THsvhx5;aN!z4ar8{q5K0C&&MUJ@XFz={JM)macr zqhrUErssjl;}BSv<=Vcwg=>ziPmR+bt5LX4ybMHc&N*d$zo!iY8V{n1Rpxt8Q{3a} zQI(W#lkgM17P&`{p#dpWC!iUI;c;T3=eQU}!f$W*L{0FBMG;8RyDu+zBO_7?p0uqj z#=zSmy1gmQ-0EJrOZlv-_~+&wM8b3$F8LPvmcY{}+Dz zf_yshX7aSZ{v&fO@b4sr(+5}_y1)eX6luxMIN>sGbGi_rxCSW%1M$c;J2Eou49nG` zuvtal(}+Z{RVc2G*JUFUY^(85Ow1(yi{3p7Jfi$D1tPy!9XBp{WZLgKrBe6c63{@@ zc~P+JYLa_=FI6=RUizONZf%BN7CAbSK?CsVBTc6cE}}F*6IJ&o+7690PU`7-KFNC^ zEmL%pgx7gvWq~eUH4lN1@uyd`Y(qfaQShh?0V7tqS1l3P_-`1QBY}0wP;P|FhLX-W zyFXg`>Z$8{!oH3*>Fi`6zx>a?|DQB2Ju-7ralwCg&wtWVUtNZ|d+Y&Au{Iwfl$Z6$ ztm{57+%3^31S9}1Khj*1V@I^Q|l_7dRzOT700VV|BkSuj;*e?m9o-M5qcf1?m{i?pLV^8&e zh2>Ym9muFtbohDjmjv_G-p>|X6^P4VArl1bIFXb02VREb^!IMWx<(0h6oUP9o)ur> z4Yai_uQCNeRZOY}7(KI^F)b*X>N&Dig#3;Dfw6rBj>`(3J+r!!wzhf5l_tl>$8oAi z;&webkeqiI?lmO}nxbwi&AnVGwsbqM^Nl?h*jIfoTY9zJE2(>SHj3Bo-OIAdt5G2n z71ir=w$zRT%}`C3)g-BQv##De|G&JtfTVujs{7~N&!-wSrXHJ%B_i#&jfWLJF{o>wE6A3O^ zu2p`OjLmC5y`uIeY3X-wgCQ#7{tBSBtvyb0`uJC>ED7AaA9G`bGRdTa0913&!@WiP zl9CMihhIkUk$1HAgb!v%xlcMX`tCfFw5Na6BVT1@NP6#H-`1q%#p*bQymqSR@Evn= z*n^BeBtZXtd@P^?BKm&Jmgu*5Pk{iO-mQ&OG?MSR)KpX@V1tw@LKk?t0xwn{IHhR7 zh#w{c1A{hzKS&!^;5Ikf&8d2~?()9cTnEO@)Xtd$uvoov3 z_NX`u^2>!CZ2)2Qt4o=0U&}x@-ioXFm_?-2;I_;%x zLXG=3=jTiLSQXmTvoV&toNur_)eiUqeCKrPbZ6Ix*I&;V%E$7LW)CMs#vurmmD?*< z>7u4QvW?Rn-Pgq4)$nVDM-Ut@VXj4&YnS_q!y2*;YM8PA2lxJW{Clbh{(#Hqt&6{r zxiA?r6a44{6fY$gmpVS3oRYHg1w|-W#TN(mb-uv49?!s`H0fY(zr%o!7f)vX$Q!xR ztQRbkpnjs4k}RpD6e@VKfUgJcBUWwXo`4*Zp|H8TNi`FIA~_^OVZgjvdz1$D>IGtl z+z<2lff>x>t}?9e7~H`-4M2PC+qZzIZDT2ysy_+t@JKF*Kpo11e0fI*;#X>8BgZUr z1R{Pyt2k0tN?~XXc;LE@+b~w1T3Ylx=uQBn#~bD!HwV`arn7z5x1HuCzjeN7mjA!O zK@C8Sey$tT*}s#-5kB%M3Rp zD8YcHZv<8d%$N54iFvE9XAHduQ-ABJsZpLCER3-NIwb5O7`N;#apcvRg$xAGTsp4c zW=;*EdR1$7aCsLi+y5W_(;IyIHFkfF;2en!QPJyI>0;8-Z;>0=kT-n{ z*dIDLI+~Pf4`c0Xn*FBbt z;BJu9*=C-(e_R()=Ko{uEyJqZw)bI0kdjaY6eSI$Rl1RoZWf(NcQ=a?P!N<7>5yED zPU#W}>F)0CTEu@YxBm7y`<%1)`{CW6U~Rmv^*nRVG4FAYd)xyS_K9A;8wLSeh#&x` zZ(FZ1Zo*G-Z6o-@5Wt)ZXYCjR|c)gh1<^;AM3)i1PRjR%%{vjETD+e-zY&F$3<0~-tu5#5fh)J(K%_r3jT z6rq{r`tR(Q;w#+8IYfkoIntu~f_IY18V`aM>BoZ2|d@rO& zjeD}~IV53o!VK`IcC{%j!u>cIg$xXgY){CU5%O>8>XIc2YI+wheu9Pu;*mSFrgyZ= z36&&W#=#Wtwq2-zVLE^Z%M}i*HAWu*+g`1~PRu$NSIB+1IZzXbmDc$=*_Jt3Z{K+7 zw&g0VGWR4?OlmZ{Jc-99;@#?_b38>?VxTOu2e~N<%?W7i}?O zX0SAG3~B|qfW2?zX}1Km%+rr$eFr>M)1b_Qi9GuSS2gA1-mq@Advt>Z5=Hj8ZP^^LKjxKMi-;al7E+}euvP%Anptx zNVUdd7Woaa(E#K&_KxigyJ=kt7RM+^5%202f%BKz2=)a>Q0-{WF!bgF@(J9n8Z$hW z{ml`@i;D{x9rx3nxzW3%IS&>V+DJI$TxZZ)&st{AQ7|#V5~(UhoTg=rUBgK(L1CY~ zE~l)WJApW&V|*(24vb!NJXz>PBX(YVPDi)leSNCzf;O?X3Knn}0r$WIZ=*cg{@=y6 zf8pymkcqWjT-I-e!k?lWuRgG+IO5}cFr4G-$VVj>oOqr9s83_I=dw!Ua59Un<*iu`ENGPBwl9NiQAyfUuj6hJzYQ({DGp!@yiZQRbHq;T=4m9SFH!1><8doIeOm-dqWW+P=9fm6?3{gf?snOu(qyoTxBAwFg5F zJHd1mAxz9bKI=N5rvT;@CX+m^Lql$CUXlF_`3`XRCp5 zcL#|6aBv1fXBrJE7l=k&4|dxRfKmGkZ}-IG60VI)!P-&z&FHnHf7<-WgG<8d_j~jE zf!~ew?seMUwDtp=UnNtK;Of>*u?bp_r{bW;LmZD!wdm=Oow;4N`I|V>;ysVTsp+0P z5xdIh>~wZ+V>3!Xo~MtLv5iyko);fY7ljpJ3yZXRp4hr2%`|k&Aw_KPCNK>*;`8TB zkBw296CZ5-^OG)vwcaM?Ax-7SX=$xXJpui2W4}#Jt%d);zCXuTvD1AnawO?IW|gP* z87LT`A9&M4{rqB{IcEPr!KnnzD3hR*?o|nFKZH9qfc%imUD?*rdjLLQ+Jxnnq$hQ> zNy6<~tP*5kWVE(D(>QvM1lHg41p>4J3dWg6x#fil5>gQhH9Dro$4(U{$sNo?FNXd; zh{^yYH_c*-^(z+>z(yjw2DZ2bs%b262y*2z9-~Y?$X~l=(i2V@BGAY>)KA}ji{L>m z7}3e$=_#V=oXp!jy|uNq@Ang1NCbviut9jXz3hQ`_?EX1<1N)f;T)A*C1jq+Z=Liq z@qHjM2-*U1zHv9LunsIS(7`QjCS5r)G5flT1 z-rh7U?UFXWWWC)?d6MVO`9U!@G9v((kxEG_n%6?xVxI|>-m|ionOTGt>iGi6*xq4d z3};?>pta6l!u?-D`iE>@A9`Xf5=U zJz1pkZV)tSy;TzYz8IY({iSfGXDyV`^gE{k!L3`jW5d7r3I)KnXM@r>?cx-_mcx*# z42$N8VCi@MZcUMYl4F#C3vBySygun~Xk>|mMi!#W=vSFQ>N)Kf+ZKjzol>_{CV^0( z0^siIHGnCg2azZV9?E_GxC8l<)r7ZhQIV6AQ#(EeL#|B0Z9KcT8$oh=9)qPnhH9qY z@X4a4_qw@TQu28W>niZ=1E>OSB)fDtJ#UJbn=P)*6vKQV3fm8pOkL@VAAdm*h1gdF zM?PJ)jdk7saSeOfzx0IsUw-%Jg}luL_L6p48vSn^I}W4`zOm-078KJR$i3v^q;?Ob zgK2w*enqTq0mOG_XXzJHCwqh-zcU-1t|tNhYP{XL1*$Q%$?Al*d%NodB)4P}lw4Im z?>Aug9`DF(c)w!2B_>&fP9ivz3;A#jeH}PcYgK&Bj9z3iD;g;_o8oIy&ygVE*Cs47 z6rcOf>N&HRy}elp%=yhcjlVz&U9k^9%9J=@e z*YJU*Xzj#<^P;k6h)tRU&0Q|DZx=mFA9~u&CJ8iQwViPz@RM9v?wq-&vbENPsdIvO zoual;NS>h6l+d1$u*U@>zXz$N(_(c~Q#qp%A|b5WdQ-dqU`g!tVe+Y4l>f!ZHwUAO zy(&(v)l(Al&KM(CExE1}w=TZ86Yi=$Ez`>~RiO(h_?CmwDM|KLN#|yy>*h|3Nr*@0 zR_zWafW2nt?4OG+&MP=CorsS9&xk=i5Tst8z`#m^tHf9jA-SKLE|><1S{+wCpAW8) z7k03gP)vDD^j0Ze5?9<8PZ&gD$6g2Ca+ z1HcHe*k=}vB_+_IhTJaz2q#x3kFT{A{5{~ew0hntntoDIGDd7p1Y+Y3_GBp<#Df%! zt(~SMHm4==lK%X#EO4w!&DTuY)1=gO99iNq&h!Fus}oMX_9Om9QR)Epd!x^n{vJI1 z0pq&mz}CkhoO1_(2?QUQ5LHPd)c}8)y65tt`O?6}_(&(S6ZcrT(dtYweo*C3&j$qd zjq3SZr13mzB3(QW99AEqp^d~IB7W%fo6HDG-(wN0=5kVYBXG3dwV`K_=6>}mLQ^ek z{pN%F1SFtk+?F`P?wx>UT(Nyt1Cnz6d8)xsX-1Q#yCTTk=n=?`D(vM?A4Q4Xyb0P^ zI-g9qvqCT3z|571d*pd?#HcATR(j(==vt+o#5F#>wuZs^nVj=i{QNJ6`(KW^E_hb5 zDwpCAkWDzp)kQbl8b}VZ^P}t}>g6~mTO41-^R-VmgN7}3_pyvU2o=X#ry7g!{1C|2 z$ZJ5a)yH=&W^R$3LSM&qv&lC=8i_vR2 zurM$=^<=|}a2vFNNJ}5IJ9M)GfU1l7dA4rtZ=djwXRT{Q=5oi^d-;&CR^S1e44w)L z%WWH1vDy7rLZgb>rrs7qjZK3^%2f?e(%pF=y1HF#()-mWq)tG@?+j?Ex};-S(qzdU zFtHUu!$Lf6BQC6PkQ{$m`T)$efAyd0`P@ z$?E`x<_|;f=yE@Pe{Ultwet4u+_xNuQ zTIY*o61ok0Xpv9mMU271#$l72Mc{x&&l9(<`qE$9c~9D6vsVP+j}y*V-A`tmKfeTM zo~V8>GfsMaP&!`gwlRnG@<&H& zTQK_8Ba1rWGq5aj7%N>lPK$zVx6!4AK1g%i;IW}m_$fZUq)zA_22GPLJygHp`T?PC zppZuz2i|{TmOr=RuZ2Pbmy4#CjQAg@AnvgoH%8BGekb+05J7R#537B7HNEVFgrfsx zd9+p);-w$))p~p9FWcxytmof;4+wzUEp?jqr3Z&sh97?aZYqlux5?R#S@h0*;I2l; zsu0udAVJGk)l2MtT484tOwK(h63mfd?ye9<#criMX;GH-P0IKVmlELbIh$fDBuujC zTU)V!utaNfDI<^nI4O(HnjaY$&cOmrU$_Ye{5_^b?lx>BSue;IWAI0Tqx&Js0glM$ zSBvAL1T?D^hxEZ|sp+N@fH@ojCZ(hBs5Wv}vC?T>wOa%Wm#c7+xP;ti@myIzEsKSV zYZ>;4ZT@kkDVzi8EvU)P-1FiU;OF=sUiTHZKC9n&_m{oLxE?+m`ci^ z-SG+V97Wd0-!%r9eT`O~ZfY)FHqHqSQXFCK%CsG%&oWbKeYMk0NKE|0XiXXIY?0md zY&PhiO;Ofmk!zU*c^6n-P3K@KdwTTCB>C_5;YZ;l@2KB>*k5x5rQabsIhYAv@M z0J}a1p#}zRc>A-#RmP}Uq@te!KJJFKJadQ6pka~8dAjr|Bd=B@sFG%fQ%i1)u>+(7 zlT&&)RbmEIBNxs?TCVe(m9g+!N5~fWD#c_I7^0L)zBbBfn=oh0P=urLCT5U=xyoJ-+}H9zQuc1`QTaruT3?I^2iE7kCmF z0-dmWfon-AM5*Pple-sqmtKJ)emePVFx#D2uy;tHFOSVDOel9$LOej4ry zyN0{Cg+>h}Up#H<`@InVvHSjHzXTMKDKf42|20W=P~{td;j4>IwS5<$7ijkTy)-@# z5T3J=1fWbcncCcr#@~To_*TDo{p0oN)Hz{j4N?Z4oFrgk$n^%31#qibTn3u7)@NUf zoeKm(LE)&{4Xhp@2+E7o7HPFXyK`V57DLec{)7-xgLBYLmcR?DUvO$NWjM$Hk326k zyrwRcrvOXH7|jOGmLT$M0Xf^#`ug+3HzEJLVtDu9Q4O2EY|nlsB~NjcAD&2 z+?O z>1_?)z1$W;tJ)7^gPxZ#-e+r9R1um&K8zc7f5NoxW6tA~a;IARzZkjvXAKU6VjAh3 z!>E_>;Rycaj-VP^q>(u)iXt|s_iFF zp2)p)EM@!NyapVaU}ufw5BG4#6I_*)hBGQrtIkVNCfyYSQd0U^dB%S~lo4h>F2`qU zUrbKxzu9oVw_dR`cp`?2M^}D*u*vW-CI$w&r(9q6P+0&?oB`0cqM=KIAu#GOXO{>a zzq6^!m6V<@tVu?)XxFcE8N8s$${M{(@C7h5<-oHVxHeR9q_K%;(&u~D@^<5cnyB|r zLOI_>+I1#0Iyx)0U222=iQM2q6nr;Sl*cVHEloitM7?&$U)^K(U7_P<1o_sT%@H?= zBk;mUP#*WoAsUNRgurkAZAt#^vtY30x-nQ7e~W>ZFh4uJ<+t8Wf*xh?o4n4`rgd2$ zq@fVlJt$$HL0lkA**$As`n@rhE3;gk%!yTu;f{+))p9$cMap$o`qBU*0ys$_mWq*R zxI~gqGK$t60KcqkkZ+^3oAqLUNKJj%w6thy70X5&$E^ZkpO_zk^SCIqwJVL)o=a<` zq}UrDn09I7O&~%0th|GO8)tQ8~|-R-SoRN(vr#gDW5hT&uL~U zuu+_CCJX0s`sCxY?x9hGkn#Qz1vdkXp3_Ro%|`#$=4Mf%pft51ho_V;o}uGDX)=Y( z5UPOX;p6L2509;USNDlwSEIBYupiEFWw7<^Y9}=dY(eW>bwNQO9g|8!(hJ&HX3^5S z%$hwCeFHo;f}g&K67DX>R#0%Ntz9Cf(kt1W1d(vg*!AjT4wh;fr@yCmkl<(>SsRVD zz}Wcp=ye~^aGRRfJTESsa&T@ay%K(tee-6aUjVlZ4^)$HZLswcG&z-v?=|G!wMA8i3$Z(>-@R$x}`4 zl$Wn~%A!O-EoE(ct&>JYTRu4lGzVg1^%mS^)@Rl8pJ|L&tSX1y=c7;5s_ftClVxS5 z5Wofki$&NskDs_8MyL*SBY^hG_3rkogNv#t|3G5>gn=AjVBEDlj9<)C&( zm8GAE2vYLZi5n2i$EL6#LtUKfl_R|CDe4NG{@b;qswK> zE?(E?1|hH!&4%^1HVBe(x+)=N=OF#C$Uu;YuDrcj7%kw7NgWY2bgoC1$w-Ho*<%|U zxrTdy$^ZG|o0Dnl1h0{@G|2(i1qlcBG8qDNyg{+Oq}nLbMTf-5@Gl0Tp@%Cs((w46 zIBYSNSZzhq@j^9$YodCwn0G8Y92^53O@~OR(cmA4Z<-fn(T$(rY0ic5_jg*8zTYMO z`TqMqeexe!K@u6tV>!@_*j2q7$j9#}#aVk%0`td>l=@hAe=&ZD`T6`&JM-#2;*2a{ z=FCGcRd2Xj?{Z%m4gvp3$Vfv>T`PciERvWkH%_}+X{0EFw$dTIM3%f&%J(T=J4E^7 zc+Q+Mz~8;IpF^=F`A|Qg$d3ZXKZHv8VUObAOj7!Z!GZ)@j%soUT-l`Us|^X8{@bOz zwPHdbcV0DCk5LvDp;-bmeFt8D5VsiRAj3b1XnZ5v4vnVpJpr+g%T;OP`Sbp%DIGkZ zzSykUc`2)g^M|Q0%gZ|VDFXcIW5f?sJxmUkm!W3=_;S1rkzS6#u;>0S7#kxo4R+@R zfLNzI&*Twc4A_7OvG@R97#N9BUS8;a5XqITlLr+SC*gGeTH&-|n%E0?Ig);V%;)n9 z3pCVBvLh}oZ4vh4hKeDHiESOi{(xTrhQL_Z;qBGZ=gfY0Nlx7i0~@0SaZ9MV`p`)&L_4GsufDiM(y2oSFcq`wDQGM(n(^jtc=Ee zObQ1zA{h5pM7vNj&Y8L`=KB*@79DCs+Qx#{y-ri-_@;NbmE*@s2mC;q*P~%I5Vz8& z)k`JvGm2SQYJ9`xt53fD|BpQcmodtk204cB4Lr0@M<^6$(qg& zE(h4$gky)$AhP@M@x^#-2DzR8&}>?^Q=Q_@(#x}X`U-s051VhM*_@khSSzwHC#hWM_w%pRGzq$ z)M3M3S0LjKQQ1-2tIE6yAl!!5yL)`T@)0w^{Uoi}AZX5Py8$~*uMr@EgVvVr`7fde z!=z5eXDy+dwTxUpZxds_tIP%U?))m}^$+2TMT?#PHR$~7Mfy|D<81QlBQH@55JKsg znHBel8T;=gLSa?SU^tvXlsG9DxC|Hd77L%B2*0GAUdtPp+tv$S?tbwg0Ec@m;`*ND zek23}%g&SoB9O!8<~1?(7@1LXS~6aBYHAtai5Qk+Bs+3?7}?&BLXeW#toJT3%wU4c z4P!}Tlo6-NAVEyi);T_ED`ial#@6Fk@$T{z}q#mn>$0L?Myr>%uHUtZqlOfeZ5 zaXm|L>#tQ|GIA7S__@8Dh%-s8pH9I)>)8G4OZ*KF|MD3N91ygI3k!?CR-ror#W1j; z0q_~Mwdcyuz`bSk{RTwKeTU`|JtpSvNU^xL4m9gUS{lhzSss_eauS&Td~U4ZTdo77 zi6La%>F?*7BctPU#MQ|yc)9ad6cp!SIDJsBU_!S}p|m)OOxG9C746`$bC;A8Wd zH9CU!r>sBP+Sd7FbX1}Pa?Q|5VU4&Y4LC+O1U~D&i6+wPWG7#&ue3wEx4L(-hsoa$ zPPh6&^t$ya=Kz>ydG+1(QTDMF8XACj5a4=1bW?)2tC%6vq1-vb&Za}qTvS-h^ITzt z*$B3uTbX)sPFhdt#M8c(lPLyjabaQWit74@%iDUb?i(Q$azq4e7{-qz)nnXMa(W{O zsO>{j1GXw8N!z~>{yM&^w{(5}#hc~7(O*A5OBw-81Pk{wv|nK%i3TmjX=|_-=idI# zCkBa_=OTmv=;)Jq<*~BX+s?mrpYqh%aNJbt@%JZq{!G{B__Z^QD@%WX7D;!8d6Z80HX0R}E z98gKx+B)x;=cAKKwInMKCvzRkkwTy3!EE0UkCxa;xn$Cv$+@8jZ|s>#zcUWo_QhoA zH)<2|=zLZmVkhm$F}4K1hJO&3BtMnIv%s@gcNW8nrBx_=-rMKU^Zu@>kyQ13%a0#@ zq5Jk0Z-WQkX;?u9Kue>L>UXU{V-$8nQ!&fjh(xA^1#z<>iF@o4XlT8FFn+w;UtZ)M zj`zb#F~YnCTBxMd%FZmR;_qjsoFQ}Clv74qr%3Jh^@nyhIshx(y{H%*#l@sX)&CSK zrcpueBO{QG`YW4bi5CDO1U9P)*c8v+dt9m5^yhnZ4j;%eWaL`9q8_m+=KxVv%U})( z$^C37cwKA5@}MxsrKXu(1^RHJKBcFQYeGP;^cu))UM)(sR=uu_cGcyRdYhd5!hbal zblV&?;td$ADF=h}XNrvXHW88XHNB#d&eOf!z`z(?A&1Y&u7yG!5drEm0exLr7bPVS zIC(n1lC1mFs{yO6xEbgVU_!StWIdl!dRL@#e@1VYy^O=uRsw?=yM_`jtWO_e?0t0A zst;JTgLgfHI{4j_!cRN2M&j^G8W^dPB2Sn{zm3rlq3;pB z6rcFJ-FNELiD^NkGuL%IPa?9ZiH0LWQ7S-nAim~~@H);3d?-y!~WYe(c( z?L`{dvu7kOyQ#q74G!EZE|&K}^nj|$OkBlyt-#$a$BQ<*{|=9zYYFiVe}LcttyIC* zHJsAXnE-V~(se~jQ_tMNyp5sHcmx#SbaZ!5<#p)?oW{NOA$0&j=pOXx(AF4rVvCrA zYL#lE1se!AuDi`ARode->I8@HMk^qg8)I~4t4bq=9bp#pVnbzy4Rj+Ty`c~IQSY?t z`>%=v5C~kO?Ca5bmwO6t6Sc5Y%3Qs4(IJ%AP>K$v`yrbfl~^K?`51(+Jch)3E-74h}^7VtgbIp#Mef@gM(i^5I9&ntaX1=5)vhP5o1J);K!3 zQku&)*TeY$gP4FM=}g@r#uFyBlx`11e@(vJ$wbA9eiS1uE_S%Xy6T8OURmuIH^n!1 zOz&xgfR1%^@=RIHxR();fM=sDL72_^_fuc7$+d$~^Tx5F?syC*yOIcZD7`H#jM;wE z!85G`ZbU-ce2A=PX2PMI8`ig@t8W#3ZZ2va-6OH*=sU@fb)-H z)tU)dH$MTB$C7y6`njKo5r>eZmA-fZMC|I`IqIN*H$`Th&*E4p`ap+x$xRI~qR;JY ziz&I(n}Oc9b;5}|oivW}ja^Mir%Uz7mj=P+dB4}q_w_($%gVes4TCfnbo^P4Ui%#| z&D><1L-cd&XT)jSWe}Qa5re|ayL*xMqS7=qGP6JMFitfF5S|{epUx4;8g~|(tPZCA z;MABw{R7Q)N_u%Uy6o6I`?b6Oa>4%jYw-=_g1k;td-TU&YCqB?8wMS>g8_R>Yq9a% zCA?4NMA*lZU|EWf_NG;H8p9G8e+=gI#;}GsIRh`3QjOAD{jlMQVqYVflDq#YRE`18RmRK%4hP5Jyx|(Sd_m@!8$GTzWO1$UORYO8Up^ zZxrDHC~KG=5w(QDc$=6TDkU3*OB!~#<>X%D=48@#Thy!mtm@Q3ABBaFZ&#e-VJ&ZE zKXgvvpk+LnvYsYzawDU0<7L)tdDMK-t29^l)2vA_x1{6!TRFJb6>2D}!mlYcoEO@x zo|m5~5>AYLvUI=xi)Z%#NNy7t0rA}D^zq`4&}EzqT!c?+ zwQjZCWCu9>pC{L_1c5^u^RTslw~(6J$cN6n1QI<@)d^GzQ)y`C$w4$UkL!uNhx7rb zp@OJZA34ky=O7wao_8cU_1m+iJ3lX8QZ~|`3!y79>w8&W zUvEl!C$rA$3Su7gMU$7^;QZ`?upDC}&CFIB94?@(1u)XE-FP$)2R?99>1jA|dn($T z>V_px$GqRMGXS+TG_5HPqGxzJ82Uf#n9qQAiU6&$NSX_^{FS{n=1=Q3gP9`to zv#tlmMBmK3h57>Rw%m&s))X}{3K!<`U!%8QIGjv0urA+@U5aa7)2 ztSP^_J};fpgU@UncSR()E!D?M%I`hoc0W)2j@G5!Dh;j(sc9}(qf_2N_EJA*SN@R^ z|D%$ybMDJ!_g_=e?kHbHl(nFg%Cu05U&`E9eqf0#A^&*>|I1G%Oae)i8yTOk{;_X9 z)}SQIiFJX}|Habl4JF{ZKAEW^#<*UID^RTR#<~F~{%8r}iGg~%kTW>% z0{^n(9QfG>lMrfQkkin}r)G+UHZ-VaHYJ3EJd7JLZr2lT?d$h&J%K19D=%uTo3i|9 zBiv|+QN(d0ETcmG!QL(l&?*N5$ftZZznQqsYbz=}D5 zT2^^)i7%t&{oR6Y0V|Cs4@Z<$h~fFVk;LmqomKQ4`t@jVYn%DE_S?GVI$ETaKT^ee zhYP~cS6svB~SEI z=BsuGEcy!ZFA1&^L9+3^M>RV*kz)tH?Cl@MdZFEqTg6eb7AqY|{@WgE#HTPFMewQ9vT&O`+BU^qTP2T;mB`7l*-m>|P(g+w`cfIzGl72hSebe(j0*CohCRnm@*!WC7qZ`6vLS8k~3c6uN%RnDtPR|ywea&>*ytN>cTOv2605C3$We8I>}J$$+Hhrf>9jd%eH{O(r8jN*$W z{-Hf!AR9FVUqo!FSntdxFiDYTZ;rlNA)uazt}(bIx<5a~xp;8z9xE8w7|cNP4r=Eq zZc~8Nfrf`ai26Y|k?l}Mp3O+z=)kSw`Bjzmt#I?{wW}q?#hK+Lkl>sgQ!Lc}`&d~c z3kpTeUl!NROWxl}{&ePE5*hL2sjEH9e3H%FLok_@5M9H5YRu2K6n~QFOa&qW$Nze? z8M$TVWBE%YG#M^Du5wbO5%FSSoG6jQ5oy&>&6Em$;QeP-+U-M0W{qj z?9bduaJvm)V5mqC;|-LO0JfBRRCtXprT?jGE9|3cq+dAo>tw&h#o=;8V{cUKr>eS* zg4jgc1qEul-}s8Qef&b`tH4(?FG$xKYCtu##AauDHN&O#=qR+Y?P9Ko#M3w^Jyn9ulK?ccL6_WuK3&z5$!IK^Tn2``<*>Pi9l>6+kNDJe>A8zy8$qu`YHIL;v$W|adz`T3gJETAEr}d2eZC76MpyOy5gbs7v)AVSq}Y84Y;MoQ*7AP#U&*o zWrKr*#@)$TX(9&<3@{Vp?vX`9R)0a$1LxZXR+|6}<%);jW~5WpZ@cYhF;mS@S4NAX z%$iiW)Jjx?I4@|!DJkhWDQmjSoooIQbXnAu5PV%jLS0>n1Q*UiC;4S}4>C+<-a_I7 z!^!B1>q&kfT3nVREt>tR=~tk9D!ODyNDR^|5X@W;20r^jO7mYc6zc}jShVNl6xe7O zQ}XjG2iIdVMnpD+lo&Rv>ek&aDte90T*>TkdK*{#W^2)kfq?~7-p{HwiF=8>uexl= zbhQ6%w(++?r}5L1#PrpHIvgzb6|0DYwwKaC+mchh#m7*&$pwtw;FoyiimmnENy+W= zx3B93Tp(=GelBDJ=5TG|;Z{C@?Xm@ak&)A1rjY%&6iinRun;$BnTUT+Vot`-7uhJa zKHsny+ed(5)O2n~t921HTy8^Jfe}&7L|J%8?8Bo}Mu_Wfh{uR?#KOh&H5Wij3?}gI z4h+!z*xJHi9`-rBPdz-n=YV>@u&}5Ln`d6%NR+>*davUmUI=e-YQU|tN?&lf{w|!r z8soYz7OJo59%7((kSJ%iyMH+I`}dcu8W41GhLI6dT1Mr*;~i5PCKc;Z7QYPHsJ0)7 z3;Gd3sD_Q_aelE?VimA4A3sM#f{~_q=_Jvbnn)l@sk3Ki#tZ(T8w1=`+E&dx zhf7Yh_i;s=owvVy*zeq&fT?|zlLmVfbXZ9$ho)2uwzwP_n}pIw>}2qZZ&ec`o=}U@ zK6wkg^cx!9U>0l(ii^`{>kbgbHJu+;8Z|p9IwVui*^=@dIM6_+Ol&m^TXgUh8 zYfWX}Bl1r%y?}@ z0y@3X5z)VbsxDZ?Ihlj&hya_fmlvejHnv*-cp~Y*i8Nu2zww8ar*}J1e$!|GE$zN< z;+b$Pm=)?)rHw}BERc+b{VFJ@QazhDLcddR>-)=cQ`31EED&nu`Hd(jk@Ep7i!i&2 zN40+Jxuy!W3IdTJAVB2!R@wS3HkU9Rw>=iOu&1SG-kgJ@Bg@(Jn$lGYzW$HmR|7f~ zt-3xy5XSj1aI#>zc|#_(IvI}!$|p=aekf)ZE5)!$hh`}fCOm(n-a%RMc8chRufogoqw|DR04~MDF1Spi%>SG}4`336TlzhdyU6B?Oocjh> zlve;gc5$rw5;vsNyT3YA;@klBSP25A^#t&D6te6G#{>+td>6-R6BF=oL(1j)KdsOwYu8LqzPIf8Y1 zN&4lu|9~nnZXnGSu6~RPU%SHNMg?LO=g8 zoB+Z3V!D2^tKjvh(9P&uw)soVf;ip+0v5{U$>nM|9UU+eb0rJu;MIF1{r$Zu={9ry zn%cRaMv4dvmq4}P^#Be}LJhB4C(6-W^8x^ipimiUx1F>Lyl*)N2HLPuBcfvApjJUh zNCdO~hOrQQCwY8)+?b=OuMtsNTDqzPiFB+wN|1?&%o>FrjW~!M{~3=WimS%wLf*K5l+-$HL$-D`oztlM3TF-@}PgwW;EaF(!)h-AYimJV-m`mD zE6pP4|3pJkAO}sS?(g@w{5ou65A%(>$SlUI)cCb)wcUb(7J#z|;l(#(m$GmETpJEXPv!aX`B%*$xtLocP5XBLhVkF-glm>^7OK zz0UWBc?66xtl)~z&gy9$RF1c=ghWNA4a$F+uh>`c1F6Cc$ndc{_t~a(^{&SL7*)?I zRIr4P%gIxM(dDGvk7cEUu^RLuD<(+R_Dsz6l3zxB0+wY@SD^*n@BCNcfIoH=pYqr(w=N1I^LRmw54J7WUYK^c~RW0#Qao#qKZCMJp4gV zZdr-=)~5a1QtkFC!x7a+YpqPZnN`GAFuOymUDpct<-Tl%%g(FFPZ2jf9sIR%FMS#} zIBh`UqN6yGTw4)`M1T4T0Ld2?zKXmDHsE*9W`oK3=db=DekmZ^Usu}+d4Eg2w1FU$ zZT0va!Dx+L2DH{Lqf|*{tvywI_X9Z-At4O_TW=v|cQ~I{e7IPziprf*zIWq0jLSZE zQ+KNb{T^4t%^fgA+HUlN4J&ICjHg(|t;Gh$%K<*i7m^9-M9}l0_CRHr((Q-wO60tz zwp4_Kd^-mRvI^5*8p$RqOPj&f0|Wb=n+Q$IH@W!ZvPKr3c_2Ko!GxH5m!#m*{Hq<A7 zmDRr9qS}Myo-Ko{3v3;gAF0v1=3~j_&|1s(j)A3%T_)Dor~70oh0B+zIDLflXEp_O zz8*4vgr(_MC^Bg1)bj#$-b=sRYyKy;^B3?EXvC+m!~V5ccgVZ}G}m&!2q4z!-vU0P zZg^x$(so7aR5wr3Laz7{7|KB}TEX)E0a{f#XmR zh-1{bET$1Fb-DSB>-z0i*7{mT9-U$)InqKN#(5B}qYZ3KbL1$;pA`<*6); z6v47{2Upr828eHGmS;;zV-r2$uu7oXTWTh{iYv^DTEtewY?Rt2;X+Fr;jo{%E0drE zbtu7FTZ<&erJGs`@+ZMnfvi|-#I7!NLUd1TMfgryYtZOiPv7q!eJwHqZrk&2hbGcz z(`Y$g(*@Z(bA}rH^cI47RE}qdpG7%t?yiWgiJGdkN^|j=ML&$%{otPZ>>m571{g!O zc{bb}0h+%q2JW7kk?BlO@-5?IH3{Oe{IQLt>MpADYmMTta1Se(^rTt-=^D7=%>kek z517sNlN|hb6Zz)T(_bo=P~OIJFeh@(PmH%3+rr>bO`^11lfFVVy<@Mnl1xoV5l4&f z;v{(mZzpGEJ-A{s*(EK#i|R}4Pd2l#q9o{pOZy_me}oiSo!N#LRQ;>CV>kma@8>&plE>guUrCTpn$ z#J{XwVnJ3Tq&o|61Zlrk7>+)D?P4LWMXVh{<(Q+76V}62pxkFjW!kS~9QY z)$_f{AZ!U?;?IvXg7Ri{J?x;RABE10cKEsTEVkTz-8ESQuu*Vr>d_JOr{x>*ZFn6W zJxA+Hj9{a@2snh{lQtLECNAuWz+Vg_I?dq2at?>tv@p0saS0@nFVW}q_b0%wsiDY_ z#&#tQG~X3i*9#~~TW6b^r9BW$1;!DMo9`jE94^nfv<(czUw;>S-TeI!Oi9)CwKzE` z=l~0wZo>wDGGk73JKt=-m~(FqRXN+#hu}uR5K+x=DWrxPnte~wY3-1+x!77>wJ-f; zgbseCxJR`lAt7URHLqlzMc2?^%n$p*_3I~F8fkF{YpfQR&YxKz7?%j@`@8wHiNiqHLu3hJoe+WIxX~_NWW5e+~ zb@(V&mvzydi2o-39>(>7{&DvgS5gYf)q2`+m2Wm2YMtHJxthXyho{!Zm*CB^($$m) z``t88dgQM*5EW2s1mSUfQ?awwcEaWT#+3O1kH5Gyf!K5zgN;KEym>s*8FcDxT{j~$ z(=eu6oJ`;F$<6ac4rb)Uq@|@{7RGWGufLone-tEm{Dj3Q1kBK(`q_l~2uEM!>OCWk zSo_mr`@`%q>}Ra;oha=FMAPU1X?mf#z72b7sDa`o>{?2M337gMWH3 zkKK9yFxP#fPm1+o!BZtOS4|Cp2V4J!IRUifn>q!8QJ*4B;?P))Tj{zv=ckn%lVC!- zop*VW;ODwRoe$0qQOv+Nol6PC}9@!u%YyrO{JxG_HuKxcP3Oh^Sn#)VE{e$|n}n(?fg%-Pxp zm&o$1vMab%@yVgaCh}ivv~wIBu*9*(QZ9QH${A}lb3xy!T7h6FUGANh9vx?fz5E^3 zG=G18aAq5DHz2erlmVYUsUFv1a;a|Djl>ihVGrh^g` zOgVfk6G6lnu_jf*!(C=F{ylLmW;$`dF0pI{HgZ$zxpW7V>Psvw(Wi zA9w$_B7DYqILZWWZX0j^JzCy}u2Yy2s$vZxfY6gIU3_yF32O+g^N-@126qz6YL^QA zE@ZYTb7Oqb&;?mp1N#SPUU{RyQJ%eeqZ$5~#&)YZusxppn5whE2Af6|;(uJ{qnK5n z1t!R&E#09$yLpL&=qz`9AOE^pqplw17Ewfg-5WpZxYZk_ayD(ZO$KOPrrf2QYTX2n z#@%1Ccff~I?lrWL)3|sjD1IrP)A~@l)i!8W*=(%iTtO>oNb7ulizZK?CQ7^a%?G|- z%{&#)%YnSr-5-pKdN1my$7}*-ZZ6-q&o}Cs`~qv-Zbx@QraIRZ>o7SuW?J;If8YWN znC`Yf=C zjO(jhXo1Ei7Bt&$U4C_7ChPe+#yW_x|ntTBd9t-=dKzl3!Tvf2J<@ zV)u~z7jxtd)ZgUwa;z7D>vGkW$s>%Vub&17?XCvM5K_3_^0G#`b@c?|L!^Kf}IJ%`9vYhS<@TL-%7Wu$*xnRM3Rrf1y!%4Ji_N7 zhPM0&r(eb=2K<#1ut(S(I}+W(nH!q^nOO|3i=I?Yzd>DSgk2Xnos4nT3D!;n@96GU7mw^ ziC_piW&6jwvb}Y|y;79H#U%=QM4IRdYlg4-Sv#;O}-SmH> zsgra-!SA%Gx%KzsUO^!yST;FMh6@OvxhbDh^0niWdl{QshJdO;HG!+KCEwP4Zhm9z ziP>v-8xRVv$+g@5%d4u`;=;u3J)m9@c{e6z{`^3Z7CPrt@x4fB?+1*<(^B9fNh8NX z0g@(}M;?=zBlu%CvAfm6WOE}6w_Pg zcJK|CN9e7UWYK2fTpW2>tKEvcA;`!WCR#@;+!Szs-RR$^lKq!M{tyWPQsaoYe$OI7 zvMGw^Gp`~^D-i8`c&NTT)?T?WV)F?cy5N#pQ^i6beg(9jfQWVWdLYF*pM)|QAW=k^FMrT-Ti3J=6 z5SFi5mN00-x+Cpw^J&lxwJPpb?S-VDoX5=BnjG%0#MqrIs23WCzI=a&l6|Ub9I+J0 ze9Aa|CZpa`4`q+1XY=71| z7OiwNm0F4aW(>od-0TRmBTE<1BQ_a#-(`3Ac54TOgIgmsF3t{-P48#1qvc*#FL*-> zjnuqe+kLnm8lv-!y?aXGK1K`B>bkF8=!i@@3yqdYrV-dixUF!Mr%OX}tcpnrMQJqo zq(gTIQf&xQnT=Rpb&)ObAhKVwuo!RlXH{G#xUsw*Ws#11`T|)@Z);nX`Pg;y4)iMa zKF15dKTRuX-o2RYx%Lx12&2Sb!&RD@QTyGq_2*;%+fTY;Ko@uelbQX`zY`<$7JJxx z6S^#p(Xe#{2P#WoM&6C6bXvp9t4=@idEs|))-7*zLk_~4K{qpJ8|$;nClhO~jmzNJ&SWhv-7nK}8c>lcl0S+mn` z$Yyg*nilJv^X{j^_sv0Y8t@f8kgS{=H_4m0hcV%790p&HW3Ysr*X(9`R>0)sEOUV0duZwG)9XsT>y zJRB5Q+Sc~63bMqd0dMT)wqdT!Kn2AXTWY{n?g7maq3i2*lmXejeJmrlIA;YnW<wDr9xo^-Iij@%oJP z*|@EO741%=pWLn`vr!SKR1<5qrE;R$SiFI!S7EsU0+^>HCDm42y8HTGPmZsuVUo5t z^U0XsRKX-(>BE-=i!cRdQSNHhBs5R(f~rC0^KJ9|qy8W9jX&c1C+;_XBm*++`#D}= z)4L`g(H7`X-3$^IJ4`6cEx(j&onQYGAwC8G03G%XizrT5{kH!mn z+HQG%$<|LreSX;S{L%T6k}J0f`(_z?mDxc_|HBC+#zWA(UOLjnJLuCWh*lEgEeYxB zTw-iG1OoMKU0q$58-@eol)V<%8Jw+bB14$_`ub!}R}QiIFz0_JHp%^{`31-8hdaOd z`~?CP4uYUFVvK|``2~f1Z36;+#>oc2Rjf=^`hD$M=~M`#>sCR}t?s2MU|qD=-{sV~ zVkD5;!yg;W4l0S-3Si#Up;|m3O1H45e%Pe3lK4nyT=SwUZSLJLnMCjL_=Doze+_m8 zOtDm-o=SB&x~qZDvG9fJj^&_?yx$mzxRg92P5xK0QO9H^Jcv_O{LVng{ir6{K->e&T}#EJ`>Y8;$cDCo1x@| z*XpaFBtnn)84U8y6VY_!$%6+Bfg$lFrF57D#$cyH+5IPI&;m^os#^eVrLnL7JpJJ{ zZORdp|9F*A0?Z+aXYi1tMr{!(D2>(H7Dz@-kt%jIn&bw6&5;XBQ?!-W3=_M0d0JbN zKl_2PNT9#6NApPr<3!6Bw7rc#T1TpBS%RK60*C4{pZM@3Fqql){pud8RCA)-pJk1p zuDZ}Yed_o>MyX?kr~oOOm*=8=D2)+UY0*;lDUh<&na{fKtHpladE>xqOU+=ELl|l? z6!mRDpeI4xnN{}1?9PUt+t&nf1Mgbu^)W4`M}hZrIGBzILNT(NW4 zZVFLD;-8lCA_R@qM^@6GuGF>BE|APyBEka~2nKh=HZU~QF*MBb^8r(~ZChEsY;6tk zOL-MaIFFS$$QIRFt~5{R=s5ov;BAc;qjQ9oo>{T*jw&~ z1ltTTHXI&-Xx3Ppp?nOwTm(lKx&0y^m1RfcocF)78n7o|yqNm^aC5pNR4WUUk%TV) znD^CF9D1v)Mk5^W*Fd2HA|rsIG?VYm)ZpLY=X+pm{3hu&pK*6rMk6P=AXr8C3k;He zpIdrsQnr~H?J0gBa0Qj)dCGbZt=BzCTXv%nlP1XRvi_0?%pJkGZ_%9p4ZC|+&~~UM zVe*j^qK*xcUn$Log;v#!4wDIixH{s#<(nV@bz3vWdCT|vQ-wDlE4)seAd601<= z{5<}fV<38`Eb!{UT;Pn4B2%1z*c_b@T9Y4dk?$pyWdAx!LTU4xwJR&)|HD2; zPyv>WgWf+&yB{?H5Wfz!0aM37DZ6g2Nir1|s6++5qMj=y6HApJc6@XIvyOjK{Y^k1 zadTXw`SGa>gceP0T^EGfgPcYse4FT^>E#W;zLE!#4(%5sq%$aY3n_z`4hkvdfy;f$ z=ff|4>4jBG(nTqvLrVImtw9EZ^Pnq-o}WJEx=p@Et5o#F=-YEfb_2z4TYKoUDQBi< z(uYGne?G7COrGD5EoC-|$ym%j=|mJO>zmK8Ftfa+5+NvFMi7KO^ugm3GGIH5wE+Af zqpeE-$yF!y(FTkC8qq%sZrC)Mu#!vCG7ks~rb@WGZEozYS{e?Gm42zKwW^nh2Vhq= zK`cD!j9LjX(4?(?8KY?9BOeK`3{~lW&P8R5D+RvimD_WZ(g(^TP8164w)SZvO~Zm) z55el#N1~&aXlVvh#Sf~!BI2=aG2gyRb2z5RSKm;xf=mA^NCqcELz6@3(cx?~GCDdi zI8x6B>;|1Mo(01q!OCdH$Bd5DXt{$JqhTA18~CL>4^HKSjn;9FdCjBehTe*a9m=IY zp$}mOVsRn@vjbFz@1|rz6HnW9fZfzWQkz+(Td%>i>i*6~M<(=fVWs$IIcRmA@q#<- z9z>z{ldCIWfI^oZ{;#U_?7zpuSpG9q!3#$GvIn1t%sH&OPvC)@;Sip3wFlYKcYMT! znR}lnqh=dJ2BP&7QH8&b6R3tREJ6l0o?6;M#T+2^&$XrhH0=`D!ManNH%295!|}&g5GHsYa&M=J z7r!uhI?03{LgbIf%g6+}Zz)Mn^)M8WQH}&V7nh6tHi`ygMi=W?d#1l+mC46o?)_r% zOPCZBp`;W$ZvUR zWreO&SJ0eXR=u{@xsCWnsE@3|mj?grCs`3yl#V4WI*yL7rHcmxZ!6{;Z0SDuzQ5v4 zWEQYfh!4Re1Uew+m66t0=H8{fkX*Mfa%9H@}^&Ct^3x$Hq>;_DFhN z0AzLphzq~k?4AgTBG9j|Iz!A7J62wZwmJTZvBTF;Y0#a`)}17ZGk}$^Kbho$z7j-@ z?3io*z|Z*q%o+LHQFyt@!p~kwt33KLK;{J#vEPo|i$6=Nzk&iy?iuj_(Opl3J;9!b zKoHHAd*(543~tI z|5v8r5Z{MSrj9<-IZ19;FcLK60!nu1cZ=iTlZ{>G%kYQU*krNzEM5NU%htEHIJ(^9 zx7CB`#GA7>e+BlFFsS;TU8p+{rx&nmzEx6RFlkM&_O+JQ?+ zxO6^%{~lj^3LCTuQ&vD9uL$Pki`X5 z^?sXwq;Hf+p{;h39L9DLOOB;s=3!DrMPb|jh_9tw00);lW^GlU09!6nK`jhM5lL1?fL%92SBWRC)N8#Rqr6-r?Ey<(~ulD;V?VvJDE(gU#rS`7V6ZtaADL+_+5>Ulv&a7J*Q^BqKS!T@lzOP#8U%LL7LhJL7}&34z3b!b zvY0138LNF>+#WXI9@sK^&TL~M<-e*150u0|i4q2fp|w5FN!lZVo(%Wb(ezlT!u4{t zs*JfanHsvZP))iz!;rKmPGO%2YjBxn-MH>8azW6~T`dGp#mNN8Uk}HUkP1WBLz4fK zcQE+|VCY+fliZ;yfK`H}c8$Q6Y@eTTy^R1UvU-Sfpecw_K=EYWG;txhBOMGxbpYO% zl#xH;1qJ{`tN{0V^}jJif%cC|^c30eA)dBm2 zPv%%(%xj4R40Z+z!aVp=`n`xaWrB-r#``sae}E#}7Jy>L4wLwq10ls`jdjb$=H?fA zTg9t(a|0!PZ*SCT4aRKj;~B=o^?M6w;H!?PJ7_4~yM+86q2rWC03rmAA4wW|v^@_- zupd15af+u0y({dPClc5XRd)l&0T(NOOWx;VWnWYKu>FtS8^I*eZDwZ**{!}~`-&wn zhQb07AXq*7SBtRie&NW7Lj(paj7AAQJL#}sS zs6n~^E9fpQ#w15fj8OAL=Jh~uNFyG!>kLxCOxf=OK^*GnOa5_{LWG|1giI)_Z*gX*%dSZc&cKxp ziev+-^s#X(P16FD#abwQ(7zxg)TVO^*DLnF&O{HE=dzE!NWwTYHIz?k85;6uwE*!h z>MB`Lp9})j zGZyoJ-T|)g^xZ;!{&fDTkkB_!;!<#7nfT*GZ1TLk+^b#fVxX*|Y$Ok$G zg!YQOHGC>Y9pxo^30TTTSxbs%E{D~F$krw z0`FlnWk&#Zlt?lU0g{Ve7`14m-(2-A{qQ%AnC;*SnFoY3-3o6C=D{nlb$kKCLJi;q zf~F%du!Wjf^Z{^YS`!uhJ`~#Z$1gBAR4m7XovJxt&%`t!fT=GPv#9D&(%S=BJttib z3-)qhT+TuRa3$RSJ={<60u7bBYSdfxT3Y|%f4U(=2|z!wr;n>1K9dEWeq0rlSl${8 zhctL^anThhUYYp^3F4Nw=D$_o3%~bTwFkXW{Oct;L3tuIpugSAxqniWCPlx<-uTF8 zAgkBH0P^V}<1WhT+i($Poc^#+c*TRpdM<2}aiXyh%zxD|bOt~+D$g{dOL%wn4Yd&bI?-?9(2I z*Pwt9#YuWVcu2Vk{BUYg7Vm|sAc*9ktG0w=p6gVH{oV8D&zmCx&%P-wH2}nH>}$J~ zx4|UsJeIbKHZ9WX_QDh3kq`=Kf9@l(ZdKK*v9^gwr`^Seu+RAVDOEGkI&PEY&j;X> zB8O~w_$X-S1ugTGL4&l}WOE5R-nIK$Ts*X(py1s!k*;*A3kZUNL5wY+(g z7aj?v%#V+!0YNgOB~SNOKvA!Aa&j6+BO)S%7@kZzSxS=~sCq}NkHap*ID|4u;svWPO9P<3dS% zipDg6_GKHy8kqZ4P14e;3ueFm16KzSgFQi)k93CL)IWFysYRggQ3b`MF-OPCDjj^5 zCNE!nDknYcc0x1hB@n&KQwl&pMBp%f^I08?`6X#TAjP&dryVMVe{iHQQ1e&6|D&*S ze@ffDiaHmerGrTJ0S_JAzRObTP5>~x3J6!$gO}BDFbKu_A_nfn zDW%YiWHFh4g@Xp6UUMbeLt%SW+-R1bVuPoK ztO+uIs-fF`(hyzbj}Liifxo`Btpt_*tEw@73}iY{qGQORG|LD;-oK>qs?~d39KXyH zY^{0qEhA*a1onucdmw1(4jWZ(Bvk?($wnsDC53bQMm&tPV4tY)0Lt z*b%Z02xm`31HT&tE~>cNb~|Es-$VSu_WgPP*(BJ4?0qJF-^k26dhDgM=u%PkP{-nv zmQMTIxM^wgkV#-7fn#7DW!6u4Vuhs{-hp#;Wau4U4T2aniu_oif(&A3Q@Y;z{y{B3 z>rU6uX7do&Y>(cDpVU5JnChic-%j>}V}lf|KpX0+BidDc@c1-329B4J1oLi7b#cS} zNWv?b?0T>O{D@ZeuIK~+2L*CBx*fTj>jDe8JL|dYpCmurUD)(n3-xQO-0H7f{=J@b z;F#dCk)4DiLSU!?8iFdcArEY05Kc>}dMzvU1w=z-$=vCTymJ0+ItCY7U2`RpmF|5M z{dqQ@Ux`Cqm79%~Tp4RCMU`(Hd}a)_j-X5wvTO3XVBmUP-1BdMuM`KkHsxp_}d>D{8M zJ=jd#H?o5k^Q*V9?I z)J-=>XggU0$PX1m0|+csfxyCD^>-@|e0NW69^p^vKKZ&dutM#~%m3@C$kfjRoCQsr8$Fa^ivQl{b;)6H5_^V1aRhsx#NIS|%B)2md1r<&>BN#g{% zKuE>bftn?$r?5x_>tCaxaD8-D4WX>$ktd`ASyq5YVRDNeM+4QG+ADH=+t)UkOKbB_~?k` za7Np1bs_pawodFE&@f-IwbGAI|IPc?MPt9M<%E`+wL`>q(S+rq$nY{&^e5%fEC910 zG|Daw^ilnHgn7Z&}Il9t49!9EQjquC4lE`ZfBh=7ooWD^b z`oA4UAk6yYl1TO8@vmHlFHN=s15LAc86@zc>BUb_hpIk103Zg|Iv*G@Qn_PPkMLJE z<(A&vmBIE9EBpFgFoVEou0TE&n@B1m#VckhE-cm1`8Q?sT?u6n4ag{Sc!eckb^HuT!| zrw7fAXzPFil(>L0Rs4-H=Mt*%evkXNS|<0!KM253L02TNi+BiuRfT(10(j=7=)@GC zG|0wFOBrrjCfL^=lG0xR`UfUc=hD*C%S=m43xWZ}T?NZ#{f|AJt1w#lI|kZe-6)eB z-5nu~Xrc!FPK#!^69pCXSgc}tp?8nC=s1xe*+5v7j!R$YP|dQnNg^muYFdrdgyUag zk+e_Jd@A>~DAI-Iz(Pk8deE7-1SBm_`A8DBX{TvNi931Q6!bYamW}>c*$2put2iqn3n8DlU64)AZ<*QY4S5Rh~-dXA3Yzqg0TYOu|yuTmpR-0 zIvh1rL61r2J?;w>Cf@C7DxO=*J-8F&M!QeH?+vy3vDsO5iC|%kE=j1DY?ceAs`Q)MZ&-Pj1INhO@z6cLmzz08!JOb;I4jg2x(Yv8PcCvb) zFyt3&D19pACXSexO+*5~jgG-`Zg15nQVU;7hozJN)@!+lfe$59KE*%qCke$yjIL9w z;u1Rug2334v3wT-Stt2Tf1m%z?lX14w1d=dt=g4A?8ec#>#;CiOPPNZ5LexU)ODz_ zjtA(+lp4mHkRLcAonu%3bl22X5%a#QW$Sf*n{`3P8|yulIclsv67*%7&yIa=G8v-7 zzDHacSunjXtO8Wzrpu`=)M2g#aHGFa-LBaMqBj4C=rsr~v?-HL^$%^kf7I-o zAXVISbS4ehL;fBL+GxR{mQ(;HM zsvP6>ADx$GCc`Oj-Lk$MUzaYLu4eOjtl^2g!&9NMP3MbX%QZ`^rFv#;;xQ69P*zhX zKu~PZ;=$q}W$_9vJQwykr?}o8OA#}ItGI^vu=!m$bB*UO87LpBln7Pip6 zM<(Zca}~E2V+}rd-}$Qnz!uj9)vaZxi?Tz&Y%d+!DPl?~E^c8tP>OMsd)D-lHM5k5 z*35@hc@?n5X=irTMuUq(?__3J#^}AmG9%BHnJ;%i_4P!IY(AL%Zd_z__a`C2%kDV* zR+=0C*l2;kKo`ugMHwBo7Qw)@7aBo>49OvH@!{`@wMd%xWi#|CbCfrhpNgdRioQ{c-_mQbr5$zCD^=<|NR45;#Cc_$cbD{*^nfPE6b z=#XTAl*hy#;g{;QIYUCfMkZpuClbZY~ka;3C1|%6t;|qk6cDm6r4H`Af+> zMw=y<{d_lXME93y>w$sdmqM!BVS#0gZ{S`9A*Soz>pDt^6V1L(eLbET|qaYoY$aCKE%A38hoJG>2-Fth7<~IMs2PwCSZP4KR5#T zocd{utUlnm9uM!RVlGlO$BLK^76j<@BJh{?3>_5@mHBSwxwlDg&{CjC+ zvi&Ehu(xseaP5M9`Q=CPk4R%jkZugQK5b`F0Bo{(5z3 zYJDcR2dozPzUXm9Pf!5`AI7s;^x7D>Gk?8KrtWzTmi(cMdcX(>3?Pt1kSRt-Eiftb zP%v4-eqsmff@6XfPuCAopLq<+<3~mM1ABle$v^N|Jphb?uy;qn`p4j4+49duVVl8A zzG>exFU@o!{4LJ$O)3rj5Pm9iuCn=aM|w#~>5rT;*Zv}wRPO+IOm@*+o*l|?G08MLQN7k#_3 z9m+a=e>iXaEXR`p7Eg6^%e!GI8S?f;r#dgEL`J|_c`!05 zf{b&E%)-|ADBKkua^l?5E&j)BsR{t(HXAX`LpC9!6F`6o_tt=N@r4yVm#jdQC~@}> zbeZL$p2Z_7@E633B9#JmdGIS`dBOp-^QKOZfQ#^KoQeAUnlBmbHTq)NQvaoS-!}72nJmaW zVRUR9U96v3{%o0;D;u7X*jK|GK`LFNcP~scO4i+E;)bWQ5dnFd&HcfR26;uRL|NmUMQJ5(3|@d#HMFs_Wo*6}o<+4qz5`HVrbKhREc-%0+b^n}K8?(I$S6#;{wu36iR z@89V!|KzrMxg~vTL4Lt=c)_DBHJ?hp!XzIn&dQ~&sUxpr7^(4yaBkA7_;EXuYFIyg z>(Nb6Gpf4Sm4PEz)l4LL<%{LnQAM-u>jo*#-a`U5Qgzx($PX$i7(zW&b?+*f z<13?kuHP7rid43}f5PfsQj})0OsaNW%%n%JSy*(qsF+ke$62IiNLU0GIifqQz&j`; z)#C5)fMGF6V&F3{tZv#Y9YTadD-*9NQIeEXH43jU6Hwsw?akkAuUn_1{sNIOm>_wc zg(GT+O1^&Ydl{$@9UWJ|q8qaxrEY6r=9agt9mCIfq1wyb+)~}6N{X?#Br-0NFE87O z5Z{Hd`&U5L>Ibx&z99pzW6Am@exHpm(#|X(QdAL5#M;oEbxi4wY8?yDREN201!KZU$FcP=b4Qv96^T>#OwEiTkD3&)Ga za2qKOzqir94N_JE@K1sP%a_hi7yR`U0L?HuJoPp*oUqqtju8x-9M*^5)EK!vkx5BR-oKZ7^z-2u-J2_n zA-01Nz9l8~fEqexRJ6nC8NNJu*&6uV1IcHO(vQ+0qL#z)Y;C!t^Xk!rz6xd2031)~ zGmAV4ZlSC{YZA;Q7n8Xh#^CP_=}*$kw*N|zm?&BIbj*BdZjdo>eYGx5DKIWRKBTy} zcU{hH+KUSxt6nwW37O7WXN_AIj-6_cACNQv>9%H9*vZK-4*n48WNRRM2nI=R@mgtT zCOH$lxR^*2p7WCU;EugpLHymHL`xTesY1e1I?=EPjcGm%0(v;zWo1)iR z?={H}A+di>F({RURxezh%en0*8cYZo<&^w~yaMJ)f%Zn}Z2@_Ku`IrM9L~HdOdj)e% zNQOb&SV+LVq|I_nJxRieLp7ET;cnN5{O(+(q~@4_7lu@VjxWOrxHe4*R|Y&ybf)p$ zKa8vV9iO+tfmAENGHH%DCbO8%qrO@`s|BUW%v8sM)JW5%)hlyF07JY1Qbu zvg#)hYEO-M_O*si9}$-UUe^%J%_Y0)lZ8*~rmQ~m_=ZusDCBW0+bcvi`*=~`6of_= z5u1cub%NbuOu5L^7UE!!+p&Tne*r;NSHw~LhYFfGXnoY{XAu$TmJQ>el z@EIy&UZZ7D#XJG0X2D+XS4<2(bwBubQFxuHTvgB3O#ah(zo&k`VH1WMl+)feew!P8 z{+U;mDUYKRQK|_G2q{%io_=;D03gC>cPi^!Sfkyy8xJgX|G_wN>2b(2aKA7^JrqjUHq zzdVUWm5oJZ^0ilVA#Aas)d)-o2@q#1p3$os@9#6Ge7@hmL)4pK6uN->h1 z?O(28kd*B0h_iUvoDUq4b-fmT{I6qM3cMA2jjnQy^DKI3jVuS)JpLrW@rneOWYyEj z-1u6)*`(UJuTP$_V0%A>*g6o_6k;3XLrKP?w|CQgcBwGE6h>!0kt!C9V z&Ypj!Fez>Z^<;IzDs`QUdNAG`9YwrL059F3h#=w@>H*1wT#py#^9#y)csmrNY#HW;W+>R6B)o^6R>bFS1W+x|0ZV$TA&Xvu7 z;QR9C{y*qY0INxZgi2Ox5;?I?hquU6IE(8>t0HsD0}@z$f->A@90#_yq~2y=IhhEj zz1HzsyYvE%I1};)vJJ`mG*x4eNtulyq1F;sjg61N|j#d zZ(m5LpC8|cCffLS<2K(}wx-`%G&w$~(7Sx6&~T2)MvW;(d5Ey>_Nceb*LRg~mhWLa zOY{+Y#wxemCdc}Hoh9he&RP@R=tg8j+=P32*Qh8Kxf8@wI{7gcijTCDR)T5N${kaG z9Qrg0mnqPH_$0)*3}fRR;_EX=0>A&{8)SGbl8m$spG3e_MpRaT#gvnVFb+`#qyy{y;t_%yMX z?YbmokmWK|B# zRACYOl0n0%vX`&cR9D7QFPG$JVA&TjN_(wxfOYA!{qJ$-(l~0UXwxg|0!d7SWjre; z=NwZ={V|9aenE081#m^Gu?6f%ZKv_0J*3JQ{> z|J~V4Z*?wg>Ix3{o zgiTHfPOIE6jkdxUn#mEM;o~%i&t=ZPe}k4F^hJG@xB2N%oXIYIK~ zN4SZ%91S-Y{DP|l6F$EBIZf63`4U{287bF*?W?X1v$f4`chx%SwIhJrosCCrPP)K) zNhJY?@0OyG5re0^(K9(vR;6WR6h%?Q2wHpV6&)cPg?7~lyZ*Q$JI3pS_W1(5N)EBO zz(QSG@NB1nT_?`Ha9^>Ofl6He%i2LLz`8!^PByDI3y)#g-P*Klj+yk|rN1Y!;4A_y z0^B8#4~`fPTp%b6#r%YM;}f$6yueIwVaf}+auc>hgDSR7F~n%=BJ`%A3>->475HBJ zWR(1Gb0(hwC#%8Ig1c{&(n3Ofb*#Pr4ofyD`AIe<<(j)$O2@Q2!c!CVkx;m1CbyEs zl`6OVCxKAuWSXbKc{kI)s>YOdij)+DiLb>8++T0oq3uY(5)85!G7-XtZ=vrkT52{N zDuTt|zjr!g@|1j7p@ozr`K_gF@?&B+j=u>+6_ajsF@@UyNmF+o2~sW;)1k!3@%C(( zg>h-hwV7^pjq_(TG>D8YU;ad1tCo0oyn48pIYx$IgCW~$lO?u}Ow8QUlGA2F)7)Y3 zmibMdrbgwE{%Drq;7J|*u$y{5@bFSHYk9!8 zo7GreEL7>7xPs!$Wu0;Pbt)p*L+}aia~XjPshBh0W+Cy?h*$%RxhiD%1f*gEDrg8T zd+&c!5i@cE!fy!?l*G6ZiKs@w?5|2FICNlP8<(XG`eR7>{WN#|(NSCc)cl{o2CtZL z0eI7yz2-X(Z&fAKQs<>QP!CM!nmu2+qoA*P;+Rdf%Q?g$5ET-t(~m!A<{I8k^G|BYEjNBvD(aBZB0Rjp^}^1Of5@S zUEUGG?CjhougEHY;k;u|Pb7{1uojDb;;`#T*_ubwt#)X0nVWKEj&XbW9T!f@z|Mx^ z<#)g){YnRl@!}pm3N0TnV(P7A-5_D|7nh`cD=n@5xkdGg3Cokx!O5}ZwD&!cLMFl; z5Uww5kO&$Ah=_6nAEY0H3e)is^Jd}*RC|Dohf+C(hGk*8?Rz zTbIKFcfd`7<2f!hAlvT33@*SY+~HpcP>+IP-Ix3=G1@B0taL_@zG_su3!Zar7!`HV z)hTy5MIDilvybotZ;`!vjkX*9_J{bS3`~~hhsX#W2BmyK9Fj_}jC+NgcqX$8YtVU_X+Rav9kyxOQ_dB!3tYI>3p-gwat z{KUHxevUGW7FVgZt@^0GkuW=+t@Q0JuwyLDF^$Fi`jzguxn#}D^X_Y<1M9onKR(Vi zY0Q2tB=%aJ6|EsOGE}~BzO8OX#WO+KuekeBc;HMjSPG$qO24C(mseLGftlZ&P3oXS7>hvbl*1q{Wh+ zc0r#=WW*NL+v%^Qj2N@PZM3w+5U+%qcvD!F5z-aYO1;NhYaaeM+p7=ezt-m6zx0Xw zkx4{X*Hx|)T|pABNCf2El>RC*b{!;+ivS<$lzLvrS!6jG`SNl)NE<6+F@IVe@{4Ux zSL<0dd%bh~CiJz|Dd>yhDn3_u2re+;{qee#p_M|{0_H#b#+muBNs-)>UBzu*G|a?& zgTB!hG9;7yn36FP8z0}QKa4P6w4L6aV-XBeK^GqUDZjZhm6-kg`6KoL@j4%86ZiWDVgGDB#VUp(Tl1JPG zaK68P#E8XxbK!z$%cxT4yO~_ zmOax@GJ}XdK>U&-GZ;k>&{%tSKbr726Y;eQz{#!Q&W7XQj*f#>`flZ!HE3+^+Uhn{l*p`V( zbb z{(*w{`;g%B^nGzYY`aTCY9PKy%+T1o1JA!*-yYe*VLT(6>9=cQ!kJd@8?AEFxwKU0sA#C*gVSH?jml^edvfc7?olM67U9`Fk>fYp zr?X@>^^!H4&R?kBR`6*%9}x2Tder0{Dp9b`^7_v9R>&l`jO%L`(Qo0p@J_r4GK85Y+ed3B>o?@wH8 zE59Z#VfTfg!P?sD>5~WxUf!_S*wD^lWE!h4?AvP{^`SD_i3bl*#RgQO1}euZsGA}VvX%JsSxql z^e}R7;0}u=)O-5Su{mY>xLvxhOc0)`fImD>n@#5&(;>&=0f(57xC#Orj}w?QQZb)3 zqM3~CBNkYAvN)Cb>^hk1o9Z}cWCXKx&h4SaP-GQJDpPbRSx~uuLVb3SQ4na}jcSs> z&Z(ekC#xK6?XEoGlek{)^Q!K;G)9b)9M*Lt`TRUc)IAEKpB_=R#5zu~FH#Wn49;Gw zs#!wDZ6KtCr=3;V>}3DiCcC<+5Sh(n(T%MTzre#M7L)ezjBzEPC@&8-}v3CHBtY{~=@lxPqqnM>z&dB(})(emXL_Yj_XrW?`}J|S`8@}8Eeb`flb=h&<@7hxDn?c zjDh2}0m4%SNhPgcOY(VKEBA#~GBslTtiR?sqnP+&?`SNi`?fbz#Z5w-I~7)jr|~{# z7h*gfc7&^TzR>S}L5xGf7}9Om&!9Qz9;G=44FBFd3*tgci!`fN7NYv*+Lz^WoD7P_ z=~KwL*Jry!B$GA0?=q7@v zX&fE{bAf7R?B&71Fkgl9zkXeAN>71k#^Q=n2}mVd;itT*3#^u7$rm=nq!Q-Ry@4{y zvWEmi2tX`1L_ZZdQ;PxlN+o($?S_}DL}5*>nU@BUd#TZastSFA>b=C%D)%j#+cNIB zNLf-(iG=laJa=fgdsB|H&wOtwb>;RFWk-=+^+FO8C*?U=i0Bu(OU0L-i&%5| zUrP6%zk(p2z*Mfo#0-U&KWJQ{*Iy?TaX29|L5W)Uf?OL!4ouS7DrR$1gc4UbWF`fe zDTlC~KJns=(C}R4^j{)Idze7rpp7#e@rMjy|BJC$psq23k+#NjZ&{?8Pd`1^p{|nR zOVR6xf`B537{7trtT7;zHlV8?W&zQ71!bMYs+B7pzWt+x+c>Y|fZ?p<4w$9O_Xa=&KT8+4rp0?nlK}3+2KJ0v% zguJ(DlRWh&1=ADDk1dmY_V1@pZO%7EBu!-*`0>!BPIKFhpMNW+;N2~ zF|;o5YHVG7e%$yX+bfMc_*2I3%Nz^~%n!-)*H&XkhYfDx;K=;2lws1JcfFq682rXW z*xjolEH+Zv+gWTxTbumZy?~$xRLV%QM{)2l7bDG+Ngz8>Jtfgi#i~r-BZ)2BboSkN z<}Q^i$y6pogY7onB8M&ZFO6C?e4rnPy*jE-*S!iQhlmpTc%N{R3bkvs!F z_nlmm`pH2?e4vlSs!RH9>jZRX-8pX$DVYBl2(RcbWWQBMl5x{A-NjyL-K%19cscDx z!h3HOom^L`JO(5yB;w3c72j37@p@KGQDyGCSM|$J)DR6%vfjDuPd4L7r^e(j6@il- z%Igjx62)x1+Ow5RPsd}_iwVDdtvh&-By`bR(ck+KVX%{vR9goAPY!nPkZ%i z>T1}86j&C+!^19Uob^5f9T^=Z&fJW^5_R`@7$5)fhx?5$Kfm`@cuTL_4#nUH2h&X~ z()C<1HZb+#U3Y{$Q^DvL^Dn;PKY9tezJ&Ya1ZJ1x7&FAzl%OdAr^%1@aUO1%pzDZQ zCZS-A0)u?4BFo8V9voM+uRM5O)dIat|977RpeBzZE=6hPPv-SsEW4B{%9NL>#l_{l zRn@&syRko>OQ_DNPEnga39hDRvE*OBN~LO0)iS4JAukBgez5N*QW-2wHCDxuai5}~ z337$Bwl-F?X6c%_Se$rQWM8`o4maw4BdjjaJh!Kwf?P(ySHCp<{4^eh%(hDluiWru zBlluvlF|9{cLGF-#zMBvC2{nWflV)YY@JH9P>yVTr)iq+--~+?AM)bWE358o`g@6| zl&@U5$Nuq^HKM+SSvK$HmZz=JJFJuQUjuCh?L`(535#507B1P|Q4iJ-94R+RP>DRK zA5y5M8UMHU{g+r^XP_uY$Y$?CvnA4S2U{i^(l>|I=fU(i`Ch;XyE3|hC>6L=s^f&a z9>bxo-oJox1BIc5ug`ZplW`cYI)2gSh}S0G-ZTlPmX$~%zr_W#&qI(4^AuhFYPnc@ zL3lVRSynXrCEj2;t_z(A!8Qp5EC4Yx=`WlVw;(dew+^g1agp!qdDMt)Vp>Q*x!l6JGI*gY#htc>-;K5%n`Bvzb$JU*L1^y_;vm;A4>Qhcr<3Wl7PW$GPsgr_$K z+nESEGm&_trICHfz)wR5eD1iMJ!KQ}_{GKOY(mkuZ^Onn+S_+z*W{qraXz}yQk&h@ zrHKc)ZZRx`+u93#5}Q%~3MOA-=(givGaAjelRxGri1&yVz6}*mLVm7BjH_YNnqa%m z5^-^3%>I0#0iS9`=D&j7$3{}yqwWV`Wna8h7u0ZH)OF3#JR?&rrS8`8)ZRf-n1KwP z`)o76#q$RxeH^N6&@U(95lrXLlMt}*xNDsTo6B{GIkf8Vi-DL1@wA-;8S0_Rp9FJ4 zJV^hJD-wb;t1_XOL()u-@5YDxNS3{^urO@(B#9_fd{dgT_fdJdob6yS`L)E;?6*5l zQ6sjR2GPo=I?j{q7+w?q@Y-uY`$hop5pS%{4Sphx;N|6An=##qn8_*A z3_Ht~jTJ(|91%=NyFT6Y`STeA`QH<=*=$#jv7>|pl&H~`fQiRhWGB8YHMKeaQ)d|d zY=0%|jHG>yp>SoC4y(66Ze&DT)+~c%*V(UsqUP3sn{~OJdBb1bP*o?);^snS@aG_jdrV`Cd-XX9Lv|gtzX)!?MMxZk=ZN<3!q0x0LqNfz$>LH{ zRr5lgU%_YK3%wi=@_F%=z;ofsP3Lk@vxO1r^{ZKO6!c?T3-Cy^;E~6ru%Ai!a;&tV ziyFH96?iAg##7JM*`XZpL}a{O|H2ljB5KvTQ|sr}YVnH@Ps^V<#*)*Ur?PqaDMbU>d-vW6-{1Yz;LGV;O037J@XJ@Jd~G|h z1Uoz1IXN-got(nLqvbtnYUt?cINp+EVFoEK1INaCRMk939}z#(J^V6>$;iNfpmftv zg}D6N3T7`6-0tfTE@bQ>^Y~DciINS5e*kU-qenik?BlQOFBp_iuS|2?}D&rq5T#Xt`xdBDmtFuDPo0$(?%f?WLc^cxo_HFp<}g!#&i@CSMBY&tX?wZe$oQvZk3f-9S~B? zBj8X}#b@AXH4;2Z%fXVlV5!PZqA9i{ZqA-vyySRi;a{e|cx?SB8cvd>HP+2W;=)=R;WCV%TfIm?!F2+Ga?$;B;ytX{?>~g*tX6enF!zPeHiQwn}Bq>!# zO%3YTcyqgN8ygXWT(L>4mnjHi*$>6IDQ*QRfN-R45u;#*2^S9iLtG>a4t)hI<5E{qF|nnY9#SBNvaU0z^{ucp0!=V zfrVPBhU_?8rJ~8Vk4^)UXrh`_Evq{Uo0a~43cFa+%yoX^i)}~&;@@}f=!@9Ubady` zT5qhFy#z6GYGme11g^N`g2>K`wy>V@6ODKA{p(aA_&4bpJ1`a|P2BULWIrBJbLjuF z&7wnQ^PtK+P^*Q=Fc<#|J49Sp#_}jU<}V^eDXmJFCQV0>MT_{4`wRG4JW&`#%yM*^ zneT;!1eeeKA^JLvu1=Zm_I@e3ua>nKu{hYRUPe15*mYYfDcd>QOxhW$5EKYnSxsi! zxOfNRl7324iS#ype9DFNpvGfSmgH*s&SvJrD7a|qV8hC9llm&ll+Dd zG-BaXace=8Zp4S2hV(sRwrezre3i1*Oai|{wV(sl>LQhzm4XkPW#gsSe@nDBhn<45 zK^aJj$jab6E3ye~-2O=$MR$sTnOfudJ@KrOf7&b2_dpFuv~%Ant9?_PM-3K$BN+Bc z6;vny;L!9|com7d0()nUU=lR`b!T52WrX|s`j$iq65k$UxMl~;_0-c-S$0RJycHY^ ziq9;^;-A2RP8OMQJF*FrzMp8S67<_(6zc!L-18`&;qt%~S4H-~BY-1l=Xzcq~%bKL@MhZoU$ZnV{ z*(Jul@4Lj<{hxWi?friL@49qdQp}h+&w1{1pZnY=xXWf!?7pf7QDl_C09urU@qgE~ecR!-69^(coZ|QrNvxa_T&_L5jI&Cs}{@u1fLUL{a}SS#~K0 zy}BpJmBRlVmw)GiU(_JF9LQ^cO6#xR6a^&^%TOtf6-_d#LX)Zs8tiUi#n(X6B&vIp zDto+z{qmF}s7L|9Sk`tMoqG-d@&2&K4S)a130zfgZwj}ud=t%?PP;4W6ym+ zC7II7iB*&Lni2mt`kc9;a~ebYmZr@3o4Q*(C$p%#0GO_yQn^E z7`$4?fpILl;<%#b;}i)u?WZ@jg@tds5N%rk`+ib{t&PC-j$arj$Pw`x*~@cq-e4`8 zcaeHT%S03;OXtwWDdK0vdI(B#OOonB%HDV(Mb?ba*J{SS`B5 zd&8tNa9t`rDI->5>}k#ji#Gp6Tx@gZ#&|+<0t#E>71=RQt&v!<3LaAW6NNzuH#KYL z-H|UILT^qEg{p!0%Ft7~`;T{TZG_!R1CN`*&NjCwfFMy<=S>wilQIwdPmZe59);~Q zbT7}RLYLJHjOFF6010#@OcZ|MWfJ+CQ6q$Ose%nL8`Dzr**K@wK5x26ezR~|_oMHB z4#B@k1_Tiyp%5kJa}!=5$Z^BTquNS4oNU#*?qgzP`{n*r|8A z=ZHN5S7iFZ*rXv)al(5R;(svzmSBva>viiEiMY79s6`W*2^hXb3`E@xL;>TTcR&GM zFI`kQL#==xLvoJ_3ko*oWd%k7%^C#_lQ5>pw59}j$nc(cIXGO0dagasiGxz}6L!q+ zu3j!xsv##R695F5Fi77G0+`wJflT`i^Lq9=-`(FC{kd9fP7}3qOY~O2pC(z_nYI4( z(D4|wcH02t)z+qam6#ZNurk@u&GX*4}8 z9(Kw+8Gz>ymyn1p@1S}(HS5qltelQu^M9-(48~R7h7~?* zd&%8$C>2W*3Z6XooR1f{5pp$CW`tU|<5(nGyv_Qcv(TC3b>>m9;rb{*t*W~UmfAu~ zKh}T%*L%xO4=moO%ogQmYG%gy>eZ{5U4RenxYDnJ7zywC?VBlS|EieQM+uA;My4Y{ z#Xk+;z+PRw$EyBU=g~p$?(&0~Xc6#HPju9(h+56WwNEvMy6p|yvElB^=1`W#E_9vY zC1#Th%wE`K1q?3H7Y_q(I<@F(7!hCOY(q*he;5Lht10w;afXV6{@c~vF?2p`^v84G?XjGQfKFdN`kCMd3+p&fp zp~Z>kU~IJPvb~jY2S(Vq9Zlyo7J09Y??60&@K>KU`+g*iGkEeO)vaf`-W$xHS%R?@ zi}CnR;t!x2{{aIaJ5#e3f-+#5l*3G3I?-?5 zCWT3pN|#d}a*$r-Cq_;X#Z8dJ2zt&mhLN!c4jOsSHB#i*}=@;4?Q!A{5> z>^p_J1TdnkMz)lGCvO>4n-OGci-vFNfV3Ertt^l;izlU5fXh=E*S(j)0c+bg397}dx@S_FY~EBXIN`} zS`!ihUM70rX94rq($Q3D90m!39*SOE5U)3Mm0w79Mw+Ex^(=&Z4MY4J4+3eI~vR?b)A&( zM9*b5_V|p^9~?wA73rw!@{qe>Bl~YC|6M7g<4Crj5h;~OdbZ$Yasm2luZTL>A1f|B}yai&|D}?K|8cRq76OgMt_N_jza4RHYBrUIH@V6$BdFyw$`jb>{ zV2N|E{=U8pj)@5gAvu<`qDVbGl|R*e7_wnj%+3D%^>$j&DWG(ppxC`9(>d*v#S1 z_~%=4GBdU>F)r^E`J?pP*t7dp`5UK;M>MQU%vyGV(0dO{ELxf6e1}VI)E6R@3E`U~ z&fzuYroKR3({f@qB_S#7ooy$cM`pTm zARM^@_Z!>ZU0CwH#%5;Tn7;8qZl2NqPoKuXp~`#-mTu>TQ?>i@g@-2J9YtOe*^E{= zt26$Fw`{w8-f6v=8l?U@YLJCDi*Qn=@YY5NTkh>m75sbuOsWvr0Sp2ER!PYh{IIA3eE_yH0Lf zQ_v&?L_B`CrOKj(s9!)y3`b+W3O4Fg3Bsk%tAF|SL~DYrpre5As6|s|K`{)+L~fd+ z5iecJKO`2n4$hSf&z6DpSi!*oCeE<4FfzrXvO)hf`8&ShA(n=6O&c-@W3VofHJ(*^ zH2Y<=pWx=(M&XBk6wP|IZ(UDMVuw)z-WIleXGaXM22q+{S*L&U+IjSS{syYRw1KDu zbf1Qkr>|m!0rlj{)@CGE%b-zN@8Y*f(XaVbiXDerW_pa7ns<~(vsL?`isNl#tVNrT z*XSOxu&%vw@Sd;FL32wpl^K6kJ|ZUV4I(mKVT;(V;pT*OXF|Zh#m%m+=Bb|#hkELs zNU-lmGpo@y5W_PU2Z)lnQXBk5({)=*Lyg!<(=jmuQ#d9}sUduT4*rl^v~Lx2QCD|K z+WtZ=XxP0yH_!2gpw~SY;Xub~XewvuH(Y?=Z^fwK6B9pMS3< zzy7s9rtrMy8gRoBdOM5;Y-ofiW-_@EC9IhK&FKC!uM(x*+qtjIZv)klAd$~eHC_jKvbEuK zw>a2&=#r#pKe-woqet>!eSn{6lOj$iV_Z<@$~R!k)v&)(0L&oUf>&Pzls_Q^iz{JH zMczxCqF-fotg7sbXJuv=)wKJB^=SI#f~}B%`5mAP7)d#OX|qPfx)iLbOUv<1i&qG` znRtyOxJp`9x_dm$rQZH_pWPp!{85do(ej3JU zFG)fxG6VL8ReFxV^A&qKR*62TsOj#O-&CmG9W<`@UFgZ8hhCwS2vQ-%b5aK()-Yix0>+dWIjc;w8Gz@t&2%*S=d|kkIy!n!O{5f}6Z|}($Aq1T7>IC+)QQ^K( zj2{fY30yH*w2u;NM9kxOB_zb^^Qm~9tu>35iN%qm^nsz7kl>vyNbm=uYNBMKU~azZH#Xkh zaunXUbHbjaSOp9skF?Bkwl@ICWBmHHmWHxPQ?K$3x_|rc>inNK)h~0Bfj^Tmzc3sV zI++>?D=$X=Qm9hg3f5kBmn?_k`+ef#iW>uCEQWL9l~~!NMf)~XtR&|ox@Bh>u8&p3 z%g#K1W<Gj*5}%8{y_;ZFS_=O*ZqH?spT#gDGEF-_Y1y3nKk~XJXB(#z84J-KqsyTo$hd%`#?t@vV+k39D_z#GTI7>#?pNSOs9_y ziez;`!7xKYkQS|ch22)8cMD_+W~4J~@m({=OD84wRH%x{CHl!Egbneb?RyysW1o%g z-m(!~236vNueZKDPqCT*R8S=TUAD3F%=ch69@bkf6eJBrc;bva$RV}rZAI_eW@;lU zd!Ce~E1VtgC~=2*#CVcJ+_x%hFQPG#-IH^-+_cbgi}j6E8}1R(>to2C8~jW8YyQR^ z62GCvq^x*aC<6K5J%Uf~*X|t?m!$KOzy8!E#C&QOx)3lM(A4?6$&VH18cD|?YSlvf z((1}=T?D+WoYiOTcCj)RyocfoEsS0cOZQ(cWh zMxurTYgx{S_L*WUT8lDLW$H2)QfAe@(2IsEWT!pnL>V=N@-7bRy0tL}Fltx-dH82_ zoK29JWc*ix#V5A^pD^UnIRZ5am{QfD=TQyr_P2fSS=J1ALKf|Z;^z@DWXBmjOJVmG z%XDDhMMG}p1f{j)H|gg=cRbYXa(S!mW7s?I%wJObY_}H~6GJPS7BUcWj`f%$?Sbrc z*fZ_<#s!aoPmk5f+$1E(@f6T$iO1d^F?1<|OS8u{JdLPfeP4iTrLxo)yE{8Iv8Z1T zr`iqfr+ja9TJCgrR$8!1NG9uUe_lMKVcqBCz23iE_f9V7q6Eiftvv6{%fjLf92!XV z{9J*in6|Fxd+vtC0zYBASp0H-tLr=I*zRdCz8JMx1>RP2u9#96RvcN`jj$(d>@ZwW z$^gnSs;{FU?I84|gcq@O`3-REq-3-V6PI`BgyLBGJHg8eG9Dm&>30)~-%?^wZ(UkzTmZja!7%SF{{;mN2U(j>A zfr)%tF>5rEwiDAHookmFwe+kLswb}VBJ!90czyJe4Bj8L)c>qX$MKWjxx@lfH6)kl zWEc1OJ*TR@?NwwaeWl>a4IQ?^)#IHWd|k8SSZZUW%k2=Y{8h|ZfP4rAsL^RY8wq$% zmQO^Ily|IMI_|V$#rtg>p$c>Hv=gC%&qu$6!e+T7ZTm_#WEzLW?$eS-=jtjiXAKvW zjy*Q}PlbLP9d`k3^+~D#NaJ7jX2)q8&aMx#Ts8@AVv*R=aTA03)IAqb-PTV*XOHIV zBHm_#+H2O7r(FDZ%N4{Fesy%PxHYN@>1GcGC~w{%SLKv-2>0GnXL%Y`b^9`L@;NwL zuq{zC9!Ir4O=f$W*ho9-3VWMZ%e$_Z7E4}(MzX$hcfJaCd^c*1_^|OG#*!f9`RhY@ z{0gBtmQ1<(Zh^qr?!*k-I^j`{3@qpu4X1XmFS7#nu+5z*$JKl28vyUb6go=T-bI&v zwT~IQzc{J0uo>L*8$||j4|_UUUw1xbOcE+*tj2h$TrIMyN9m~3;Cr0av;6ua`Kws~ zYpBmHN5yET=xgXg!=DWQHi=8<4zcx&c>S6Y@NL8Tdz9**`3PIKa@gEu^SrSzl4n;` zu!Mee^v!C4UnP*ddr*VamQy7AscmatdTpV0uT$0ul}+abi%Z@nzyQ!2c#it#4PTNp z@mnvSPv5HI+^n39)9GT{Jkm&`YfZJR^CScPZdcW+?NdPKF-szJ+5#nh$_(r1G0?Gz z!h;`7eOHX2TSdk6wRW|gxFhBdEx0r-Xn_QsV`7q7t{xCqXwn<8J5nAizn(R(6-s34 zn5w7(8VMpst_A{aF=Y6$CYz$Kq`=LsZ=a}H1#VeM9>e=~x;%mTFGRyvB9WwrSHqDn z@lz3TL8#Iy6`%V~G3+7E7@$9?0GF$wpMHOet=GK+@8V=|iru#xtOB*X8z>ezAJziP z+!kM{Se7gj8%SwpTR@cdne77AM1w$j*~a+<_@m)fY#gAOZ1!2AScJTFdVeUwUMHL@ zW7@9HbvyeS#ZySA?wacCbZYIpO56Y?G7CItsinwfPk>{7h~GPVaHOuk<^G|6?fTWf z>B4my>}GH0g4O8n64h{*sazJdAx(_e}#nBe#h5ZlSGR+I?5ooRS(65efS7-L#Mk zl0%^%A6oGCGLu1$*R48QV)vgOx|@`GiJY1|p%(ew4Kc_0h$ymYIYiE-CnbnL%bHFu%*&(Hf6NA1Gr2bb16 zGc7zyY}HOfC~TRhOs-zN8s@YJ5J3|t;}?ZA>~x05}2|T~5=VzVQXR>ba8gd=ybfv`|auY`gz%_cOvdE_@MxSB{ zh0}_(>GIC!)f5~L4z`G$6mS*KDFsTA6L>`uaGBaqhfe}O%XGIEmdJGc`nO2}yI7Bd zo&0%}?*8-ceEYDGokBLq(0eHX^frukqR}txJNZhjf4oxFF8G8-;lzvWeilj79{@xOwf_ zz;;d1-0=1mOT`rYF`y!>VAHAP6RW(&AKI3gjG&D!tb)2ps$sxF&%I z^WNLdmjg_5h+0y0bKZ%GtCF`i`jOud6FUzWY#Kqv0y>!tp}z-jJeAHErjw3Q!H}yX ztZo-^b;UuE$F*tLF2@>#E;ah|he?-e6K?^r^DH^)*#W+X+-GU(md|TE*D%GfvzT`f zw%!{;G_<_%+hK2|yh&nJdNG?+6)wXeM&<$GkH8R5vzl5&zQ7l{o}1y2G@?S1Et=r9 z(t1t`G(C}0AdrJ1)hVJt231Ss&oRaod3fJmN&Q#u{dW=uvoGSP2mu8AmvR4#H*`tv zPKg7~B**Wfv{CNx+{9NIZSRvf638G)*K&VDQZT@rF05Z$zDwqI&H3c6i^pZuWbL<= zTTe6Oy$(mvSc}n$!7NnB#oRKEoYXX?JH1;iY%WuP&D=_|XbFFybnt!eE9kyZfp+j- zQeMs`@VIx*;wqf7d26b#?WD{<|43Wz8luj$#S<=-{iy+{G&w*}e)L{mgz&3*7U`6N%gv1-9lhkC%ETUVJ z3+(dQ8EBT99@E2t`jvTnWW^tNu5q{uS=C0S42yb03?-iH<#IY2fgAYjAO|U=263;p zW8A#MQic=_jka$b3fq*3O;oTWW?! z%kP0pl4KVik)!K9o4%!BjM|6Bg^*L$yb z2V=el@7lWJ&Z7e%0i(Vyl_vWJmOQ?3oUwGv%XhT3D>w}ESjPpuK9NDDd5q3h>}f+N zy6+9{ts9E^Nvl5{k4nU^OWY=&{vl*ihBPCCa}k|Fr6N_ViDJkw>90E<%h7;Tr-h88qB4h}FM#9EF_9*U!=>sr z6=LIZ>grPOoi9AA>-~oP1$iz^xUqk0cf4$)e}`7dk?5j zdYe8w84;U!TiKKBNnq)tM|yB4ty|w3P9XFOTfrGCLc$jbVTgE42A1WuGPsLJceE!7 z#hxT&RdpV{E2lrMRXHDO4=Ty&2?_6bX&7v~UhBMp&BiFfoVm)0^B9(im-s(%nG!7M z30l#ewDgaQ^!TNj2(eiV(&QCx;*)qe3XcB%SU9<-1bJk1#=innI3z;R$Y|fAkLQnJ z1E-bedXp~E6I|%>Zz6$d{Dch&#pyeYdDRXPd-ti=Qt*1f(af7P7j=>QgWJBMk{-H$ z1I+)Do$}mArz&|StQ2DJ7t5rzJa3PYy`KoW>R+GSYyrLKxqFG|>^J~Tktc@82ODu|ly8~j-E|)C)L697VcxT8Sm?HX%E-0xN9_l8cTwNy=|hhaf*2~1IaZ-B1%b4%r<>b?cJ zr7eC(y>$lO0@hHpaz<~@wz5SAd4{gU3@E(S?y}{o^!z-mZ@2)=AV_gnVo4|-Nj}um zv%dXpmN$rD!NclOsH=Zxum!Z60@+^9n{F`*vYcolRruxX!d!9)fg*Pu_rQg(L~I9M zC4+coO!4~E0W=JFfWGvr1?a|`#Uo2>5`&-xKl;QNK;cuo!o;dv(aMweLwXfifH82L z#5~ju?_bfNy~%5ZEKW_)5irLAE?U1=+$k z!v?uNr$4{1(cUK#7WSKS{P6in_Ekj={8)g@;qJO|%Js+k|06zFFQX#(5a^evxc9kt zdv#!g5;>IwqEp=txJq#$bIk@_NDNHe$j!W`!%HAMN=g%#6Ec#X4wVptUORxB4LE=g zYZMFGUhtD&kTe1R%Ny7L2YBeWsPrhjfGMOT%pI_*Q8Ak9;h2+7!A2zfW7SquTZOG} z-5K&n;y=G4`kD|~DLltF6csr@kbHjn&400f`WSSk1q{qh86=ZO>Y@MA0ys_9b2yJy z?CwT)uQ9g%6&n+QN6wmH3kQ4G!HQv}D|d2vHWZwFjI=;+wuC^&iI$sPNrfP@+-!^l z#)-d^mEq>>$fA_;tgo#!V*z#*IM&1x`rF=F&cy4*g_&sok2x7GY5-V_|K52 z3n^mx|G3}sKr-75U`!RWGW95w29SR2Cs0?cxF5Yl0-PBXI&=BIlgI6J5D}+5l#hrk zU=#Y^Yd%w8?}O~W^;^$*n!6W-KH-sWIO$}3C1GLEk-pVnL;YM2j%V7h@S z@{<;u!f6{XvlH*Ei?@EP!~dM(yMxX?$6BZxB*y_{H1TRa-_L6V>lWG*{v!8CWL1V> zLeb*tOP5C&>R5JXeN1=*0eDU;_Jtom*{EG^KEi0-d>#w-2;LS zlo8u?EBB>bQnY=ic%#$B0jVH2qE^eOiq7igC2c#6erAh|cQMMgauML*Dx@&fx1TD(uky(TTz zhQ8F}2^vbx6!B*7KrBRN>IHu$)jntOBPcOtR2aXC>Xv;>7`n0OqW{%m0vJ!Nmr0ed zx+FO?|M=}ui`(#zUQGT`r!ss5=s{kT4F*N}1uPnRHgE>k zR5bxp*=VJJL$t^0Almh{(TBo8kUgLI`8iXuCg0^}&q^zt{e8Lm@td0V=)WP_=Rn{r z+DvEbNx5pJ=uz?cyfy?4l+LV}tI`;5NhTH2hS4dndcQZqDnFwxRpz`WtE)U4R2`*+ zO9Ve464t)g6v1?3Ycemhsf1f~Wg79z=5JlGe{t>4fwK_E01}x42U;N!R5#u`NG5`z zZa^pSev$-Valrig$OBKrn4cXQU{S+gT{W<~@n3tE>ayQ88`qpJ<-`-9>UJIDonB=- zyC`N&tJ{YJ)c_wVG+|APIKtvJmWG@`ND=Y*|vl$b`b3hL^ z^#Q$6$>WOa0rPTy1ps48G7}pc4fXjZ3y@)fErC=^JlCe$4B8&wsxD4h^@Omg;F6|4OLd_7`Di_Q%e#3mhCAkU)x(?y3R7)VSLF zZ$wq_Dr{nwWB@zZ9R~ns@wXklmg|vZkVXST(+iTffBS;04Ja@GgdPL_cfQ`u1Uw0F z^~rPkE^$wid|nHXA8LAe)>{UNJ`mcNEA7dvvi{R;~V8P0uZGf;wY&%3$ zfnb8^t3QwyfveztZ(o#dM9Rb~`u?XF5AO zB}c9zyLVo4t752%fcWiMQiFn>pUEbneaGG{S8TEh%0SUUX^xM}dQxEJlhsKZD+P++ zUILtw(p*G?fZAXS*j|S@ySl&8*4Ew|Xq94XLqQEg8ToXqEuH`@rHCI3_1m29k*16d zkuFfa@(W%$`1wdC=hqI+j%!NLS)uNVU@n?>2Gox+3&~wgF@{|ECl?J)py`3P9t{5eOb9?uyIB?2b8}i@;pAkuOrVugS}g zdS_;3xr{jud$DdtAJa0mT}4pUH?6!vbHBo+0S-@VlC3M{V-!03CO&qylox>xMrFxp z(zGu64PFBHdb|d35{0*JAcgf+?9`lpmkppuDgD(PcvVT+7SC>t%153 z{l%Wv({P$?J$pfl0V@mUh93(e%KaBFY?+kVdQT7AiTMweP?SqcG5?Q@NF@YRyQh(f zbZ71nAIcycyX(vuQbl!pPrzOA!Nk2?dGSzwyFWWi`=h+)nrQl=fOW|ewU7vz32)Mv z4XwzrsF?Fj%YQWT0-)g!V=Sbgv4`>pM>q|Boo5!eA49hz#nlz;=B%L_61U1Yz^p87 zB=*r`atNc_nD6T6`E(`KT|B7FFhJtR<$gT4Bgixb6^(5QAv6kWyf%TUh>0bY{ws4A7zdj9l{Xk^>QibWSqJuGR|f-gbW_vkrJ#8M24dk_A}4 z)z2}(EBQHbzvYy7#sH@9nhdxMAW%hd2RnVSL5;eG2lb5RPCSLnw@moFfd9P*5AbyX z1W*GU{-iP=eg7UX`IVrJ0uE~iy?la7+1OlrASAtUxv#1^VE(`ZWaiBnGu?%#_LxyX zrN(75&Hxjw*d~B?JRj$#unMw0RS6xw3vKw#xWViUc0>O zz;SO(ChiA#&|9DGCh{FHAu3C!Zbxa^$n5KcP*8tcBEo7QU1rZ5^;Hlh(p8id!1;D; zwEP+Z&G7QfAh{)&2mrf6;hX=}hh{*vXas9l>n8vi)fwf2m7?d&=bl6s5QORdFKT9I z-8#e0DXFNwZ~aIMN#HZ{8gUd3p$HV|36|bj>{J|Ib7OB9QxZy+s-4!j^6rtM#7$wt z63kO%{WEvT_c=-#VJDyKtq}xesgS#P5fycrK425*(fRLrcCv!HFL7kB^rh0Nczy<3 z9Ko`?j|p|$uj}?k9D#Vdqupke$|LUJ^s#|yI6;1ac2(04I=64fj{vQUgd11Vbw4Bv zF5t|Ac2#CL5gs%2>hb5jnG?oYKLCtq0hZUc)Z0FBaQHOs|J2J_>0b=kVt?Nu0Ftz; z?;kpS1q#F*ZR*-&@^E#PRH-zwR^XZY7VZ4VsVPQ2S4>>7*#BA zLoIEqzPC7G{RHTq+#1O*?`Mvlmn;#@5H%k_L!!OT*C z=@)93wLK9XIosHGWjD$adc9%RSDzIjA7SoNBBBnDyP#%fIVPk)n49#+e(3~gM$?`bek#+OM zLV(0Wr(2#siY_Y0De6PHFoiEw-~ zr8RxH?2B_ZyTa(KWx3?n-$pV1twPV2 zBY^;}Hh(gAc9md9)XEjKAKW)QTUge8o$_TjV|&IAd`1h@CI`6b#POOx*DImkdg zz1N`Knh=x14TJ(x51^a1J2AM>l!h_^UWWdISKT*r`?4dotK9F%0UaggPOg5A1bxn# zajaD~bLjcO8qakH|Ac#XogjwBUG?67(N>p$fi3U>dEyeG0~SLKlYn4=fA2c8+f+j5 zT<@0&hDoIS2_wo5mAp$r!ZSpKBBEwuY>bM!5B48|Xr;hVIdA_2v~s`if7 z&9&j+;6NQu(w!tEnARLURsoQFOH@W?Gg_f&m^`${BB55!&~UxJo&QWhT6!?=*2##O z;Hf79$Y#LsDIJzu7;VWMKF(0NBH0tvpQ|;smr4GnmXl4|NmSo_SK51htat~UCm2CC zM36Ma@Bx6W436Cc{$@O7y|xj0?Q=&5P^IiB`*^5(E`#JuBc^8gm%D~m_u@$1fE_t4V-i@TJsVi;(# zq8^ZXJMmyUy81k^S{piZQb?vnA}H*bId1uL)KVTGLq&v~j;bG+lR&`c0~wOrU|YS! zt@wIIs-68>nK7&+Vbf$mXh`wSPDO@aNw8_={=ttPX1Y_&=A<^q>PXn>zSXQ9E8Qu3 z(@l=!F{w>bmkf?hAA#PfllJf@Xl}z|8St2|9hZ94IcM*XK(du&z(XleQUrjtnJd+I zSpscw)zuV1oC}Mu<$nJBi4iT93vnA?NzGZrpFkwHPWsBM%(YtQCNEObu~S8Gk84%;5B7EK3`CYDVKMLVWHH@F{v3Om_7O%2p7KQ4KZGFGf)m zT*7N;2=(?}SsAf6CAo2}7Y-FRtz%BbSMikj zeG36iD`xVQ3Fyrdco=a6p@~uMLP5jq3FkJ|3Js4CekR!}*2-?hs3k_$7{bm}|GU!G zO_V0W2=kPVX|BvWd`F6sX2posyq~&tEP|UN6GkIPNzZBGT<*>^ywg($iJ&#}nNM<9 z#Dk)cHT>0tzOvnyX#$EYdoJVEIg*{kT@NKCEU5yA@X=!a-*^bpozIHno&mdgk|cwY7_+ed^Cd8Ext6BPvG%oR4}s zI!Gs56%7RTm=N9|F<@qFky}!YbRe!NsF;H#D9z<*H-0fGeR9l_3dkzfU|LGa5&;t> zvY>c%spU!wwSeMRfmMTl*4)ttIRg9O8dOhPPcLFp*=s14m36sxFLU!^_65Y0A0279 zu%}F<2zhbl_*3Q>*M>8H5P%XD<_&>GRuajWUe@&$R^cgY=7i=$+LLjxadzMqlZWEu zD1Mb%vKB1#gEKU;A0NyUaQ(6?XcmOJJxHAedrxG{Mp4YiK8>`)Zc4OWDLe1uzim9& zD0s7D$8(x_y3iwB`*ygwZFEbj*A>hU8LYZL#4WOtO4ts)Y_;{a#sm|4JoK6HJFfMh zpG=jX>Os=VrG~=fx9q5TriVX9bBhLQABo?((aTVXOM{^zB2Jy=JfJ_7RRwywaLS~x zZ~GGnx`-s^n}wfM8A-8g-qv&xJY#1{-(mC-u_DD{c;^*r$*oPkW1p;`&8hqwOY`;S zo=3+0XKD55nd$s82bfP=aRH-}Hh||8K^;O%GMHus=js{1WzW!fdul?;Y{_!d5 zq7Ir^oft~f*VV|-2>P`VfIAEU;u#EGa zjW_SEU76vObZy`Rl!GvsC>eCvbT+9QRs1^bh(^gz+wsBVyBcpjsptP@-`}$O8Pns& zRGWrUVp=Sv!YS51dym&OMNv$gjn{a2T{_-T%xL7qXURE0r6);;s(vUMVsKnFmSmQd zk=K~VtV<$P9>t9Wn$6(HNk0h(OJhTTi-h_&VV4YxeG_oK1ReHg#o*Z`df{N$ul%2Cs$7`0%38o+l3>d~H9ntIm6|X2LS?9}8zb#aQbkHOTaUD6U zS*f9`xh8GPgXG}%uU|hobN-Y)R4OiB;yZuuHE+rDWt&8)qu|=fzW_WctN7{ zODvKkx_No7RLmouce!^9_(=~4ytY2i!zG;h@#9cgZcdrb>jKBL&~Tv*HNlM@qlUn` zK8r@=e(7(?tl6qpqS0lBV;7m2^!Ymh17-d>jVwzCoD=SIo|K}L(WFMn%N_0O{&9=# z*(OQD0gtWl=OQi9D4~v>>feFzFAx`4;AiJu!=3a>@jU{G4OKJaV)FD`-P3)9M&Snt z6e6_P(a0!87v2%ay#ROPJ5i*p(Q*y<$7^3*6P>ANb$6y5E3=E=_Ah&$F)Ci$MB*5m zD}A?m$RLYua>wycdp^*5O}+_=ieHH7csX+=wFAkjTtJTeol z{#>>A3BN}CUCu-l8NSKV1x3+48w6G$TNLy?NSE!Cr3j@l*-j26-=L)zOHWGcP;Y3U zpTGh;6A$OhO9elsSVDQ&g-h(bI4NGp)`rv6c1>@BZ?~|3L^K;FcfGq)-_x5o&WC8n zpHEHA0sEcR8D3Z@^qjwkiunEe8L!@=5`Jk3kz@F3`nqS`lr*i6XkjDLgNyd*mpeZL z2$ysAjc7HW$+XY{Gvs48&MYC_ot@y(FUE8*5rQ1X!8D#QIYk&EC9cXKB=9S=KNNnq z@fOW)OJrJHp5SWb^b-cdnl8t+m?;L*JI7U#J61SGWXUMC{P~05MvEOU`qHy>ZSBZC zjo@zL8m0waJ5pF29c8F)ZJyjxPq3Xc7N?Bue*iQ6?3%2?kh-Oa$||7s+phc0PA%ze z0Q*T2up!1=EE7ZmNq?joBt6(Fq_?;L&VKzG8VMS{`Zd|iE%QAM{+o+-m*m;E7a{e0 zRZ$Ic+R){zvl2DA4QG;HV?{RoHb(cs<=eA~y*>G5x%U$6oL zS}i>nz~XV~>SM7n3p&r+Q$5z1#QktG)_t#Q5f8^nnU2{l@yWp8p>tnzzUmSqBQwX= zzSoVwz?z`$-y=JledXkX$8{7VX8#0*|2Pc!c|@f2a9Ufh`w&79ozUWPkex#h)gm=K0FmgM4ZL|O-Ye3*50Q7d(gY2D?I(Amo-LS1_Q z^@9QMymea{6@e8YqY?MNvETJ6c1rAyD%VubVmuxB$Pw$gK8`0qeY z6&uv+$tC=LVda-pY$^$4Oyl7z7su6-{YVa}&PI}FOhJBe4JYd^Q!D!ma9InWGg6vd z_2-NR@}OfRPAT_6)>B3Udr+%HxDw`(a~LL&TLB^5OcAUOtirEq)+raH--`Qx~v1v+Z3bKdN&Z-vu$n<6aY66W{2Ol9DQK zS&VoHrpc|JM~##22QKxXyUb62zr|+GJV2u!*!C^4*rgMD{@G$b*0j>e&Bf7vv(brZ zPDNdB|8uPugA-I`7rwqHy^zt9ux-=y3Ap_()-mOn~XW&`sgstA~}KAP8>rdU9}+x!-nR?I_Usg zQ5=@;P^(&=#>~xG^Ex$klTE0rj_gYqJYBtyMuDkVHtE8Vp5OjAVKDE^W0nvYHaQfA z+uF3Dt(FMh943y38H+Ku_r%I?*7kcp5d~$CwwYPxwih|Yf&wKhi2184y+w@+wg>IA zvycrk&8fJf-+v`>v>173iKVO-FAkH05~?i8bJ?L`3G?$yTqAE=SJxO3h74I@(bpCr$cB>O}j&!-lsCW5g(Fbi9wj>bzf4 zS~$Fs=#PWy;_4rCkhNb^a;dk_jf)qHpV$vcR5mJ~qsen*%|uZ!jaL;Xo8rDG(g;^w zS2W1jV>c-usOufT-DKD}nqE2f&y=f-lB$tJNCps_X)vLX16Jk~q%ySUOQvdy8eK_f zfYI_o+7lU@D{DY*K(yKR8fnVZduySt@``|-HS9Zb3#!iv;yjI zHpCRN>XvLxQpr(>-{p%gxae`J{i<%Y4-WTK#X7$i{YUB%2Rf2uNImSAK1WSsawqLC`Cuj9<7}~wj z>#~F!O(0{H&5Jm6q75_1@9LUVCJi{i3)Husfng_)38%Fs%u_P|tj~^;ueD5DcaQ7A z6WE!syV9kIHtGMeFW1^Fb&*d~w7v`PPci67-CEWW%EEk3AB{p-|Xr zVGBASPXR*1ACz=(JtGzhsXloX(A4yumURBFkOeg}LV=i^b;a%skl8FkVgOovnTV1h zL{|9`XekZKohvf*0s3eC(YWwJVWK?`*AG@j-cEGjMrIP6^xx?!TCet8e=|`6D+6eGx5Qk+R1&SM5Y$UyxVx-!%iPW3sJFH!*!38UUKvK~{ z-3GFz1oT>oJZW@i9H2dUldd>L*xI;oLBq&S9U3=2nwohm~I+TUP4W zh2eHoP3(kLtFECL4(`S!uOO=M#s2`@`prpG2NRt*WnfSoi+@YeY9QayWKn+S4R+B2$<{sjxnw3N4>;eNzw~{!>_J>>1 zqy`6e-Z9PT!W-5a^gE{?mrdfY_QE&pfJsx!y&*s)lhdrwv&+H@#k<~FdrC6Px}vvJ zWq~|67Dn?2)SGb5x5dV%{!LjN(oe?_?ln_AeEv6(f&Sy5swV>b!9+LiQ*g35l=QwS zcEdN`Dja4%+~aypPflU$II|mft@6 zX(1M`e3}uxxy{~4E18@)yC_*KB>xB0e1rRAa~|`Hl2}Wy027-mX2p6e(KhLr`+tDB zIzztT9HyJj7DpKfd!E4wGGv&aa%ABn^apZQ>CZ-?osSD#J#G2alis}BI2+GTEYXz~ zC53UiuP(UuY$su0MYL}^pHgU)Qw(D(g%V{syeRuQeFJ} zr8lM|wmq5aBlOX(hVR!1i55lvRpBzzT#4*!@}IRE&CSh`pIN(S?%=10dT?3Fqz18e zZXb%RfbMi3&@HBEI7UQUM~8%ds27*;Pj`C${bveH_r5TU1#C$*-BN*^BYPN}oxa?k zSL6932@h)HLuJleN5F#UzwV2_UmZG^;poP)vQQRZS74w&r9c2W0x9?Jj9=u4y$dwN zfF325eRWpT*4~C$NfOenK=Qu=rqm3?BoC0Avl7KIISxd1ZEQQ^VozIqjz* zxR^(t9tbKLtm*VLwWMU?PCEyL0jKEu-2gMGtO_hzpdKrF zi`#}%r$Cf2T+U%YzbBkp?8tAjo0v_4^aiQp(l3Ixu4w$=B%lbr&gm-Z#n6t509E6dyjd{q0t&CiZw>>Wx@VOR=KddJR~;AC*0pDbPC-IaKvY0lx(7i-Py_{} zQ$k9R5b2SYG(b8fBnO5RgrSi}M7otuQ98aodaru*ec${2!|yQsfOGcQd#z{1^Q>nT zn_Uw6BhCx&aDY+E-F&!8@3B4hKooRo>3M(T?y(1=FH->Sf3=>dv5^GICR{ot^T_LR zLOtu?Z_=_nZEI69R4M#mODEBT?mCH~k8VGFU*Zcm7$%^zhot!4O36cfWc)Q99lHCD zj-IQ87md&mq;HrQ(81{`GHscKrlEdWj^8g4&E)IEVliV(%PtAdQ~ucr0(g3#bCvrE zm(D>9O10LvV`#3$2ohZ7;0U{T&)L$Faw}5QQkh85W}=!l)_P$2qka|NYb2TJrRfVh zG6cAEkD(nUIu7xj0o@bcOj((kd$p`ma=#<>vpqM#;e@Q#?Au9#x>!F?Wv6)q81?)Z zkQ+{M<(ZxG2QB{V-D54FS{nfLBdU&C!QPUUg-%aTFIJD8c3jTa>6p|CUxR@mQeZl{BOuy|Fl5_SSv@KFU$KTUK;7a(MffVZIy9x?ZTU<{F zk`AM_1k$2rKo700t62{6l#cMyJ_!frbSjRNk;E*d^ zS5XsX>gMn4`JS*Jp6{($gX{j8E7ysGE1wXw87b>z|5A``)HgVB1qgL+fZR$NNU%DO zlh%PG>Uup9raND6^Xj#0ji6CsF(G*$7jUFmFgiVZtROtX_(_aviggvgX|vII^+PYl z_T(@*U?IbatG7nV?-iPVoj5)!*Kutc5eophhcQVSv^^8iDV|19PCKYnAJ&9<5xvaJ z)LiPQKPKA)L_YL(a$GaWfAfQxw5&Tu;h^F{QJ~1Y|HAW& zJ&{ova5=d#Y?g`%>Qk1A%5t;KVWQ@n=Am!9Tl~nX&)28~r?R_vRF0d}m7~m!6F`FI z-Cc>_jRi>1a7*>rA0KYdfLub=(mUOJ%{;@}@hm>9RfP!w3BEPy2|2(Tne4BmfIE-OWnWT;T%s z0xAsWOgd59+&r_l7qi6z1AtUngE+ziuv8RI5t0xHz68BZ%4k(z_i_psy^2rKx}lSo zK;>Y{N&HE4G%jxA&N%2;yR~v?vG6X#0E>)7?7@oeAE)bQaG?_pw?zbaH#VDGVs)`> z?P{wZ?$1>#@stSf>S&yJpPJe<8dCt51LIAF@8E~iUwo;Zybrn;B8wgh?AeS46+L_? zI92#~R`xVolu~LEHDT`|`6FfA}Q9Y|KU@W|C&WWbkM~GKU2P+8*&~V4N0mr$)P3!Z zD-izB&w|gq0Rzm=oT<<11ASG=d`|N{RwKeLDTrra9f;ob_33ZAf$lbpXl-)WRr;$b z(lAU5vR&1RaP5OSJF(5V?kk|=a_Ci%^mB3k!)aZ=!u(u9kfF7!Il$2S@==-X{F9{c zE0DAMj`xSl-V)Lv0C$ILb&y=2){;iD;%!n0FNFo(S}3<}kL`>?LfkW7A_h{!B5ep@DlDuv|&0N5R?L#P&KZ7^NV7-{WW=*zk5c-h-gP(8&MK*&JnFe9=C zlzmOvLqNU71D!Yaw$t1_NVl(6NKW7V!AeIqAmqEi8DcmBBB-gyKu{LYzm~)UfwkAH zYIaU!knnOHmrEtHG-3{@qjALKG+g&>g~j_L;SEF{fXP<@BDo>}4a85F7isZ5{Co!~ zpj37KGmFOD)w@`~ACF%SB>r7!H(UZgcMSz0VOmNGy7UmZ+A#2!``J!;ix8H= zv4~#D>@N!p+|_ei$cPbh%)F7+wA46>fBS?36Ij6Y<@5Dj^q@k!UAgIZ12U`#E5&~v z9Zgr5KZLTF0cCq3@nkUh9Q4Y^n<1v0tYH0 zhdT+)VK&K!*jpl|k=r6;;h;UeM(%V%)kM{;@N!`V7H?Q@k<1M>XExG?y7n)s4 zT?Y)K8K8Y7R4@llzFoqztXJI7&(ES)B=b39u{IoaZ1ot55UsNSCixl(rM$=>h^9B9N;r`LEvMD53EMddM3Wtg;ac*egK^HK@5M5^!1Uezr6q- zY@H-HNI)R1AGr^}sP{Lw#~;sBo;(6tQ)(;q-hgl;gbS(Y1p_G^ny7BmaBiVQk1>t$ z-<oxkC|M_~Xs5?1?WDbx3WQY&!XR+0vnFXIe;nnvKAhWIkg8twQdVp-7vZ__eZ zWSZ+4l6o>g872nm*%$>>pqg${DtC+#Rs?5d=4*mQM+^dh)c2wmE@iIZ&Wj#ynh$JM zw#@P+bL>DK=OrS2INM=Qu%Y{o$z2+b15E0GZGYTUC zO$-7_AU$OD0;oAZX+sGw%gidEj>z1o#Jt5OWf(iH?-b@n)T61S1e6H;d}2}>4y>McjZRbT(* z7Y1$|0VkNk!7|rR+0!r*YvySoPDt;d=Nl)bF`W$99M%3xG$&J2-64+#79+e5SV6B) zBxnrYsRd1fU)_TDz~Pg1wF8hR*G1B$(x}yUio7do`yEiT*Z^eKN4fs?>(Zvo0o$Y! zH)2@D#p!t8e0kb?-Iq}^pyJTf6y!1zy1`&s+fm+C-|Y^uxdc;5K;{So3fVK#7VN$Q zb|91A>@1AeAW57U`a!0;e<|txvvdCw!{C!3B1r}B+%fu^qrq;P!XlxI2L|0ZP@AK1PIKmzas)9XLD zAqI_o>L8AMFYWs^Ztps)-K+dWZA#@uD*a+V`!1NOSjUb#hcBOkfD%wAqGCn|>L9Qx zWWzT*dEl8-_9sI9 zr!8mUn54BdlD$vhbDNv`K7);kJX7)#8&?mG0kRACy4Q8!=05 zIZ2iKO4)Zm>I*R-GZfbB<@83S0+0P6Bq=fyGgJWv5XBqoDnR_20yEq zXmSe8w(g14Cm)s2uaIE_D|Xs__w%Q3iAZKeTVF=0qk}maj2pv};J4>6KfsmrjrJ@-#<`-hE=^YO7rsUz@dzx2kk zXtHkJ@>+r*!CTLL;kHg(-qyNXIDiBXs;gnjnD;`Yxz7t9Gr$-ozEfnyaiN}NYVCgXhKYPBFs1+YdGOnzPu zlsSO1Dli;%GjZv8gZ3VNAi!ob_L{1)vJ(Hqi7PGPj1Hi!X&U3W0g*ibJS?M&d!BAN zDLDSj)Z99L2L~Q!&!0B|C=;XT3j$#i8>S#ql2yDTKnUFc?M3uB3z#(ZYYt>e4N!$^ z-o2hEP6g_wj#6fIk8o%NW{(GoCLezM^l8^4ce8pBF$szle2=G4C{&oK4i|NUUkjt4 zC7BAK)bJ^iQ&D}|tf`z@9jn>^rfd?dJ0_JjD4Pb5uEK_70~ABmGu+=C9ZV)AnRQfF zQd$SeGFpA%c~9WEMHxte)-AQ?{#Fz4I}YG+(}7xVU}u76@wXcFmxVX++q z>dFnJogl0e_LXYEz!jh^a-Xs6O2p|wz_>?drOy0`1AY(Rm|tRJsvD2Gu_`z( z5CV{6kj{PZ5-z7Wc0o4r8YX3>gTjr?)tp-HxE6YWyJ~I>~)iZ1jFRcfmc7F>0JINn!byQvf<4qd|gDPPt|;)qRy4 zgm4=#3?p|pyJI{iAqr7Z#;WrMaXJ>Wi#pk{<;(l_kodw%@m}6;K9_AmTniw z&pxJ#xj#>)5d9+Eo8pb^|Ey4MEFVgJ1_kg9fW{GqyR97^@*wGWhLv?`RKwVqMf|}k zv6oN_{k>`onKH9$&gy@Kl7HWl1r%hLyrC5m-!rjFN`!fu)?m*0KbmnQv6(sMQ9V$4 zIZR#P1DGEY`l;Q)+2FK-x;k?ue-D=ZH5@vaPqzN=dlue)5|maK^ww5J%2_#H?aADb z#^_UnBKx9bu&!MtV2o`iSXT`WYAp|;@N9=mUTszm|6$F3-)V4Ir#2cSea?m8Y&SI; z9rzI_DqWRzb#?8brL@Esf7r@^1h?s>T}Hg1{KCWyST=Rdv@5N81jpyo;J)4l!#aP! zY6#e5AFlIx9k^oX2?bX-nXV7rH3pR}q!w3TV(6G1rW+0r_|aJXH4pl(i)avu3UcFg zYX0$u{(uGuignP!Ib_v@X#oTZPxH^7J_3nOG~@dgDUO~=R&{~VJaD&~T-uMmFnKq= z0V8pZ%hTm3-eeLBQbKlm%o_|@S^1Y_j_YF7(&OfbEQkLz1S*3FArmgwSB<>x@d0zFoTe@<>sHg;P}iKM48*$r)f=?}xexWAJRMHk+q*NF z9>FIr^mV(ccM6iwwOBj5CdD*ccKzV=hcCYa95_sx0CZ4O+)}jt0{Ffdn(rkChoXti z#lEZ)pzsq0n4-1Gxop4hvfq+C7}q35=t?4}#Z@759&`oFy7tDS#Y&&U!Guq2rVyYv ze{?xyy|^!UN`H2Jb)5QnE#Fy+{z4E#7jqP-A z8PyYOyuYXER`$DvQe@`C)+T)6G3Hx#%Gst2>=P=_lZ>m8nz2a)~NhbXZc5mOCjdSm;yWJy_&wx-K=GaCkhF$^zLx zG0!vFKss7fj+VbZu{rv|lOE?h%q_M=;5RGQX#je9GChL)Qd7@wT94=>OcJ6UV$i`B!8T-xxo8-Onna1;aWQI^M9ktNZbVDg# z*wuFS8ZnblPVlHRG{M|9k)_(R`@m5}F7X`9mA{1Zx94Hu0sbJ!koo$Je}5GxEmbkb zQ6xlV-1hHYfcpA%`)kAji7s?*884YZJORpc^BFx|W0=u}Gan8a_G#G7GlWQlotJ-f9(%^!+;&lF!JJi!B}ybVIPS)^;t3U+xws?mNmQ z$oBmPUwgPfvBr}6g<a_S@t9hwa3W>H~s=cw^%oFn?4<{HyvGMHK}bn>-lF70bM= zUEZFXFcL6@NAbpumQ*2YvRVh$)q=c6pYwEGzsffj=re*{T9~@lBAFJ-ODde653cgd%^)aMQ&=M7{xu}V z?2DfFn8&laooCijo`FqANJxluoKw*fu|cZ=9Dc$@;^}BeYkbeAacm<3p9hdTWws%t zW3Q)%UKloCZ3qxbMfIrDUq@H3SraPS-<(a3uiZLW0kz;9u^6o)={r^f$dSKyZbFOHz@KZ3Df*0NGeY_QrG zYZz!unQkxF;gI6J#)I(%?YBaaxaiM0g_0$294*wpECtd=$b{FiC6F}^&8wco_kmwW z;CaI+66&8|^L4x$_%aGfh<0H??BT~42aHxrb{sDYfc6pJS93pWN;d!iak}yE)(;Nj z{^lQ7kbIISDSTN>Thgw8!KTyGMpH@yvJBd^v|4ZOpKEhjmA~mCd>R%>**LSL8peis zn!sXI(cWBgFE2OAD{XBWFtBf?Xy4-wo{tg)4`PFZBm;u${*b3oEw`=4@tKGg#_fp+ zs4wnrwV^FLl)#nTsI_icxbC_n7WHgj^KM0`MA^QJP-nvnQ}?ch z&B53FbQ)->4s@`jYYStH!(3vRI2)thkM$Si#NfXEPw(IUf1cNi5EQnn>8S%+OiX*d z-?KABC4~C*YglJ(%)&3XRW+342wZAeyQ0v_@n}G$uZ>Jub_|CeZR0Hj5D$%pl)ba;&c0s#- z=udi^ONBH7b_}5StBh~dCNb~iS5JtIu*c_m!F{NtSxyD=TmZe%YN-%hCux*yCS3qYXd2nfR6)TA!p z;gl1B6tQ@auRyjSgV;u98j*;;73kz(PGLx%<}xiG#0<>m$}N0Def90~&|mQR`gNnu zI3XGV^J}GiSlui_LR5giWoea_zWa0I5xl;uHEd(9MUxa7cKLG<`FvbLsIcuYdrwL{yCsa9rAJj;JNQl21Jf?x@Z%B~M(>of zp7!CkY^z~xB|t+{UgmH%JkBW~-h?LL8;Sa`L{H2mnid&3#E|R)B4Q($`2ZTSBTh@v zJm~r6WDuEWC%HS&j`Kq(HkZ}Wq30@B9HV}&HogxyyioXio*#$*=g)q3Qiui|9uPKX zOn8N`wYB&5Eyz3dpC=ZSq@wVB`Gl3qvL}qf2@y?Z*$O1tk4gk>^r~t4?mKRm?N{EvYCYc49eo-f zLRrNatZ~Jw_CiljAS2z)n;_b45`frM{5fC8xw zH{<-j-Q0VQN#z)Xg!UVt90Wu<#J96Zep&Ol2=E>{=X4gY{qo^|xg@&@dobq8T3mZb zJ$JN4AD){HkH{JFB%=<QPJshl;lm|=nF zksGA%5|#MD8!#os4S+ zR1L<6yL7UCi2^2b!IRb~{aN<@4{r|5i)dkT!*>Ty+5(!dQZq8<4ZkjH3)3fs1k1hv z^8z@;Xh9@(JEe|S+g6VWD$s*W@pN~RIC3QxJKEV>=6RX43+I-1RwYW}L{69z67iQmBQ5cDvvRo}O-ghbL?jF*icq+?k3MAUwmzroLvW88>7AivDTxBWBU)Oay0kK=~4Tl zTpjp=B@!F*B{x(QKn?4WK};T84u6bYHmS`7GI2$IGPle&4BimTmPq-LR&aC*;HJo= zr0~!v&R+Kx(osY0U>+5=N3^F*Vp18<)R0<;7Os)5MmFLNUjU2-n!@Vi3Ymh`L!QHS zm>G78gw}OMjMlZ7Sx#$x;o)=Pjnpx2k^#PS?lI^3dm>)!H@V6U`a&z(nEk#<>AJsC z?f@G6_dV|ety3eiOTTm&rF;UxXwUtE(yl*y0)IIc-!EmU0O_AYvokTozp&DMCK05I4v?0dwYs zR`f!KHbTP~UH<{zL^iqe7VbiAZ;9oz3;!&ef)Zk2a$0!g1u~QSOb=fox|OQF<+A}i zW4IfGXpsadPS6jqxW{17{fl?8Gy##IU=dN~!Y{t_pYQvJ*GzeZ4>V?s7pfn+E`S*s z{YQrtWz`JSkR>ka4ich$X%!c}nqk*~;TRd3X* z?|OyHg!HxY5pq)IQ)uB3oQTVpS>D_;3>7sg4^uC&`)uvm|zK!@kFoQ4pecXC<+95-S{NVyi-dYR7Dla#%+gTTBQ<8*^XqVOBnKDFQQQfB3^c}& z1QdL3%Y%DKPm{j$t4Wy2g7~nqNdQO@DNeE453EwP~m zG_|f%mqr~nJ7d5^cFvHH-kO~3U5HPht+35RhVX8nv}+SYt1+yY{^Hg5O!_?DxwY{ zVohH++g`2MDyXt=dzF=T<%Gid@7;CG&#_@t=96Nb$udk}v<_)TU!UGDew$7eECOz0 zf5D%*o!^(D=N*nFk74)~An@V~Y<5K+7cq8EP7dGRgfM;dgXN&lM}P!>gUM<6J%^>< z-zxwro6B9QH`V<<5m7Tcj0j)rYH#4nqPQ|}rh5{`U_X0H2z@q(kC83dSIxaC_If*5G)g6{q%?()%hPp>+! z{&>Qa%NP%k##65H|40zlQ4Ll*upVvB#v{Ap1Jl8D^H>)Naj`^pJS5trE@4p1W1@gD zoKcwAb8pMPXbqu9DR&l$u!w zhgR_*m6cw%_~Q@>|(Qki?mjB%50gTa>oRge*8WsCjdF|aX4g_(JY?8n~vBToE# z5iMWA^rWP@xk&^JJ;-&(y_q7Sqtj{=KlRt1QsG7FY&?i3nQCG1bvfKiwJ08?vRH9~2&TdEXEFY{|Wd4=W?- z*Q;DCN6NUTXJ$anjH)D@lgPc!-!p3C#7sMPFi{C$^|OIt}&trI9b{msqZ^b*QMh&=9={jhEjA(9Bn zltE2YZ!0YC7s$#cPAA6C-x?ft*;pR?!kIInDkS_xMM1$Ka@RbnH-vza3ww?QUSRWS zAW^P3QjF82TgL3Q@1l20JD4ItrKG^v1SF|7{pki%&yd0;jjBn2EqOrN?r*c8&{|fKw+mw@5eI zH22HMN_V`=5sn(^9hic1`5^b0RNO7kz_@}%s>qOo-VseEk}iS%#l8_Fa|+tLMOW~Ld+Y$g4bfM}-1R{%RQ1}Iy8$hUsHAXMfP z{);*bnI(vkVB9%}|6Wmr!vYCBj^47x98U!X=@w&W-7%Z$P>R;T;&PoW90&A}2LuG{ z%2#DUlYMXc?Lr^+iyf-!T9$ctY6BB#w^kZ<-ral|{lYZ60fC*>H{U_F<3$FIt#Nth z16y4>h;KUjL>;2GV~EX6gdRuov3^8yo`F@_3eRjeEiaSN1`BU&SoRk%>YO`&Ce_(` zhMb9s>A9+$xdQGMfUOg8LZbUUEC)r^3a{GOHRaH?E6`hZ zxGM3)U#>#a(xJj84x&D5wb&5bl36X%MTIOS;IN!3t( zuO<1yh0t((^TPgPrl~6z+uGZoBqv8KhY~Xk*D_7T z#?ITXGrN79H3{kq_R{ODv5Gnx-l~0TQfCg4fFMOj7?PSMxhPL4AS(9txTB4jHWUlw z50e`9SvyQ*{hCa$Z=^xwB@+9YAcNhkHH)0(ukLLlKIe470wE08_Gqgn*$|uqsjA16 z{{E?g7YHvqIIxF?$f??bQ4zl?b?`|f{+S3$fsJ>>MFKdT+*kWyM(BR$Hafjp51mRO39NHBb5Y zS2J+V!}P_Ud2=6ZVoXMw^%sBjUoS~`(Drq&4ZWK}-Pf8@487_So0|GHpYviP+f3?M zjg7OH2TqLPl3beO(I=y)UvgwY^)2`Tu>Vk-mhkiDlcIY}7t8G~zXe|Uqy40MAeMy~ zL(oS0H4}A&cbTb3}{<|X*-RRrQ#+jdnzz@M_k?`W^2^q3UU@F zUvo;MlCU0Ju{0~EH>6-7JuA*&*@9O-wMBeM9Y@nfC95bRC}*My@9u%rjp3LvdKaw0 zyG6{MR!v(-zU2qv4nf8t+3fOcXPM9QllKM(2i@(%Ey@Qn+UIefJb8kT(lI6>+CMZd zrQ4>g{UGG({etq;3@DBbZf$l44OWnskE|%bv-I_EkWOz8Is5DLe9-kdCp;M#4&O%k zEZO0TKfpOTs04%GB|vVAOm3d=(RYN*U6?E(BqF^mKa=5yeQm$p(Eh0DR60h?g+~5+ z*iCnXc@Q9o1>Y0WK|tb4aQy00>n~nU7OVq{yakeE$69I00#v(m(@Xp#c5B< zCq$=AI#$O-dl%$iTsSG=a|oG5-jcfn`|w~jlp=scE{jLsgU7r8q+T2x_}_tmWVS#* zyS1}v1K3s#b-z1V6#CHg$wZu$8tSoHi_&R;B9>Ri=<{DY$&NHO?&-^0c+SASN>uZ9 zn@@Ro1{T&hGq&Kr8eBo%R!6HDthx=hw@q?!A0DdRgt@DcUkC|NGteQ-Z9phyQP}2d zI$`%TO`+91L=)$6Q?6@FrWTmG?@O;~xY)DvGf@*M?bwTZpODbXZzVo)MZr~cOW`t$ z)EStzv9bN24L(RNENSMG4P=IG00DWphetJM#VuX9|Mr8u8qXcG-TP;=vSyxxw%8SW znr&xKiJJ_sE?@8F#6=@pP7w>7g|YJB1tdWe_$Y%yu{$z3t-YbqU3k=9q+f=J6THZ@ zPM$`5F?d5Rb^mPFoB1=uO#Jou2tj#!w#d0W&u_s)7c7k2JY^0e)eLlG^2GWUM}Kj- zIl#d6{$+OR+Si<#BC#bLvMz*fv63ak> z3Kl2rUv63u`^g6S5(}*x7cnPJ;fCN05ld)sv7?42gF@sUdPugNJZTgWf;H%W_5z_A zIeF0IPuKT@;s<4^Z2mlUc|*c#v!8K5!bL~`{{&w`~W4>vi{VKTmRPk z2$E>GPO@`zH(~nCrmEJaedm%}CX|%y-OMu7B3EkCjw7gvYRZO?%;#~{4)Z&SJAxG9CIN(~$!l2@GXNpt8s+1i#3I=oDV3{Bk(~$3o%wf7 z%N%MEiHomDE~pw9kd9k}2o?}vt0v)Gs{I|QK&ypJm@_aB# zDl#Sr6m~#Od>H@BLG>MiHsO2C4q{?4dfLHHR4ht&aqbt);(T82SG%=F+7~=AQ^`$$ zWe|!Jphv9d#vS>bxMY@y9DW%GY0J9)b|0p?>4;HRAdRDQdPPN791Y z4TYKN@Ax!j1Dj5uV{(sy5I&IIO!5B7F96kpN;ReKHpj28=f9q(_sTwrl#d@jUhjNi zI9&^-mr<14H6gL^_}c6qINzOw7UvSySO8r->;0{4hlMMlfA<2+_hP+0+)oGN#G0+X zGU&aM5fM4H@3l{|Q02lREOP42=g;;g2B)7UsC>CE-b)UbmkN0|K}aMZE=UP9YQ#Bu zR124w^4KI8NYkwYhdL3^z{l@ysw1DtJrrweZ&Ov%BepO&T~B)2Z)H+81xZE_6*X^D znwC5kekTy?4Yct+%G!5d4CO9I0CC}GM{0!@?otyGLMg=)TM16Iqz2(L1UyfRoB0aw;o2YKkThODbo!rPy0~5aG8iVaW28L`0NE8YD}hlfIh| zj;#s_y%O3!%Z+wnOvWTvbqPPm@!9R5z~7x>nL>7Wq| z&E5LaFbi@~qEbE0m2=k@dr!m%M!b|Z6GJL6VOX|0NRL1C8%WPN*5 zAKWXk8=*EcGh+visVG(#pScAA8gvRA*T~6w@LrKoVZW7RF#{>34p%llkzDXtc$tfYioJN)L%wP>o}tL> zZC#C4^qU61A=$bEfz!!jlveJ1J?MuUYT8sblef3=w%f^?0A&DnUs+t3ShFIrGN=G&+Fxj#0-M?!t~vL z0|hx|b%3k4|HjpIDW<>Vsj<~CsRolJ)xVv~f5mbqBO$7)sy<^?E>llxkEnL0@J7{i z9veW0E2fYsuPM5@Mo^q%)jVVw4}}X5gCCq^sj$ za{Jq?b3H6y?u*)U`4|HY%MT0k_ce@CY8c5RZzNB_0`NwCvCU&9nSI_+6KRSj4(gZc zlUIpD_-f;7&H3t=6VNIop*ZWtM{$O_bO*Sk;zz=F8@FMY< zql`oOCX=VoK^*7`A|HxC7(u?bOuH|h&%+5=p$r~F6hT4^R)QgJUfD38$OS^(lN1hZ z{->tn=6X4_aL7x)cD7vo&w=su znD*}w?b21BrWqhh>v}x)py=+FjXbwuxTCT%|9d+T%{Y;eChd=%{fh&-Tw0+0&Us@) zacz)1*xz6Dg2<`E$05D7#V1=t6D@CRI5Ey|CRmr6s5l8?9G>vitMd=P^jd-mJfNS{ zxU^VMFI^0uZxY>w87{!y)-Go(3ne5ZGVW}blegp1VHEYLNIP@(`HS?dzF-3tHn-bj z50;~QRDBDfxbA~RcVv7La(DAcNqEY z7j{4+oludQGWf9xT%TOv zf;s;*o#u-u9JRWNlr(npMn4)gVs>UE7ycu5S}LtaXWud#*FQ+w%N}1%le_-1YR@?g0=mUL%Ym`x^yYD9-GbJeS=wP8lq1nk?PP9e8-Xb^)}5~( zl$T{Cn6M?drbV%<)xUd3S(U=#1A*aFmcpz3X`PO+aEXzCr%f${(;^3fVw1r!U)W8c zFp|r}T~pt`{r1^^{DQUtLMU5()enWi#QT+Wk#VH5unlrm;(<>7vWyK{@t`ME~6;lzdhY-6+bDAZG0 z+UU3>yM={?=*;92LFKDruB%7(we8)mL~h=@w93VHxf=9N5l2OLpV?}acL9A5(~&Zp zBB`ney6JD+6O%LDx3p}>e8t2xn>*SVb_yRKop8QdQ}s^HyvK@o59L+J*>abB4j)f$I`j)d3 zC`Z)JG)PM<^No0R@N1&~+HcHFHnUQ8PHk;B|?oVPQe)cLk(28CLwNMOi)WiJ=13OBC8E$kp$ z?e3CV)XrcTeM~ad{K}|NSb#p+e9K%Lb$%{B(LPhVrNDfDEB3IgW4Uj;<3qPdyOycT zq5>-YL41?|s$2Qa;G>2UD-`47w^+=hWv!?Z6%|q16NY#MS>cm7vj!BkCxtrOw4wVTp@ ztk2mZxMU!0V*z?Tnp^kj4xzo(&&BOJE_s%I_nhU=PyWjlnuV#?4Y*C&+r~cW{_8w8!dq%8B9L1Tt6A z)gEiaj|j-Ou)A(E+BQ9&+$56N_pWdZ=SxyF4rg@V9xm|Q=i-zYsl?6b$h&Hlqi4DCGw7xX>>RA-GuJA*9Q3`PMnV~p@XF5`VilMk=Z<_xhkU-p; z3S^?Lz|OG6QE4M3|I3adDkwm?iZ_|*(GciZd%uv zg(ODB-YrF;xP`(+)k~7@n!A%?)4OE69OO9^JJ+-|_b~=`!m7wTD&*_KMo(85MP&wo zv|Vd*1Lfx{i%X{krfVd92@U+~-N$>6PIt|xq_iR&_Q!50);@oZoO+_THFfDi?9fp3 zD)WfA(@%{Fq}sGCBaIT`{ZMV)!?6;R^2 zo#8`vE+6esPsPmJ``+1lDFoyLV<}PXY;E0}9w>Bo`2FICTnmjHbq7uJ@6L#U4l(LS z`$&!m=)(&gvZGU&kOu$ENIC9ev{IIS+ z&-kxbO`1kP31Dl2igS7MhIEnHt<1r3Chrm+%$b*RUmnCt4e&L8%Uh6BNJdiAfxQTn!&zn2hINE*8y&eg_}zUEle&mHJ&O@ zL^mth=A3yuP@hpJ6^t2VV(UfRJ8fKYh9aMuI|_6PgX6$s>vE|~d+v=nqhp8F$CwpC z)IH_r$l!$qVF{_R@U_vQ*U8>B&eESKb2X~UGP1ICm13gcgbm4_XE3+scWUspb1n(J zFc-4^l5D=mI#7Tc0i;~oC;Agmpy`hSL|%@87v^Xms4$T1*Spt(`_r@pvjUs$P(a0c z`Nw_)h;?zdB0KTovn z@66Lv2|w4zwL|bQm8OIjVIwed&wQ^?Gt~ZeSkM>46+zx)oI(ZiC7SV?J$EAy4vypF zxs>CA>-_Q2R+{{5O;&R;6kNl$=GJ}hZ0>$tEPJg)HKJFPCS*50I$UCFy&~>}yr7Y* z^Y-aEPugAr3?gK9zyWM#FDGJkx3} zGVqqe+&gSSVppWdZ0sAb?0n$IVP7mnAmsTs>{aW#rG57;k980%o9Mxdw{F_hdfmJw z=XG@LYLP8)+-vB$s{8kCZd>J;Mf2ElS2-1FGD_&glQJ%^w?*aaRo>TpeT`OGS=m%0 zV04`8%N4NKPO2Ks_oTW2A^pn?4;2&wY$s}@&VG!JSCs?PSZsIi=VQtLgv*MWz!bf8 zGZW(ltM$J&>QlH8Af=a?f3@280*`CfOg!>A`FL<@X<%eZ!bM9#>2XFT*%BwKePl!3LR~-ls6E#jc9iQF_ z{!%q5-BtGLRhRJiirm(xErRi5#6;y`3CtJ8d-yUVHX}D z+Ex+>S$^gD1=)Tk1ju&Wx;^$^{8^+REN*Cf4p`tKz*ev2F|g77P*{HR)hleer?Z4D z1HqUXpu;XY!2=up3P?Zg)~h-~cx8KMRHgZ=mKj}2K^TqpJ<=O3)r zynENjEydcP1XkeO7sEq#k0(j1;5XH@Qq^DG)GV{n&ebYP(|C2WX*czI#AJv7A`YE& zfND!+1jw&0y_Zk)y1>8~(E$KivD-Q@}odJQdUTbDR9ft-(x-eNjN* z8_4z=6W6VBE43Z2=)D<}FG9;>tC!ROa@Dq=t9@(i<<+w3{k25qhPy*UA9y52+G4bW zY0}5d%;P(3+C|ir32&u+ zWMFd}ew?D}Pk+D1V)X`)Ze$@iloFjMdvPjK_WN@Nqo3W7z6+S&_Zm&3c=U%Ul{6H2 zZf;UoVFs%J`MC_mu3+DvrT4rdX=k6z$;fHhDEh>rEQ0jf(&4D5{!mK@78!#Hvlez${Iv-G~YgEK^vJr4! z-b>;?4h#V&@OH+$j93^8^uH|$89O@yDDRH|675Rq3xncw$)4sdJUVyS4tKLkTf1E9 ziO-oZfEls2N>__+C_P8wTseJLH(X|%=k;eLiC3mqa&<~`GBPr#-m4Cs`0kMc^(Fy* zAGN<$D>E%hiivJ(JgYKZzT7!&{ZbWVhC#gb@omkv+?5}9hG;wq)=_I9r1zVn|G6Xn z(-q|-bk6b704C~6u3dj*b|cngV0FZT1Yk;~P}5H_+L^J3(Q#HX=641g7yG&20I=xU zO#5N?{jL1E-Yci-Er-tib)TA(U~FP>tbm0ALnCGwPr5=_+gIiWe>$BKOJkst*7>z& z@aOt5^JC)+o^5tEdH$a_`SRrwgHV;ixBr?lj|1e9Y{KY-9=lBfu6=74 zU>Zu2@aSc;uw5a)^ozy3h_RT>xou)UHo$+s#g9rxA3|w`_r4C~cRc5CS$>z{BC8o4 z6;XtTLmQp-a?tOKldf8A&5G^#sLIOtm`<6kHA#d7&+V2hf$z%}e1`8%E7{UOp<&}x zG_T<}kgcf^T0tEj(TGEXMk|^>#4PllOoh`Tt|> zD2vbmB=pNK%-WZ~wlIn8FLJtDPDtlQKQrY>a`+fCL?;mc?5T<2%dC;M;nMtFZ42!{ zaF5T1%ggV7YS&dzP#}*;YWV(tR0Ux`h_K}R^*DK{K_KsAf)NKm5Vw*D0m-BHU^q<| zY=})l_Q&=M;>83h&Qdfa{{s8KGK0u@2h1-7Cen86qwk5~;Rxws>*JjUItz0hA%PJK zbKMRbIi<(kH z=`yAbpQsBO#hvjYr{;Yqt+a|v{7D!@k?`&IuAf$BS`NTA4?R2u#1AC*kF)XXMj*q3 z-HhNpJml$P1L<#vd*7mPp63WFP1 z$G{^xKG=^f@MEw3SnR+2D?*e!=Kt7x&#X(ARtkdA;L z3Za8YZ-y=^V3!^QDMBdHdlytn6zLrlq!)o8p`5jSXGY&T&Udcs{5pSTf`nx6{XEYq z_qx};L_PA?$0jpvK1A7dXNXxHyiT&caN%OX4Xw29Atj#cO8FM1PLbkytBhRT_w%eS zKZYOzoc@!@NKSt9N|E2UBsUIZ2fL85u1;fdUds_qp!;V}Q)%>vkKaP|;1WEuOGetN zsQ-F3fBs_k5ek?vl}#gbX&Cv=_Uzhnh(AQ z(ImIyR6YMVV&UNwAlCY73nk5IZVy;UYY-!%ce7>S{PVL1iS#U3$(zgEJOBKre|;+d z{)@A8I8Z0)EOq<3Cv*wqC$sMFRXR{xBy#r8M~quxg;OTe;d}qjv;Olg_%GYTfqxE0 z;_8EtQ9|e>j3mzji7L^V*Uh(n+H04Qy>?~SnV`SkYkz(V_az)Wf=*D7-V++HpJ$ox zy}qh&;tbP|%p?361r_JEuf<0#|Gb5NzwLjG!tiIQV2RC;nF_V0OXIEeXYO*S?=v0R z{o_{O><7PGl)-QA_ctz=?OA2?amREpt?DEaXaMMev@vSx*%aNMmxN!TW5EiX>WCEm zi|qEF*7C-FWHN3i%&y$#5Vbc{vbsIPFe=UK!_P~va|?9oDgN5z{J0%iT^ty-P7s^g zJAsT;757}RU;MFPEDaAK$UB*x&H6V!G`yDr#N%Fpr#U1226Rtfg9?0PFH1DfpPwNc z5BpXCqwjq8$Cdo$t9===72fOC4dHyO7x4g;a{ZrB1n{3zlTZRFWT%32rd5k z7ytbU)L-ov`GX7a|o z^o7(fPJlL1j%v(_{T;U*#eY0x#ly1r_=Y#fcmKIf{&Gv~W~rb+2C+zkBnvC8Zl;km ztlz*eiHhR~+#*{Ir|s;s3w5$T?Dvl)_%E+;)jP06yxhmi>OPkN8<+xdZHU=_?+(*X-04utP z@d|q_xxE(O!?GRA{pqd*Sipl)S2w5vo)ZZMo$01yx zf1xtNHe4+`q#2zZVefw-UHh>#-(T%}0_#&-Y;>1>3l&NooDSdcE32Qj@J|ouzn=~` z5hua16z+$2<0z3==wJQ2pWY{M0v15gyy-qHKr<3uf1|$Y`eWDs>Z^0ep-Vl?&kw%n z8@T82UDEk~#~S^9MY~<#K5mRD+EKBbMT))WJROeze71kO@c;2(elB8E#&3i9@N@Ae zF!jHBJ;8i)KqKgGj1b+s{L-kbxX+=UNAk~IMYk^;G4$K6<_aFay{+slohr@kzqSN_ zh70?i$U+Wg4az~Rw0#vmK3o{A+SM4ggdZ1omJV+G9~<^ppFZ7gwK)o8c2bN}yPmqs z$={Kms$J32Kdzh213tHIgZ;N3rt~jgg``!gNc3IXs}y?IbrtZQ9GD=4*5PgD`r}l{ z;=^InupJXA`2}#`&m|ky!XuFqh}j3%aKY>lm&i zipFaz^X;Idof2i~L_>gCl|SwfF9I1iTc8m6N3G`1>-q7$|MF_sU=Y;D3UrLz_74j{ zoNVDZ+IahGj`2??ts^PNPic@pO5u7 zTqm4_t6c9XfBe&5zB(&}gGbs0Q(AW{MUS?`*{MWg&b|CPdhN$u4PQV)TtntFe=BAz zuFUH&g26V+`n4m`_SN*_R_*EXyJ%^DJV1edxZDuZ(%96mn^rsrN;6&eJz~M<8+W;V zVntwpqmPCj{rHFwB$H9MbUgSsjN>57cM0%zXr4?-&@Hr&7qk5Mg(d7!%?~@huLSJx zwTkNKUBBpTkWI+4k67Yj$0cT|dHNw-Gh!c({=C14$U!)9^rwgNY=dW@SluZ1V=w>ZE1ZJx9Ozi~ zfb=xC6HCR~!W}UzagfOLDB;IeVBpKR1G_o9l!j4{e)q8xHSU<8k%1Kd;avOKkqKtdBA?vN;4$P@BHO6`T6gD zyjj)&;_=`+?<#ly<@Wk7k4L}=F@+sVqt-v{*x&oC;H|JH9UOLYQ2qJ}|MT6{A!dHQ zxIg;P|Me3b_`t0lK1}KNV}JhdS9I(vAn8j0?H1gXrRkmyz&2?v@u56HtJN9C!cd3W zPZA2c=Z0#w&IeBw3s8N>^7E{oI;OmREZhULM?!|PxG5oYdnWCXpJ&l}KqLbuB6UMu zV#GH3J9TeQgc*U}yGX(aJC)o_d7C&V!H0VyELj z&n<+zMn}1?<~aAu$rgw2%QXxjg~FN<*O|YdYyGif*e)Y>$!DA%!&c^|&V3);m4M^j z(=2BLMP!dfE9~hNzRUXknz4v`AV?_vW3$V>$S1h?E%AJCTLn6^FgyO$Xj7C_RJOc=?a~({Oxza- ztNf`XDf-vZpduuPvwG#<30Em^aDXO433uUeQ7r%?Bi1n~5F;Df0r+S1I0wbSiG^$TnbFPD3| z8B-yXYRX`gJVb5>FPAtIrUxnpUTPC8896aoj?KsG5$R-@lyK+7Ffv3m)_ZkaHV)lOHV&21=ECWApgO&j5S7>Lanv&@mjzRBkV5EIXUB~ zu{fW8+wyN_W3!y5pgKko_q#1&cie;+VHruxKttRHgb=cTywkbMXU*ir`Nyvi8=?*n zx?%CnY?w#Z(%}l4*gK>~pP5qBPxlt(sKlN;J}UWf2&8~=Vd#zoQKCIhy&hVOI^idC zP*u;ZyR)MQ2!_@`ZpF<@Sa%XZ($)Bt)rZ8}nGP${k2+-iX3AjxO!p%}4eO!mfM#hR z(jPW&L@2AT?{QrQrR*3F!;S37W{H*llA%B@YnTdvYdWC(%os4nBuB4~biI+28i14E z$k2e%5HTKSTa;{jU`U3QyO9&G`)jB(T?00mbL`flG~Hq-#Wt5+VN-c>qwU*U-3$QU zo5{}sv~`9l?~!KCI!Enu*}1VPke!0^>0zSRaP95o*IagzPlQk|hn&h^O|>Rp%s8}t z-MgW=*}4A$5(%z@?r!MQenN4w>dE=jB@T2&h;2wngD?rB&* zfa1zm7W<{9b6Y)^UTjA^qwFvet*%)$?EGi{`CnqeN!rXEeGMP}Z{3 zd%8u~$%V6LtE}eExb!*%ZI89T46s7c(vYLz{>@sym}B8 zmn8cJkhEzSJ{sCtmO{ZOw7VQ;M<`J6zHgQb$lqaLk1K;oXR2}*a=E=UoS@EU0a0H; z+3G}^s``y|s3T28k3bP*#-Hc87+N$f%V7G|yTgw1a_&i*B2wOKD=9rM2UnnY?U4Vq zRkJaZ7%smrJ93#&z6mP&rm+g?UW%)pFuzHacqVKLH82gkcMIx>2;{X0=E*gZ-W8_8D)Z&q-;?#*rMQZ$d>uj#n=hS-7W<`mi4A`XrJ5&?i!}3XKiCs_hmNSLU_A)B*MVACT$MZB|zh>xh$DoisCuo9Z-c*!xO4;D5?e$AIo?9%}v{<%%x zNaUN71`kVSO6;eB>gdvV;gJCAyz~2)lr!roUENL1-!?Vp2_m}IqAFXT7`B+TAb1!DjqQBD~!_)3=bRV8p|W3=lR}2y{^d{l=aij zUI80D1uFaV>)s2d5ey{1kZDM6IbJQ?olGUGGui%jp+ZM)wPJJKuC+wiwT->6;Qq`s zl$VdMJK4EMY0Ih^pTSAae$61|YBQ?^r{W`Lu1H_D)o73(OEj%TeJJb^XiRo|j}p8e z>3bZo<(OHoV)Fg?{_XC(r79yv#Wz!PURK+Iz~72)V4h_gYCOaIjp1}viM$_b7R~#C ztRsAF#X|p_yqvs*=a_kvz1Q$McWy|awxL?3kinhh(2fcn8U_w~qFHf0hz(A!8C5Ar z&?S3WXgwQ*i71%?Yg~IXo2|cB2*WubAlf!^;^_HbN_c`zx1eiUBE^J7+up`>S(u@qTi)6raTMhf+ zOrP~hxseZVX{yrrupa2zRSTiWbuc9qhIz&EbA^uEv1%Njz=tp#Pd8KPupSZeb-8nA zb7h1%na;58N#u)un@AG_#mpi3EsCtz!r>6%DMCR%>aJ1-44{eAxS6rD3jIL+{#OV- zrfZmGa-nQ{B2BMw8VIPz(4%7opJ5wDH02Ek^mU{3(2qF=M^(kV}lYYh2n^Qm%I&tEX{8*?n)EoMKFCXW)jV9)H>@V zU8++5rJWGv^|eWYujO8>QyJxAdYT{$GRe@$ynaURZIHWX1x(4h5eriW@ziAu{e?c?_g z$_qZ`%HNacbAR327P{!+WiFJZ7B3%=MJAQUIc?I)?C8H&ilZTLh`>ltjrnqIDfL1* zG7+VSsucY6yxN^G%+h(=$D;H$Zbw>I%c89AW$715fQQcoV7D`*tUY1Wh3sPD1 z>ylx}xV@P-Q-|h0!nE(!R;`bm2K#1glZUUOw-u`hb7Avs(Freoa=WtgZup1X?~4f6 z;?A_us^v~i9n>Z}n>XmN7KJDSo0aR;8>l7?Qc3hC?Tql#c@UiILw$s8kNsATJo#Ff zsv74Exfz^{fp14Fw=DFv`ayByZKM{`?Mb0DIs8c!IuK=)hrtYIo}Gy%GpsC+Ki&M$_w`daQsQtUuxSPhz@ z1=50#uSC+?P15XHltN2eq3?i#`}e>P<>_x#Y*&_3WX0}+Hus1Md5kWnXUb1$&>xDi zulv#siYmwSknr8*#1ZQAsORH)A4ETkQ!|&ZP6%u0?laKHQm9+9)u>b$n`}NayKzdA zh$n`c8R%5y_g}2%aWUxhx(F;KK?5e+`v)HmdCz5VXuQ-EH2;h{D_l?t$$%=IoJz|} zZ6o{3iI30SB;0K3O}Z5_Gj`@4r(&sBsY$L`Q{?fMve=?EaWKcThswU954O6TPSiTU z7TQ|an?$yOIGDC6E3*Z5t4+e0d#FV%y0dcP0Tb0?0naq4W;0x&TcLmK8zbeHzBHFR zu~yV>d!(&aZIPOXaf7>e@71+6qafFlv;mSZiMm6iAlE-eNWj+eQgwt z3D-)5tgFI>sRzOA{wC!iNVbv-OJqUPnegE@`=MM#$(Gta1%meY;YM8*(d$-8?gbVBG-wZ6iKcRb2(Bj*W3la6 ziF2YUR*a&6L)WXiX>MAAh~N1!&o`i_`4o97T(4>GJ(Kz2x}^DH#cx9WS~%bWXeo#b zPRaTe*c&M30Nfwu@yJxPWAp7I!(1kBN=9I0Zq>_HNZaoTk;Kt3 z!n|d#t;W%U0&M^K!9uz#6&hO#t;qI^Fq}AGy<6j2$SEaRJ#UGeo z|APxaO+y&nMzBEhmDTj(pKruGA8^~09+~lz^&61#_eR3{c@}^HPiBbzgm3;wyzqAv zCqQ5jOo4z=U1;R|34M(!b3jMs&2BU6q)#wnuyNiY`ViH-BnP(}#>nLeTV1E4=D#Y| zWSr@%;4jBx2LbdSwW`(-<`enPdS<82A zU7ClD?C|+{MAK4&-iY6wwY@woT&HfcugA5uT@8q$5Gc856?ci?Ja|?V@LOwq$OgPek1TcA5gT?N1vIUmDyO?n|QfU zwg%X_c98Ko;0Jb^M-QE}^N!S(q4$TQLH;Npt$?qcK%723bn8 z=F(g<9`dUC)cdttg&6e(`GkevjlV<(_u|7`dVJ|9zZfi*)>)$Ts4^w-F1LKuzS)3F z(w|q_)F$R3Aj5cUtBXx~5;}E}XDS~%dxnBB8}p4DkhZ@Gzv5Y_N@4nQW<@^|zF$$g zG=LQQh!VZZ9sRNjfW^n`QLrnl^pKrBPY2{rn}+PGjF4j;VTf?Ml2dH;WPNb-kh}NF zP>@Q%E_07X6t_k4f2W7%*;|2IO~wVM)6SZWCsxPA5g#qO5)1 z?0?#cOdvb9Sj~iKz(Di9%*812CQVJlk4<)XzRVHMqgVa=U?LN)X)n4V&98v&NM3mxAd)C(UxR^;nHJQz!6ai)9$OjDonFeh0OR_&Bq-3uIo>!R|9hH7CjW; z8UE}|oZ5upoJ@Cfq0@p-`1Wb3dL(JlKq^nDrv-oW6dy zT-2BZ1OBmF?u2h#_?5U*UQk(T&-{5hf2vTPfGsqSc0S2gGlFQ7eII;S_x^xHKUAw_B&wwxr9`+p=bATR)R> zv8`1|3D*&=Eg``4@g%*avZjmpp(creT$uDLl$EM&Kzxh#?n&3n0WF<;+zen?x%)3X z@wYbW#36&;B?GFEz?GW>?!Y1AGIaH<$DYS63WMj+rl#{gj3HN4|27l}8$mSJDrs3) zrKJuuj<~+CA2wJ7vWq@|ag<(b85@JPcybBAZ|ZSfx+9C;8E9T_7$04k>9lLY`(W^B zp61a~v&yixHQm?UO1Ui~u*e?MFwT*QL2HOIAZ86iZG&<2vERA_J7;u-8q1bA-&2~_ zy`o3Y-wq?KOSHf0LHRnpi6YLbZWpy>uQrS64blsjD|5QJmI}}U!NhslyXH6dP#;jP zxH2}yn0c31`ozAIpRM>!PVBEaUYPvi@!@{gk$aVTXSP0P#Wqax)How%`vyS2XPYPA z>itxw{O@*KmKEhn$rx!;0kp01Ga|OVk{W#FJqTCvo&&`ama$R&O>h6KimxCt}n#F|uRZ6Jq7?aV=8AT(iFmK17-*uRA`&f;+Z1VcO@ zJ1*kmeKt3e(0si~zO9gaRFl4?a_A@)*|vu4h@?MRh<3)y)h{%!WDZy?J2i1;ULA)q z%zcsKHj%SCyG*M-i4n8B*WE$rd~=%Zlhu+RkCd}yPM*2Bc@X!doZ^-!i6e7T5JM79 z;0J@^Mx}#be;vMN<~eOTH(14&7QD7T>r)^HQ$V`PT9w9jcn)A6!<4l#a{nmYK0CDRmky>NYB_c}87y$2i;yX0d&g}`UtW69%20$0jC z&vwAsG`v9Sdp=nLnUR6v00N9&dvTvM;4_fxtLhy|TD5Eo9h|+RO9tRCuPH*5pEwPp zW^b>qKPOeeyX?RLB!Js%(Az2JJ>#{@^JLRhCW~JWN|=ZzSp|Qo6^%}lT(R>Z_sFel zR_cSVm)(+vy1MsX3mnzu9y?}wU2MJ&`VHAe=(X~N3tI)>YGxONl=o?~;b?d+3^5Qi zSu;5FWxu zglLsH`Yo`Pu@e2R3A^-@!!mU2=gUYt+ocpc@Vk40S@))2j63zM`vpl)-Jv{WaXlY_ zJ%KaJ_9eq5U;DvaK9rQZ0rRuHp*1LYgpftSsGoX$sx!MhkS!AzSbdU~!2ZH2ndQ6@ zCoZrwB^zl7P&4UhQ(Bq>Vmy2&& zH01Zo*1%z~0gzLvaUB8H0cB^;i5p-tk8yf(Z1MRI&^{fxq8?zfPDbD9 z2@xXVN4&s2HaE^?%M0k2$qCzFuWt$9M!f_CLIjMrhRE(Cax^ZbLGaG2OE4if72lZ- z^Tqi{YPK%vBt?5!C@2UakcQeo=u7h)QYZxsq$XoE!9)5FiFL6#r zdbVOGYA-Q7B4XU&0)gs593(h0?$$`fnhj~psGD?m%>OS4^zQ-d@4r=}qkyNox-<#N zfMt0o28uhN)nJ34g_bF+J3EdrAx3cSav{u$H@%#Ty$_X)@sALAw}xy3A5!S_`R!wE z7<~|)fjXTMtgRxv7t-q{+g%yo=rIOfOKnI+flAzGG{RgtP5e`mo4HPhGP%lB=&h`u zlxX_hJm#x_d480*z zZ!U3}<=tlAYP|u=Y+)>lu8RZqQnS>-LPPs1YSnB6%#In1qmWxYMQ3ZILBY7$Di|W` z=hC)~$52>kocDc&4rFfE;W6bvGgbKH=(_3wBFm)Uu;X`ROhq@^+h*v@n;?6d9KQqo^C|^9wLQ$7ZW2F&y$l?E`884L15^BY@bG zrZcN&AZnyp^`K+~cz}_f`?HH8^8n?Y_wUK2RxeP}3EolKK@lh2Zs5sKA5yLoFF*jd zq-xiK@$!vN4=+vu0vPN@2WzrxZEFWgiYVf<;mL3PASQ-Kat)L?v8eZniHWDnoPj3S z-+l9Y9XWWnEFO3H7b$ZM$+skkBIeE92w<971{gu|^3#g7{X`wb=P*p3p-VgyM>EUN zEfg%XzS!z@Pq-k)dAj>^qkP8ZOQce@JLpldbWm-wuO%ZE;OVg%%3A!8^@}H2vfiHRy0=j9i@TXyJAHbiXtl-6<}#tSwn- zgLLqOpoQ5RHvX{`HNYCW4%5yVb!C8ho;2{y0u?KOXXyp_&kJcGMrc;}sD9CYwDKBv z=5DfU90@6!(sQraz`lUi{xO#be_1Dh*N|8!SpERj=#ER4(PA8063nOGv zGJY>-L4<;%oETt5T9Gm*M-5YNqd7gZ|Iwmf2_shQx&DXm_}QF&W1FMlgvz_=4#S)G zGs{lFLw5#-70s&A?@d@i)=^M})uvTrP3?i9=Df#D^E0=MK7UAoLc0HR0?ck0mAU7& zrR%kRD>3`5jh9!UZU;(Xm_F4koCcWb+64hVCx?kG>PX&wiXA*BZqiw2>ZOA7sSg)L zh8`n@HKsMybuft&7d}Jp5na&}YF4a0vnPPJJzI~IvT)QxrTR-cOh|_VhX3uh?>^gi zD#3~1f|rNy9HGgV*2D$QkJLxapbOCchTgq-Hh0($A+=9jAKNEOp@5xG<|kKi*%yt3 zN-57?mr)UB6Yyv6t)}MehSo@EOF`WP2?d~S&N~LnPmXx?0|aXg}0Ww3m zp69L%ixgd9e*Joc{E5}f$Z}@352=9kHm+x0E@%#w91afmrsCYFSBH7nvv0XjMFLa9 z$vohH^RK;mAge>c=>74_clzhx+GRfe-U@uyukvW-4gpSbTKMDg%p$mkTrjGFb5;R6 zX3EJk;kIr7p;WHJV_=#}gK^Q~?u*!gvBy23k#*mC9a|W!#bJP@hI$1`FK?SXFjl^H zY3UeVw}WAxANwFncCDd#EUc3c`H-%q<;%=?EA8dMh|ZdTbKVfX$_gk**?`j2*&(-F zO2OUp5KmASvt7f>37e!yb{^t51r=8tz}w23r7rQqDTBecbDqZo4AXzD@+fwg=?;3dI4!^(9bxokjw*#a5|JFnM8lWcl@8a_LhLG~0l( zN$Uh%b~of3(=hLv;byBi93rN33HK9UQ>`L4jK!4b*^>VT5 zgSS?5d{KbO=%LK0B>>j=xPrhMvX$uF#LBY&o(=tcl;}Qb0Pxw+q};JI*--!maN0BY zu1!B3Mj|b&l680P8^IG=M~fm+QCj%S%~cD|r>G>Y+Sz1;6%wI$SuxvE+I=yLS!Rt$ ze*_5xaE8dVdjuayDOuc(B{Ct=9T{e?Qjh@*MVjyHTI>msM2KI1`$%@6px^yn?%UJ$ z8uq(8(>%W|09!Wy8M#Aw42YecXDcA>n7$Bz2S4XvR@J^fSis}-QC*d<9ErrIps@S3 z#G=#NjUH3Fu{zlf9{gFo)|P^5sj6u;YEDcboB^p(+g4?A@vb#Y-}XowB>hX;Gv|xd z@7lN0F9pMSW6-Cs=E0Ed-sa9B4xlLG(he%XD{JIh1!Q zi2xu#86nWKMezhJ^$tk&EKzC5dTq7}Ovu)NHC7%FgH?P8rAX(q|F71OIFqX{2eg!g znQv*C<*$&wMWPaQTI9Fxl4@B99lGaXz`NOOIoWoQ1Cp8n82irq)#0~xH-ROivTYzQ+PDB&nn9 zvR3)z!LH>59%Jaw*M0#?E+sCRttw;NxSQvkaMCerRGc(GdIya^I%_v1I}PVkc+P9v z_3C>2OD*BnXMRyLj|ba$ePx6j_jvLsk+5@bx48$RchBV%2Q^<|;v5l7jvl58<%HB= z$3msJP-sU^ygY#PkAEYuvk)v4*~+YXlZ%PYQgUYX7W%oh1hIcEl;8X1wJJ`iH)7PE2I5v24KBogsBl5{XRa|I$DzBtdKOq z4k*vrlUL0|S$ktE$*nY|CN(*hb6fsW zbm-6#f9vmNI-CmXX%7bX+(7+OQeck-aEk`5n6`3>`a|S#83T>`6Sw(eIbIdZCT7Wb zQ!qxZUr~H%Ym)kU`K@r~=|k;WM_-0ailvqJfFyt?8GPVX`LvW%u1Ow**Z9Yry;qn2 z;3zyJ0}8EXEU#D&Zi!(^L$MtxWVkY*)h(U9T%0JK?&dd9?=WDwF(Wkdv2kT6+T$VtJloxgn?M1A6>({t}QLp}`jW@u;lIMIcf8KqTYS$Ig(~t$H z3K|K*F_76=v};H$5KhEWHCVtym}&g>$vjL>lQxpYG*xh1Qknrly_luJe)JhzGh zvG2t*x_v1?kfbWJXZX>+^S?-o!%E;p3Ly(u7WLEte(A=1m`|tT4#Q84&4hdpk}Yh4 zXblXffwE!hrTxhQnwv}caI$kVfh)Lzr|?0K4?x_M^jrh|$uh}@poXWoPS^%P{92`m zX8H!W@Gcl};pUaeQR!raSz4eZGDd0g5O`Nh45EjKv>GH|38pg%>%-plD^-=@%M=dC$yN*#Iu1OOy%yv~rlOL2@d zt>>oUO=Ugz%O>nYCH0r?=bG)+ftduFY90e#q~pSSQzZ38C({O9A(Uyh+@`O!zi_-? z%{X~?WHc}}c^0M+SsOv$&39Keu13B$@M634;6-fPAVPXPQ8%k-5pj^@7kj0zqiU8q zfO9c}Sn`2!>PrlPlo0C}LxyU%@odFrIk52dRq_fF@dJ~3%!faAgoqUMIY$9&W8!_gQ1mHRyrW2N9dCKvXD#zs?r8u9OxLSr#b)q9O1Z^p z?zoWu_EO6`QilWl7I{X*@970Bpr}Axu>D&eg@rr6RRu(-_SKSry5>Q8*_u1y*OU7o zAXd!I{_F^m>;gq~T)F<^vqP!C3+Z*x6!=^?66$y=tX@{3G{!H(@!S>ps4viH$=AvJ^V7uAV-uovzTS_Jod$H`!o@ZP4`FoGb8Ss0Ha7bxAW`v=?@9D?ti-%dG>(1E zHnUTm!vcEpXbGt2JOZAr8HQ4buto!M(JNUC&BpuQqsyjB_#;+qH}yGRz#MT+XQ@!cP6>j zuA?#ttt|VrMBQzZK5@)n__pwaUBWPh1Q?e@2TGxyB{%=bB+BVI3U9n)l#sh1xH!Ldvqr58r3 zLh7>5Tws{=vhGVu2uV;)z+Rj){Z)kY(Y~6g3^{ zx)}zN5NE~8@Ezufmvgt|#cYMA_N)zV!M1G;*mBkIvJ00qGm04PHX1=)^pw(3iG}x7PXu_ zzv1ljJ8x2d33{lEX9eT|(^_iwK${HttFq!Ngb*%f)h^#Py-=|QoKA#)n z;;}qsp>Ozn_hnlO#uGD8>>sA$!dR7N5JGaaP7dJZC?`QTZ)v7a$~sGNh!JgmL^rEa zuW2|XA@qhe<~@qtRybsjXJ$;bQl!lWK$VWMTGS77Pxys2IH@jZJLLN^6vu5XL0HhQ zK{5us{JoJhykF_!hFW&Pj6^^ZTl4MqkhjP5W@x25plLMnD=)ICW5}`rJ&=z|1O#W4 z%$$I%OYhbiM4Qg5sfw3Psyy!9l+Jtb4zRE2G2nN*_veKHmGCln*XYMOY`?t()Ezfq z+dpO~7iu2o)qXs*KMK_ixv5S*ggEA6)MW}{t>xNj<85hAzuqN-Tbh(on^mFa`jiS{ z9Af5m>;VqBGG!yaQ5k-y&r7Nw#oc`humY!Rc#{_5jL&-`xJ&MHGC;kH{J$FDJ( zYwts7C|S(GK#fo+_G}^03}(DeP=Jv3gI>UHRwxdgEh2F4uR|E6rZOFa+ zuMqP4Z+})ezz0)70&fmmIR_fV^dT%U<%I+@8&NH!Uj1F?hSd>xt+aks1y2_9~F98^6!2dn%LaqeaT&{ARY0H`-1Q~)|}PdH6n1F_ew zi)5I$J>|Rgu%y5F@FtOpbM5l`?Z4j~3h4+NT7C7SyYr8`Ua44~Iia6+Y<6=+EWguO z*x59`ljl~0sc}M>>Ak+^ogpWj`SX1Pwm9Fd>kJ8IeBFsUkZ(#(CvB{Q;Vf(6A)l(l zecb>dD8{iV&uOdKkzE5VPJ;Mb6exjz{!cFD7N`&m@_F1r35dKwf$qi0^ootu@pTo^ zCd?3=CKT`$GF@8`(x2pb;=>OEEf9zeft)S9hVs$6(?i$rCeK}!jS~Oy${I6g4uiu_{3+C>ATqAYz-4DUgRz_$?kb9FqbrahD0txxuFFzm2jc7K;$4BgzzWe(fV)Wob9@0zy`yKzw zC4B!e*9CbBUR17|@D#GQdIF)rzVum2M%0M~f?)=UOmRPL57+QyyGLs0_^4sL*>G9z^`9R`j8In5`8 ztt-}-#R_b!xHzy_tBbXh>fb*fzm9^RD_Z)cbbjUgaAw;?h(zUZ-ZOAN1NulwP{<)})3}f}zJcN9CF2%hc{lbcYW;4d;Y} zBlGV!h}{WK>d?r9I{L5g_dh=pe8?>vO;FIk?Zp4IF8}G@a*JWlX!Dc&|6*_br@#Hj zzZv7Jj{fs0`0wxi_xBMF!z#ADk&gdA-vI~Kp5gC&<3HV~Y}!`X1x`0Eru^F0{tsV7 z!^utgPoMdBK8ZL%LBpvZ)4N^h-yh8{ekhKn{_lL_KY!2vzx@B-F2Be*Is<6oGXV#n zJo_2?u$ci|#V(XdgD6`(6l2C6mZ7W19-OS$x5Diczd@m%VTX~ci7Rv<)If`M4fIj6 znngRj&YFMC6;$O%doksmrOQ|hL^(BKG8@l&U7#jb4P1t<8HQ4mKg?*Qte@$x7`fl= z?g4tRN_o5X;sT&NDMo+vlND%5F!=MNx3hu`B)S2Ea0uiYnD?H!ONXH5+Y0#>j{=+@ zwA1VvU!!=BwMpuWCn$&m8KbOUozr#hx*oM;0%Bt>CeReA>UV(K^JQuhD$aA^+%u5D z;d07A+SW|qo)2{uKyAVV#F0&k$CIo+9^C{!RS=YKj`TrKU<)HH&rP+2(6$ewo8*d3 zE`SaL&lp}N#MqWCwP&?yUl!|}f}Dl{0%4EUuTb-*@wIq@m=)O`Hn?u_xH~#8e*L64 zfqO_{5{G6x*}Y33->d1YK*{LDRCvJF7C*GP1$*2$~Rs_I=5!-F89w z)kuPvZ8~)Q55))Zq5$Z1T7g?giv{f+I;6PQX%fUkkw%4i(Qe?_WZ&o15kSqZix&){ z7f#QTcb%`>!NqL~)U0$VYgXn4^&r5UJW#XftbygLP2`maTJZ6t)H{J@?fJ2V)N5#4h-$qoT#5>KQ!I=?h zeWZYhTau>Gq>YYRKz;T%<9yrfs2ix$v!a)Qc?}Sa>+ULGJwG)VCIJ4u)wBKV5 ztT&veCc6pNUw#~F#uRk0{X)yfVm$)i9jQ3k_XSF~R{5`o>E{Z2dIb?Cc~Ugny!kK^Xo;)A%A3a!c%L76dam; z6n08+JuTxLrn;W<#7%4`aF<(sa*E%Gbr@)n9KPacw9kBlC1@R)Q#Fg4y%UW;iVLK_ z9?Oi$5^7{s;#U78&Q*2~7kH+%C;|4Vh#VCIMw!L=;>%w@U`>a>^A~@S0kqn_O-ttm z7b8T=7Tg7qO2)q*nsZEM`1n`j5Fu~Z)-?%0m;o=iSdAosMNkd)=gNx78l>vz1Qg?@N1W5vKi{nOB=SpyZNYUpj_q}!*4FbP2XbgO8yr0I~=wHi0JQ0^0G{$-OyUHYxnDak` z0{{MRm5KY|E?2)|h{RVTUSRcsC;e7d;rb-BRn86-Pi9<@Sm_zqV7CQ(mj!M5;uBjC zX|SQJ8YbZ`m(DDcc%Uo%Q@i#N#4+t%eLn@cL3jM zX%5KbRA%>MuZ9R#D~mR) zs2ca9w_eV0gYpD3Fyst6p^j1mT(Dh9k(MuCj!AyO`&EOXiLI3lxb7a&=7S+T)+xOA>M3jkuRle~->P*L}A{d8aH!OpS@=mejG%FF&77ttr$`W7#;`rRi3 zK-%J%vP9p_>tQvLplJRB;kYTgqla2-Wg~A+*BsJTbWOCM0Mu5-NKApWIC5 zz%T?_B*%zHICy5)v2O+Tx^hO;n2z1hG1s|4gmoMQI^zOv^{%Q0d+T4QyWCe~KgZOg zkE4m*+wyP~lBpV~`&I*s^T}PU8JNd)eDvAgbm(m}fsBy}xBxFn`45l2UHR5gvGLgR z3P(b()GSvpCDsF_cQyp}5DrXO6-O6ChcyE#8LV*NXg|HO*NXq0CvC^k?D!&IxwlAItxk;q0 z7o6EBT%zJUkXr;4-Wnn!H~^fpFj$1XQ|@*KzlU4@IkEdkyoS52bn8HewdfLXIy67f zU71nE3M8ivNyb@j1ick$iafIl5(P!WW|+of4_yw1p36B-Ql)gx7oz6GmYN-~r(o}zhYniIS7bAwYgjqV zT2xqG00&W#*YFji=?Sjz)b`2?Ib!jl-~}^A=jkQ04w-sHS|p_wNplfDs*3o_o_!H% z{pw9MUl8|$leA`T$!_B9zsC(~UkuvB-9eP+ygYsO7BaA)lsVtglQe~Wclf)6h~q`s z>9kn~Q?#h001N&kYn*H#ri912JTzAdk3V}Tr}5Yul5kJy7266RKZ)^3VZxwABIphI z+{$h{eL-TS#Dk+Z;29?k-LmXxa7~Jj&N}C)=}659gx2!JqL>Op|C@-K`^%^GBBf0oXXUpZ(#+WzqgT5*=ChGpB@OZ);(99hOGgt( zpyv?X7^srnEnA-bC{Tg(0R4$a!e%ZRAMajt6jNz`9I_6fm_~NQ;{z%b%%4L7)y&@7 zWt=f=mfJ2adQQ~JM_N(gKnq@fuNSZd9wd$FHf}Uq?&ykZJHdai!oaj>XNN^_ti$V_ ztqMegCKL}Qd7HDqrN+RErouTxPt&%mO2#LeY=Erc1>gOjXW|X;xZkL9x?1NVk8nOQ z#U~jMaa!jQxip%4C5RuF1ksw-nrUFxym3~%L$f}$j0tINj6I^wZ1Uo+XXmY3TTJ%! z@85Wu36D}jZ`{u#P22w@UHYdx*>zHHEve_FuXD{jB;5eXoC_`%sj`$?P};YK4BC7p zx~%xI^1E+YWiD@gH8O?|+p#{z2}X1SiP0t z4(y;2mhQ-oT;n!WKVQb7%?;yoD*?tD8h1pfh5gh@Tjt4)61UsfUe%$FrV;Y>R}-dC zj8rppj>ht8DQD+19A>Fx^&OSbMfo>+M9$D%%l5r+aE)$OxnWQAS&lvILt)k;6AvyN zriXHy-748@xhr|@CHK@LW(>>66QINMVC1Mby?E`O=$jwamD)ZDaAL7rVS8DgQk6hJ zs_rt_Ud}R9RKJ2)84t7IQ)AD}>w?{OFg6=I|Jdes3e3`M?u%dU zZ$L%t2ovVW>*x1f5!*?xd9ZNM7Z9U=;4Gl~kZ1m{)10%2OyTDA-% zm@aVMvfxNkk1(cg%Eo;8pnDRiVRIn7!GCY8k)6k?-)&4Kl0O;X&jT`@FkNe(@TqG$ zw{?L(^kCFk`_MChA|E(zFa+gKeZP21CNU&Cku;g+2}DjI7Us<`*4Hx-*%#PuhiifmuKIe<&Dt=?UD zbmUapnQL75A{x$n@0wPcmdv6YBHqNwzC|LUMD^&Sxa~tBHu+r#BBW2Uchnyo=z4qv zpzcSQ;#WK!imV6RAXa&3uHw44N78%vHvfS%v1@nqW+EQT*eX#T9SIm6)35W|zGBiw z7m{?dKV~I;WCNq_XxD|`YU*d+kdt5%y~iJcbq|>C?Wr|5EbypIT$`Hj%l$(eO=Sz* zrr6-@i+hjBp)&$*ZB4VRwM><*L85V4ykFNMz3#j!3%7Cl!qmfRqbJKv3_dkeD1Z-?A21cNOD9>oauE19x4l_Q!9fZ^<%|dN7_L^?%|kLs%r<` zZ`UiffZWr$Sjv{Y+TEZDu~6ONf< zyf$TTm%g#>&V18`C#`ArHYVXxqAWr@=a(6cY6_7`UzKkVVmBp&;@CL~wk9o4pOFF1 z@~T43G;2I=>|Li>?_A6i6qv9Qy732h*3lC6FIVvqZkp zCWMqT=dstu(! zOM#^0(&BA7()WV94(OY8nwhQXVwyrZ#e^d6mtT5+H`?ZE66*>iLPtuD%WaA55cGwR z{O;MveqppqZ|`=-zHF>+vyrLkuGR0s1Gnn-RY-D-vX91|u{A^0?`2P;CK?-L(BX*D zTz3w*Muw${U2oNGddt;yz$|u4)ost3Q%%WTfvv7<;D%1p8#e+;^LplF740qtfEEtx z(fi@)<0CyC)_au>zTOwVbJ_ffo$vO?A$l7*qVui)Pito$Pxbotdm#}k$`Fgln5iPm zP=;j6oXD~aWnPwf%seDxGG!?9P*JhS5Hb`IB2y$p=Ak5G$dI1v+wa-udF|&s`}{iR zb@m_owO{z9xz&6xyQDZ-P5;u9)onuJwTLuk--Spo9Y+%yPq$_m!Op@)~?9lQcXb$ zX*kG8+-}6xWow*%fmwj!{L3j5u>m>G+x3~m z#Ur=-(a*d552sB9L^p3nF6rKBKY;$RM1#$bO#UUU@c0DlO98Lg`@!LrW=@cA&+p0# z$9qlyB43YnkJbK(iD7pCuvxehJ}s`Z9ix0E@p?5<+mm(XVs`p;_CR0bEo9Zf)W)*Q z)=UP7aZ8o^=wT*%BU4VIol<$FnS?|{5eF?fT<vL;^W@xt?x$W0TXeibp8LAq!MQ;*);PtGtut?h9phXj{$c_2)=S96CuzPqJpW*1 z9|o{--GbbfJQ-_g%_|rcD#!|9xwV#E4?84xQ zQ2l9H{5mzZC9-*t*W~w#n{GPkA2bG;&kY5n{ZWkEge%MWZTHSPkKKj5* z>Mgq%QT;g9u>vR~&VRB7nL(JUv)`RK`|++bYAgen{Ibb^N@B#N$)naTXn1u1E7a2< zt>_}UGsZ{mS0=PQ9cKsv1yctKgBc*KOM#5h@DREb^WK2U(bPXtIubKTw6aR~)qn)r zra3(mrB7Z7eZaJVYq-x%6mSPxt72(pb8y^J)b^TauVFgFu2l0aL&GcW|NY&?33%JI zrv59+y*Dn=+ZVM{@D6T3&w8liP}WI>Lqo~zQ60T(n{!6bTW8a3Gj#S3ya`yXhaf}2 z9%jQrN`oG6ZK;sSw3O?0Cdt&8Wqno5=UO`@7uFW7S)Hi_i8b>D72ztYJBTX5!>qd~D+T3KBNT!e>`(=6P>1r{ zF`~Y2B~uxl>5(6w0S$$C-LTDWKRK1fJ9({fUSmXy!hCL>YxcUaq*+m-G?L9IW|4C% z`>@Opc%$us)UZ)G02Md^ZH4yf#AN$enbkLGn{O$|1!0!(o|Cb_W29^&^@XnOZD4l! z2_$8%2?Y4Wy~mI`^+lbw;#9o8PT9mGF3tj@*64a?yPV*qk5Eh-uX#WMsY+YBB$40> zoUdlQsQ#LT7%Lstd?pPS{b(Udb)Bv7Y-Iq5AnJRgC954kv>R>ogeLw-Z}<`2+|Iq# z@7n&&1QwDU`7cmbGd;XW^#Evl!aObbyJCa~T=->qQL+Lj&Ru^-PloT645@GF{FVx4 zy=KG|X?=4LS#&+U`p?Wu&ExyhI4;3t!}LN2#ibA*@Hx;Xo%;^3#Y@Py4)yr0&nHXN zje?Acs1i;krhzJ}5FaH3?IB;MTNP&6brjdJ(cQ7JWzir0e3j%C2`R%&FaQIby!aS(7;ca#%$PU?23b}fvSwio5-oa)iB%)(1=q=lNA6sG7rMCx#p~&z7{i`&p+q_z3+p7V zX5qO|9*YVqXngi_h8ii0aMm6xETPM4e@Raaz0l_@j5Xw>y!;HL>Oz>B?eTEOZ<$&r z>!TO0UCQCyVRz4Qvn2Mem%1rezDu{XHqeXQnIS{%!Y;T}>@&QTtOSUz$*SyQPZD%r zHT$TZ9Vn61K*3&ZZuy*cG;t{BNifA8g|)%H#~zCSXoLa)o?p+0OT2nH-1OOpl!De1 zzv@7N_})_=^vn0qJK}IzFa1Orj@*^9Rlk7#l1!;pe-f1W7zAn)fBHl;sX8V!ln<8?HD(#JA9J}FOmgJskb zxdZ~~k?l*S;M7Sh9&I4D+80$|&rrio!;$G=>@>4Kuxn|`;T@utl$DW`zn8o?!^&uj z>4xsheL9`iRu>e?w~2l!xG2L_+l^TLCtpN32>b)`reCuD65jLb@z(qB)!o=?`6i@Y zU;>p?A&IzpK`cNRZHkyx2?1-t;Q${-0F?h|b_J}GiH3^Tf;DH9N3zyNz{vQr2czPa zY9V6vZzAMy=2P%@io6{$?@Zl0#lI{;$m%P^!AbZQfnsH<1g-zOO{hA7@3avzAp&YR zV{fP7{&ARN5FEh^L-N;7YEKxO))O^ITgemtbuWY0iP(gDJgt9-9u7w>ggB z$FD^(b+5-O9(r;PyJh`OUQsSobShdb9JZ^<&oey3E8k$oj-xMta=gS&wQ_Y#I<3j} z$WwiyQ(~rCwvLvka#CC9qg0iEI>DynF? zQe@w`7YJH0ioD69boHQ6iDo3%mDk>{GbWwof{Wn5E1I0~M--JYTCB)@94ai?d9cce z5rv^En{W;^>5uH`gY*?LxbGQ$?b&{J5aKOD{j^~vm`wtRA>t}~`YHBL^fS+s%a9pE zfex`%dPo?T1<_AKlR#;;;fSBW&yGUkE1xEKWfL%WL5Y+aW#4)=PG9Y%VWn+YKwLkM z)k|q45wslF`qEVfA@Wv^N(Twbo`4`7Xb9Z*97OG9V&X~>N$VQ;X5vl2@adMFAJ8PT zhfv(cg2G}WSL|fk(UCVO!Z@3#g%YAFC!~IKow?@2x5eds^8yh{y60&scQmF)Forf? zA+6zb>be{U!3^&o*fP(qTmbPT!7R0w$J{$aC*bBv!69*2jFNn7bCc)RP$fv$az@Yp zorTH<^{MB_KV^KK+%9Vt^*K7Z(+lIFJOtgvJwxRXN1%|tPSatw&s;kJrfh;GKIFpg zO?|zTiaNr|$T`o26sJ)LwZ-_qrd{ifwx6+)spYy3X;Fd^#tiT!{pxk~x)9+I{jIb`AuYQvh(}0Awn8Pus<(2mZ5k}|qOA*&vI2+TB|RntE6 z_E6!J=8%KNo0~RlLSt;EOT=x=d>s5C3$jvY&Q^Y zLZ1kw*H)FxgQT9M(^&cE(8Tm{oQGY>9D)&?N{$uEmdq;(H?oZwzm&REoqe==)@_*X z{tu+!G(D_p@nH=YDnr1YHbQ2d%1AYcu%#dn73kf1P1gTukr<)d=Y7s3V*ij&rDUx{z5X?JC`*vp90_Ly$B z)+xVsFL5lApws=psGpv2oThDT6IfFTS*z-me^s)u_i_cD`08_argEnKgeRP5HCcLk z-Cy>8TXZo;!N>EK-n{aEQbzxh<%6k?yMWZoCnTl=jGpqD2mY1S*P%x}ghUmr?m%Em zrPYQv>7kAz+AtJLv{G@$U$mK>!2uA9Fc6L|5go;s#Kg+aNahvnM@yYT#e;o!sS!1l z|I=;GYMmnO8?1@B1jd7DZUGC@pkG5QhnEMsl?e34N&oTwyM!f2u zUUEGppqCxMzUMdEDk1H>(~*@~v?~F-Q=k+yrv+J)&{|ScpM0iMqa_>D;ra*}L}cM8 zMbeIWJQ7ah>&6_)J9{|{4$6sm!hBzn(?y*KmW{P$pJGT0y&o!GmG1e`wvUl#P|8{H zb7Z{YyGi!v_i!f}3CEdr;>gSoD{z-mDlQ+pRRJ}A7!vUN+3~|j?6|>(ziR~SW{_{n zw*c1W7oVuEYuPVKc4fzakjn)ToOb{*kP|u~%-DE+513?D_)*D9qgZ!v0Tb|E-KF(~ z^iP#1_oI#MHTx~E!})NJ{HgaI9F|_P5rn&rhG%(p0=T7`$BY!*Dx%`Y;Pgu?)_&bi zh0Ii@1nq4JEgD^d0%Mt-2%lsEfEd+SwZT#Nfy=oS`zY%gF;uo=)o`#MA zgfyJ6e?*m>EN-#V@jM^5CEo-}uc3hyHwPM-nC>gll({I^;{pSB;gBo&bY8X&aYSG3 zKdM>v1@NLWJ4M-MI~q(ui-o5Tex+*w3WK{T(H!UHwiqu&A(!}Bm4ituZkq&u+c`0t zKHdj->$lgCFh#u$nROGtK;tw|+k^SfE0viHc|JWHEjhqRrf{^>2zut7tY3$&h`o_q zoNJQSI9YK8Qb#oPm^C)8LV4B*$v30p-mv14?6yIelkNTKvt(G2n`I#$zEE(8$b8tK z`&MgPt;iyCP=8ea^&cvdHZx7mF|wY<2Qk0vP(hBQiQ(1)hMBz&AKXWLt7cdOfLa-- zHE#YE2ewxNqx&i=q^y|zf=r6%)Ag4r_nUy5{U!G{uqrpfpTo1-v8zH!kzxe~xn^11 z2UesC{c9Kar~fkRWi<12!hgw!N$V6B$bRMhbza(i6JnKFknv*#z+spSKEO`dVWRym zzFYWvDMFYaB*uwfBT%X~0r1R9awOlZej$qLM23q(*%76p@QxM=blK4hA~*P~Z=#9( zcW7BlzJXQ5rV`7R+VOcL>Aqq5vI-Ft>vO5EkO+El+TlTYvY2~AL+kdLk$gYkv={oc z07c4a!y;~|B`6#l$(3*0NSig>@K}R;Pxq734B2Vs1nVmkraM2n6|FPGY$H*wzF{+(3^xI8}!djScLb;AEwntQJ|gRNRf}^ zWLlCP>-Mz+>_LD^KZ)8^oUcdzu|3#)YNvVY+b_xv42}#}=E*DCgE>oMXl-_j_b&gC z_3OyP=6T83f;kbbk9X@I5T~1hI4}m+7e~%+4Ic?H+?tZ$>uDGhQ}7N&Tgq;Keqas? zoW|Z3Y=L2j^Yimqp@DUMz{=6z>aBYWChh^02AVYhF7bV``I`AZ!QKBIkO08DN0W{0 z08%&h4qp5OhCp!3Sv&ZFxP-;LVM5&m7f~ZptWiu1^9z4Bh?JxQf9Wa$|A8V!7{7OQ zBG_~TMmr48=Bm!HdfhJW(fKwAe}qhOf^1O$Tivq5HIVX&k9B!`j)-*un~CWhjnEbF zUunNoDjN`_<}%z944>S754+=0JUlKBJ+zvkJ{PNS+W|B}2zoHy1&sb;#rit8 z@GIY{HM%SeaDNyV=B(P)Q^In{n+f?Uq|>6fW$d+_6KYgPi2Bl$7a z7@oeA4!Z*o%%EDC7o27|2@8LNV&{z5nV6TQlY7cJsmW=n36@|tbFzO$0+67fyz1*v zoay(t!cHmgYyLzQBa4OV&8d44 zm>4`r7UN!UZ-`F{I7tUH9{@2l0Y<-S)r-ZNue}YLyXKapsD-y3!wBZ*yMS~t9uU0T zbG`I3gcT$vpR*8sum^ACnr9HUGzD6sMo?rkcC+#ay`9jnSWc5G@ner5V2a?i16rG) z_rgzeQ6prE8~v!c?V$RGU)m2j4H=oB(d4S-D?Dg+xDXl!WQ+F(eUkbrJ!>h~fh8Rx zP$rLgFufoY@L(9e0+S_Z$eFi%%gzA@rM48HZ6dvvX1M6{qlgN{*#4yexhpF1Z2kOtV%vG z$}v|+XC*xL^R5m-SgA$8+Md;3TtxjDD@Bc1iRKVhc@Sf#hk!0-%E4hwM*MZKLfg6t zByc^wO-Q;dU_lA`D1Q9-BLUIcRZ_7hef+p$f(1LAhucDX=TS)&f@A*O8=WkKac{)n z^@dmN(_n%8*%Y9N?5`RPjm@Q}+B)z()_DlnQyoR2FbFBcvUWkzbgxMb(}ZjQ)) zapte37OEs-3bLhk;+uhRkn)0-@Ep3$CY1=A_D?P^CsGXCt3Z}Wlfb+ao2_m^>O+LP zBonG*Fx0n%Q6cjzpINo1w-_}oZt(2I>%2j9NvEcRqOSeXX_D7kDd4bYD+AuwmNGo3 z{(G;6dG*X)ArA@cgK=YYp~-mU81fcPbEiR6pd1+vEv{rB5Q;?gpPn5PY*92heCwxS zbx8dbY*s!mA~dQ_BsI)am*OCSU}ngSgYzK}E9X9i=Nt+e#;rUUos@3!JGNvQC6KQ= zde4E5pS@fF5J!v2v@JiC!;?G>Yluj&m(GK&KxnzSZ5qsb>6(#iaOx9+5SVpLY%}&x z=*<)!@|4W%9FprTEH*ry4b;LV@~h5h>Qq!FzS$oEmP86=nuWW%Wj9T5h+KdeV!OoN z_Cvd;I0y)Q(*$UlX36?(Z`zqmAOsKfU8Ll$qOLc_m3Z3OzK9$b^^QnQ7WeI4y% zDc};h#9X*z*UJ68q~pw6a{_X-!v)v>l<~Ti7Oif z=ct|Eaj^By3(my%B5Ogu{9JB0?klleyKSDMKLe3G&Pd>1+_<4ofrgtD)tEzcx)HIp zLz6xI27neHA68dk69YYy>ATtrcuj)tY=dx=n7U4N{P0131E@TL%))NsAgI#o`E-JY z9s3>-8Pt%L>D1;43uT;#7@dIPyiy~N-S`19CRuyFAt(uc!>b{tB9(;Le6`fcVP*a& zBa*}sAMf*q7tDd+E1JIof@Zy=>|F;x@WS&4%0R=60C=YERRywAXeXCPd`?F(P4J+* zsT?sj75}OkT7JMN<7r4~Je{|dh8dMjNy_ZNj(-&6+Q=1NG--~(5L@;ZmvhIRQKQNx5 z)!E3N5s2&=**4!Y|74^?M2(8gbI?2(?`DU zhLx0_bX{+{NK6-*hrANU=s%c+1^YuBWz}mqZT3*3aq0uAis#2py|gB3Hi-#t?hVir z%$kp418?=iT~W&*hKHx()1J)JZ6SS4zgwA51#1iTPu(2aDGX@xp`G+1Ld1evNuKIV>(uW$0Y<^7&g4g# zI0v#~`OWvo`TvMkUe2Sesoe@b7f>#c0B#9d)zvFPM$(VOywf< z@>a=raLJ9AH--O8Vnb(e2w|IuFc zki1N*n|vSPbBx%An4()Hi)_%8hH$BpHw?)pa`fqN*j&jn4`)f3T~rrq<$&y`320BX zXa^wb$pu!<6_4Ngn-FQw=T4e$7?##^AUmn!O=jmXc{Z$KwrCp(TWrQ-?2!J6!D7Jr zCZKtC=v_nbO|s6c(gN|$zGr?t7Y^{2e?I-6Uu{qt7OG z{;LEhNg6ZUiTh3V4VBg*7bdQ~2t+b)o z16Tf;-Qx++Y}IelVL0`o>9I_2&L3!@N39Iu*FoA0g}Ac3h1!Oc9L`J|Q3&iifIWwF zJrrsEQ$B0C8AOgHC5bxu2NGH%q?L>EE^6HBDe|)wd#8$*u3;>!_-ZZo`!-Ng zjeO}23B(TiuVA83A7J-3D>66zygAfECrzhrDW0p|-wXN~vtF24yTfZcrQOWjcXG!5 zM}O?7Hbm67%|y9&Z_Xpkd+1PEb5(kM(3U){5OZn5WnrwzBsxu(+#c5!ksM}mxS;(h zL*ILN*0aYZ1ERy|&0pavNKp<0A7@uS(qJ&wN!3r0%}x&4?BeDYuKv+x*GARjAoo_d zTwajoF$oFkyqeO5D-X5iIyB`#_L`Qn?|iSdc0HprZFXfaT9x}$XHBvl%mTFul3>oX zTIf@v`z-0t332!IsM1ZC{@OMG=(QZ;5S`8L{=#7{AWm(YI$0^9(z}WBjr=bi|OO)Ac6(m81 zxkRXcA#gv>jrga4ZL+M}-fczA!B>3Ba45u832-}`whH&yg?U=cqgk81xH%BKgY7w^ zSHO74yQi%uF`!Hc5!EV9BeM*1O>$(I^NKcTalF$m*&8{Gb zDWIpjr934uahz0q$Td;z7%rAksUbau~Yd{D}EIncmYCAO|Qm;BZH*HjnzCg;zz)Amd--y?S z->boP3ffU8Y_aB967^@5NF<3v@KS`Eew{Abt8*LT@`U$tZv*U7nq}aj*U5tZY>B3pFBnw z-!}Hu?6*()v~{S-@?<*|`95`B@J%`!1vaPW%TOwq zz)-P$8|M#anLXpvOuxRVESHrw3-VWBr)(EWKOy_D&T(=wR4nPg6^{^oDTT0~fVWmz zba+Se3tSb0jG#tKMgk+z=qzkw0wv(M`-!?RDOc1T5@5YY~ zN@YoF(M5+@9zORRB={!Se^NRQU23wZBxvWgWri!@`yPSCy#Z@sxDh2e62I8K_E2CO zL33YVu%QxxcF6xBo(+i4QNdg9SmU2QQcC9=b zQUYQ2fa;dZ(pFcs<9ygQOH&7AEwXPafe!gE#qWxfDjSTiiw?n4h(A9IXO{ zN?+z!=R9WV5X+f|%e<~KXyXAR`yvkx(nA;zKngl7AT~yeR#Ek)=mp9XOiO&0$?=M3 z>9I}69g?%p%K15tNKQmT$@gf1SB#H&U?^T`B!1RA?aSLRzex#LnS)C}X=q|K1tbqu zo4#a(`vwUj`PCW6Rq~LZMoTv>8FvM(tx2Df?Tgj+mdL%-GE_k;SDlI{jW015>N>)M z;kB%RWB8;jjCyQ>vCKPBkxvwSy}1mKi&~@n?l1qtDptzjxZPvi3`+5ZPn2=NH%$Cb zu(*ddS?I)0NgCt?GqT{!3r1>@=6C&BxX%ah^#}z%fkAuu5QASd-3s=OUbhbZKu4z+%zBkJ_{Zrdim3y0{@_A}RKRKAcc| zUm$U6MiI3&Mema1Q{uHW+V+%S^{5&dG;wkfAg?;9r^YB<;}?S1>y(e?{ zDMf9mE}40R?`_fc70LjHCy;K2q0$zq4Jw+vIyFdSO1MhJRnKA0fDJdZrf6X+pKRq~ zYw)`Nq9k7MHKp4@AF%P6*cHf?qiyG2DCnfQe)@Fu=+BJDDd%z#O=pd8VN z{8=XJb5 zY{eU{+o6a{Q^F#46UerHHEzlBg}yiK(H(GwuGME?6naI{v$xXm>&Ot7ZNj6=sYBJN zL#a1jL+$!ue1t7Mb;33_kJAkai~#Ld9q;|<@IAbFS{2nX2PpGTp79eI@P`b9a8QB7 zsU&`v_SX?hAh^XBea{QFb3_JD_==28B{nod6Oz5qG*2TVl=jT_M;>f6XiZy89#R(~ zgMhqR_YphCZS2SD2;7y#2wv2q2C+gcco}d+X0qLz^g=dj0OzC=_`Hkn%?={-NTPXa zcYh_Pf0Op>nx(|No;v(E*EK8OHER=Qp;=NGYasBV4c8cRoMc}LbAo`3*{@&W9m}#X zNqCo-(ZCE=i{w|?D{UKfv_!dvHH%sIth0q;BH9SGQPOx&h-WJ4>xmmWmtKJH)>dw@ zende6L1fO9pW6)HU#R4AD9YKe@$13EUfI*V@!xx{3PLPVQ|UPcmo-b|bU>m#5WgTlPF zT+^};Pn~Frc+{Qh6}p)oKj{0l=pHepp(duqj^F9^Li0_ztF+1F` z?g*u1E{H42r=DIOcIisgJ||Gk)M9Cp8O}(`OpWnswTodymr1@mVp(umRo@d{vMQn8 zFEkGV{nw`hq6+6qxF`!}MP7P8Vz!TdVb^RY;D6r7%VMQya!J))Kd}E1STvP9Jp&oR z6pdFyyWu&7CA@Xk1Whxix^t}cU3?p{SO}#{Lh0okXQIAW50CeZ{OVi#Vh>( ccn`}#kB`+yI!C7ak-$G{%GyfB3T8L|1GC^mGXMYp diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png index c3780540f8d006bf06b294c2e0e95e0d02d557f2..f142b42c8a6447a6a587b46311b4abc906e7ee4d 100644 GIT binary patch literal 16484 zcmdtKcRZY1_clHRL5>h2LUch8L@!|wNhE3#ExJVSqPI~(h=|_n5G{J5cM?hTHd=I| zj$X!$HvIPF`99~I=X;*t`}g~K{~2b?ecyYpz4p4+b*;69K2cR5Bc&sSKpdyvvTdL#tG40(KCPQ$}+bNZr(#>nW8-3Od5k3MEy zdYkD&^+_%#^f|>KkHP0aV>yCGL%auN#J3C@6N;E0JZ%)c`r#@bOBTs3RuS3P%nZ4= zteYL|oPOQBnJgj18OwE!mGYEzTHEet{$IC`e8uKp$ff=|rs|DP`u<@iU${`b)1 zPA32Oo4@}RX2`F=|8)iKZBQ))@5x&kV|#Ku0t#8kf4qQ8g#PO#{v`er`mpeUOOoH< z!ZjiPISz0I3+K*;bM{ioXvy?UB8mUnXrT&ZG2tEA|9*fhB%qZtNfJwq^q6+F=jVoz zK6i2|p9~-W&vE=~Sj>(DtZZ!TtgK%*2?sB9@Lsv`zbycs{DoH*a&@XdvPj{dx0oWO zfYhh8__=}E$euR0z!z{Us${H&wJK@f!K%s{HK8_i0$$4 zGv|DL^`-wg{y8mw$p5X27T`}I?u{<4i(q~5?oqSP5&o}~T4J1;16sg(918#4(fqaX z^=jt8+rPqcJ@=O>sj1oDT%t*MO?b)6)z4$l_r=YQ_KNj;H*e+_w$Y zktUi)8xvJLZ4ctOH5DhS?ReZ#t1M)6!copEeVt5xr!2ZGaVaU>a2Ptd#~WiXxNv$f zW`rm;xJ!G~BlO|q&D5tt*91OkKb!6ZGlMTwPGWszgpFXYwaT#i88PEUwS1Rg`rF*_ zZtY;*XOp=MmTfk5C43GYgNxq3e-|_9&|*-JS!JQ-)^PN`7~*@TlcxsfV`@Ba9@i@J zuXo?(%k7SP)!-m&XRNtq*=m9{lxO7GA^8}#^pe667cUp09{WSyMiTt(Q7>*~4pj?o=7@couW%21x}R71wh26A=4LIg@6W5c_{!ec@d6 z*T$UZbvzu%LUA*Z!J1FD8vbCWTl`jSYjqF)^XGG_joOG&en|VVhB9#kgB655lgg%x>nxePi&jC*6^HHC??1^&R`?XYMmlf}(dT zB{h9U7e}N#Po%`Xw@4@;OBr@ijLDE&kC^Ba!~gPKe@^^~miCm<+^k6S(kq5srNji) zF(ZdOHv^Z!2Q;@QOO+bi`E_sZ?(UX5w_lcU+ekvLo4}B3M!LK?M)5q_qObt_x}|IC zyV=xo6E`g9X^cAN+8JXNYQ`I&kX(g?Mcg@CMwgctGm;&Yy^q8I4jLBqtA;M z#S|q$i0?*-;@4g3imzz6G0EmH%SXHeUB>4Qx!1!$?~=<`q2aA7!(`Ce?P^Jp ztqGmBZ&3O0;e()$+J)5V2KVj{Z!RsR#`BoHRo0<7hL+h}XOVZ^J>H0-c3F^Qvm5lXN~#vU z=_VG5D7#60*Q%SGoRc%|18k8UnF@^6O-5hWMiBcETh*8$hJ@1Re40gCRZZJDBvfXI zAQJGQGg6|7)+^Gh%q@iPNWy&Tc|$|8#m9a`Y8IRU`^PxLMA{RXikbHej~klCRTyhA z&?7o*EC{(=nR|J5=ni$>a4@yzGw{@#+1Qqy|O_N?8^?XnhhitW!&Uv6J0n+*3u=Av5m-L{51gYMHwiC7Om z%D8^&L3C5k&uFBzJ>{#2bzHk2{G~j>S4CzK&BG&s6;4KO85vbivlQgWvV9WdqkYK) zM^nF)aMNtHO@4!k=@AS+Gi{vMzZ^r72>GbiZ@7G3=qc&JMB=aE&m``=a#3|g0iRjz z++d@gVVi9`TMT}K^8)i`iHV5As8Nmmbjo~8B~5?4wt*RbVxCH>`D%CejSQ(*_q2-j zt+-*nhw~Q)H5)3A6{+Oqx zlht8&HZY9I77$o1E=A}9$+})~`FC6>$;vT)t>iG^9z>LaVg~#s8!5LZ32qrO2 z=yC4s*b@bBd}NufW=_1+@d_O&vg}RR)o9A^VM<4POG}@>1m^1OFLTf%6wMgw!?iB- zCJVJ|l&rtX@LA&;qI%?gvFcs8$fU}7zh90@swjpG9`#iT2-Ks9s+90;1z<}=O>bVQIL17${I7`|`7&W-RhEa^W&6TL{6iV`r^cuG* zdhE_B3OST_tia=QOn#ji_*F-17Azq6560U(TE$U?BZZw`AB6Q_%4|mzBj_bqG1Go6 zBvId7xoH9-WuVW}*wR4s{fe~mb}1u}Wfb^)=)rS%o?9xK0pq9 z&i+Rk47C|cX_jC35g`J5UHKSwH&U9z>0pG_qW}0}LIpF0J;3{U^tb65{{Ni@GP@I^ zHzyODUnUYk=}K!aZ)Q=sZ&o3iyxpxlkhy}cT~|F_k6pO*s*8&iA5m;JRk$FZRZJbD z?Iss@=G&0!4V5Vh`Ic65>c!6mgsPNUimi<3HY|-YE^kgMb!(Lj-m$F7HASO|Z=NauxzDi}WRa`Yrw>`-M0e?q zEeEm#qJo8W@p6p38f$CCt!A?V^?i1~f53~?Trv@PRqbt~>zTvj&3m{ZG<4DO3yqPf z__stOUoP^4ZT|W{np7_gMOp2bM0Q%heXY4u43VQMIWX^rd^2wXik<@eS|3xxsz30D=9Xm(J3M}iUo*V6@GY+dPAeg z;5)YT=FtKZ1?RU*JlZMLUyHNUdnoVt3uHS2Eqy zb>I)cQphsj1vCtLBN^<`!$*J1$LBIzx27A0v^NlQ7LlbcOM;a&YG5&y_M%fd#b3&HDUV$$KI>%)&Zl+!Fzv~6zXv_SVaDx6LV zHCd@Ry_~Jla*zOA7&-Kzfb7!#jXJgJ1ccuZOHpL9Ip8C+(+|=5zWUDK{IFf-W>@aL zhc$ywEI=k=ZaucQ)U9Hi6E6cib@D2|;gk<@z!yrF@qBiSXiz{vAP=#E=;os`_^uSl zoIbj=In37}+5eu7y~3h5=Htg(I=j7Mv~GSD%gVIajf%X_mB0%=Df0MNQm!roWDxlL znYCux91~{?$lw+j<`l`BX-olxv_YYd>@PBU$elS1e z8kMVFrXN!JK3Bc|8lS%9G5)67V*#u`E+{4lTOqy?NKS08wA)SgSnEnQDFrea*cI6| zxFMQh-gT=V!gBOYbNaD9J_6(Dg-EBNaIqBmo5eaNTJ#k^KAW^Fzln-?v%8z89fgJ< z3}q!i-r;3Te-e%BB>)N+q(SJ-D zju*!3NS>88Y{g`?g`|>lrW552wHs!LKb34cDeahaIB_D$`s~n~va&7jH&R9?a@Neh z?mdbz*#3Fotpk%0cB#DtHsn*VAr)lZ{t_*S4FWbNtJBG0h!pYsoE+2Iai^uO$16AN zqZp;V6%W=%_>-J+v()b0d))}=KpuJDu1Py0-`*;AS+~kM*;iIu-!qrQ6(FQl^LY!o zOkCoRNHH>aReiqS`57P{eHx?UgZ&EqSxTKYxzEPS&3a>Yw-S8aF>y>jb9g%C9-oCR ze?D3EJA4t`+a7s?vkbc;^TBYo*wC(dOq5S`xI%k-W=~_Oixo4ozIFA>5q9Gq1JB|s zGN0G`m+PzvD2ORR5NGy$qR;Usi2C~x2yf^#n1_@2iWVC=XpNQ!YfWktJo`=n6>~?v z%zJ4jQdwwmg5DG~L)_G~ z^KHS&%l%c>V+p{6QkLe0w6Bhj4D4@D)TtZ74m5S@O+&BpJ^O}QszV`^mIm7yg~om< z^=Fo~oat^gtT0k>m*~{+wH>Tot+847)x&NB$&njaFKgn!0j)~W%6odQ2a{D)5>DT? z>IN=QD7zevO&u^75$< z!|9Sa`bs7%1+pHi%HI&?H*9=v$S5s}tM({k(5 zw@|9RRv0GvOjh?P>iCAkquj3e-sO4S8kCjvhaBzqwh~)+fh=+l88>eox)rR_K(zmR@CMI?@H7d5oEtH6|OWs1G{2M%wOtg~qyT6ptS(*-pj zFZ_taEQ(f4=h-Ck<+Th}*-ds;Y8!TbnqCOJ*qsmeVI8pqZxoOugk~79Zo4iv;er(lY4C}VfPKJv7X1uqhJ$+G@6+Mlmb4#1T zcS`mKbLT`(-$g_u@L%H<3`i7lQ8eh^n$EQx{7~*R!tD&5)=CVG3=fa5Il<7>9a~4s zoV)x=m}X)tddFDkIo0r)5TBR;=zmWJppty_f6k_r29NA^r9g!!|0wdQh|TaFO|g36 zy5OsBsjN2N`%NOD+_Qk(cwK0ccFvPXupy2aI>?ZK>DId-U*4ljXFb?qi}YalVG4~b z6?a?btw|!yA9r4Ul>H;T*VSrd@P|W7JmYjjs*Ue97Ng>^&^rK8-ZtP#LS5hP$>5Ez zs;hX5w5tU4zplzgn<}^o{o{stZe{vicf}Re^d7j?+=%4>bF^7^qXew)#I$scW%boe z5*w?(Y%5N8JZ1ZZ|CjFQBrkg*l{17)h+1~SLg8f7lApfeOQd0{7CDk~8_VP~pfTDg z?pB;kWR~yVKQAAWsH;HS?QHK-Vfj?YBHsK+NHO{WMY zj>F{LzPq$}pV*5HdCAGH8{=1tot+p}94DRm&iUhkOxs8iY^%lG2!;oxEi?NHnJj9v z%_}uyg^b+ZQZ*(@Ab^8(EAx~0;?$kL0=VkA*8-p_d*4Ez)hSXZ&&w}`S#xl5DwQ!x zE6XqVNn#GeB2&l5D{RW@YoYxz{M7Ys)Z?|gU-e#YCO>tIo+<&&k|{il7EDxh^swWgSzxHf~8K zi(AEH_t1T{8L~f><5qWIa6)Fu9+na#to@smL2O zc6Zxl_;n!8W9DxGA`zjM?v0zqZ`%A-e{M09%3Sj{nVuI0X>$C_13-qkWV$N4vz@6s zwk<@dH$`M=+H+r-oZcb0^ldJW2~rRR2%{H6hpD?gnYBxO3K}1Ag_e3r^U0Ezk8~bd zolfFqkWaJmmsvSgUE(~J{@49bp%FQ{cj4DX6zyy0gHeu;cs_HeBr&_L4GZ8sNuKqi z*)1oJ7F*s31gIAj2BJ-^l+_m1pV5ZdK$ho4@MYSUUUO2yj+r{g)02=#7ve!a6+33+ z-FutueDpo7xmT>1e0~&8J7`!F<}$bp9S8}Qalra5MTo|X67^rWNY*u1=Z&#Pp0{2o zcbJ7*O%x|9r%35^CGgtVE9Lu3?;bAXU2z8(x7g&lFJ&mgJ77=?1!iI%062xe8R{tg z7f|_L85k*aSsTS^oE6y$C&P|MBgi2Y;vAT*i&tz7wXD~IcC|ITLIizu!&bdg@MWeg znoA9wgPQ%mCs=pq^r1Y}_%A$jzWy)|q zGCEP^GD(El+;-iGeZ`*6c?e^S_f}m9q+_ei7?3U5R(Zf&$g_U_@t3tK2{_bJOpoU+ z?|kNF`I4WSD&$=)bw1_%46y7Y>rP6cH{Fv0_8ZUDRWwTVC63GwtR2V~R(0w}?>=*8G)A3R=Fe4XF~m}mq$h^N2nrJ^tI@^sV+x-tFN-mHZzLM9TBtx>C?Oj1i^fZKX@k07b(oU znVgf=H`bld`2lDyE_@92ub{GJEL)4tXrj+aNE!}p?vJgBc1@4$A_HfM`~6x zA0Bwc$1^%lPgI#}ergLLSE`w`7YfgYk@W3-ee28$w#S#7V0$R5h1op#_x7N0RG!;N z7D8kzkdNKF%HUTpeJcx@vV0Q5uvN z{{+aeBGfYJr7ecsnuVt55tDT%4Bbtu@58$b?Y(Oz=boD)p%D?)uX1hQ;aIh?HpuKt zuLF_#-yA#Wed{WV{9<|}RFFrT*RXy#{{)e7j|sc&$8mV*wEGesad0^IB~K-uPCfqK63oQdYX<(r6Lc{&#)`dFF= z#idyoH(ac#q+4Te$NhR(4&%(A%O&#aD}l3*9b-vW|0RWoF%r`&BkegI)0|QCZ!kCy2(QNwOP@5q_s_(I!@hhzf6as?t^A zJ7n5vYvI|{59xlbCI;W(>g+5BsHTq0rk2s|GbDfv!Flnyc>{S0#ChDW1LCmGAQLh%-yUE06Ru7h}erBoH zxNxC%`CD#-R0Iti!oc}KcLIk8Eo!F?k?&w6RMIs$KhducNN+dQXxd3xae5p8_f;%g z9DJhC#<4l={OcPD6@`_tDIt_@YSpFmVfc+yq(Lv>gm}^G1F*^##1tjl#f*RV0!TQU zwgr>@Xmi!~Jz7F!nJCol6&CdfVv>u38k-c*@;D#v&;cbTHR3-}R@Rc_c>vG?RsxyC zOf0{@+k0B@jH4$>#3G`h*ZI^JKGVc5z#=ESm?UA7pw{k%PPSMK#LOm^FLiYuCK|>7 z^*WCqzSS8};tTalyKCWvI^Ag_&kNY!D{E0L`!;Bt?>PUJ12tF(3Q58)h^#N~eXUy6 zt8_)IMhfFyRtMzPhD%bLV-j5%CQwHUkSt8aOoZKJbtjkr|HaGncj5)9I8|b-M~YI{(u#wtG#b$RgG6H|nC--a^|9{6 z-Cbn7I9=mvV(C=wm!3N373J$WBTA!{{A4f}9khHt_lP{iz|vBewAClL)jJQ$TPcct0)}V$HNt^R3N`L2OJ+3g=SnA{8n6< z%VU4AI<8(nMo0SNK zvO(*);w-fzQtHJRCBA4hgJg#YFl(-2VxJ>YGTvsPW)@UTsk;+X7l4erl&#ccv!h<* zX7_leMs2iI$0osh414|ehNxq61X+3Kz@qf`n0D&0Pl6w%+Ng2xpVce5trSo39n zM*OPGnd2$tx#s5&#oSuTlCzG1$@WX#s{_qVID(0*ZqeSgPvZ{}WC<5l^F7K~gtAi4OX^}Ib1IHf@EdvZnv3L5H?9izSkgYzq7BG8FXq!U2~fR=#QC zpy~JEvUrUNpGz4o0;1dc|gwpptZZSNWgbdv}fNr57Pm#%3fE>;)|fE1}hnkGE*W z9W#+vu256Q&(EMv?z(T>0U~`!bSdSsr0^XlyEz|Fg!Qy*i}*brPe9`1+|g;Y{|@ZL zMgdZneac^NYgQE&hrf+#*sfCumf8(c>o*74@!t0pc&@7Hzq^5NO=}L$Y z@8CwN8F4_s>;h^scXuMcm`Yj+sE8pH`X@7A$PZx@cswiV9`mFYvyZvvmWkMmcBGA0 zu)jF4mVh0*1h3nGTEj}dTW-meCTKT+m%%Um4i$?y+B$RW>;_``Z#-v~A`srusn@vg z*BeO6q!wiq@jgzwJ6?z^LAz9UsgrNqzQT1~%X4u)gq>YN2dCN%<*A8fDK8_nwp904 znEc+BuI1uIY90Etcvd76B_t(Trrgm}Nvm>?L=)6YaXgfC+ptWLSchAQsC6e@cTRC% z>5VOsIW@-5+MKLOz0*l2>Dr^bjzAh%eTh7yy@0bCvkS;A@2%)KasJ!=Wao%$iJ%TG zFz6x4&gV*xSDu-Q)Xwoml$1HP1%pS6%TZ{F-^#k4ElMDa@l`peB$ieRs8Ph(_SP{oD@)zsWK&p|m4Ih`M==AOyYce20S$upD}iYDaN zDo)a|E1I2lPj!6E1Lu?#Oy*=fP&AVV(7~4sTQ4<5*o$v`6#WTJAmKny^K>q*j9V~@rcLU zZR0145x<`KJ!UeWN~1{Cw!-HHF*+ZbU?GPo+|tH) z1#R`!p=W+Fyj&k~@wYpHiO^pmZq4hBn9|M*^m$gE^GAV3XAu8{uudxH ziC{68fi9k~*`DcRofB*3#m&TUocpZ{+w|<(Lbgg;s;G^5115?e)6@Lh=mA{7=t=$TH%qx^>wO}o zLTs+*w74^jx|A1lhY|bJ&#y55{@y${2w`%P>D`m<)h)(y$fp%~^c{(69BS#@V2@zX zPiWCYQ3~>KHid`|_f)ae+$oTk>Twy=S0*#&71<)Mey{VM!w6r>nI#aSnuoSdlz z2DtooS-dnGKmo_i95Ra zUS=5+xwDf1=94FKr2||>fG5VwX~}@B$A$XN|A65*u97g`ArjDoH}JNLO&Roi9G^T_ z|B-;L??GMKbESYBad({kHVO+51wL7-^Zs}bxB9~jUL(VI5AS!RRN3?j^ZJDw`5rw; z;5FdJ6=AlUPx=TRj1HI&(4kgQd^Yd2J7d_fu2yLmf5(yzT%X}79?{;C#by5u0zuUv zIk!HVjtKo5zvtJ7KcW2~WJK@5Nzola();vzQ)BW zU8tQn#45NQNWNI!&DX7&0oYP^$o>k*M(fuS*9UTEN~{dDWZ?QuNe~I~?W&WD(eq8$ zqLY%Y*X7!1WA2s%(J%-XeSboar&?Ya;WLjFIgvpFzWt`70sKMa7u$?MAjs*KXgD_SaVcirRhcb-|&A6tP6m)F$q>B`ZU*UFD$mNS=i(fRRpo zpytA7F)*$iFs?_?(bih7e9*M9{bP1zA65VJGR}alI(Q{0TBz-FuN`MTNnKT!O>T>q zFMC2&ZQ?Jn1&kr)CK7_HkkRMZGWf%@fuD_%^ft7pM;q>TWFqZ%8)VI za#7I-C>Kjj5m?l_yy$x@x& z*|-!3u2t-X^M6P98vCqvMDG+4mE$ul-H;Hx@C(#D7m@iHF+e_l1d>0~sl#1F&SNUQ z?gBXIK*2FmP&QIeC>TYhEYR4~=$XDNvpJg>0F&bo5; z&!avI6AZo3l(wRdo0e7HzRSHiBM&7&v?{dd)?BOG@7r(bH(xDZ2OTG|c;wJqICZ;A zv#=vmE-(ia`SK_qY40Gic)aTP#(V)`_H^IU-v>;AAv!u5*_$eI*tt1#Pt|Y6X~Cm$ zjHXcX%#aFy>4!q12`fb$Aaim@KVL6=z%q0kp7?y(y;`e?172YQ7q3Tv@bva>q)H48 zS{c&$ubzvL2e-Dz=3A+RR!~JDvD$Q^J@jX@7s-RQ0xc7*3?!?%`v$0Mn?YX*EvP6s zZLB`!(y09;Y&#$e)H62FGA5K2h2EEdt;H4W=~OyqrHQ{{ZQ}yz*@64&P-ES22a8L& zvt8CF-tDRtwZRq4@f#XTicJYIJyy_PO(4s1V!40z+M z=j)|v9{qB4gd!7}bonJ;zRd|uzR-vSA^`!!KuGhwnz14azWFA*$wn{ZkY~>pR~Ajj zW0GzaQBj&2O~mo88!u&N=cFuj5$aWRe z?E0!DPF#Wp6EjmRgSoso!|Ujs#JDprZ0|4SF|_}d91rzmwT}^b{rM&@O=s_Ji{D$2 z+bP5Yow@F$&;$WqiP~~Nf$q?5LTpU{xKwnCGs+v7YZ{f z<0sX{iX)s6M=v9IIQkLO}HgDKjx;sN1+7Pp5 zmLh+i%ANVdJG_?ZPt{kA@L%hbA^C{`7gqfp@U`Oo)zw?{+nC6Fi+9=&xJCSrpe$cB zhMtdzHBY~B@Ya*LK2h*6Ma;8&HSw~VJafsr!qJ8r9opN*MgF#^-CY&z*QQ>VvY~vH z)!3M{+qm8x_9>7k+&(~XH>E)>J~BpPj(t3eSxRSTYzqDF9k~8#rr3E7v>y|0(Mq0w z?Zb-oFX-QBf+kEWrTm0{xhdv~kcF326_4|qh^?~ufxI9B^{nin5+5YXVtvcm9ZSut z<40fa@EDX3r6i0_whtklN4yRMLC?%1)r2G=iwzm!e2gQ=WkMo*p-@$$2u3xY*QoBQ zBWL?GPL0S;@6E}|XYiTzWFht+AzUR{$H|M$6vQ;R{u)n&rz8CAvgs+TS&Dfn4hOC~ z#I@+C-9?Ny`V{6cihlf9@U(~a=#vIlyVv<}M3|7A$~leUo%5CHF@bVzekuZqr|CJ^ zx0SRN>SN~9shT7?EJJ+cUjEOipLy1^CIw5?KhyRnfHwQ8{*=k~S49p}bPPQ~q%#39 znt>v>MR;D7Fj=C(dDVn3+jyxj^d&=XY?GxC@qT?jdsnM|1MIRDLczx^oSg`x1ar@Q z_lGk`DpI^CHJ^?5z$oIh!XDnY-B0RHnyoD^Yw5%N^XFBx0+e^89!Hi|+V!TyJo^|` zpg%}@&FDw&t5;5Z?B7R+`Q2A8B|sjX(1x!~PhPJt!bgyDm3-^~f))XE3#!Y4g%zEX z1MG_&FT$iiWt+1q#PH?#0G=$8--+Uvab_MePwzl1j~l(}#j=X{QCc;rF7~PQozL`j z)QB#O7VvIt^j81&rGQ&cTI>y+b!5Eig6dt>>YlP^wqFL1E<5NnZ0hMU-pVV|!FysF zfM4#ku4MteMgZ*-5AJxnmM_w?+=RvkO!$^%XPf0-RF{Lb2u6Tt7J#cjyj5erU&`eS zF~w91Q>>j7SiE@h%q&_L4$3Mb<~UKCd4MpD)ZeM7MfDD$tQJ4BnifHW_~u1a$z+W; z<_gQsZXd5Q+KC(TtLa(=0`5ERRR;TGxNXs-%Z`;I1{X(ScivKdLo!@RKC{N5r%pSH^XFFIQm4RAqTlJ>HqJ=JvJ287 zemf*#pd!L#5YhCIEWxb*M4R!u;GJwBccklv53+?`T&{Zgnenj+{; zMWi$I&51Pm>n5#Z3vP#g0%a|U69Na!rz3kW!l<@@ip+=%z~@I83;(Y{h$%URa~X9x0%tSq4i(>~f6n7P>R z(|M)`3cw{uV=8XZ_ip2+8nZIu-FvdS;k;-`e8@V7{HvYWqaGYo=)g5JyE4c#F|p#> z>NjB~dew0{&MQA>)Z8tdM@C}O(rmqFzKd*mTr%|Fi zf^LrGP>y>{#R0DA&s{;8uS%~qO)#{4!-AGy7jc-Fn)lvKn%lSRK5R~|hMF@-F@Lt` zpJ>uJ%DhiPOGj(wEi?V1J>zB>+B?&S@TmN`KqQ7YDur8SYkFZ9U3z1!2`N3nU|oOauFUVPH| zV)ENhw@0>W!Qlk6p6HfY1vShHtVj19MqouPDt4O0;j>=O&2p! zK-fFD#a`TMQfq!6iSaNxYhGK1{n6S|cI~!)hkj*QcdHQL#%V>(iJ?Q))A9C`q=S?1 z{gD#q-tCicCWp;Yl^^eKtnap*myn5E7`WY|}&Jci_ZRaXej$M~@b@Ik( zlzK(gIeCUjkfnaOQT65o63wh*2h<*+8+cF9(D}U!7VvlRi#Kk_bgZaRk5`X1d@8pX-bn0!jM`uaEdj{gS(&2~ZoDVr81&w9Q#BQ2 z7fK27Jmoh@BqQ;6(%MJ+MJ=MB6Qur)o*y>?{qN%C=lR#&RlDVTuH5WH8U5hajdz$X zX%>oA{KiPnlc0|fr%@R(9>TOHL~*3sau03j+qXOI1>y>Pq<08=bfy};$~>9UVG;CX zct!+LFeW74Vwm8`G6+K7E)x7s`9VJ@vk{@t7F=8AmZUcgJ?~FIqS9cm8^`**oP-JP z0RjD19NeC97EGK`2BL~P=oI7+4n$RuM>AbbKUlP!0YuMpC1Kj||9pwRIw<=aHsw5j z`Qd$%ggV`iACeqY%F_Oqb8|ZUYsDpK7oKaw8I!-qUzRH2g&}TR?PP2i@d~w#rh1wv3v_i2fa1gS7 zU3`$AA=$pG`L8fyJT}(PdcyYaUSO<83#gHNTh_n@j<=-Z)DUW=M^V;I-bzQSmdR`8 z$FU4u#vnM^jI1%0;CESp#puiTx7);hbJs9z$8Zvh`Yeq=twgpS*5?;NH7nRP9*Nsd7_M8PFk#LSPQi&8F z5AepBb;ELYfk70?NqeN-n}L9zDDka76Oi&w{pm~d0YMt$?1zD)BeKM%myL_Vy7-bl zH^U8XEp(oZrw?6>;yRygP-wYKPJc_mXJdLnmvB*oKhv1le_18t_VLo=gUEIAVQ|LE z$8lUl0dK};R))E8toeo$0l`<$%6E$%UJu_&hIFV6q!9%;UUlTQ+(C#^J zVrZL$aDIc5hmw#W^4%RG+b+4+IAD!-J`4^znT(ZI)7@Kl>Xreri5aMS&|Eosxo7I0 z?{WeoGk39+&CQlmey{OScjUBCI?P9>`s^f#fOe#zMxr!-XtkJn2%J)oXC}f|y|iPv zZ+I7*{L2HRQaB&8P_7niQ$ zTeW7-haMEER&*3)u|)amWIee-E>Bw|^VYB?pISpp_Tf3a(Q9JgG=B*sq_`VtW;D`P}P*gk)vu)hso;Ogd(Qp!J02}&OvjqqEoqT|5d2YSk}t$z6G>~NIMqv zuw`4d9|)fgIzPk4DlqNck>cHU{qZCjBl(9BzCCS#6a`S`E}$GG*#Bx%=rF)5xpp1u z^3jUOjMGDIPz^ejt16n^yw=;G7>K&;MH{kyIQ zlvydNPlbe}_Z7Oolp4V7iS4G}2FuV9SRFO*Y;}3%uNd{@~XC z1gd*DH@^z!#svMYe8>`CTBStD2b0AHTB$^o06qJS)TSrZ*ZVp%DOwWLimKO2oDhXf zHeIRc(?RyxWHhxs{B3K!(TvS@#>MR_cl(VuvbDI@gZ0>z=6|(*5x>NTJ15=3gg` zyX)^;|M>z+w*9~7{hu!s|8HHw0a1M3r2C;ri)>eK2~9zKIUsJ)bf$gILqp%}Iyi9` z{6&8GTHr%}jDRI0H4PmR0Q?s_QFY%lDc`<-9|!cQnlW4a%=#*8C2Q-#|NleXd8&R7 zBn{ouCoc)&JxMJpV*zK9zyG&0$;Kp7CsUSnd9F4!G!MxC??02>nzWuP0sct<5$^v2 boZ}4`^06a1Pf_3#$m0j9_e<{?zyALKN{t$; literal 138829 zcmeEuWk8gBx37YL3?PC-w+y8;NH-EAjX^gGO2Y_@lz@PQbcoc@A`;TwDGCE9CEX>R zQujamJ?}aD-0l6a_x<{QaU)xXnde#mwSKjpU`=%;A_z6)(xpp8aOJz&mo53{krtQoNhU^^zWLh0eJE3gfG{3#-hTX_+f!|Jj?D@l|I7=>F=A zhR?72lp>C%Gt=DF^U*V3g{RgLct7a0|LIlM0_^K56DS1s(-~qPcG{Tpvy&h^dUupo zc+`*de@X*#Zxo}LUS+-Y%?PBVu`AP}6tdOL6(8A%{HNUJ4d6EZI7DxpxohbD;f+y) zp;>W=+$NsujF^XVLBb5|${$jSA*^>cc^Xgolf8ef%=C(H5;7}>UA;K&^O5_t>wFNy zrg80X!p)@WaMGjohK2-*)Y;x3uj~2-l$m%R1+G7eXL%5M@Br; zcyYGLyOiuQgm{ZbNO>KXnBLGeb!fa{?_RjXPM71ss1=1bVxxK~u=Sca=kZ~ZLqnpj z)E-)XCPqUFKZaEeveMUM$9dAn*RqqHU<^s~IY%DNhVrz0EbXOUd}mWwyqpmlNF+4E zXxnhSXtv!>(f9M!$$bsUhi}hEtWX zPjlhofvJ)nLv@}{Onr3Ew`N*f@fbWKtJJ`W(eqA|@@k>B`55)lqLoOPP@q@DB6Mg* z^&j0Mz#hxsvaQ&}5|OaB&go4kb0k7zKs6H6Y>Md4 z_j08J9_kpC&+io&q0wVM5+or{^)XSqx8Xu1$-D+4BIl(P_{Le<9-WM5G^UD z3A`h|mO@ilv-$zXBu!KB5RHBWu7fe@9LKZQ%~KI#tM7~Fqg4VUq<&ey^SZ5rmeIOQ zN0AE3{T2R(a{PW#_=g6t=19wr}x+dy=(UaEn@Rw{66x{UXVfTxaElhXXR!T~xSYt$-L zq9;?_roR7CPk~!)vdLwfcPcM0Cp}3;F1D!ilz!pAQ}1TYU9eJGNuRkgH#ty#jZRF^ zw)Cq|z$mfg9@-IH({hAUZ|?6}lZ+AOnr)r#_60qBq?cW6cDtZVJ9?!4*J?h6x8lv? z2%portqHfOfc;?;>8)u_8c-rijOh||u;Ccf2Fx)=E~N-#CP5hWom=BR7iZmNQ{E?b zW;@(QHLsfe@q*}FN7AjS?&qo#rFs8)I%9=!5doi`;36l#Nlkd-fgmyQXR9=?gN(HD z?+4jBEfxJ-dGQ6Y4F5Ia@yzhXV%H#kpu*N6Zv{h=SvpWzbIJP^Y!G zyAW@{yQP-f$ch~+t%+7ne{7B5P@r{LMiTQ>kc{&IGf|w8_s{NWh|7Wt$Sp5k$dpk z6&crK;qYT7Q;7!WVcNy16)LnN!NgmytZM3XQFz9WfSbJ*QjyY2y7Ja6kczYvd_+NX zaJo_i{R}vX*CM3P-K%y!-);?J@YWSPYsO=sJ>N-ad@xQd{ag75W$asVOTs#TVW_sT zw+IMUET$!%a|{jw3H|uuQ2Uey*QRlC2gGt8P4qHK8y*V+HKK=>C zYgte}bn6ziX$q7(HpJv?Ri|4h+utwvWTTdcL-#!tF^rm15X1DVEbH_Knv7fEPEkl@ zu={e;P1L&a)Kb&u6cx8X;1nU0G`7XEC0?Vb9_)4kzF+%m6vi)BvO@y+oW|Dcdbn$C zr{D4Z)!*>#Hdd3Hildbd4acmQ2^;V=eQ=db$56|4S7_X^ zbsjkuCeZtqFj|}YnUQ^_d)bofe7S9(-Lu%|PY2nRGUgnVlr-YgB#_PnPm{RkkhtGh zUn_mgWXKG+HtrJ|M4leaMeuO?xp@+fJ^pQz>7buK*6n^# z9129bGQ}wR%sfhg9AEl$OWv%8Nj?xZA-&V~md_&k7%5BQKYLy5Ddk_$fs7RyW1^Il za0x2?Qv`osy*v5gcO8?5ppw=l6VDBDA0JzwzV1m&iw}|`_AHN=(tH}W!hvAki+EDQ z^VgTd3*T>$JtFv#zG0bV=B#+dbHRC3|`dRIj4WT}tx;XKf0aK)CRqKQDG-%!UV8nZTN6uYAu%Pl~!@%fcX=efuF!c!) z`1i}Kp8!Bx(q~A4EwhvO&pFQqv#AU4NQdO3;_|@ z{UV^kof+>Jcre+ZjYC8%u_c3gpP?@SzHbKb0gtMp+&TDoq`&r7?%NHuEY*eO2z2D8 zdFvlhG5_q(W1<=L!yOwNRAX|;QrfmiZ6%hLNcK7y9sJVU>Rsd2*7XDD=BBG{NjIz6 zNU_;-t_#pOuG#7k)(D`poBu@m|4n?vGMfOBriuq=zNJtPjUG`FJzM|m7x*hYE`H&x zEN^q%dBfZ{+!!6{ZS`2z->UNefyy*FF_$6iQ6m_{kM=bp#-MDh9I5k1`mWqQaf=-=BW2GlCdk6oZH1d#|Nc#{nzY0^{&O3XiyK#mi}cJ1j&ts^)U^ z)GJWFH)9c6@N%-v;?`?34n8LaW+nc_QX<6{qi<~rt3zrW&;@>lWCdghdsK{kSPxI5 z#CmC;)E%zWgah#ZpO~d4K6%ICdA2{C?s2$rhpRLAudbJGIHMy#t>lu@fHHrI7%QyZ zpti4?3AAM9vVOm*`&4gIBk5N!*Ah4R@-hw)2G`D+^P+%A&L0R>s-l3}ne1JF7ogq`3--ipFqI$1Uzre|QkDxxO6V8No@F9O- za2r{Uk>_@M>*EBYc$>++y9jvIT460jdJKF6!Xq&__?UqDn#lCaCU!%lMJJsbq41Qa zi`fpSEfcT(hXc*bbjZ-hJGOZ3H(kE)DfMUNCOhBLa*|732%{0^o{kEShc3?RB@F(i zsSe6d1B~=_;$d7f-$37LyovYm)=m!(TT*=+smiO$$rrbePsBItVh~6=DNpwSzF7Ob zqK043j#e~$^qnc#G*XihJD|&o$1I$!nOxk%jhkMQkk8m%{(QTLwgRw8%i=f;8qNk- zJF`X4D&^tZ4N%U6UMB}?=aPUeI<}MPyaFvm933}1b#dVG;>?nlwBjO&q1HN#>EBrZ@2jP~Vm4s%;>tBea$Et1K(GS-y`rm-R{Khb7erzM_Ep} zKT%ZD#f1VQgly5bDImj)wc_m#nkD|$qw1wpl}FvB>b(h+w8Xfq$mR5)mXpm!hT`@} znE6mCX#cpqwL`Dt_2c!0`v@Hx&kmY)*D(-<&-{nS{wf*eNI-AVT0y1ph<)wP7S7Ty z1Jp?-u2hJ_$1mRjm?*L(aRKU$hj5@}zYOqL*5Mn&+SS)u-q@A`b{Yr@Jg4}ASt*>5 zfV;|c#{rjrcFY@aDs1Uof5G7!n`9zN9KGyr49~v$x5$WBPPiJNR0IwMdxJ!pNS3ao zIAS!Y;-3{i0*@DyidH`mi?0_qy_DgTIzO75ADa^uKb%jO4+_-ER165d!4@bDc)su4 zuzs`G+Y_3@Wzd_%kVVbsjtq13FVAY$3X_sGZhtJ6`~Lk20ksJIxG;W2nj59?q`QT) z!})S%L`xPtre)lvk1pQGb+q{VBLkdC8_lLT;VN8r6InLfhRg=Qp618Geq6+)ox-Xs zx9Ck1AIEc4>sCZ9%;Q&7j=xk+#;(Jw#%K$GZpM#mG=jH{F1Hz;_v!%inf4KoDCWgq zUsS**-RIsk9f}?L^x_x#Gzc7f8$8X9i{2EfQGLMwF?adZrf09$L6k+;ukA&tE~mB^ zpcSbUcGgXO;&OVu>v?f@*j=BvSq!G8l&H_K_o8vvC0pgYWRR_vY*& z=j0pbuUdp{=Z+3Se+5^Ual{fZt)mTZ;rmfx{lQoDvbqwo&=Ygb28U0LO@*7e%|9s|?zd*zaP9I2_=aueTw zg&mOLfjI~7-6R<~_f$rzBr6Y0N!(WV9)Pn20J-NA@7Es=jVZAHe!bW%cT$zxINcqp zDmzZujN9=`RxqbU{OHI&(WT^Kz~$nS>-1-2Rc?IE=c@eHp{XoO$`(L~^m}D-z(uYV zn}lZoA-@{(P+6a~ImRy$$Rx}hSMs2Qms)r4MZa7Nj@Qo_hL>=+3k;k1cxhMN=Tg3f zQER6@;4e9)z*5s3TkyO27=wj1G-;i`Kh#l+c|F-BG|n?X=PRngK`HiYIWuNAL%W1G zcmjc+Gs2-^_JF>1PmtDsP(xaBH2m2iuN7+kIOpyuW6A1u6KT@d(B>_;8^6p+v<}{ zY>rnh?7IOQzHjQ>&5{7?K3uVW+_S#U2P^&xTUjoI6rdb&Pk?~Ow6Zcce=9K$KSy9rl(EQXwH>r>tKgjaO zOW~q>&R$DgCt|f%Q*l)>ekMErH)IQeds%UUwK>6*_lDwWcyrf}6<8^du!@%x8T{|_ zLL_9d*qIpw-fdxo5hArbKU`8CaN;*VbSI1k>@W8-Qyshc6A7_ zb4^z#U|aE!a2*Mqk~Eh$0QaTnj&}(ex)^%!Ei>|4c132SJ=_JfWg@z5bBLBH)#fqK zPn0**Mw`;qNybf7$dY(pUfb2$(!PaDL=APnAo1@%~M={m*R(XD5-!qrK zMe;Is_ZJ|MV+dLC9L= zV!DqBg$&TEk28n-a5rWUee4fU14$0$8+b|<1-|ggAA#Zj4jNtNTI>K7nEx5r^lJqz zt3w7MF4gM0Gs2ETRN!S~`DU5$E(NVvL6-kiP?eQq1n0gu4xRBby4@}3H^sw_-o_a# zK>0>}-;sDw0|sJrzr)zg&twn(r%Lyz#@ZM0js1A34Q-UFGeTA#qPN;^Xq1gvOO!q2 z9;UA`Rx*a{V72}Z6DKtl`JAoEbox@lv9Mc&KUs9L23I0{9qWh~2#NewW{v8A@+4OXW(ESzX}i%41}bB^GG z?Ab2@eX5GK5wavr;8oMYXw_zg;K`>6{cquAmaiNu_>v;wve@voQPUGDP5&!8e)DJm z@!3qfWav2)`lNt5oz>(&>nFZZm03(ldP)iS81BmZ>@CI=Shw;fEImF{KR#3de`v*` zwNyxqz?9^x9zzPby5#;h8EqsX=aFb<=>x~`>3hW!h;h`~?cJXMrNNg>6z{U($6rwm zmtMoTJ!Vd@nV2>Md%>S2*B?v0Z;w`pjD_<*uPN=q=z)#^83h5zz`dd?rzs)dsS`q> zjM88m=GPa`DIn1?bW+eF!5^N8Qld|k=*&Xns8mo1kh+eh`ke2k1w1Uhfcdycl=NE* zA=*%_a)b~A5$UU>7S$CA`p@#vl@3!d*>jMVQ>mfJ+GJ4esSn>RC^t_qa>W;(K-@QT zg7Ot}K{XtUUbo+XwnVmlmE=kp|Iz4kF+UOuIf%H%$_FH>cxbUF@F3Cw((b+_F)o1g zX+62p+x%h{AXp7Cr7Vk3t_o$ynD=(5$(4}Lubt*PSc1FilG1IQ2_XWYN4ttm@7k7l za@NeAJQ>onQX6WnS#DA_li8c4Q>kGO@*q9@sqJs_xUmN#DbAm~yeR?MHOH-E0^(TuPYlyG;e3R+!dn!y6Dz; zVx*0VbcN}?^Mff`@{mE7FtVEhd>E#GANp`3^?r|Rx^6JZs)eSbe2HLi-GX1?9hio| z%lm}UQ*hTl+>;*fPDatBjH`t#8@FNYm5(Cl8}|lO*xE_>ZcW%E2KL^7@!ZcM^Y@@@ zzc<`FIjC3W!$1TdIsVy#*h%rVp&m(*39dYCC#H#K>{%hQzFk1WNrDE& zLd5v{+nI5HC>;hPurQpM^R_F}JkfJ_U^}42*SXn^w~?(4b@lqmy+(m~$wm%!(+OxR ziQ$ytZRoF92;|9@x*HzHb2<$4k&~4-Fs48}OTWrz^zE+Gt;2ce%~y%>ZYcmLvD1== zyk=+R|6NUsRmilG3G%i;c&-jKV~;o!YZ>@A{!6fU0injdM*B8Q|As&Lm+j^kHdT)k z`ss0q>ax1SQ#<4zE1KK9G0m#CWg{`Z73aY;M!klh`l~b`qeSr@T#+T8m8f{CiIjP5 z(yzC1;HhEbDfDECZ5y_ge(U_o*Td-;kHRdcK|-Kx{)2mJhf6uaw)STQ+}u0cR5J`g z%FpbPt27g_8(l{;{M9?=)PQ?Ny1ro~<>f1bX!b#G)r88emrrfrf_=4y(ScNU;P)f)Jjj1=YuR5=8`gUPaNqsa=s`H~)g0VmyC^QZ6B#a@6Dbq#tg409ndw z^J$a3NH%q)N(KmzdD$bYbz8nUU?pllXwv!|a7`Ub*}?wj!W+#Xhmajz`ykXr7a)fC z9HLd2?`bnRWf=cgriGIEK_F--i_KhPsTBWtSG$D%gFfiZ9w&f*P2+3zDHT=x(sCZiA=UHqNCM)w)qnKK$4yay2~`){ z!Gsuq;DmJLqIx4Lx#M09+qIRIpN!f`1ErCrqC{BpDLQhJS}SycCBcyNn#5L9%QKEk zaJI!qWAut4CV;3zVl+qOGrS~?u$Jxn^L2_^_;*=R0QgG9!8nokPk|IChPR@7kw|Xr5-4!~!0lM;CD9b|w*0f#Y=*?f0h)bx* zJngMooWoh&tPZ3?ZuH(Je|89L*VzA!CK??-j1!=myu^3wIkcNT2;@#Eo@enqzvyup zPXT)ue`#qbrz_NjC||81_uy#z!O#8==-*fT7fjaC07b{&AIC(8q;IMCR$UKfd4H$> zF(uMOzikECedCAXu7L5A-5n8Ju7;J**ZmV74ja0tsputZ{Ph;wZF3yQ`q{v} ziT@dIaTvK}(XpDcdlnd{Het zd%+6hNSvRi1guTNx$qIqQ%UtSy5ziAjQazmA)%Fx7&dYvL_g-#Qn0e{Nf|A-c}W?) zY@TB9Io+-a37q}>jLW*KR609nCbbxhTMDULI&}&ybLMS(Mp>A*JCB-xuDg5O!5gA_D zKh4C%CZ?PB<0O~Xs&Q%3QRxMR1Y+UEK71H{mz95iva3OS!R@j)+iy%gpgR>}rk_kV zL7iD^AlZXTpwebs*&SLe{5Pfx?2ch$Yi9~uyy5TK36x29n;Wb>Hbs88HGIhcg9dn+ zB5o?)|12fJQyDXwkdKl5`mOI;B|9ljFFYcozq`8=5H#=`xe3)&hN++A=RF+#yU`7}A(eN2;&vu6?^Ob{} zB1t~=dB@Woa(Z4buHZ#vy!ewZZ;P9-2%tgWxO`l{uk@g}8&v*P4LQ$LR6Zntmrr>_!;QJCG;CcEIEQXks~_?q(m8Y3 zDGWQfhhH_GK_U0{T4L4v

_+MoqV;HcRO7ABq<&l zJ^$V^4-LYY;0mP)x2#c`FJ0IG^}$52%(Q!5NY^ZiPl2)5_`c`Pa3=^OEPY_!*D>(% zAQMEdSkDAdaNDX^`$>o)>p+?#V5PXDZnDb&9cd&Tybdc{db5stfDrF?_3o?X%$cjT z1PJ5ymlm(M6C0bm2jY$KHpL`=u!OF6n?S+xZHcdoqC>yo)>^?Ts_StQ`)jw6@$De7 z?gGf4>0aY&voc2d!bQ4%f=O9_Tpayifp^kAB?a+=L8u{Me~mW)JT;=EcyzC^ZF=S$ zBrQ|LkJBD+p;NW&GgyfCRTRKy*m9Kg;6@jE0WG%Z#bZej8u1M}S}}c)vnTJZ7-%M# z%5gsj%4$)@Xw19t2IGCxf^14K)z4_qsJ@~zl_Kg&#Z&$|a?$BmRzU+dVD*3ZjT&RQ zP9upke+uy5={_Xf;B%U7drIDJy$a=P1J}xN>}f6;k+;@U8W1Yk-vZPf%F5I)Es4d) zz#F{>*d)Vp*1K!bhj6S#y#a8QXcmFD@J?h0O5cVv6#XjAs+w5p$n zkYV|RveZ(8T)MiLNX|Z#NlQ=;?El^io5&|SqO2)<5S0+$=()x@|2c)+?Zk|R#xjjg5z+sba& zICRiW)0*2J(cxGl6&)|tkp$GbIuZ>Z(>%<$))+9BDF{M9I>UQ~>(ZV*O@6VOr*Mch z`7_!1GY6NEVZIS&C^q$$wLg!#Bfa?6BBz@EHr=J(i#H@?(e(p?Ae{Ld9=?T}W@sI{Ev*uYCevVp9yLT}K%`>@C|Mf_rTJZsVixlRQ zY>D*r0zjM<8_6r8pmNheR-UWx`3_XDxBwFsiLNr_&P%k^#kO!hd@OneMeO%@h0WsH_L5CNK5;0ay9ajS|Lq6*M?i$71&q1A1%^poYEQ?7 z18B&FqhG#0g0U4~E216Xj?jlo{aPLmogS5JI2FdFGk9^Zu6N{iAhu{E!*%ErLZL3P z-PW>m4VYCKSV2dZ1FpeJb1PZunW0HD>f2Pq^4V^rP7U$of@qvq8QBK*)hzH|MR)Fz z32M?tac8xNOwi>HJ1IQ+KL5?FlJUhQ!*suo?lR&ayL3~?_$?Ys?8h?+NfP*SSXSR_ zDL&;gt5@;PS~kGIu{Wv5A+lY=gr}BGBd;kcn_nq%X13uI>!q?vCQ%3Zh77zz+dg23 z8%CE%5>Qjl*uA+k#7^z|nnYK`0pr*|t%!))bVsGwiHh5f6wkNI3sEk-mW$j|@e3f= zXBUm2G%GaR!V1~Axk8}@UE-B9{k5RtKS?}hUutdgwdXyz(fJA6*ersAT*5Xg)q%mHd)(|voQ(h~krCZ`U}sV?+y}5N4R`H&NpvY+ z75Nf@ztuxXjWC+Zzkgw{on;iM4-%>}s)(Od0F#s(-9AAAd!s>qaEUA65hk`AIvkbC z2e5f(xk;mUK}kc^^~uNCn{UdwlQ*VTT+#z!ff)2)G*34~DLEp%Ley8E^~9x4f8Dh-b*QN>Wag&+3Y+Y+~0m-R|gvl>SBCZ z{u{W^OT2Q1dDeY^plW==QJ`8uxwK&bewcnI-xAJ^6fzOv0R`?at@5k3=}Is3l0B0B zSEg}r3Wknb3A%u0eg}Dc3fcmTP#KO!W`=0CNO*45L z+r4|%V|M-`L2HqIAYOvo;D56blpPM3HeE?w;>bznw&Z_j0e0psi}4|h1G1HBsV@EB zU#h3VDjthd^Xe-6LJse7TfhF%_mUbGMGSJYaPluwt@k$B`fAFP#&;CQ>MB|ZMWUf&ET?g@XkoNC>qQKwuejK-tRn zxI`zSPd%_Oq|Glv>M>UbuJ;>^J9wS24H;~(Udgcak zy}>W-K$37}Rx8Vld;J3d7LGIwv0Ix?Aw?BQ&p|r>dxk)q)~0*jJ9~v>BTWwq!Q%6E zmG^bxodouZVV@gDdVBi>!F$p`Stt}V6TAf-hz}F8DeoOS&Z$JD@6rvvIAk|6)pGE? zn=DOkkaa;LZrFCQqxZ|oY3#*e=kfna0r|30SQq&PhH}@ufA7KWpQ1^q`2pMNAX4y| zto#dcDt3R8W(I(h=KC;#`mZh=2gewb0+$!Al-lAi;`OfzF|1kCZoBS3*F4Qo-X^y8 z@djm-1a3PKcxO)iH!+PY;1&Ru(<0HQ1}f-&=9DrOr&ciSjC*cAdlx_N9FD&1t3;3K5}-BE;`IQ9hZrTZ%WSezl0=3DFD zAV1buUlm0Eg8gIT`LBQ#6_%pm7}XRHdAY0Lo7Sk;OdWv3#7orn(NsOT5ml;SHEM~R zyohW{6RvWt3N)v6Y9qOvRwqk=9nxDx@4hJr_|wxTTsmJK+JLt$v{E?d>El#)?2z4c zAN|s%CJCXkp|DWF1X`7X_DV*CBBfrM2M3M?m!!{ax|kP*&0zRi)>g)@y=xP1#6%*B zj}1FP`!JqVxtUm)J&a?dHZWzf?>hSaX=aM<|31Y3+FND9p{_wOg=|m9lRPT<8Ql}S z!;9FgKfDGKr_V;o*H@4R0H4wS7}f`a^fqw}lCs->^d574wjJgE&k>6VHHgZGH@5te zfM+~X^qBJ%$RvMAU`*|7%==4w64i>$W8$tACA>`P`@G!zU0u)G)*wj0%@CXAPWkFW zqqtmATYhPAx1!l~M6`NJ#3Vn8zyI?L{CX2@j6;NpKC}W$LC;ij?PF;R#_$SFR8K<4 zzwT$JqrPP)(YJ+JGI0FNkqedVv#|7x?i!5348XMi8h~Kef_s&^xoZ~jwSXlaXloh$ zLn<;2_cp)#$zr7PQ?%8I)!_{X(Rh?{S>SG?O zLfGe#TAly|jv2r|@Egy5I=FoD1QlThq)#5zo>FJAj@Y#)$yVuzeXsc_B}j~Rayba= zEhgSc3_N6AxppHP61)n}>8)pCdbKW2Zn*uG2Bwf(YwJ>AS?g~ZvtX5ESJ8AQR`?p= zOO60RlCv@hT5AsA)MPiikUVJ-oIwt%3BQpgf_4@u^|_{i)Y+`zL}_1t~}Hkb?sW6 z=M2lGf<7v`5DG@{vGuyiyR%hu|G@ZoIEr?2#603p4ZcWin>M&@PWmR)t@o*m|9l|$ zOS9aC`AqZ?XIfOG;v4F?Dz&$~OnUT7GgqEw$Vl3W-hQYb0{mdeA7(}b5*n*}NmSi6`+ zErz9LC?G(UxmxCB$3qsq@(Xxzj~x)R|Pihx{``nTq?Du^&x%9ZuZg&fc5fH}uD( zIe`F33?W$bvMw*2Q&nBs+N+*O#UXOC$Ty-ma!z}#wOaEu4trYeFA^*0RbpW>Nl-z= z+j=*7@R%4c%(Gb-tcEjWjD0sIE`A_yp2IJaGJ@`<#E6J&<&#hONNg=onWQdtS8hiG2wj~z$GSW|u9)icd_nHs%^QKS9^q)GYZC-)g zUQO{TSVj>6z)?aWNxKI*M2{hF&fSyQ5)OdB7X$7Nm6|oQgq^>b1))ts%%C+Rf#zo2 z*vRMd$S8c znhnWNV}FQlx^x#a3=7q=lla@s_?DkE$tdsR`qOLaQiT4D*EJ8$Xkm#rQIT!ssvIZ9 zC8X3G;XGGQmrI?d%@|Y)b6yf@KwJbnfv!ezoM1o^@NDHKs=@0d5Nwnb@FFMu0&Oc3 z0a>qG*6%7UDi9?)9Ka#hMHMTDtWctFX>4CwGOZDLRmc&_S)y#F2kv~b3WhzK>19LC z?ul;IJ2&G{K&9RRTkm^esI3lp1CJuu(9ju98j@i9y?b*47G%-qi-lUgi(r2<{W!eZ zV_X7j6bmne$z12ERDQO*-|_#lwwEKZ1~XA+VA&0VNo}nv%(Q@20vhEiwaz_uYt)U) z!3D6b(sN)SWUd}`;ukjjS}h(n_8`k?1V=oS6uwJNU;I*^^y@BnLYpmVnFYpd^X;ud z`aRVUTght40xiLz3M|p)B$k6>(EK7Z>m7#CWF&ysj(i?jC6jhB$G0$shY>qn22@qk5 z=SuGvAFjGYyE!d2$e>4GwOl_p-~v!KDeLxUK>CtYKR1NYit=mf#)iL$&daxxKXB>o zMhruGM-jQc_j=~^-9b>5AcnW)6s(aN3aS9esp#7XB0V4Mp9z_Hfq{r`(HYLQsxIk$ zdIaM;15pY>K;|E7X}>5Z%0t*W_7^ z?RFDr4iw8F_qiVFJ&tQSXqz5!xz_f6iTaCc2`bdR=BVgfMSuI{1VpoyBzSli(nwRY zZJ*qKQ+@*n>F0-E?Q6HtIkX(ow=E`8LJ$|mjbH?d!~W#7*>{^pCCSd z1R8NZ>%|5L+q1;X!4H_3_-XcG445*S0d5@!C%?F#RB#^Ou}eF-_^xJrvV6jbSs)97F6N|mo@3-NrkLP#p$(Fz}^>W3D zBeO8eY#IUvD!nx1(P|}J!qB(qkhkq&_(zkhNw9n&n+|$Gt;RNzD z0n8B+C99rstc)x1Fn7NU1_;egm~!tPED95E>aP1DZ+=E7@I|w%<_|ry_!FhM9*2l9 z#}K2hPzP{Y$T3K%<}@*J0}I3g9n3_L1T5!Aozj6ID1I1lj7efRVwO}(CHKeso=u2~ zb)n&`iWlc+m_1p|=X{tYJYAqW5DfND_{zlq#pRRrB*@HrvT1&d|9LIi=;^`valXmf zt<#?lKDSjBooEjO^6uxdN{fT37a~UTU<^M*1+$(g<9odsY^Mnv=~ei*^ME+f7O*d3 z4LNsnVrq_!kwDzNC1&1=SW&5vAH*jntP*fq>#8okdxr(z+B7?A>sAY2eLr}MKe&$T+{ ziw|bburhzz>+?Bx(dK->0rL43AoonD$j3${M)T&${SWfk!KI+ndGx>ET{&ZH_B#1l zNxbetSlEu3(Y~{EFD-`m>+&97RBBYmCeU4F_++Z5r4%n?4-?C_++j|tJUII}bVd#2 zR%eG}uslUj>b#Ldz*Eu#OHY}7J2LUIujgw_efX%uxbk_YEs%e?tGi(-_bp{)wZgQ! zcVRgKT+K))jG*)U0mqUPSUd;>O8}^?ZI0Yz(r_?CGP;58I+&3`5F*6>;r8pR7_jaj{SmAbKGu-zDMWDh zan+$O(bdejJ(xZ6d#odaY5|-1du}TxVAn3g%UpE-RJ|D)H!18Lfdq6V2J4-6v)8lS z6xVxFRww45Xnl`=?9@yfE*+NY>UREGMz?Lo#D!2V%|a-N=Ak%mgOVZC0rB2#o;Bb3Ua&y{Lf1E8Taya^T@YgrBuNy*FapopW#*;8N3?rdV{G_2w)e-CGO1pFQ>FXC6xtp3_z4gBad>e9G(8nmx{Nc0>E>1uW+H zPDZ^bOHaiNE7*d2n6k{1SmXg8?#Vd-Yp~3jgpl}DVLLsvW+= zxK+I-Y)in;(nhQ#GB)kaA8mOZ6!Z*GaMi_B(cO>1;l!6d8SRU{tA7x&wnyx9B<~LD zF~s#v*5=;TU;Fey^4CPO-qT!yZ@~CA!KNnMS+v8JI6w(D>cS9q{_&);@ysq7VRUP? zI<4HY(H`hH^AhTKhu)+!9EPv)Phl-CX*p}EzfR}G{jt)tgU=0bBu4;6J?Fjut}{^Y zH42#^lI*yQ>^B*!(=6ULusIbziQpKFQEdcZnB49pC&``~vkyA|E(L6b5%s@t2^+0Cv;PLSQPJvdvJLZkh#vWt?CQxPx14k+UQSqfEGCtIr7j*xI32ogg&*yJQm<=1YC;Hkdj$E&xEYpxrSCZ zb+NIX8dFJVf;Qz2aA=^9RD4;CSlQ#}PNGie$Po^+o*HiDW~|-`Dw|3+$pqZLofT&| z;Jo>`48NDz#XMBhvvXYXk&N#JzUF#U+C7Eqqvo#>zOQgdQq}&40MW_3%-VbVTJM?5 zA9-oPRZ1>3RkmtpV0I`+3xQNVGkzMZBl?t*S@N?GzBgfcPffqf#YZ)toBcC;gWnwtVVS%)2_I8nl5;S~F2 z^R)N+y+0ath?4w&Q0>LG=77*-E#cC#c=T6+1o7d zjsA5Pp+|;J?J^Wey5C~Xl8=?yBR+uyEK7jRxWK@nSICd5!(1QorS$wu@TG;29QKkA z-?TCY_GOyM;petGd5l`Aua2E%GlbgjUcq62zRMu+pEGMcb8RV{k+5YEIO`;tzj1T?$Fsotl2xd6hRX6OV9HTH);jB(WZAKhbmqs zygx}*IHT4D0vHPbcmnYbV=Wa;N=0+2#vsegNt?)79Ek8P?xDp-k7q>NS{N2t2t`R0 zxKBt-ksY6^w@UJQsdw6CcLn%`Yad$VG#|cZ4)5xj`(MoX-w%By;sj6e!DgTpR`XS7 z24Cii#%{dEf~ey8j?mpCzx!YnH!79&+)K>1B>#U_ey!Cnlj>4^s(MiNNEW;23Br=J zxKx2?bU#|x9gt-hv;GZO8()TSrka(%W%Ju6U5ywkOmPg5Z_8Ksn zNH_bBh$=WVLjkI zIq)WpO$vB9f*Q!a7CWTh1?k!$hS-?3&FS&?~#QALyBUYJ68nn^)FT>>-Jhx=+ zv1+8ym#s0&b>hSd5L@{d4=(oFR{U_i)tx9adw0FGIF5`nZzzlxX{R{Po+1RMJ#Nt< z+!&dXA6tfMmaM%=xj8_WFfa%_@}|0RHj&Nh#%%GYu|KRJ0?Wp7I_U^sl@0$m3pq#% zFBOP=f6wFiKa9P3Ak^FcKW-iCj3s1W%D&6K4^v2GsSsHs`!bdgS;lB6+f*uL8&N4G z*~v1<5@9Hjb!07BBeMR^)UEFQ+}`*1y?=BkGG24e^E{Ww^YMI~)8hlJU4rkqKGj0L zMH1JkHG)plN6O*$(eNFmy&8AUiI?w@xa%tekO)tE70ey*-8ZJo_R0*IDmL4$ueWa` z`yW;GUxOQ{E+JqLGiu2Tmno8Dz)NQVfeI6V$W*|kMKCsu%E$B-)Iqh}I(dS9-p>C#1#7(XYO;ZBrS3J(LZ9*Qet!ef`)Dg=;Jw0%5Z`a5wtbN2^~(08)>M!6COG-(>47_m3Cf+~VW*d@fyfW+m$fxF_gw5hS|DEO$V3#{gN2LtN)GUj}|n-`aoh+YQF!VzJE} zXP*o%yxUQ4X3StBm0%|?HGhLYB)@*6s{UF{*G{yr;`^<$k8bt{>K25!RhkCs_}51O z{@#r(o-M;3igmKF3Nyp48EgK$q#2e;P4tJGpn0sz6k_+LNY0z-t6a^JK5?Cljbvt#7c#Os}Lx!Mgn)U;a@%D2N|uG;4G}4>DzQwpDQd4PYNC6h`?1WM?!RNuq#WAa4F!T4wYl&cp5HP1U$5jNK;TcS z+by(1O_Kl(_2iQ9N1$7B7zxVu z;Gfvg&Un*{o1uY5oU)_(Bao&OVkz#^^Y!ux7TXC`2YKiVhgknJ|HqL&`KO*h`+rvj z-%A7V$Dj$&!YD7f@QPlX89e@y?RTHzegbud2p2kBy(BaOjqy15kd{Hv=G55ve@c+^ zodiD%yEriH{=eQIB}!TdI#}_Ge0&hVdz`8TC{(|%s3*#IWY=n#`GsB{1OJEabN+|> z3r}=Tb^UV@GR;X!9igX3#Qx`R=n@1D&rR(rC|r_c!OL6$p^ER^TtOK)`Qh?5u;?S~ z2X;p&XuAde@g}%&Ql7Sfn1o3FuZ3571Qz>57;(ghde8zqN$^xK$#9}6=B1f6;e>IN zu4325SWNuJ;)X-D{{QX7yg34XW#y!W0xuRAdm)=vD|Z{rmgiI!Q|uc+Tp7Ef9F~1X6X$ zlCCI$gP#Du@a@Z~mp|-xlC_OPXLZ)RnvzOa_3!WcKcD!=H&75ZU^C=QSJU(0BsIXC zH+&~UjJ`iEC0)?Rl`;Le4YA-*qdjR3L=bKy;MD(K-ro!T;}vd#v=YlHIpH|?_m>;3 zZ8ATyB{K4>yvFQWc?kj=FLK~wENMW7XBHrdV()oE{*>ka;X}-Zg3ljR<2=nFMOX%_ zG8@|ZTIR>q2)GO~K7n(Fao#xy>3E!Yj0Yn%_i-YCl4;o#j^EW%f2}l;==6Euxl?c6 zQKuFzx8u97mEIh8f+PfUf6lK`|CdAf(|!={fX$kHZP*`i3P;jrbWc4v9{j^-2$2+a zFLo=2nvN^(tk*9y?ImAkI_@k^fKjl?kR}A3+EXQ*09Z6$7spR85V7geo9UDV)cIm| zHZR);zBU*4#1#o~s0}pa@WHSJ|94gYuoS?a9{_>R91o^i%|f^)33f;xC^Y`=olr1g z`2INKBTUJuVrC^@x~O06MH!W{=NlUl%=7PRCYZcN*s@CIx7&xYahBkveYyAYP^JByD{~IDpdEivQ=7p zc3ni%+tFIY?4WYc&i0o)T+UqmE_-zn=e6zHp{>O@bum+ut333XJexp_WOSxgR~D=? zy71tisOx_x1^irfxGz}afKxkujesy8=Y6mJJDc17;uME;r!|{91^Dh=qTq{!AOBvd z2wq--_&OGR(Vd9C9rXq*^E`dWiCbCSJgbXH#=|p%(OIxIKz2^W;Cn;~xzd zs0xz88V7GM2)WVI(w(G)I#3{L-TsI58tfPRSYy+J$X!J2^ApJAYKdC2s9bEIX(|9# z>O>OyT08y?rDEdI=8Ry?NK0p(BP#l9JwM97iwS z@P#p~&GV3S46jqe>^!agc4dN${}HSH$CCmN-b6ZEF$gz31Op-Ceig}IFH9_s{s^N$ zz``{xC!hzB!k_6Rr#Y;%wCDP)=BrKU)O_{lAmdOfCF``ldlvj{T4#5m_Q#3s6a)e${tc9`J_+}>?ww?IDt(M^1=eej z%(ZWUTSdA?J}fA7yrjD^s(j$UrHZ#F$K$4MF`RPCEVE$XYWKO+Z>lRJ={;+Z(-hA# z-YUe#t|EK{2AZOywPDm(xx{^q_N%QHi9fLDX4?PYPv-isukj(i+kx00?SPzGA4e3j zBLczG=Dmg9Blj~Xw)X}q{U;hrz{~5*dF4Hd1||L*j$W&*Sv3=ljPu z;3Pri9O_me=*59kKNd&|bi=J^hRx+kAx z@&!_IjrDKrczW%4tIw>S+|dZ2|7o*=A|$Q7IFeEhP>(eG-4glt`Ez#!ZomeK1a?b) zw?wG|BwU>l+auwBy;Z(x^yHTD2;Zl(VR3iEU$$KvUw)WH&s4MNS-JK~tZ6;`Gs}bR z?HQrfx&0JJgznR`x1=!H0Uh4)bic;ayb_nvOpY9|18O?;c09AA@&S`kdzwH5Z!O(V zU)q~k|7vXOEA-3P1wLbTwb$}ZjC`LetDgT{R(LqQSsRih6A1*K6eV0qO1?vZYlX-D z{ULtYzb7emF_0Gpv^#3|uHIn~S(Mh7Ll*x^Q2;HocZ3&=#_Xm0Qe_I(0Vyzf(9%VY zEsc*q5JEJ*0Q+D7SQu%geU?t2w7$d=O5B$1O)|L~`yIffQ|mbYTo8|&U_WrPG zySm})nK@e9vpPcJ^*vm2U&#%1+`HjfG{qdcEq zwH*3zD@Krh;fg!lfY#b&F*7}Vcr8k2W^#C#hr(L5ifeK4O9r@&D!gUArt8R+to4Xf z_;8Be!^p>Yv=TQX_S((Nq{P?9w*%)aKeuVOkYjxP(nTpui+i)iL>-6l@WQ@>Jgw3T=VjTKtEA%I0GYpt zG&6faPE&gu&AmgJT7n~^7KfA5n>pswW=OW-GIh^#W7@?~Ge^PKqAA#Ze)}IUDJ`N= z7+>3}EGlkq6&@f1ed_*#hO#nyYl?tXokwX-4!NG59xW47Yb@P9(v0rJ_ zYB#9|P7?u-BdBl>sC7HOdt%+y56IE#_L1Mt139$)ZLeOLCv&l~##C0Sz0T6+0jk8! z?Kh=z=BAsLUUVDk>%0{DudWq!Cpsv+eYXl8^?jCg)sJ9 z!`zQC4362l0`XV;$4qsrPHNnER936!<=@sG6Ls{;;4rhmGYIeGMg5q7$dz!*a42kN zGF1)wYk7(0sN@*NLK^2|Xv2?Hiod>2+LeDSI~y+Akebtd7UC8{2?e7ltpN79Qd(MS zB5moH%z*NX59BQG-NjuttNH(t)q&&LCo740)rexWkuj-uNKu<|eC zSq^I0TAg(otBa@vkjgUPD+YU}Pfog!W{h3}Nyw2$YgN61%#JuGX4}JA6hGGyVS?{p zpA4pv`7F4&){y_~nW4GAf{OO8+Sj-JxyYUaN~W3gt)(8HddlR>Us2f|p$^K9q#s+X zk6W~I5Ry>i^bgY(P2!2e;o%~cb~fgy&oLA(931y%KbJUxHW}*G4OCH)j#_#apT3nn z3}JbTI{+&hcMFR+b86r9vx7XgXL&!|%N>HMZG7!1n|uF0!0Xo;hsoDps^qsQZ4I zQ$q~3TF|W7!<5YH*JFT&llVN8FNs9B1EY`!U*;7|fKFNqAU0D+=x$8+7j|XNg_wii zARFU<;nxEax~V4@mkNDgy{p8{>h!06g>EwQj9c}4{0;(I@%1|s0&O~rT4#J~Eqq*Q zp%zwUL*yk~YLUE{XLT`7GbX||((#W9npThAVCLZd#Hi?gBFMtRqD{@8Vyv&9bod82 zE0cAHjyV)G)V4 zjjZd|sl2~@Kr{tB1X!Z4w+HcI{Qo%n-#r3Bmt==67e0F8#(}K>;N5mSI4?SyjMM^4 zQ}xU0#R#h2di(C(huNN7?ArR`*kbuEc*U;)J<{g{bQ)BU#|a!^vy)wcUsjeD`|X?D?%&_Q6*1rPDn$8=>%)EVxACz}ismv@8Ccx%SKEeNC>XhIkGsW(tu`Qv)V%W8)nbU1MTo7QIQ+|!v)E=muzKkUmxRpRY!bEALlzSLYmeZlWYQ)L%;qUqv$_|Zkp}YD z(k2;d-fXr2w&c6Fp8M!h@Kk&^28kNNk@6nR^VJTg!^1{{S{kqQWUI*vFRK4JM}pFXJk&0 z1D{;%Jyx|ZYO}+^EOhju_+2fo@~XgbBO`Zh8-Il$!(_bQqWwnQ#(}PkL)1;V_poVL z+;DzW^)$Ihl)SRahZn0sycIU)T0Y!&Z_8euc&&&sQR=%8+Ro~Nbvi_T^Cn?xTEBmQ z)(|Pr%jzO7bGfjbLxWDUt($eKm^QN&Enl*sHKQWb+kl>er|In=8kKkah;+XGHOv<>!nnKET)VT9fbiz0)FC^d+zd1iRfk7!`}GgkhF7qj zQ5y*b(b6AG7Qc9Up!K?QxvJ$;o2jopmRGJ^F*PuMdKDX%74B%U(%8ua&I@rMHg73r@g02T}iZJ5#+^!_~Zi5)}h6Kl^R zc;o&NzO}VzD%oWI%Q~w2Be}SW_|?ehPHv=dl8?pH&ibgF>1ZdUT_ZnxnvM6M0bU`p zrWnpIc6|0dukCc9oQwq}toH-%GH-D)vqwdRimI@%T6XJUgK{1u7NP_D?Nx^;SY1Lt zKW_~ieju2{$arY=Yu|_6U#I*}`=Gtw5tqY*v7=M+9;s#r1B^<>$Bvm>T0Xe+CSU85 zhJWB|Koa=$?y;jhr`g%F1xm7|s)GzlKs#9`6cE2Ov^pL<5IubOFz)&Do~i}FvPF{y zw8ea+eD?Jo5>lOTpCAR;yUJb~TFFnaw{Ji6mP;Nac{2H9zPukeGbk997`x`$OMcr( ztspilI|Wfy6}r$Nx9smC%pJ9^sV4kduoH5~_!#OsD`$nb-piS6=gp;YPJaI6)I8y- z^`~9ig;N^y`gF>ZGZXPW@sIB)_SAT?^G>vo%OtUks2{Pj;SL&$pvkTn)koTJ8;FVs znLUdudrW`pmO2DN-C#J#CC%}+?=9}}Jqq@lH}h3FQzu?Pcv6vI>S^ST@r$8Z(+smF zs7+hWl!A`ZX&=A%6f6ER(YPWkHkcB&qAB^yF|jSBlA#&1u1`jO&m{k5=>K?0dF*@4 zeO5@tJ-AROr8U1kN_^!Af?Fh+{)b%wEs0zkz%gaaje@HO zDuLFj$>3K&KB0_Ue=(*WB|9FQn3yO#qE;HV=1J;mcSQ_?>3hJL71K~QEmR@{CyXPS@s% ztgBnPiHVbiecL(SIC5D;WFTZoa7CIUZTdB8{;n5MZGuryt0p1*w3TYzrew_5g(Hnu z_HnwFopU*Nps}$rwb?~QN-rS2nWDCVm=TVC6?^rucv;B7hNX{}Qu z)!GHI!DS8QZ`0GkP0*HMTVXL_H3anNO3hSReSN(mQLuYwdpot?4tgWVGt&0TU;ZAY zCr5lF*aS$kiBKLDB5=(DtFBslzs|(Z5clh&v*GZLtR$niDiK3r3V91_YIqeC6nxV^ zkJSsfWnQp+@xp`0om0`35zM5FenhnIExmv492XezXd)6!m6!}hep{IuDD%4gWhT=H zg&et7YS|V%hz*8#cn~@BNCw@@(DCNCL1(eI$x1Xhj9sM3rlC1_Vby(Lzf6qX*3QEk z-s%tMHoQj@D=BH@b%d!7o^!sY6p$BiFv8ULfuE*despBtH$&@FlI-QJx?ZfXx`)Sm8iszyaQ zHTU%C)CO+c=!2szw;% z7?mn9Ji?QBy8cZ8jQjJd zze_W?goib7`nA9BLDjmqeSHn?O2Hnwwilym>G zD+-o*d`s5CchK;3>LG~{x9oc)v$~6+`QOz zkPB4;9=p&9+Dtwx`->vwz9XM(Yir?%6DK;4s!ou~pCAUYpy|+nFG*DLwsECLjS8q* z1=&c2kp1Z_)}K$zwv-Va%k}BFsMhXu`oQWdu_AD1RFUi%vQnjYAL;2+-=Wi1gBUy7 z8z<@Z$%~5IH+;(I<0e-hb%&ehn!}m+(t8IcAvC$J%jc9p#tKKu6J9NqMS`TJW`+L2 z+dik7XU|yOXMN8$JfeWDY~_}e>D}dVk&rX2efCU|h>HbwD%i0!&i~@f<`e04Bs!L_ zxERaH^${4m4X-{ze-Nt1$p}g5yrTK@P&zu&%D2hO7w&WWZ9IQ)*Rx(AQLYvm&4eR7 zJs+?5n4ioYQK=-{ln4?b6gf3PNYe(HqY-WtP}VjqPe7P+#=>yeMCh=a0KGhc5I3O3 z_G^JSLn-cq0!31?@j=K~^NZbG_sAtZHG|~SXIVbY4pm@b=xg<1WJ2 zuV2>~eo!J+3RPm;3(noYx}5W|sEJ(`lT_Z*iA-@|N}O4Gn_7VjtR>x~U-O z)LhO>q!`~oSaNJ%y_yRAa2Y7ovDrtR5knA~i=97DKc2|$h;>@BKbyt%>l6Kb6r%ig(Ftt zS>h8CPQB~@7}V8#>diX}Sh22*nqS3`kQ3?C-{qMslTP-Zc#CX$dBw9x@9d=r?L#7V z=kF^HJGOOMQo`Q9r&Yf57Kyl2b2g!=Xm%Ea|2qD=DTXFjHFN$7F}NWL#zR5r$vh|j z=p+BilrgC!Us*W}GA~k&OBy8;RJ~aVtMcCiocjhaEPi>sDej=KFqMzrV18kt!QsQP zL&2jkC0_LaDsUOtCyY&NIw{znsR}sXDix4~62rrr@Go356n^c|ECMAq8cI24^E9-i zoZ|$zIApH(etXY_>?l~%!U$*ZhWz!%kL9;sE3$C2_If!%`cL_Kdmr|&=Bm^2r%=Ck zO};ywW@xwynaB@~#grH1YKE~@_d6K2&14_UDPop5dXzIOEq*p%92~C-Gc*TsNw~xd zulH5zS^C|(sYp;Jh)V@xcpi7Uy5aOZ{0aK7-oxWLIdbCeK1eJQVUo-m5Wlu|psb>a;X;?|I72?i7cd;-d|jTf>~u zos2p0tQNCFN4KFPL04{3Kr}jPu5w6cjjd64m(w}@uDqlc??h|jM@5rw5ru_y{9Nkl zYS*(<^k49u=(yda6Qv{gl)=dfjx4I)`1a_Fq%3A3-48cZ#!$_q8*6HQjny?iIq|eW z?mcF9t}F3NOCaZA4Op5a*zmYy4}RI)3{!q9I1ageUr3y``c@01A{wC|qahNPd%<($ z&cl(yQf2X{P-|;rf}R(WlZ9t!aG2Qp0fe+!MzxKtEkxuy@y*7cT!8Fbt)reZOR=@h z=TM!lr>0;1b*?!*fuS;%Np*d>|F`VuUoS%qNV%$7unK`xC`(%xznrHf-QNJN2g| zw6=cli*LA|man9yRyqw)ce5658`lsXCL~3pyIcYoRNaN*qKgmRf2wE0lUJ*k)p6*M z&M22VwkX;QpHrbrWA{GF|LB$8*yYy@a(I_RPSd3xYI`+b(Oy1ZqdWhJ4Y~g-a$FAy% zJ!brk>G&4{BF$6Y(fByyIcH}UW@f@NOuNS5)Tw=S@9PB&OG?abEvUUNX$j_F+Kkpk z4&2*8qN#WfDfT&n|0VNZfbcc$>;Sy1f+McYXsRVbhA8-Of;)I=>0{Nr$zAF}6;<(P zQj*cP9MQd_f(aZ*c}^QjC`f@c$>WL-l{E-Sb-X7E3dJo=ySf$WQNUP(u+a$HpwhGX zdJJkoU)Oz1HH|lp6uyyqR(G`*C@2K|sPe=yhfP7wkjOrTPxd&3fa;!N6z}m}EDdVd0Rmq4MyV{Y=t>D)OH& zsOZ~5;GFs%TVO3AKHK14s)k!KXEnlYZ2iPR9G7Q%rqO-p*KY|DcYJQ6us!J2QyQl1 znfJ=XhCJ^ZS+su#2NfU;xTbKT6rMkiPfo_@`DQInnA=-lSv+~_n)TU)1Gy|`YPo5d zXjWFDhi!2nR~!(`fym4X&Q+GHxOYP_?~sUNZF(`V&BVlajtCdwd-v|80!&V8b}bAz z*RRzT65KpIebI=E7rh8MHN48fnnC+S;dH8{R6M*ZX&ILSD)pW%TB6Z9a;8uf7gr55 zj5U~(gEOCsH}xxKBXs7=5`h4sl|hwjg#6=zf@?Q#pyRT`=(Ep06;D%vaw^j&KM>_i z=G8kLsnbG!M*V{1Gyq)yW)dobdqcyfMfE+ZFp`r)xG?x5(-Qv~+&0ZfF2gYdxD3}$ z?iwKN*7aQ}G89}sqjBMILURnDU<+FLV*R;xga}JO|7#owiTigM`<6;bOMedfa`+)x zWiJtwX--Hx(=6z(h_-~qFZk6rw}&rYo==I2T^sa5VVU9F^LNw7zif>i1orOlYfR62 zFPBA@oLnyP^FFbqkp^^IpqiP4>Z4<`S`u{P66U}@i@+H_pt|&;oOJSwE&fguWB@qqoBlQjMKZd zJaMyGDCPNc&on&_nE^s(G`jB-zpp!;x=}8=RJjrY5{gnaDhLE%HO#7}OdiWdn!$_$ z5o_%H;a{y&?Jlr$TRn|IG^(Rea37h~vB-qkoh^l`BIYj!Nsaf^1LY&y*`~q*{z@7k zR{^*{Ic4mh^($feLymz$iI9qbLMt~)C}~#5{?hW18J1ge4$0uYu8LEJH2^7Ix?R6L zm3IN?tOdTlqxf(n!uBs`q(z4O1> z1`d$rw8ecDRik{p@Z(1CbG8|*zS!pO?(X?2vBcuQfTArl(^8}fEI31ryrVk`2GXQY zRfF@-^2(JyuQ2lk( zW-Ur>4Xl>#p49;KiBi}1^Hl|j*b{L zZ&>b4oJ>r!r$r;!Dy$irHCSBE@QBY-Zdbxxo|YuamLxQSzYG+1+@;NqvjY{K+?&0< z@1j9RY*R~$;TkNC)!VEQy1d*q1B&W-2ygWk*U*<9!;O9(KjIutkoVY8l+V148b~R0 znBpigrAkya>-;U}-JIuv&RAWj!h;i;^a$0i7aeB9f1M`65pudiTHw+R?4Ibz4U%q} z^UmhlnM$OSX>gOze*&s(-!Y(|iAInwErGVqIndYjHQeZX7I~Q@bv=@6Bh5j&K$IkO zGLBRO=HD&3*CZ|@(^<7k>S2N&MA?f72MG5eMMZ^(&7ima{hBk^Gcppvd^}XqtxN0v zCva5}65REo$6uxpFlofA9ah?eGgOsjSN$jl@`BadQVkb>!|{;^%}!ceb}FzW4;i7> zTE!04B${fWmi9Zm9QL1(m(;PRQ!<)^JEUCiJt;!Kjts<~qq7|jmjlcQyKDmsi!E{* zx@TTFkbWd0G!*o=$Yr3Oc}KOitrXz#`>Aif)#m?Re$mdcZ& z8%c{`2>@1V6->0Wcpztybn(k{&VvUKfG6JiQd`HU)TUSA{XXWx+`FpG^xdk=@R8M@TUH|-)2H4jFC6U4}!xPU3EG`{P*FM zLPbR_kr(d1$$lG*nS17^?R^4zNyYbYZ^)R_!p3rZLb5@T5__lz5_M8QrdYY;8eM;Gi(>oGEWFMs!otIr9p8=?Ilbmo6CNO}@S2;0_{X5!<{Ux+J8?oRj;FYo zcq98+ESKT+kQ*zy>Yj zX&&)Gp0zc?;!xbIcDQ`SJ&N0Mc2|$dR+0e{h4!AeKhs~?Ha{(p;uUMZy}Vj_4W)QfFTPrB0d zV`A%IN^M#|eNbc=w3@K#YSkK~t{)gVbzJ+@XE%~M$D~ARp$@W7T>9k;;LjL_OFi~w zb#z)#Lfx|GwX%H2bT+m(`_mr08P8DcGK-YE?$@#2f(^zrRaLc>3^{>|=wULs?lKYGF~C@1(1=yzHO32R96D)T%0W}*@4%o` z8nL>4rF_9WW(P#dBOXX>>q@{>&#jCnpq#GMV^9Y*I~7$v3gV-{-8W&wY$F3KQwx8OcLGP`9Lq;{(>NEOSyU@T{s ziq6YBRdK9M`Pn0s|5k9U)*72^x~{-&yC9b7&N~xj-C=(AehcZ}Q{>J1XfZV7T>rDy zdq)yB_l^c){wu(d)35T7AU1yqfJ9-PNs0twE4a`@(}JdolyKrW_=h%{>t3uZIXskQYs=g3KVLRDSPs}J#> zOEeG}ATp{OB_Q-E?j1N_La!D-1ah$G+q+v1+frgQeNtA9AW|`N1b;F^113(GhJNs3 zOWw}b^Wb;Vwjtl9;*+j?{J@3$i(vs@r{;8-t>dfs&1U%1KHvjMr=qF200mJ$?CgBd zK6IR#9yoYV0kmeO&K7`6+H8cy#IluguU@4e28rZAxew3PgoK-Z z;(W@UY3?Nh+R?Yy%jfBUsFf->vULa_pS89q`p*lLAIK8t5DHz19jnMUJhzx)R1QWdi(Ox&2 zmh!~`g((KwJBh{Ow3z5%mK3V2(eFWq5jvivij8QXcDH%KfgKBvxHLF(9h>-`u}Lf& zzt|nsay?Jj_W3z#OIsv);}rMLBtFbMS`TCYa;or`@AwzwLJHrr#Q-3*6PTl2$ZB2YsG1}xY zmzUzxoGHE9VMBuhYT~p$Xj1R9!u+wPXDWn-#GxBy+m}mPOL@=K6?Xw`P}o`xaoeWz z2%jM|m($rfA6%7v3dKB;zTesKta3nR7^kd$=D6tR&B=W=nRl*SWsr+??vqse@WF)7 zlME*%8MBwA&AB!nR~h=6b9?)7fqcMA+GnNLSHE7E{L#P0Zvm_-bdMVemgA4h_19N3 zr15Y{U3Rc$i-7b-*lN-GMb~2Egj48NuiMvnJSR(6rMw}k?pC-rdysQ)Y_I9Pxp|uQ z`K!HM#K6aXm5a?^$_BlSHJf_2FNuH=Z*a$Ar|S9#mKRlX)2_;|ahJJE4e7K?p{nlB zM24B!f=;&S-M*0v;Tfdj)rVq0kqux+d*G5E0L~#2!!voY!;4PY2&YGHT-t`)x9?t=d`_0?U4$q5D<-=YM24_>WYaF2ou1FVx~! zI{3F3iP{BAg@~%t$l#%dBmi4OPZ_Uh{feE@hExYEpTO7Htw0dDo!-6%lA7qf9S7+< zs!VQ)T)Cx+Mp7VceEi81q>bjM&=k75WtroR3|nE`cDnXHJ|LdOzy?oRg#-iwASth* z0h}QQjg8G}8lK+X=vyi@9$xXix8iBt1{xgY#erkxh^wm%K5^oNCobniTTaV4e+V!y zTr6K+v(wA?cgXL(%NOE>-Q6L6NNf?pRg_nB-(3t8eW96tpudn>ID;d2q28jZ`2=Fe|^?J8k8Bpj)*iUa1bLv zED0M+GyH9Ml!u84h&cK6TW6!=1RyHj$n>(^WKC?P*Zy0XA^e!;7JVDC8ijx_E2;1% zx)*%x`$WljR4FD}E;>tUYr0xnd*wGM69vQjD4>NWU`|eA%Btchni4JzKt+pzuB6?9 z)L&bg7euHMD(QZ?YJsUDkzVN|Np=D>VftgrLx9 zCFizsRyGArlc>ixZ^~aKf=(1pGsr^HDk?w^3%1TB$I8;F5@&QC!mJQmazDTHwyHnh#mVbKZ1Hg68flNJrOn*~Z z*|_q%7vf39qA%&(7s>Of)U%%p%F6U~J{Sa8OY447O#zv(kP(0_9#4y=t>XBJZ^K9~ z#W422T?z`glqPsxScWDwfT{q+>K{-Q&WifDt76P88Oq(6sOb9LzWFnoC(@Z$W^*e6 zTQ-qTn;S3}+fOV;XtzsBf?l0vg!a|OCKM=Is2MiHxFe!!K6xq=3FQq9E}lN#NT_Oj zl9Hx-0!J`m?xrJ}6$wDMwm=e3*4N#`H{O>{waqzv98*VIlGf=eLLhP@u`^|`IM6=! z0Qj8hz&_UDvpm8BIGL=%C#gl}&Z!}^%hV)sOCS1yiy+kYPN49Pv0|eFpY-X8lmkc ztv@nqDq&*r*HWp{IlMX5PkQ(vjo!p_xD)R3PCkE;ZTGyrEqZ+FHp^1;e%gYk%^T01 z6?|9SMJ5k6U=(rZSbLVi~$KFTuMpPQ%;& zN-t{!_U8U=3RXPlrzT&&`dYn4Snpfn;ILq~$RsmsZzMja$jryr=on@1o4z814R_2_ zOJyPeplljpC~|URG$LFERvTe030wt$=C6MG^bUuxV3%HA_QVTG(1F_*-GK)!z($kG zv8)i0ON0ShI};cq>toB40HM)t<9lAK1= z)RGd~)ALkxZ(9sGkyIJ_{t&5@wJ-6Mzq2%gqBN3|LS!|OgAq##z(OwjwmL+aete-5 z3i7{EV_74GhS>NZieDqweaC*$VHOn6@U zR%U=`Wy=Tx*h?CSWCMgwEz#s?!|bF>qOq}l-az2@I0Jt{@#xW`G@!c`{l*FFgtt3n zlJ;LV1V_mNx(|U`8Vs4z2c04{7aIM4PY1|{Qmu5f%YQJ`rHI_|BAP}8=spKX^tEoC z1c2TMfvU?(%+B`YJ#ZaHr)%oVR!R_zOI$Dd=ul4MZ{B=LP9rlcNFF!sTJ|)@2aPV( zFsc+1Z_}P6BJ(?;HXz_sDX3Zje>xA9(feL}A5!CmUG8v{$Ga&3RFuhGOR9l=-8kywEiM^D#j}0PnCM`M ziCzg1Zf%vy0W>0`BE4IH(74f|p#J@ck)18~)-y4Ik(3U}bH@SC?JBzziF%@Ph%rs7 z`^vB4_HTLJua}rxq{uuM_QhL*$OmkzW}++i*AJi~g_n8@?KWN=Ov#^T?6)uII_|44 zCr9I3O*iqTw+Ijksa~B}u;*@7RJ;~8NgKcid;9uME-0MSg=>_ak%tU4>f=ENYaC)d z*+Qzea&qR&RdJ8$t5<{8u>gl(diF@Kl*2bZ@$lhLHGMRC+*uy)TOs8Hp;Ot|*gSwA z6WC?tcUKf98^2;nBV%N4OQ+$ZZ((*uF9SPIK3!R@d67D#3 zE_S7j)P8mpr#Dh;YP`$<6sbZO4td!p6%Og(k1Flv-8cVKg|H7#V4tFQg{V4A>OLZ4Kw1izjeIFD);lvX9+B z&4rWli7D)bviVgAx>%r~&#LfA_)jjtRSX8Aq@vPT_@<$|e}A39!9xK7*c-RwuD2V% zRaL^ z##9zo2W_5N4RV*7A$pg_jkpyko-=-CysPV}#X@gJd`r>S*Jqrjrw;{#=nnNTrN7AG z()KlJ0>9^eekV(RPs$04q!7A(JAPjt{@>#_Y_oUpZO7z}jP~9Kd6gg;)-S`)GiKr2 zj8n~)uWj);>IbHogC*!y$GO2ln@fPQnrvlxz_d z_4SF-@CpwL9z!m@N~o{rcE^ewq}&{~olQu{xxupm_JEm_R=1YlplaFSF6-3|NIsR<^c38L1eRWc*ML2_3#3WWuyIO?y`Q(0I@JOzyt+QLVAMs|Fxjg6o_o%Ejs z^yq78@yySsN%;%W1LZRmUD8D%{C4W{bKemS@At(=)B~cRO7d;Q%S;fa|0KfU;PoVS z&6q8{Nh}5W3~;}Cm;5jO?p@)WQ3A!q@@t!O;Hnq0$gQ&%D64vgU1G-Tw&Xw8?=_3; zw~vqA*hmg}cg$;YKZhg~Dkja5`bu^77!GI?*lTcy%(02fg)phP%fMJed$@T);it{S z-~|xrBt~_00y`Vo`Sb7#%DjMp|K5A4?<3C77nA##{@t+cfTE&PTeqQ0z@eBA9~>EB zm`-0q=OfhIy>D*HBizq$Zi5Q3sek{4wYB`4gxKa7LMj{Qz1$w+1RB$O@-3exhPXU2 zuIS13T1cqKIP_jA8!hy*|90rWxpPE!&lm&+Br+2DvbjOWn-lj&Pi!1$&_*vIyCVfZ z2a|e_DsSIW6u*57Xv&~aX@ojKp`3TH(bukAG0xY!HBLv@exQ^6djcIMjNDd}_sytg z0IsQMJToM$w4=~lS`R{}g{|1WQwN1bf5^y#Tpzm`Lf^#KujPkAs#spFnTN~j_K(h)_TLHo zNm2tj2J^-om^ZpDSI-C#q$1a(>RZF!S=Y#$>_VIZj$CGSUz+ZGW0=C%)UX;fsll6n zw)ikqiHdsp?$8 z;}DRd=zDtIY{3vV!$by{-wnizzZl{2HcCv1D`!kdm`ixS!bzfj?;EIQ2XemeO0Gw> z*6l@RXPo!+lmy(`c+cB=vV9H|P%t&|$}pPd_d@+?Qyl+6KL#wPmHD!HY5}cpiu0Tg z8Ek@rwCweNW^b4$_{R==+(W|5)fW}zonkgaZet*`!Hbp@P=?mz=56)BnrY`Uo14Ly zTxx1#T*FF9HhD2J)C%sq+YbN&axeU4T=-$bx#O z&CJQ;hF2Ho3d%)dW5xAo?EIe(778|?XWgf?Ge19kOb@H&Ck!5N(fn4$VTs-8n6bl9 zU7M=*swq_I)C#h+!&HZVOQnB=N_IKT<0p?#Qb6yNm5I~RlBxJo-I84!yc9}2McZ~_!-mw8 z7M!QF!8NRzH_`#TGjD$Ubd#rr4R31mg|=>yR03-(vhIFaH*_*Vw9uv~=dm%JH?Ejf zsCU5ekkGwHbS#~n@#SZj#pXd4ZUlG%+eJ=*PKpQ$QUY`x;>?UHmR&6btWgD3-ZiK0 ztar70GrD+otJQZs8C!N0zI^50?*n@MYuMcZrLkX5o$2Rt{HhTDVQhFZ4uC6=IcS+= ze$S4>1aZ{-)jU_R^BVM~r4jWsZ>Apn_yH73a>?IQvTHAUkDNc85!}Vs_a^_Dl`l?Z zG)mVXa+zAzzMQeg+}vKXd0$o4#sX1qa&SIBO^L2@-QMvv=d;c@nuR>LhX?5JzOV7Y zgIu=M;BvVT&1n1>y=+wLO*p{tB&9MF>WW!el9J**J@qp>F-|ZV)`&}3;#`7L6Gliy z#gb0tuz|sW0|)d0j#UA@9JEp#pbRoEEM1#!%2c-0Ab_D~rbi`@DLm&>dqp zR#t2%VTIiYeE^LEx(AQ<)XcoH8fTK7&NglY@9hg!Nxe4|Pa)#$>Fb=eE?O)Uk|7I@#5p?`l=8?kSF2lliS$NVw z*Sgiy!p~NFWRvk|==LH1IFe0lCcsZ1C>w9f(L}CE5qk{#JglX`kZzA53%L1l;`&sF zf(EDzPsvKjweC{VU`Ghi2dW;~4RTF)ej&LGdseL9r>;)zi`O6&GH;nVAh8$@%cSS}(QMM0U9_k1C8#Wpbtody}r|TCV)9+fw70RD#)YBO`p` z(Hrt}uNALdPo+9IBp3FPvTNidE}MQhLbb@_)ZFAkH3Lu{wom_DePON$3`@RQsIQ

e;0%9Z9^Eno$3guT4q60NOuW86HmR#|hfWblv=M(BwI(HR!d1 z*s|QW>OQCZFtg3e__NuUV#+{g6iCYAPpCc$^z@`KKIT-p<(v3zoaX-{>?-4;-qtSN z-5rwBAl(g0NP{#Yf=GuTAu|l2NGT!>gQ#>#_YevyDc#)-O2@l7eZ2R*emg%8U;cac zequdqt;alIHWVu^rK3SusH|-FJX7h4c_8BXp2k64edn8#?}#iZC!egugxgUGiFohv zNlR=j(tNdhEECMo6q}1XekWLl2T$@iASArirmR`_4t7HbSwO(d)5s7D6vF0aw}D|L zAb?66%-d)sCPl3iex)uB$dI*R7@X$>Bw^~BAxetm9;ta;@EYpc*8(B+*=I=)9CVb( z_73T=mDC}MSA75D8no;8lvR+Yu<%DVdl@D0=FME?m)8l?x{A=~1HOGD($j%FQGB7mU z%5fbV+8W+!oJ>nYYs1H-sAb8J92`s}Zi5nFd)Ink-6p>%OoAIX3b3_emGwvhSP`~m z&8Fsf55dg%$rJgz*S@>E_hMqSO!Xr9Kdw1BjGM7$W6g|-2v#Z%Z+MS!0)7}49=t~n zUV>sftC9i;E6mv5WDO!ZLgx6@K)7w6 z^g&IqSgJVQL0FQ-rdZ3JU@6r3usF37Xr>9F>k0~%sGFf61u-(Bp<%oky{nM+8BO1o zr9hN6z)KSCmbU)BtZ>*@!}R$i>cZ3lexPF3yas0BOtHHj>1DYXOSP?#Ln~dU~0e% z)6KHRB@D-hCy_my4*|hJ?_(d&2ldZyX12%H#314TT*V9`;sSG|pjpN=EMW7SA^GYH@ zrc8L#id|cZH!j(G^Zd7Y^L4U>*NQYWA82TFc&6_+xw9}K<3(q3#KylvqiK1x+48hp zm?u$=v6U4MiIW*4We}&qk`UI6l+~AWR-apQ2U}3xSK-Oh@^ZHHmlKlLeJw-)h{3|a z37(wQ8KY;#v#BzT?+tEhk~=#)kIxts5k~MRprznHQDs4a1zUTH_xAQePCls$e-$Ob zJPQc4!NY=7)KGg@ROA#Dsu`c6-9%Er)>1YD<5sbb{yt&;L;|n<|?_mQUD+akfKwq-~^xm{7 zS75pVG)~Eh+Fv9s$WX$0G#<+r5_>M4Vz){txagEzIcnNq*2|H|R>iobX{}nr7+}{El|89X{Ji zNL=d4!ERCr`ljigVhsXdmmv8-3IK~c@bifuf%$_t&a}L&%qgY?Mk08b{nwGP?<~}u z)dRUYby2K9NC@&5F7Dk~v1vFHAHk31G|cw5H{~62#_DzSQ9CkfHk^Q_WTu1ohx?qe z_X|ktN}v3#2pZp=A7Hllp~Dl~)r;MYDYNU7>QVg%^h|zP=!;J%D=aO&u|m|LpFMTu z=A}pGNoOyAh^e3LX>DaPq& z5(DAs31a{pjpjZZhwV^jl4Y8nJprE$7PX;>h=Bgdp~p)3HHnZZ~JPdt35nnU8dl}gRfwg(Oxpi zZ_~MhK^5qAbO9&)a-S#sNAPnvE^avUxp?GuQ_L|Gdi2>Y!KS(Xu{!X*5X1XMjadZh z;P3j#$3AE2GKF!cJwXueqMea@`uh5%ZnKI8#>PGmG60kF54f@TA}w1(-u!PJ$A3py zd=(&241V~2>|bpdd>ThxDr5p_bfN%^Ce!zP^Hipmud37DX!*0XLC(gbyCS_aC!6cH zWwGZ0#}~{SY{tqTSeE4%=If*2uiDvlybfBL43aDHcsIP%it4WmFVMsmMr%4`cyqAz z@$vq$ZD*pOWvb3F0k0NeyrH45>$L2Gc6#IztqVkHjIyO=fc~a`Fx~?&?_^a6%vcdR zxgreOa+P2b06Ecpibn4iM+LI&R^rWa9q|}jq2{A*+NS}lf(5A_bhi3DB_=;c;(Ra& zRMNxq(DQBRMF_$IPX$iS58aCf^MplGeJ+lv*xP5p7h%Legc)v@=+f@>&|=?yY_0xO zp#_h`ab<0V^QxscR;l@`KKbi({-8_$@wiuNz`#L9Y=Pmg;Ed=ck4<5)P$KluFIj*1 zxG0pR91;@34!U}%0`CrBvE85WW!ag5A!H7#GuEA}m@m4-O2O=*t-am9E3>591Y7vt z&|s#C%T(jGto7c#t3LJM4Mdnc;5%`P&zADuGg1?QAX(s5)F7T&L~oi*!`kZx-Yd}1 zDvW-6=cX>6ogdWr;e%-k?ZT(|EHx;L8d7Pjb!!MV&~~UA}_mN&Wj#1ePW z@Q8^a!kP}y$Rc+)z%Pc&VX5nU5&0vxbpcNe?~xC78dV2Ac~{-;L&<4((#RP$^$>&ck>I6oI!Dxc& z?K5knC}8DbU|=){3p|YlTi8nqtq57!yf1G|4!o@td;2ao6XOm6BZkloD8N8-^#_q+ zfynOtVqeza5(YMJvZg?N6Rtv!bZ~w)V_U?#`ynA~JDX2X51!Bm2ljF6)GXW*XV-#G zPc=L}J$Y#ER66tRLBHEp+q0eh-3RdrIbSL~D*$P0_P06P;`_lKR`VHCNAuV=!8HL**> z9(cyemyz&Xgqycy9CBOs#$0Zd+BFUvzBPM(s0bIuN#N=1Vdssb)%wTPP8R{1fP%*i zg>Lpp3J=K4z=!?kHmV76bP)Y0KGXP4V*|Crbz3M5emU)GH~&B%EG#BB10O&!FsN&_ zI`Dtd8baE^AZADWIxuSf6V>FL@kTB@&veFm<9rIMWH4i@fAU!z+RVZvW`xOS5%HeZ z742gCazb14a>N$PZ%4tr+JX2}3_UI*BV#cd%|glsppD%z4sU@oS@m7co)NS4%0UXXv1$*|qH z{5*!ReO6~g+TilY2%brdZ1v>X9gqg+Y+BtGCu*qpPFFjz2p$oN`jMg)7{Y#+NX$RjT>+WP!De+bt+z<2i-Ka4}}OFG}_K!O)Ka zqZQXWd=`+PDS1poMphgE!6oWNTuMF~4Vcv$XeWV@q@G^AAUQ+-IGDA^F2yGH$hNK| z({#!lnupxNMIh0Mrr@jC*&S^FEKoZ+B+Tl9gy7g*!z>~@tepLG(~ZUH=j^09#+V&q z@0J&kLPO6VPnFDhperO3(qHv7ZpY-f6aEP%e8s`7YQ z$sY5}(hu8yNNnci%{aH?vt#v$XVAuc8$4{z(9jA#%M<&^?CKgu96S?fhx&2rlw=^b zd=%|)R{sm879hX$D<{0|)X41&QZ~Y-l>P! zvK_T_WK?%invPGWcW3M~kb7j7r~Izq2M6)8T)S25i4K^Ibb@7u{0wv>^d>AxX;1H6M@{V+nEL6X#?}K?>U?XycRg8 zd4}@l=7&DMwY-~;5Kcxg{E7-k;J#ws@a)c1iX?gM2a+S{b5_1*CunjF=)< zK-%hFP)-J@#ZFBp{?_U zfujKXCKmI(>8j5{RQ_ zV`6A1EO_qjMt6^z``v4rF|s(yYN&n<`@?LrfP>J%-t;g_jhh*BvQg&g=`#1x;gROq za)W9l1L}%5;y3_*>V%VO`+leVrN@~uZe z-V)f*mY~%9N1*jUVb@pNnKfm`dQ4A?Zf*k4Yh;+MnkE2>@SQK*Y4`K|kL}RTk9(@^ zcJD^UJO^bbO^x9xQq^7r4qaELa$_^(+m72zwjBD)ml!mhOEG_P0emUwy4ldWGcaGq z5!c!isxB@tT^A%SeZ)+ckZ8-#VI!KNt7jT9iAexwx{l3DD1)Y%h=hh_J{mWQ*TFs* zQf>-w8YHSs0jP&?wsy;W)Nm=@_|6W!O5zPlEF6sFWXOQ9%+#3xR{M8cou)HwllR@q zJ93xLu8)rT-rF)SNR}XFp6qH!;4==asq$Hdz@+T~Q|^SLL;}503Sm%+W#50k^#2U4c=lJ6js4N(v47;W2@Uxz-@w8M!UG$uLsM#dDP=U- zks8wJqtPD7uoY(G`DV1?;IPtV8!46lcTN{=O=S~xta^;q?vjwl^9+a;SYr-+VB=CnXru#clZu&TT zRPBdhj9V!wA7wQ%X3)74Yd1%M zV&FF}hdn+f0gwap@^;#qE~Q+6NZXQu0hJV@he`m%!fpZx2+VVebi>;Lm&c0W?K|%R z_x|_YO$!`~%c^S3=Xw3h4RR4&p-;Kafe=1`4$3Oqf4HNnh zopIw*Ypb(M73ct^&(^KxMQYX?&}c|V`496X{K!tc*9B-1Kg#U6DWfz(!J(w zgHg=OO?p4vk19+?8{Z*Q*ADYBO(tkB8CtfdO)sXV@Q(gaI3x~#azVVN32ZI=_H<>8uva?Y=4!;MZ$n#A#UHDlaIE}BXMV44} zY|r)u0SsWKlUn)goQ-Gr-E18pji6l~`NaiRTY2K!i44LeWvUkc(|XzGS_ejX!a|KR7c0h_z{M{r~}wq^$vx3 z)Zm`q=o#Ugx=;HA<<1@XTR1Jin$FyY`6US{F*UK^JvyA{5pHkbNOxFN;TP*x;Xe+> zkqZyL{J0sPeiksZq6-kVoZ>2U+J$|=KuID>%ntO=9tDA+;ZwIhyQ(N4f8TBl9i^0O zIW)RI|A~!4Sru6*^m(Z1+s)qjENA2+Jx>`^#uMZKLi*;XX;QnBcgoxjy@#0}mE;MV zKP+@aDBw#7%=C`?U|7iwpozL-yghj_#>yI-JeF^G>-W~1>S^Vbq2KN&TCCS_654+q z&fj?2U%4Iuzp_N*+@SkoPWt7WvQaCND)sQ4m!58d+gyS_9qv8Y_b z14^#PX~|%s2fQFiKa{!8Z;WDL;{+cvS$t1Pi-Sc136G@G`AfFnLSJP!2z>{euqUUF z-buFJD>TaOompL#V5Q@sz+GEke-WP%(_r5XU(L<7K3)>5BNXn4SgbSKf~O~7rb<7^ zA7Yvw)w5%houW8N68=o#wQ@Tyf{2a=3gA9ovtziA?0q{yOz9BV^Hus(B0gePWIx+wli5IzsX|P_m|gF_KJ0iDa@ew zcQ(Gl*A(RQ#7DyEYK{B_Xij^t6S|W_{VjcwQ)p>z&YLdFCPy0@9vp6mx0m(Yt<2_F zYHw%Zwp{Q4boG7bNPAOnC9;l#mLOe#>F43OOYxn=0;>~3Zb)0q}Bs?LtEyB*3O7Po|p?+`{i#zGrs|N`d#^sVm$PX*7(<1{pZ6ED+DM}>%oBM>_4NYn;>!x+^BHR zt-_J8U~lFwN1?4`)^;7?JK&{slroJ3;*@3aS=QEO)ohs!Dg_&>HE0a62nfQovuSs{ z2ZjbgV4WBof z=)9H|XUz|z#D#0~pX2;xAqM)f0!pf3g&s;us59#i*MVU%a2qm{SCrMD(ds#M&Iw;? z!}e`D73=&ONEmaOga7O%1sfytKLx-W75^EBZQ7PML;?~>vpCT6U%QR1wU7)zXc zsd6#J=NtApPiBy*7P`O8&O*$qapf;taGz>xe`-1Mjf{vi;1b4Dt@B-d2|}oYXqLyE z@=TIFU1EV=I5|Mg*jV9m_I?}vSfs0!58Y*D z3#4@3DQ#fL(QPG`;&O!M*}%&?4z-6;J72#vzr8KnOlVx#G934EW_@wd(vYTT(U#FI zc3TxYszeuIf$rfU8BV!S_a-k-E&s*u<>CwuFCQNPW6+u4{hM|)qQ83T$k|{}G2?ZY z;NO82FA-u685j9(ZMCVu_sPz)8et~oGdEoKXtqVH5gL}_g7PU!pG(*Q2L~RsCBaHY zaaT7$S}_-ec_!2|*l9c$R3V44sO6@p(VNYte$|k^Q4J92$6v zwEGeOsWfjLgAJ;&aM$l#VxS5qQSY4XSZI!%`kXDSicSQ?Q9rq;1YApen);oW{IcAs z&%eb_2md%@Q+An-X5?U-jc!wJ3kk)q+4rW_2Bv{&v#6-lZY!fw5yc+l(5@6HaP7Tc z=0purQr2kUA7QlbA?BV6uwv%AT6zzqdujU%Bo1l=Dy7yE=}mLtf99{ST*#m!u5`!H z#Ki7M<2TqxAx-y_#tkdrhPn`jL1$G@)rCumqW_*V?Sao$NIUR5EozdxA43hBnX&eL z{P;&8T$W)Jba+`wNmuTwD*5E^w*v`dZ;?2)-iGI5gNk#S(u(Qsw5++uV+6?F0*5iOBt+f+#J8#N3`X=6XcQhom<4_{uu8i)-p>Ct*Q5_`LRlY1r4{x1zPAvE_{tw- zSA0bwfaO;X<{JZZ>nWWJ+OVi!l%P5Y34j!fx5qd9dj_|~#pJ_kj7o4YNWW0(bib^w zsPp>1s2Pv%NtBoyrvOnMDT%d3Y0D$%4W#o=Q9D7KBCOFgp&^M>Az@(zU(yD-^Yh$z zZjdh1((3Z~$Rw=ciA}AL5k6X*L!smcZ$5Uij@bXCTrbULpyLIf>}sP{adiRSDIvWg z*b9(TcW5aeOuKin?Hbo>tQEyO;I>AlV}bAMKQ4Qy@frz)9BrRXT~o7689y}3j6ldp zc~!|pDMrBNL-wQ7@x~|I+z|Vqt>;08{GksvVLLLfp)WFmqB8*6cfoQUyO!BVH>*8c z8HK>HTH&CvQAYL^|652u`fGm7Z{H-tM$2MsTRr+coo@|7ah@}3E1EoD$A?{`H)9+qwVxr)5ArOc{`YX>cey;1yt7ifCK7Pz}92GJ# zEp z-Fpf}5@jdfkoi=*DZu0|i!ooOxF|O_$U)n?Clh^lm>AL}NUJn6qIX$T#qZN^O+EiD zL*a>6pHh2oABTsHwP-tjy~OwK*BN0B_wu$jg;h++oAyR$x?@Ck$j)|f=9}mS8L7II(NFM#LiN;Vd;g{#zf@SYiYTTqHC21@zEoJ0AHZ<_My2M|aE3WZk6x7I(F_wqWlt*UIX9j8DGIHNF%k&V1GHw+ss7xn9C37-ZJ`+G_({ZH@T4FWN6Eh*lxwpvwS_-fH( zQBpw@b<`EkI2Sr#koe?KD$%$Q#Y@uRTmS6&YIb65eCPuxG?9vtu+T_qhMN;`2m3lT z%^h4+9~hAR?q!AwWXUTiC^a>p<5WD{XkMw8W@Tf)w&X}TR)_F9l|s)Sj2N(}+p$wZ z?W7e&B)>xQ^*^i{--=1t=D>D}e}!bz5c?llU9x)(<4*X zY#VI=hrqD|dIccw4jNOMG%<{nWX?}#1d#Y1FS=M|{24J7@4HO>`NCZqakT%Zy&@=; z@EXAjhXoOcqyFoKLr|=EnaJr_cX~xuddG0^?s{Wl3rp{wtoxR|$IxmzW8>-1=7wS{ zEH6J656WF>@RcM5yA)uGdMK_9<#v>q)*+~rAhRb9g7oeF5D^}p5#)tG-R zZ)_S}v)nxk=sG)$&na27TZo;`Nr6G2fMt51&Rz}xS)R0gg8fwNSH}W7Idu>xH{fB63)_0<%{O_A-=g&Z z?tos_8=V6LD#TnESf>h$D4ZrVAuflTJ~>xS1cOCW@HluYQk88|l6c_mH5^`wa=@C| zxxAQ0>VdS@gg^o?^z>%ZUWavj_v!?Ct$pCG{w!DGAqm^!;)wr|01hdsuFrBBVjx#u z{b^a)`b4pT6L9y^CMfX-niE(yhkzZ9Kv3hRe@l@hy~cj`h;Up- z2d=P}F7MQt_*}#Dl74A)pXjt*ZjPXgTCVZbr7a{(F{=-+(=Y5RCke0thM6bw`Wv}X z@!2{CBIwIddNc zXdNK1+M7EH`0`Xy=cb*z6Xs`ur;px7(>+TCj0?NIYvc4IK$C6dhpjtaX|r4H{`7fN zXmPP?)2Fq~W?;Smn4a3+6?&P-J<_NJmXqTyM<?Y+#=V*1qYO zj2aHRHNuhFd(v7%Ri5kk^lKqnLQ(ypwIS+x`Opb->&qwOuamGr?SuFdUug|9KzAUN zTs_=|PRm^cvo&J6ZNJn=6zz(19{2LyiYF45+t;veQ9f!o6KVuJ>xAtlM%ncA-Z5i8 zs&Dq5u@oH3s)bWb%eNTHbm93Bw1f>nIG;u`H1zt@_5A;@d%*f1a9)DsR{t39UiCrN zSUBq5;akB3YtyV)Zc(q362c2PZqIGLXTQg9inc%L!|ii-_*H@uSe^HDw2JTsK89wZ z0CJ|si+QBVH*CpFomNNkEMm z=pnB0yx~G04{Z+`iO|~ipDP~!^k$>k-lp%gj$F}J^8 z>UI$j5*qT|nIKS_YkdMZz}RySQm-w}J;?0^PQC3@zKLeIZ?lz}0;R5f>laih23v9% z7#Lg{-agc7tf(Ll4Gk6V9|$2uMivM>9WUXrl=fYZcLamSD>!I5163^=sjm-FScQU1 zfn@uMGoHqaBf52ayGiYh9b=w}-Es8q8F z5??%d((53MDr6V;`K^JyxY^b98Ef392YYZa?>Q07-9;h!a#K5OJDUFKNEPA!r(|zJdhj_0IG|LJ8_#yvDG&bF391{~&Y#NWp9P8*v-ZPho zK}wIP;Z&wmnEq4LP2Q0^0t~r@8aA4y!H_wUHV%$?HLnx(2j;4m z=X)B$=SS@VJ!uc?63HR#H%L#wq&{wKO~9uOtL;-8Vtm|RzQhqo-{h5CEa)TdY36p9 z-2DiN>{2k-gy&$X-&EMyntUqp2=C^zXHVlIkd&%#!ZQm#kofnct29s42sG@V6l`XE zRj{f=)6C0zn_u~L_tUl!^-mhs3x*ug@i3S;Fu_$)*FtCYVufarbHn>gGN&t0b*<`Q zGX?y*sncO$#gmxxq_>+-Ln%vGPG{bN^6nE*KqkkAaQ{H#hlisfpXlimsEK8`5jJbL=74fL0^y=0Q_uUcj6v zG=-tjlaR)1WeqoP6Y?u$ypH_Tk6t4EowES9ID9MKcn8t(;s~rFCyYTp;d2-Hz%0QS zbQv8BGjNa1BXHVcE_r;T-@)=&N5toSeP5;7<5KKPLPe=>R5Q_RvqCRPSX- zg?j@6!Z)>;u-(<{D@W*jL(81WO8k@Q3yQLadI9_I4$2|nO4|!{?q4TYWA5L-R##3I zYQ(L1c|MH@I;Xrn=|<+@WRQ2`XnP_Tjb`a~TEum|Qro9u*dnZ8g^H4D7MMAuN+ig| z@l||(O)>M04V0xa^qfFhw1euv&MxmGNt*046?VMiZqjt%y%G>GbG&MQ^f}MacjvVk z5d)dZRU!}fSw#{-0RMW31d7%!oo)%Q^HMd4WB*lQ={_!&Urs9)Mjkq zvvw0!&6^J-?Pm|OW>$Vie9M#mlztxSS19h{h(*+gs&t( zBKGx=`x)@%sscnj7b^osL)6)gxlsM-r*B zwZiG^sv)YjxZ*h}A#@9_PN@7$$e+NR+P$m{8WIA{z*PI+91>9Gxm_);nK=3GzW39O z!myeFmikBbrZg9z^?yUoZC$g@2jW3Kxd2T(?w5wk1F=rgBmr(df)_7dXyXgtOO<}s zPsum)=40@Z)Hd3av-xJVIXnzC>v2)vckh^mWaw{PyH;X-an_vFjuhkfec<}W=P!!$ zU<6R@@s77QYnX6{$4??PzzX0kV7SFZsS-n-g+|LXO{qrMYTK?o0T2b(kdT?7Hf3e? zALODqIVgG+z-rNv4KsHQv1I<|fZ4!M!bkJq@BJMA`7(a{Pytp@$5Oq_j(`4B%_|^) za=(lkI8hw!SY5XCSUyHKTpw!o+HR=C!Pg5_$P>P2uT*7++cM=(c+=fIQPvJeT3QOYwEFktQYC?Px`J;dOjwhhr$%ObtEVW~9Q4o-+mR7NE;Vd9?ipW@U_}( z+?L&*4@OLe6EN#%DNLRpw(>AXSBnozicNN@q5xe+Y!bH91Qr=Na+y6Uuw>TK!uOJT zG_zh&QLT{w(U!#EZWf{fEg(P=m|=UxE;~h&16Ha@+54;>yRVP|gZAj=ssHEe|DIfg zg$a_(Bq)_k=X2TK_Gkp}RucaUotQ4!9Q})tR z?v-*vFe?QtSu)SX{0|ovIROubnWdDGdWJXt+AfC_gl=Y9=t1l=a*;Fe6`0* z;D?0hPiMl+WG$5R3J1IC^vZJnww%h>T5o~rfU?cIx<63*)*M%=TtW|1T<^Y*AzZqh z2#KAUDaI297Hb{%g_Gd@j=Gk*nP}8&U>3f!s{k-AENZh9RhDNvuUd4;1id18{mh!4ibj(Xw##&SwQY zbi913qj`n`JawYY3gqC04NbJnlS~rq$kphT5D>b z%gZAXkqwlVCihhIm^{ubidrxkn;!g3~u_a zr}>n)Z(H7DXUn{^g(nA=H7+{z_h$wjT7-Z^Dbd%LDB?^bEhAloC1S!uq0WY}s?R_h zrMf^t2G4wlUU>gTUPC?bXGd37QIN7HFa-sShyalhHfvk^xFWW3f*_P5C(|Re z`!2JH;AFtSw`re%y`sYAVx;sb7A~yud~5fcnx_WtSfnbIsi}^Ed1UgKY5CE~8&LtG zDB$(Ecx^eJ+vfH2{_}I2sK^jQMLa!sg*=50`ij9kqBXKbm-B;6j34ewt?}`+tUF9L zSlA*Xu8wTsMS=TKGs!6S-JIk!Er4E8c|{5c2@S1TGN%{MUmG)}lk&!?$x_QYI$1|P z#(RWKA>k&z>|h4g8go|Dk{CoYFXg!h)B|#vQ`T` zq!5l{Zzdr^%AdfNl%A-(S!UwI9F`u2Z)zq5e2!R|nK7}2)GNY@QU=EYt24ij9m%>e zLuLHo!2S8f>48l|b~gA#*bP2mjquy=N~)=nvTx6yrAp)g76s^*JC;9Mqy+Hw_s?FA z+GE|;XuXs^Vrp!(hSn8@?K3!{?4?|d=i3<=l$_%yi`BT^IgRx0x~>m-KarIttNs}{ z`6)?(^oDsQ-(XUI^oQ5MpD>i@$Ofd>pfB_cY1oe&Hl6%-CcU7ikIkeO5W9kyPxB!pzs5nT) z`W6nsv* zlmwVhf+UjEbAs?y9b~I=#*i=q-UG6l=zc{>% z@d=8gg&H{~(8r7@Tr6#AaW!>pXO6LQCdSTe<A#`fh9xzm#=+}!f*0wX)tn;n47~s$2t3ptPm0R1tKyVr;JK7!2+?| zT+eES!YKidx1>g`e0Ag@CMi_g zzdR80TL6qpkfcw=`ziPwQV67UabD;B_z++MDY&p_*^S(vY6?kgS;5U6{{F!alsqn*{@g$b9cIf1x( zFR)zDYgSm|B&TJqwzg`>Eb69kTdDo*H=qNnWfZ}Qg`=f-qCMJx*gJAvVVp9Y>e#|~ z;YOyW5fi~EsnHRNpU;js_h>xIkaN8wqTm6a9;>Lme{3A+M-_w{X zr{+&UL&ID~jSoas{dtC!CBdrwrF73f9!y-gYMU3Z%Q23DXEu^brwMkKB?{Vt?H(w( zJj^K}f?yk>#ns*na1z*JnyC)BA~}P!3$BHQ#zt3W*27=$9Yrv6$pD;)Etcc|n2uM<1onZ1)RN`1Ka+0%VSU@~H_v3l!^2uKAvgRs!WXlJk)z>3ox8;)4ot>TZn_Wg*G}5VStgqPq#*{x9 zmWuhG_K#OpA5|Eb8{@Ucb+i2pNWO=dZdz|cQIFcy7;V}^aXBqYQJkkwUIVgsJPk(X z>QoRT)U1+oka`XlOhieEsU;|x9LFthJ z84mmHupix0HuQ2+hS{fs`!C&effdDgW%GW!+@~I+qPAMsfcgBGd2UVtbF>8?1JF7Q z(tSUH-U&2G+!WLNtt4(iM0V-^y0v@@T1%z9au3~~A}WRz!b#Lt!;#DKbOtpQ3twgR z+q)7T6QqX@oV{AHh};`4z^`kwinzg^kX=mJx+O>V>9c36eX+*4;s(P5UPV)YCWI}S zs2aUN=N60G$u`483C|;^O-`0%7#BFlesr z;^50XAPl3k*4r_9?CiRq`FZ}vB0S8=`?5P&bi*a=%Wl4kJnb~k0w zq3IviV*tz zr)U)i2hMU+Ug5y{jikUx!{tDNNb{cx%TC5I$HJdVAgM7Oxbv zKz!i_GyM!Kp#!lV;7vSpn^Rxz2DIRk27kf#a3rA8A*QBYZ9}%mTCY9vyO$~fn|O*v z)|reBpXZE4!2VwK*3qf&4hGm($rWivnvjCw3dkJCQn53*L)w@y*m?t zI+5tTE-ANd;TjQ1@oPwWxo4qK0D1XSR70nXqJE; z#`_Z8JROE@V z27q1Vz52+2T8%L#dOZ1J(^LyZ|G@+L;*sANcDhHdb6N0t^W_jdzut(Rpag*%qI030s*dj=VDaCTT zkvqZjfdFFOrwMj3XzV^$F)Y9=IutnEnxv0NLu0+?@O$?|&y9s!cD|IuD@CiW?v_pN zQS{Tp`1#`@D14j%;m1uU)BcBY{i>En=#UB|X*xJLwQ&GKWKjL3tkA7ny(El;>#wd0 z09p0dqg}9Ro`iVz`@4rt0)6LCGg@f1&3B!;-09?z$3Ak*6)It6% z2Jlbx$CkwlH8RBkj0Xq6c%YY!41M;DN(=xtCZi(5y<-4RYmZ_1I!w7(HGvXm-~c!b z4a2<6S)j=nE^KX^Z+BlS4)Wgq;dVgg=7W5k7W)OPvp~F2q0h(0uQ-qTWvK>1IS0s9 zW(Gw1KYZu?_;f6Fp)j>*>*-7-aVzskfXk7+dW9eY3p{BC++ej;C#Q$?`&0FLe91+* zP%uoD4JTw_i|ZSn!Gd7fac(`3zLX`19a0|%_zx7({f2(k4NaZ!#F z>>3%}dDhS#o$2-oZ=k>&yE6$jl4^D;Uz8>jY~dXP!+2(jo}e$x_?O{U7WQ zk<^efMS0ZKox>(2u)lcZY@@9D;p#UiUD6fb+?e#}s};m&dh=-5e+!x6aofQ}fB(TG z%PhtyCI*V14DU~${$I|lm*r}r*w#k*bDV-?p)Dw$FD>0KFE2NrGBq>PwJ>{*k~^kj z9*O(mW_4yY)jJGWpFT6v%PDLSnqXqatYNAEC4o77Euza>2Mj1TM>4Mll*u8h{qJk$H0fotzq6>h6_gTt zA5LQ0-n}MZ7tz{I^@?D)5EXdg8w4Csx4?oi>~OABVJp{mvKW!oqP@;`!CsaW*G9>> zs;bRHt(aBm8G{G6pPEgc$nIDGx7C-pnioxWR$X0(&Rkk(1vlnf2&U z$de$W%)9y@7M*n>fp_vc9vxV;b8B4fMao>aEFQKZ5Ekd2=&cBb zNxMF94%I8o)ab~Zx~Hdz{{cj86Sfgh{e4mKx$2r6KVovs7`H zw@ZRF`6GB^qb;9aq0K_aR9DyVuu(&EW3tk=-%S25FI5=)s{Gk` z>v8j^C_ixrAv<7wd35*YGf?#BPV`=wv=H#>>e9#40$S#Ld+XZ#JXKh&q}fNHOwU0M z-*EDM{mPs`RK0^)nn!aK$VrN^#5$B&S7vgCEUuIU!lELhC}1d5)_ec1*D{gjsYa3 zyBh(eMCopUA(d_hL_$gFPU(rp%Bj|(Juo_T;=7lEkHqn9#$XK*ZTp# zb(NZWQq3kee@$p6?JE!=s5}>{k#D2IHpWnT22@^bjQGZn>*TSs%BB)< zBYX}HYTg9x_{;0z ziS|}^ADHxjM9}FJYQ6OtLJ_r!Gdued9WN+0XNf2swV~({#-CgONmc8JfYBgCz~pgM zt51hjsOC-iydtoKP_9#FW@n%Jh|A&7CTg~dPNJddky!yorFPtE=uq#K^$Cn=AjWrD z&_2Wo9iw1Q3A=cqMM3r@XLD)H@Xx2G-WO;?dCFI5w=Z zRf!_uh1ZPNYY(vd1|EPji99S=DMUocVmROs=}ja$rP;K4-nGWeT2x9e@bv&PjvXaJp=_x#D}8+GLg7klLmd$@ zIq(q(*NgjYAeo#%c%Gjo^JnxYZ9w9qN&}!nC(Z{vtZN9Ae}s~beJWl}OnHJGUK{pCVEV}=rg)+l&wSEdf)|!YrgyEQAG5C)efN(NR zX7b#0R1ChdAWDbh;|g%ADv{g{9S_g>OV#l5}V)5HtU~9;ABC-{S zNH`@eI0Re0zu%65CwbnV%`xpf4V7=RHI#7-oNu%A1!p^fc_*>DXNWYS=%Q|C>97|& zxK3?d9l82@zV_!w`%^W1z9RbEhhX;pQd;?(z0NQR!=VHYk z0_`FuWoRl@mdiX2bgxmduzB^w z?#AC7+kgLZ5)+ZkB6d#rIw24m)xQ-}VB41xl?W2n>bpP+BqYGaAz*M22oJHJ=-=Jt zN5VDf9-%fdqLa!m51?pn;otD|@Sx;AfVh3YLsWwb*Kj&@#c*+Oa_^BxEBG6oIAq)T z8#N=VBij3XzrcO z64WXMl^33p;b|V<4F&-90YIuBKVlC#P;wXbp@SZKtS%B5QW|%Mn>lJh^c;?P?fm{Ov#J=MQH#KiXEg@q z7FH6L$^>ROr~?lkGQT#OUf;sY*DewE5@1z&BSH=8Nb_e|hG}vPT50K?Uy}r}MsLmF zQmlU*zpyE>KwCOK4VE_;p#oxkAD&X1_^UMn?8B_!ayJ9I?L%&SHB*MXuD< z)p4ja4;r{FAK9*d?h2Sq59)Pl!I3V9B`WM7HR&crF{d5R0;?Nd&;CCq_g&g;aQv;diM7EE zlRUrn5qpCho5w%uBn7AlGAJqg`upu%l~YM#V#GGH^c1u`T=f)`ki^yF>}DHWCwPD- zq~;$YcG%us8}}IGANj0X0Zy7sq`e^jPzvrG0#ZC!;(U7opJ|X{y`op)^wjdu5>wAH zirgZC<7JtUFxB^asgRSQmU?`ll|5jZeXh;od z>)>o;%WN~Vh}%48%AlaQ*Evqn_vTFmmvkDCkRkgikw8{urv_tfE z!CBU8-pKkgQG)+3&-&l>QN))8c%zv_@E85fAQ4~o;(=CN21tBqK#?hj>VLzm3e-Dz zyxOcR{zmH~EPyd*C!zZCX5$7D$P-U?9WD zooCZGG=%C82lwe$SJxDkwL&m49)hjgLicZUfu(CahNuOAp{K7u*^^s7NNf`kjB~@u z)JheJ>SVs{y3IH2W*KRGqx<^LM6MWQW?rWxTv&+atvm%gw+JCBGf;V4#15zxM&Xqz ztSb8;C$BAIPAG@S<-z#2$10PB+sSheL8gx5c|`7(W`g8>jJ3U4OI2LIL_PCH(#?rg zZ%_lVWCR?uc2>Li^#6{KT><`!;Wu#s@$x8$+@07$9KPgobOaH~X%K9TQyA*+S1cDT zoTH7V1nrjdf&mf#^C^R?J0R-#D^-gg0Mz^x`n2bBG(~f^A5hC3ZDtCd(kJLy)zxGm z(aS9=mVE5U72Nq*QANow<~ltzUVto)3kxi$ig|&o-YS;4;w25*eV9a`iSGUl+aU<| zs`~+L?mN^zMMY9FijcT=sTU|H@abt9uyTF2>Hg0NuPhC4vYBu5=Fp}K|4;Gg(cd@AA$Ap zMn$D{k5d4?+I_FO!eDXtb~rit*y*d!0b77Ba|nv?o7Q*_q;hBNn&`L>?W#ocX26#7 z5)PxSb$k&SEkrt~psMKm;luqXh-wD8kN&`&I06Fw6hVri7s#}HV@}_f2AMVDWP7!% zu5{%o_fiYvo{yHIGqFpS^}W2;*Y`5`rHG9UM_qk=`kD+^=v1n&5RHDhrlPva3wkoL zJMs6f5q-^RsWBre`2O8<^Xnq6g{jZMnXAkBUQQJ_-7>D{*0K1m9YYbSjy2&`%f|8U zVct-0Y{_Ja#QNggV&xMUH-dCby0?1!rr!T%+xpZZC^}Xqp}W6}?P?`)gpIiK)u52u zx1~$cMJ6lJs5CP(0fZsd4j&t@<;jPD!_Lsg!GSyJs9n|eBJ#Lp8}7wBcDWFW^+P&Q zQTcst@~}I_1&zi(3O5*^Znpvb8b*WuDgD9Gd9 zWMRg?230Y=W00AVHoTT@+sBM%Kr0$IpYxRdeD8VO#c89yb{*-^^RHJxP(8s@U)rHA zD0tDfIl1lm{c(X_8T!*n&qE)a9$%0P6#ofvkf5LKtqDI8%kEv9dDSgVpGnH_2FS25G4vBp@{n&vcu_Ni!eWhJ_A7p z(zWXp6!|I^=or{9f`Wp?hkK{HpG^WxlIP%Zw3cAGs_3+Pw-MGXZ-7?iGlOKKclE~D z6X~csofQQm4$iEv$_zS^H{1D4Zm=X(O|Ebf-1DsA7nFAXn!?E_Zqy$m@Pw4fN~Tll zLwS4#r8(VWTarVRkJ1q%FR21Fzn$sLUVn^!>wV@Gk1gJ0A{nRL*`FVkvG=|$;q4DKp8YUSIOXb}y%Qwt};#JYZg{%@WLtR zY#>x2#eS&>>!C|`O0;D>6Vn?XaE`dtx$=cRCYpLldVRf)T4I8VvR-lUs#$b&Y(5>S z%JOC{k#41Y`r8`;SXkNX7EE`GwlIQPb_NC>A(02+eYT(R@n{QY%6zYgQfmDCU~i>+ zyb!?=o$TcWVn^8_1tFt2?9=m-bb1~3qf^k>RqK<1V>&G?38hWmV;{A)P z5JLP^4CM9QeT$U$Z?XcSYeFU|u@Tn;6pzobi!aDo7Zh|h1S$$$R|llh;LSLSM3l|f z&W*e)-Nc=9;dv8KEpzi*q)6P7Nt_M>j2Sl&PJhH=OX`A z0DspVbXt6RBxG`f1qlx9-*wN50UtMLu&?iXwvRuXpEEP}$hSbsnpEe-B}o`}6@;?p z@S1M>vZ^II@=Z9ZbAF*C5{}g%Di)thPqK3VVE!8)f35m-_tcaGzN|zGBG$37F^84@ z+sUvS2Mx* zOI-TIy2WkA+c?h)t_kwuW5Yhcq={nL%`fwm&89v)2BL_4Cl`rIE=9K7Dmm}cC~Rj9 z6uUd=jnI*Za!(4Rd$jaqn%jD)(QP@sj}&ECV?{~bnTKTTei~pM~g1@1UfVP*zZAcsAHx=~NCqPH__e7;EddS5)i^{mr zt5Xe!@u=w3gBBSfp*D?O9Jlq1VK6RN6)epJU4JO?jl*x4dal>ntLAjHB%oB!gD#oxcCs+LPTigJgUW=V ziGt_KIjbaKP~W_-K!cu-kWcc8?^Sda6)COCgQSQUhWg`gSNLXnZJD5u@Ci&@Vw;k# z2ASu-xvgKmZ9>PwHzn1F)=2&)a_9r(0ykfX&9Y7_oVZgGjbfs0pZe*o5e{#!EI)Bk z(S`RAkQkK)tSQ1#9UXalCWCP*4wHnpUQn>EM?}ZGqr~EQX3RX^j1wO(KSI|{tc;sh zUQwC8DTC3=A^rbhoZZ3^$7N^YcT%NnrcI!7=ZhtT7r-mE^Ty77KW2LBWON z4Rguz3JEb%Rh$+-Y)1JSiVdjS~#OMJ3b;aOufc!)5dr8&S=b~#V3`R z(j#$&o#Jv~4hIEuc$5lbuLwE|^ZND_q)P8|a+!aV&CzVJ;i?>aG?*>J=f0WLNpM3Y zB`RyC!V+`z$lfk+O^JT`^`v>D@C~SxY!og{jC^VgGfVb?)5^k=yawHxdEC6*c8rJ5 zDk{z8jItZv8;4yiA9_9g5KLCV#r60kozACe1Y>=IX=7~A{+vxK%Or)Y_PfpE2tf&^ z3}}!QE<;bVvPLKv>BWAR(tm8&*OpEsO<#M00rl0de$uCD2F0S!8^n!@ii)*n9M$?+ z1IKdK1t=IAAF#31Q+HXj5!uq$RG{UXfL;wMy6ak`{ptn9U2Pj?ZWn|^mBz-3@+W3g zZK^cln!XJIS0DU27UJ|hqmzPS@Y!r=5RIzMhGt%x$OmZPdH-Hl0$XQgz@d@R4p4@z zoK$IW;3QN;gwxKRi(hzp)FdazyfcbP95&KB(Vr3cNg}z=HC9Bqf<*E$mBw23N;Q)J8p)VW!{Y{+N_1zOkHtw z8vC!$Jf2SrvE5-CoP}fWA~P&Tv$@f6_q5R)vmNw5RG-3LYkv z+0H}V=j%FdLZ|V7R&jH0%n0E!xMobHCx>YTa>jE6i|gEqUAHDL~^J$W+` z8>%)Xp2qLq7TgdiHin1g%gOQSL9#8F(vlxnMYg#6~UDD~=$iawUH`0}d!^?V~D|XjCvEpvs+S6_+ zl-Dn=eYa`b)%9l0$mofs<(mj!Ek`(U(a?}|swc7QByqu*BOAU!dZ4wJassEM^wZeN za*fW!JR7GX6^+|l)?S(WUX9XcUgy@Ao6}76g6H3yTaj=dn$(7)+(zfwJ5>H+i;gW1 zs`8uO-zJO)$yq}mi9q^Y2E3YMRm7m+?yVC)hU5% zX)-&1?ryJAg~Ks;9jt|l)n;wf;ZOyz=??}r@qfo6ap+istkt<<3Ld33S56m|K;i-E zHSd8<{&lUHj0)8h!?q}g8K3(=@MR}%i>~zv$;pLvWSk4%U6MA8yFM8wLX4_Bjz7q& zFW zcUV?fAP*st6vH3NNv`y$E;D$%;P&-h2LX0_WL#R+u-DzKj(N-_`AEjQPn5|M_6jvh z9iHl@G#u7%O|Ig49D62~YQcSdTAI#zuK6Zn{EU~B`rdjC#|*~k*o{7j>?35NtxvRW zw(+Lm&0n(oU!F}Q6cgX{WgkUL$v<9-#Wy@Wd<_YAa~Ei|c{(aL@OlRm6H@zu%MmSS z$C%?tt-cTPv7sT`lM()c2d9hAE$WC(ZTxUZ*!g-0)>f0i;uw_@cuG#rJ6Lu(1OPJf zCFvRIqOm4jN?!#JdElsBi6j_YdpR1*&BVQW)pM+yhtxu>(~>kygUkv zG_iU zia%b~ZJC?;Ncl-nQ6wyCN+C*&8zaTJTG?n=JnBZ*ux_cNH+#{IGn=XVz`s2Ui7C{h zur@Yca7j@S)o4y^fw))n;Rqdjw$25kD!k@%j*qNo*Y?GC0@0I{GLMp?R7{ot|H;kr%R{) z@{qv(Wbu6!?qoF};TBq2$`7LE*oiytm$xm(va_fwr1hR13(^H0?hH zPij59W;R?HJS#B! z*t%l};eN2JqLU0`y|Od8#cYv|mv08e@JWQYlvIz4d1A3e#YiBb0cU2<8Va37ao5!# z%S(g4W^>>$kDjmK3MSdHxImMj$f#|c z{kc{&R&DCRMDum0aJGl#P~YMFs>5m3Ip5dOif&R=lHIwprUA{mNLDa$E!#9-@oylsOePt8UP8bAQPZQsP7ely{?F(q!t%|jb0&8ldT2ZhV)$yB| zdDT-75_HCi!{k$`^M+=^Tc@18@6~>0Z*Bd2*kMiNz0H}Od?8yM`}(*`Zgc%h(D?kjKEAJM&1hxZVwDAY2M1d@^)iy+>eg1oHX}yluYsvK1 z5Tb@9>Hr!q^$!aEZ0n60(J!V9OV`H5j%8xAN=+689i*7h@R)0BG1pKc;^3Hl=}-jMigVZU^`cq7+_V2CVmxkN5P*9^Zlb1k%ci$>%pamvGCVg=PlsAL zx<)KtA`+0igoT+=2E{y&3|+2duD>$p7LUhcM+N8QrVqija_5sm8C7? z6_p{);=)*;|2Zv$YW%G^a+>^Cd$@dFBw5UI*oD0xu^~J7>REWzeQX{eIZWXFF2ujPtSEq>h`zVI@sC7q@AizU^|B5q zCq|&~K=ar6umN6s<18}}V1}DRT zB!zZn%8{FsgZYcD%XBLjr$o9XP-r?TN!oiw>iiqFXH^2A_B!j64CZ%~*3i(vlud?J zw1x~?LCA&*m5+*QZ${%YG&M^JTJHLSFYE;IFsTEYHs#@-Gh)Ss&gsmG?zCo zb@M`q94_hv936LL<1@CM8}qj_U*n$f)%Td1M=rHrcRk#QG}+Q!B2Sk~B>eEWxq^p> zpI?bdpLUQoPza{K0k^M~NZGl6oAN^T37U}7YPGm#?a_yZnxZGJoJi8~H_xZNlXE?7 z*BpwrS>*Ra9=S%>o5x;s1>&5P(wv*Bw{fl~S6@ZL;vE?p<6DnS6Gt{sf*x8uKRrlE zkB*Y!clx-XKt_nv04xwMb4Ld$ zaM{6Y^lULU`-^M`Oqh^R3RI{pYSNr0xaXRglj6#etY7dCTlHHv&ZU%}dcB(~2ysix z(q$obgk{~z4Rl-a7qmSoz7!O7oIW=!C!A*4is$UCwR>E8xH;H(-Xc7}P2=TKCMi_5 z_85(_Aov;)W#G4t(f2GR_BmzdYCT647H?8q8JyZax8svCUB!CvNX@>at)oM!K!un* z&-E+&KMd(FB-ij3C_6)Es#$;kkw~2;(1ETE7B`X$Be1c_=TWbMQ*-CMlYl)WB<2%E zTlx+%Xp?8yq4x=cU*K9`q0(a!=E#Ss$deWsdukEA>=BNYPl*brj>e^ouqgN(^W^d4 zH}wH`3XlTWVnPRv;jd5lj_)Q#E^Uj-jb5e`J5UYR%b2T_l|b~4rA0cPD7gkm(s-{A zy6b%zN^JY~`LfX>Qcd^vS=aP33l_<0!)WP#Sh2Sbiv7~3RoPSSA`x1pYJj4u*es`# zNrvJ1T8?L(pSpiKnXvEw6gF?T9(u#K4I&^nGM`1|UVxrnMI&IHnb{AgjGkss z7Gk3kzDvbV?5eFu$Mpcq0Q)4aHM$_li#BF1Z~Qm3I5Rmv0X| zb2Z9?93;I0RD1G=GaJXVvz{^C6U9W%uAJIgp}Bk>EZ^lSMZ!6pyVejU?Xsk^*m#)Y zwLQ6I=K17R47*;@(W{E>uYi1B1+R#SxxloiM0$UFyPaN1S-B^!KvUey%OdPeA1!_e z(n0-@8bJT>|CilVWdm2Nb;I`8dJU1dgjR@fkk%2Ky)2rsDX-=Q(ig*tj^@)-Ot&{O zf~_svG~-+x?-Hq(OQ+XvzBT?r>QbeDi;)~xrs8O_8JpOO$5|d$5M^eT1;E#-N|8Xz z-EU9qze$yv$b5YlwvgK}QHdfjHkMVx=PFOBcGgD2y!%C{u$!+q<2hvPL-uE;2XErZ zn5=A%KS(;3_h0Udeb5!ImQB9=hDT(9*D<^@9QssvP-nK}Vm|de-dHyA9n*X5R|Zv4 z7(Cdqx6VV~`JC66IhywnDJ!#OKS-dT(L|ROxO)1w%nbKnl0;_^PW|?>X=x zg>UgZGj2~sY9`pIHXc5TefKohcrl2Ggrxd~5e=ZVr(PV3z@`Lsa!WZkqc3YOHD47s z7V$21KR+*fK2~KMMtwOs9o;r>Tk&LgJq5Ia$SLw>I97zN%s*?cb(R^gJj4b|AjaMs zCSj-O-{inWaSNg>X!f^^{O)c?IVA+<*nW2we@KF(4pGMsM^61ic2Gj(BJJvo-KCzj z`FeLpz(Dczn)Q>fEN9vav%XVi7TpY57Sib0SvP&OMB!^;QPiX>Lw(otUO=^ELIws1 zNAK!6!RXulZ~%@myl(5{bZZ187NZ4z{wUOM-v$aPX*pQWGqFW)HJR*eoIb)D!!@^> zr?VWrp`b4+g+&q&9YK4WL0bPw7>?5D#62>#c@M|;J@H7j@>qGk387Yn6d)ZBWzL;|>g?*N zymJdq-)Y~GbH~D0<4^z4ia*o*dpAYW=p?L=TmGg=KO?%Y7S_?Z7Z*48+O9uZ`DN49 z4Iu}qQ&|4u<*M2sL}3P*tXWlpmT_q)`7w=tG=@cbHQU|F)^lRBlIYV-;~vQmC`fOh z{uEFflDhE>XZNm$?iTPs7PXtN*#@9Q6cbRea$0F?#;2=eEbNmtU3k%51Y&O}xp;oY z*;O!-pA^~H=bRD|b9c{tu~Xrh8D~pX)7>p*aDbMp zwp=b?anWskO>cNek_Mu!omARqMGH-H5@xG1IGj9qfGnW}Hefx!yhzCx`T^6KzV=%K zAZZvftKvv4Ox*56QWo9s2;6@FIbYkmASNYEiv+&@P0^a3-KbK~gxLcv+Vc92Re#<} zV&=U}SKghR4}J0~Dv=`302;CM3jPqA5~x4KJ{R`(>_TcE6_o!a`f#M@eK$M4 zL48rMWYu%w$sxxhVke-5$Lp**MIRJ((JCqJdWj==p;H`8Tn<~Pi1=_nyKHZb(S1Em zjj@|yc~LFWaiCHn_S-~W?-z~W!%xpw6RlUxLrB)lZ{MytuNY72#GZPC>mRyTPr7k2 ziHU2K8-R(M>50a$v`_82aKaG=F)!&Q1oAS_q7@R_*}B2KJ|k2i!tlQ&2vki!Y2r@c z?_ly3r2gs4vn99r%ErN^*%Ij-Ipvwe=_unbFJF*Z(7AY%^k^-^o3X>fb^x}r#h7}h zxJ<^cex=E4$7L~Kq`Jm+HSJ#lzws8kvq-v~4tOTw@(4TVfo^JY5gIO{f4 z6#LZ38|$HV&8_HInWgS0pa=1(%tjxu8fH~FlT%qEJ%(rsx=^<}MWa)x@N837K{8 zjE%ew;x86PP0D9CYq>1J^~LbOu1A;t`l%4^2@#Z_S6-EE#$H53{X>OZ-J2ZAZ=`HoYcnZ z4Y7w)_DPbFnR#xD25dF(e^{MbTDu%rKkAluW!H{a>ZQx}zNqe>a+TDov>IGbqCEB& zO>T5iH0enluI^VVH+q(v&p*=3Wf*w&H7B2wTP;0LnSM5Kxz+CgtK-1DgMO5?NRu(15@ed%`Z26JMQ#? zY(jU<+A+Vw^i$IB!ureSNvHq>{^d^pZ{2YqZ|vBnMHaQagW9dtXadH)l;QlD%-77% zLiW)5&%8ia<4t9q_LEePj2Ak!WwYJjUw-OT_`?-8xk> zF90ctImyO9fc(r!+p4J4Q5}M&g>BmCVewN#wY>8su%A))wV@)t0al+>VmynB1yNs~ z{Sq&g3$GZ{bPZPR$d8!QJ$9euz5EcvkTO`mhNSskAnO>5UT0)w$f(QcH6Onq*z-^< zB>Xn_D@i0oaLp;&6^p2DL!QYMHs}2vizqwCygEy=ai5K-STlQKLfciHkawh(w`#XQ zDF`5ZAjKek+0>of4?rRl3j|2?MZ|3epbK&6NPTp2r-z|}m4bsY49$~9xc?GVL}Wqx z^5x2S%giqk*Y`WSf~F=c1f(CE6V(aa)>B8R_?)DizJYeL_St1=N{?rUhIeP4y- zX!@g2SXj>nVv(@J-j$a#jzmPxBU6lVat_9)Tr5Jx&CG7iaP)V1!KV`fFl%aVYRQGw z(VUmgO?ipSd}V?3Iw%}YQ}kMz`)O9)DX2P#8S4I;vN+jms?d;^(KYxd|Em!FOP8s z`g$X-Q zHx;(J+dDFni$n2nd3(0SliGA^--_5{naZoZyJi%Ly z(_5^cwyg7u^7@YZm2~c~gjkTUuY$%Wxd64JW(gh3XN-qsCeL!Y*yMDq;@}4r+1ZaD zY7z3>=#pjw1e&}jQv`bLho8(7#%+~cNrd`q`1u`&Exp+E$eb{rjFhntyCnJH>Idw9 z)@wDtBvE$g;Fp2e?y67-i(ixa%nU3y$Qr&(%-b9{V+sHV;dmZ@xBddauGyCAb8{1+K> zbN~^{?%-Yd`fJ-=LS`l}C#Ao~>!4JzdLpbDkN71Ja8=*?!%64q+|cL{Y*}cJwRgVo zY0sqwV{izh(zUetbIfD0s}<00FVT?%wuR#2*uvh!vdYiyJ6UsH$1+5p+RWvZBUOos zVJ;mvJU7yV7Iu%Ltl)lh70U|Z&o$yZnVD5oHS)l^g(4J+vHq`v_Z?xH%F0A#(ug)7 zjCaHsPRSC<5k-voxVxfSEsAAR&Du<}OW(-zqG(fl5Vr5^XtvlH@iwx#8;@;R`v6ur znIG9E&Sy7}v%}H>i>r|}@)amISz;-1@)xtmTHrqjxN%ocvH1MzFo0bzW@%ghIGh@yZ}-7ir#gcOi`ca5 zgOO&VQ{g*sReK^S={lKDdeeCg+4Y;%BDMA#?8yI|~a3L%$gdzBdYq=}Il; zdi+>gN-822%y(Co|lQecqRejeU9HxLhQ}ouyFU8}H=oiFeWPs8y7dBbEBUa`E4Otg*PL zS>f`2^A1yA@Z#s__&4cw@tl$-O_OTR>)ZhO3*ewTozjeeFQy|Iqzs3{9#+8v^IyF( zlX2!1`8eukO2?K+-r}LDhS26D#w_nfJtH~mRr#%!t zD~aij&wM+WAN?k!=+Wt*(bz}AlAcHuiirqu``wR8jHPdX(&^s(q|-eEk;?ZyQAseQ z?`qI;C$4y*F;@lW{OZ4W<10v>==i2HhQ7Z(0LLm4F|x~QUXH`j_N-##fsM{KxXH?V z_bzqO=Ca8ZBw~D*)APgq?s4li;5r5ehg26yh@OA@V3d&jCOs=07ln_n%QiqPYHX;$HNmoPozYSy=^vD$2M4=Vb(AwDIxrrBzI-0jJ;g8#471SJ zYD-Z}N)i&!N}=LT6;X*Sa>--%DM-XWmLjnXicoV2TG5Or1%bkdCik2Ry2E z97z(m7U8vvsk~3SlD}i#l7raHDy@X`XC;v5Rme~6*kzYhFmE(nmCJ+mCy{aPHI0>P z3bD6m~&5^T*-B+)=Ma+t3*7Mz;umqEq*s6p!fx@n2*mPd+k7~NGD&lNM$FA2@}O%T1F0HW(KR%wYI>n7``Kx9-&+a z$KcYg$%3t#>C|{=#NO3;3yK+N3k2)o$JRXfyrK?mnvG_HfQH5n;It+s=5OzKzbrKDQXoIiX=Ta9t+)qHS%L)MXq z2-pW2e7UDgbnDh~%DA-}e0?;5%Q9i8Kr{PHqjUk3dpAS_I@F>j7PJm zfjv)Is#x4d9%d0LH0ZfSrONxs$x8C!1QrVJiOr5`gxVTeP07w36zgxLWr(aSW1Ux3 z0ysH|q~#zJpmwr$EFTzy#p@QoOX9ojEf*HUs+qOl+L{obTzDK1pb0M0ywiYYoW>sI zwR7ARR?6gFuBb@C#8vHp3ni9~5a;GbR9J108JfZNhP2)b8cPHrQgYQMm_v0mF#R5*8r%p2Y>YC&JDnw`hbPyjmzk5r~QZlHhtZZ4yFtezlf-gN_ z=1V*#5#b#HN7!6q0^wM#+H4GQc2?FMVNPWx;s_oObwHkB)-9E&*3jsbl^guf8WJ5H zy{J-NvU>f!=BUBk#4LsY0oDWc68OXXD^OoFO$&_mDK^XLDb9CqZ#-`cA0emD6a^X} zAwx??cf+ED4Mf=ll$)mi>YV5ih4v%$6~bRWuLv{^DG2as192#lTF2gx1P2EvfzzoH z60Eqd@5$Xjq~U`aCF$w#evY&xY9 zrJS6LmS%4&GsR1dyOb1d-`jECk4lQl0u@CLxjz@yJ@wnDe%O%<*SHeCuCE3oBRsFn zXH(r|^Zna@Gzj>AAXffFh$4^$Uul`ww_r;;UP>Z6IjUhlV0=}!!L(58IykA8ww ze||zzE8qTpCCjNgjUYT4>dm5{0X;Xj8Uo`x!1*c(CxtfIV5%QA`GLtqIl$m3FNc8s ziahPCnN}iskuF5XvhXbd0T-jN-eVRuSbe6rj;~KYAZ&xU_VMGRB^Pp}%)9uQ`=GC# z2KK<^;_3J6+5Etgs8REWwwta+rl4E_=?qi>$*P@>Zyo>KMIqVlpN+zwpNWGPQM-qq zeqsG3m-n@$N2Ky5sh+CBr=vXv#$Sr-4-yE<(&+F%BM}>yDELorIg4R3F)<-x!!8&n znRK;^Ch-u`V}0uXUe5SxrJw(XB^EM6=_etio8Eu!1!(U%2P~*=s~^cQy|+#g0{D}a zxSIbB@babxsV0UQGcoKXewF55b#Vt35b*gbnO3C#8TLpJ;J!arX1+Vv7M z4GfI80Td@=>w^E*=H~E4khREUY<+7I}N78RL~ z&kbyfsE77E_a_*s*BWc6Uz+$~Oz{0yjUWFwJ$o9#{dLn7T2PXUlSl3 znXCDo+s#<)reMdRnW<^j;`bI?p8&Fh_0i0^xw+ZpaG@U`?~^nw*yGA zC5+T;(!YLWfuQQ`?EW?U0d+uO?d?@tPIo44W)|!H?~=LVt4|1ALTH@B50U=o_vH{k zO7%L)BQQ7`?eTgjK!uwYOQPqY_*8Iz;7a$50;2pt*j(Rrjdp9$eXA@BO-#od7hz$} zD%5hXk@*44jnw4O|M)?SyECeeHu(aN(5N%?5@)bw|7F-B@F|Ej+Zz1@zp4``-w_x3 z7~8j}+_!Mv=fIOMChU7a+jzsDKfd&*Oj1Se3=mkwu|g=Fwqi0G*M2acKTX#ge*7W( z_iVkXW+3r@FNpRd3jU@Fh;K6yeqSZ7`nRDN0C6MOIR+&gA?yvLoVkpt9!l)>d;M`b zsaQYW_v6c^N5ykLy)xcG3|l{E&qs8jpB;fX6(rr_0sbR=o$qw_?(H=6aObJV{i84Y z<2Q_y1E2j_?fe&#ztk3?fiJHkX6G0`BJ?7+0gz`UAu1|ag6;=*=;;k*+u*G~EXzOv zngOvLsgN6MY(yJ_aS3dTU^jE#LI@u*{KDD`NC4b3(9@%%l%<0dhmv8MS~$TY0$`1O@(;#<7b-?dHhq{0ugY$Wx#(n)BV|$5yOW@iGg<0Bc!|CSN6hZeuqfm#RD1B2JibQR2%TI`} zrQ8e$Pk>{2*8b)nN{H?61F;AExRNE}V4KRRo(;$U9`6Vq0V6`Lej|JB7b7B-@g3H6 z@5=iGCXTmoT}i<>jQmS@#p4j-{n2S~bm8&i$MSJ>z@XXAD@!+wr_(Nu4g?lRcJ|@$_vtLijPLWJJVvH~=GkdKQs?{_CF}L94(N(2o%rS$Ko_ zw41r?yN{3mcsM9FO5N02zOZ`xtOOAq>lwbz?Pk~$*|$Tzy=n7p;VWT!XJU&Gh?%9e znqN=O^XlpZev@$3=qS_Kx3?4cor^qPJYwj`@q7Lc%5aku!XlV7PJZPqG31K4x>f`K zSO~mRd#N_Ku|V)_guK3ehq&GfaO7#cj%Iy|&%uyUdw2HFB7?&U1y!q6|0nb3c`O2^ z3DrVH{S%Neq{XMQS!O}+JLTe^!jTDu+XUHlTsu89-#Xn|^KU%YDp%(yE0k-f;>lk8 z#%#Z--Bok$)TLD}je7!hsC-%4X$-+K2$K02^n z!tJ>_KDhOMFNeJ4{BT-$<^q+#)a83C$^L-yQ=B8sq@NB#|a;!?@4 z{gGPxV%!Aj(ehLLnyG~PF|NJ?u z3!H*n`C5Mbz0L7b9FK{e{V4_p2Ejt$J)B<*>qn*u-2*vrXbP9wufr#wvYX6{>%SqB zO?e(p(!CbuIgu(nJrq14VB1dw}1!G5i+o!|i5WW7~#%w4T_qxRphw_%ijzVzQ* zimVlIB$1~VobJDT-n6H_P>$sn;7H;u3YDOnLpxyF^f-%Q6B|p($x+#PU&DAnNJO*( zl1cFf2CARViK7VR!-p(XEx+N(i&>g1jnYs1QKSNYhBJ_5VR5VD-*lrnuTrC(vlI94 z)~!m5^*S>Qn0A%C?AsbHvr$jcCBc+|ML9Ih_Z830IoKXp5P5ExYhLz>*X)8GMM8{3 zd7#!5CGM{g>W9hSM5LOxesh!B1b5ik8;L1zW@R;t*5b<9?Lal0k3Z?tOm#^}%jYtwWDL-s**1VidRY=B=1# z{{@^Axdf%c-gGeiFUh(u21|+amM$;`5ZHKF?LGGTB$Lgs52w8^OZJ9qBmMl4qGMvF z%C`3Q95w(#3IZ|xebhgQjnE17x}D&?qj|xW$tp#+%X4wjwWj~63l`VkK>?$_;h^NTk;va|c3 z90vEp2HiDkJ8$l_rupv^AG{OCzjY;AyHcY4p;ogfUVHQ_$4l<-j$3GSFVBpx_=0Ho)9on(nD3?;PVvXq6>s@u*y!ij zwFdXizDjOOB{7e>Io2$WIOC<(Hc2tuO`((b6do_92wswgK3Muql|Z>c3MMv4#XatZ z{VBU2KN1=M*jo-_*!<3$1AUp2K>{zDo5dJELbc4yRwGW=o}yJ^J`gyZupeviboZ{A zBmHS-3=K{1abHwaJRL)a*?!yI&vjrN4oZ?`Pw_XrJ zGg0DSPppHJQ9PWfM`1y0Xkpw1`u0CO+JF9lCLyAX33ur1uK~!P=sy-@!9Cm!y6(xK zIO%q7;9O`x9fNlv;XD;O&eC;T$@X>X`2N$g$ZGqpTjVt~n0Vzp1uQ+>Ee~)yl$l4p z34rJNT4R!bJ=v%KBkV2XqHNbM(4iaYPEn*oQaYp?B&55$q+w|3kglP-B&0)9xO?+dDQsx8SSDL%3X;^K6M~YGT66EI6cIqZ;Xy2PDykzQuz%pLa_n z(QhLN|7CGcUlX1gNIWO5>Hluvh(G~*-(9_#CeZad?J*!c&IMM#!4e*||9UjowPVRx zq#0BE2k^5jIimmZNU#-FhX^gkb28mcOm)d^3BD120R}|Tf!3kFhhv3MQ39J`QbI;E zrz@`yCuJ(zN&iD|_ zcb%8_0-!Izt{|&#aW6%W?21S)aLpxw;a3X_T7%&1bw`1xZ`9F^<+h2td)nu@RqK#@ z@pxy%CZR<^Kx$t_hpzS={0CL&pnwHL!;-pI9ZEWAG?8c(+m~Zwi)E80CO=O)pr*C#= zniVj4HhPSKejE4Ypo5O(LX~v=k2*%%<}Jye*?3u6I!+CWtF!@di zw52uNjf_;2;m-apqJ}Dgg;p7>VW=nq#;7)UL4q)dRnP_b2bqHADs#olAAw1h# z{}%r?m`N`fKyVzaLZC}!j zY^!(yZDDeurkvhzqznvewze)G!DL*Ne#x+ZMTtMY9SEB0sr>N6diUQxK)?YG1IAYV zptAKdj~{Nw=9^sh(=AaI_)fdWc!!OIja9Mb$yYbKpp$??+8(yAIn26@yEJZ6wLA8>~GmID_O9?~**KW11Sd}WxjA;Zo zR4u-JoBayCe6%X$tl#k!dK?VxIf{h;HVE~g(KCveZ|6bNnWA%dlE3e2$pCIU{fKeo zD*)KSqNCNl-f48AF>*t}XDNL9_)%I)TDf0cfvB#V5o@MRR~^_>6Xnt8Oq&mzFbR>26txy_in zxgQ{F2!c0Y;KEAs=>EE$Kh$fm1G9cRNLz1(EpoCjKM197rFQ=B2)K4~lZHU`o8J>_AxO10T#1&ke zd)e+hM*EeVuKE8wzb(l-0g$ui_$K9&ylqu0}in7=oU9-VhW`F2@T`hkZ zRCNAz3725e=YYg>*uu3fh@@;@#97S$s4sK5^5u*Ev=~VDCmcX$o(2a0%+h#`g0Zl% z(vi_?m9Xq#utdvWV3MZVlVjr%=co1mU&aN9t%UzhC%xGn`<3lSfMfs+;)U@2{38@S z9Q*3YBr*^>`cf?kJ44peR_+Ui{QnXoyb+&Z*XNaIN46;`vmwO2yqdt)jvuSGSLwe$ z!jcW^4`BC&1($*r?Yn65S<7KepxqDq>s4`*|a{1$<_DS%mir{~D(_63A-24@#ds}`-=?yD%7{YQ@>rixV4P1oM1EJrhOpx?c5sw@m z{yE)8zF*T7;_~ytV(Gm~?ldE#reS*wIr`wEOk)1T#@Us8ldzT>1y8>|$hN$g`0$RW zKyVwaK#%to54%AEae9Z?^)i{dXWoiO{!o=fO_y?19;cM5Zl%15NiiRz+@(sP&St;imXhCe~l zhUlt z^1Hdwf@=G_lLN&SGY_2*wIGp!#2>`tN@GAf-CGn5xDagJ-CvRM(89E@UJPGK?HYW; z|HO3XRdV6sBCNcA@LigjVQMG{r49lSLNObii8!#9lahwU1?(u=Z7-}m z*8drG^4qKTjDcUyR~ZD=6g)JTq*n_QfBXypCrNO+z7H;d`gyfr_blZVE9*EC>s-C@w>Zjcd=ygPhCVtfDk{9-uYam@ zp*DZw&WPW*v-c{w&(ayF%8H5ido1=Hpxtj1k%%H8 zd@Us`4E|H`%FGn_@woGsSN5iKq_9ooi17!E47CU>vWyh4QFoyQd6aMiWggSJC4=9> zUxy@+jSMmvnP<%;qIT5n+RHD_9C10gtW;Qv-mFz&n}#NsqRa=x&A+Uh-#RT4Qx5OT zt+1bSAGLWXMrYYE`Z}BSJ3%X_eim5jt= zo#!p?Di5mCHmap+Q8Jpxoh{_$RXLCBPmbTX=}60~&8+v(X?~HX-yT&r(9QfjF_{sD z_SDEhQ2@JmjPt?H_sg}bkLHzAa|Z#9Y$H?SfISa70DzY!ZM$Yfqr897O&{xjX=`Drhy^Uc>i%-fI3~ zUyr`7Og3$P{^C+!QEIJf9e(M&KiwQ?s(<}XnumV3cD9rah}7<_mWUzKM7Zn?78sDb zh8-gh=AsXoD?1IuutXJ?@=^G~}jF zUOT%no|*TemER<+&0)pcW2d6I)^(aL|3wPke>dg>=l<~X|MlE2R90(71)NG)?=K1k z54Q=q1P`7z`zkhIiV9*nWCx+qtX9eD2+R;sS(Z*mEpPh>1((#O6!ME4=F zvG??qvb_|uv9PcN8hFesOGJ>6ko%Sljkz>fj$tuvPjuUDeWx17QEoDv?8c9il5Qj_ z=4SW3$rk8`R->*>`<9D-?d!HHL9+2B^(cdOd~CPIJtMe?omenpR*uz;L<1@~*^2;G z>TyK=rLzmIAkM^ry@pel0ppe1yBEcI(WCb5M<%G`#=eggZh3lld0n^4-yJQMs4ZN< zILOkQ`O4Gy%9D2a=|mQ`rJu+@Y5tg&s#H%xLH-2PQxX~9=kThPjZJ(N0a}$Jj|@;% zSpKWk$xzQvNc3QZO8gHc^DiYNqP{~A*p&B1IQYwok7s|9ysWJAQ?IFz3oafy&qjF9$OS9>2c*53F~%e3j_Ve)8Rn_AB66tbPRq2a64n~Zz0Y%9{ z;PlZ#5?)yhAo?;@KD^mO|EV$8x8$MzP_^x?isDeB;rs!o^@HArYh9@$(-5tMxY9VE z-S|h>u-YH{%HP!U@5tg9Cf(N}E`B}azVm(;RvE)NEse5}Ut4t{?$r{NUogOHmB?v3 z2e~_L(_(XU{1lfgS!9s&E8EcLU)d5Ur9LSg7sHKzm2du#u%6}<1=|^a^S`HtYf&=8 z-&vrFMbx8-aSigfSG2-@uF3b%I{Ur^Y;D403bZJLvkuB4wzUUF&0P?lo(+o>9CRln zDwDVH+11hXsPC-||NIyvWMLsguR&qY#4x=2+O2h-YIinHO|nUS!aF;rAlkkz*eOon z%I)GBSd`$jO_y7xNXTYtE^S$Yg@yGaJlv_Cd*ROOLGu$oNxQfpiMQ-Tv~GI=DRNLc z1#mTPdBxOJQT^wM;(@X8`I47Ff_8N_7n2Ct3ha^xz3SnV`WA=PR2q7*FCxm_|ER4I z+9|?SzNA%{C-h;b!ynP&Pn(rCp(x|6(Vxx|d1b#(2ug^}@{>o}S2St}iuiWs)$4Dc#Qi)*+ zd8i5rzZEiOq(R2BE-htBtTTA;a`@Qka(Fb~jB<5U!md;Td9DmA?1924B$;(9c>MB1 zgHy`4MM}1=7w+xbje$eyo=0!mRgQ*-u6e z?48fIBuhH!2i^+7{`c#-xR8HvX!bj?=M>QYdMVN(SuZw>zcTLsX28%F_Wsx70~%!) zP&uVniygs(!o>LfDw>B?s{o$)v#V-(QeOwr=_BvWeH{y0{V?LIBmNU#ve!=^ELw-9 zF`bJ~3i;ChNHl0RD!yLXz8;bD{NmD0sL+B0mtoQnLRlX9{)WVl% zjIPJx%@23u)p@XeZms4Z0`$$;`eIwIg1iDlj{x|h_=F%e3GzrDmpy_Mf<@b=z`+t| zDEK@Y28Oq~x@2dLPStkDx(DCCJUd#{egRxY9RXaO8=DlODJEvVd6`o;8_ucAya&@C z`WzI7N8@W89JdMLgrR}&Xi?z1@eM5w%bEr{mhy>JFQFlXd6w47M#}vzhwK8!3I^#c18Uu4%#F8V|PNBDF9A3WM*}L@r zti*F6Vd;~?&Amb^s}B$N$o>o&FZqL2>tN7zi|)O)TJKQ5kTBG?*YM|n?>NcZeknN6 zq^8vH`y6HONrq-`iE8*2Wev!*quFOV_gU=Bu|cS z2>!JCr~iTnBmvJE;I_1^K@9c#*Na2|94+`rFv@>T(gr-MuFAXvS#ft`PIzQO9$cR0@MrOQkqf;tBUtA~F@gpZJ+U35HUZK4CL_K3Fr;R4k$I@?V(12_(*X}Fm z3OLIm;4IBX2(HK9VLtc>SmNX79xk_0p_u%VyYE(>*@$)8oMwFCjSkxDwX|mtLq|4HSS5OpUQ}?(s)Sz!_ z!{VzfiMhj3dIC0?Q&RzTp0)Ux)vv$}Il!E2Lf_qi%%b6VT;NjK;lhx?!)bmAgMP;= z2=znoM0U_kcnxD?8@*FMj1L6%Xr>M);I`2T{YQXa(+S8+`u}n)3g}o03SrR~G$rW& z@f3f%O{g7o#8#g*D$Z*L&Dx@`kv7vM36zGbu_@mwznT0K6fvm5l%n@+uVqtVBgjZi zf!0dY!3)}?bp7-*7mQ0!1t)(Cx0 zCMFh4QQ-E=$IZzpw#q2Pq2cOK)YO4BwPDFzPczIq8bJa^l77$`R?Pg5AB$pR{MO60#!atn)88xl*^)ie zOd39hp?}UP4u;8MpTmFraeNOOF4$36q+Ed_jgxvOr#xfMow24;N~(4Hi!p zW@ZS1rvhgF*xn#(HfYmgR|7bS5dv1|2aih;*TFjGW_0t4jA|A8S}N zG<09*8MRn$ODkD+mp(Z7IAK>1|Mt5mo>%-qoGPYcRPI8D{X2Bs+!yoK1}6MDs;7(vYbLpx!li{Z}lkB`N9OO zl~{9aJn6b#p|ZPmG(MgWI+vDa=^i9OlISf{=Y$jWvf=PM#_}^$0at8;jF@0}NMNRl zJs}w{Uv`A$cX--Cg`0sYdOFa8I@Hvm1!Sd!9T)0%obFE>?uXc7Q`5bSc?wIz{`=I0 zR4D=9QYDnS6#X9<<8RbKhXhWb2Ok^+M3$@c=`AWsHD#NMgF&r;Dlyl5-Jx(E`ZfPu z{?o(#Btc;|%jEUi2;L`+0|gERfBkth!cvQ_o@?-f-`e7Xg$Q(8(R=LO4BlJ=HM~@E z7o0^~F6|0YC&uKQVE*P0M%z)ObD8l0fpu1~)g~yZo7=exQb-=2eB$-NpSlRhkcpDB zDZehbhtvlDk|VOB~*NP0`Vb1V6<#!z2#?OnA0J+P%eUSltFb;~juvV0d<$tG*v{ z`q-X(RIhA`V6rhym3_>KK*gCZ35ttAb(@@6m6sEfR>o3}i;w-38fMIMeJ&|4ZnzG< zf0@Q*-I16;Uu`q~{GOKi8C6)g@OQceQs&+=Y%A>!9ImR@DE-GU>D~fk`3PeWs1Dld zSNIyOSjoI-8m~!lKb6Ps@1+Iw(LuAzOG}+e&5cZmW5U}kg)QqcrzY0r<8)AiRCJhR%T-ar)7XV8+q}mc zEL6IR7e0=E;};Yp_bt-^4_nPZ?6>7FhK75P+}*|5AGbg|9hn&7Gr?R-wq6-2A1}+b zsA}G`O_^}!xm6<~!sjd{AcqstnA0!@6*kQEm#xw=1Qr(UbSNo;m}@W&SE45#?v#e8 z1j%iq5u|V!fKZ4CDeeo%uU{+Hn97M(VN2E;aVDI5 z4)#XgSUh?e+sz01G=CsYkxYe>ED`d3?oAgYWd-FGhbUW&a6yhj@&S2lpW9ESQ8o)K zCJ0?q2*oA{KmQ1y{u$%hvzGcFF!HM0jVRkuA<@iY7@WZ=v$%-+uMa8^{1g z3?zF1HJ|7C|Hy!U=dy%=j`A;~L)=L+khuNM&CACHi4a+XNn-=djYDv1wmTSoeTPu~D#{3(26IfzkH; zo~^*o$irz1LI;HF%*Dn8Zd=ZDn`~!>D+M6rDrN8hWDN7u|8&7XF(AQJ*%w#+f91DO zAu%LW!u70J;Ep!^i=D8Ul5??D5R`ZaXAj!F#iO3rlQncug7pBr-a_u%%|-4V*hb8? zzBi%VrL^R{k-6B$)ExoyGKe;C?JS?W!?3rV|ZBK<< zT1Up$;2M;ok#H8fKErF=0tP-1=8TIMHIjOd@1|YnVV+(Jz}Ux;k;)!sjq&rwh(2717%ASzbCUDlgj3JPd$96uV-- zJiBqhWI3nOA2HUyk*8?vhOX=YJrE$- z$^UV-|HY>br6Icf`mdG_2CRRhj{>=|o)SW+%4?ykVDG#89&|Bhm_OpLAXve4r2E2R zGN#@f^Cyt1Rrn(|&`0Nq4cIJBEOa~uv@K=F)q}8L=@riJ02bEItFOKLn_By zn*&uaE{?vw5@yt;Tg>hy(fj8jeSOiAPVc1BF(4a)ed%AZ$$CsAVh2s`1uGd)x_$=2 zmdQwVq~^US1N<&H5cWs2wxq1Qct!-O@l<8B=H*_t>*0KVnGP{fH4H|4H4hzIu2rw! zwKuJCcRtGPy)7R>PX~=no=m6!ZNPaqkX4N(s0dp-2j`W6*pdOA?uo|Y_9A8pN>T}n?Hfx`}pnhI$DmPW6Lwv;J5~I<~8D}~D`ZE)NC3E3dDwQ@? zJ6DV-Oeq#~zKR_5f9o7|+JamLqYQceyzU{B#i#{CNC--6u|=yghdLRb6dG>q&Z zfrp>jK*n4=>fe^70WcJx*Kk(ogr~dg$28lLrXGF|NQ8qkCwboFtxA@=H^XI$22t@X z9t;8|2O8qys^~dznbtjCL2UXQoiZJf-yEd&`n zE@2wv0>Czt2$DAw>MNJCdeMF4zI=w4AtgKY3$|T>NZ4LIK&P-y1Q7?_l!Zq-H0I8bekWJab(5`%S` z$J!Vyy%YQ@ z^N~G6MnO3p{2HWjwe+E(z6h~PS|+m5+Kyv00Ef*Bw0isb09fNxTTfyGss*7sJliDt zgp=|Wet$IV!mt44h8pRnmYT(p#2&b}Di{rH97crfr?7&6=Z$=DL(W3+O!BJX)Yy_v zo|pr9Hp^E)IW8_Hx#OPbw*>GXIpdGxiUA@T;zvoi|Fj7P;Admbq3l3X@!NZ04nf@O z##ZPa$>4>N&j(0ij;UPla{NajV?YnYAdD&zdm>iPrSw=LnE-&h{_UYhXc6ct$#;wI*HfaM)Zx#Jo_gG4Zrrp#GJam0A&y{$SWf`v@ky2 z!THyt`DA0w={0@smc&B6^>Ree`L@x@e4Y7cZ(b&tF@|}3)dvS*KSE?5N!jkQRE}{L zUSiVuFA|ZTaDezl&K(Ev7u4$H5L_q`19UO8{h5lM)O?w7`)RuL22ZX>ZOyQ^X+_|D z8)m;tkXqt{FS%dK=dOFf8uc+E5M&j+4o@aGfbP@u=^a>HMe;K{)C~{P+%#N22`Hio z!#p1D#Y-sPGU&DkST`eRdts&+)xBO~DJk>uc0u?|uh$;rPN+mv#VTODop=AG6985x z4xDX~ctCl@KU`G^_URy@LQB3z12Jz}W^C+>o!(FeFV_xT3`CgtZ5|TvYm1x`h2Q5a z1Z43JI$P~(=>CB)p`H>E*!75x$A^wK??*#~FmhuckUGfd-==Z^9e|^2kEar~@9U5Y zJzC8VE^|V^6KXTb$|>}z1H@crrOkYy&3owiy4}KOI6+1YzpsLiLTd8pM{p2cvqkyb zP|gESWQ(}CllK`s=F81o9@o3r<3EjbzGp6KTQ9W`mTrwo%wFz0$S7eFd9+GCo4|Mm z3hwTQs%ku#Q@(QYOqm03n}YglNj_noTx)`8tXZBV$}kP?tmYjr=yWg-O~t^MnWLe$ z;q1J@FkeAB`2@{Y2!(wN75odzdBDY}m>!CEzE)WIi*3UX1z(XXC5ayEEc*%a{{?`+ z4KD$fzla`5^dHH@L5gDDKlr%)7uknp_rl8KT=B@S9JAWkYV@(6p%nxl*nvSn{uMYfw^b+--}_T2W^T_b>x<)+6}Mv`a>4hNzMlUpXr=1vyk;-c zX~rwptUDwA3`|JiCF!^l60w{60rOG0K~Pl zoypr`FMj24dKe(2({<4lM*>k|I_yuTeQi1Gqv(7MkB+L&R8i(V@HaP|_aC6-D zS~hVZ0G}x0V6Qf}je5TZHQauDW$!MJUUBIbL389Br@QO8w)P3f+IEHP6&i6caGzST zxK0v;GLA~8ajzuIAKuhruFeX7hCwf?r^a;c7!Hm=RoOok^gOm^QY*2?fY>h*^a!dV z>YxMd4=x)e1}B1|=L_fd8{sq9^`kP54Rekrv1bBrt8|1%$yV4d_Zh3O>)ajss^DS9ZHWCA> zRWSb{yX*YcmV}IvSaL-vvPGq&j4N~J-$IBmHCipOO@G}`JwE*0Z!qpd*VfgxejA~8 z;Amhe0+c49cU)uBiSBQKl~Vq zkOb(xi9h^4-8L!bES#4*%nctY%?_e7H(bN2<7zp+U(YYN;0kyw6rH)u^oWG--*-68 zF&-VSzGLnsl>B3Hf9r2xx+le(j;~=a^&i)M3kKX>$*+Wt6jP(l5_i7dW}lv3IDpF9 zK~>T}xPd6ja*_avsAO2NG#9YHgdm|-4`8hwf>yI3T#Q%}YYHIiyhX&pB^_GVH+5Pa zHEeQustgZMv6y|sV$g2DU=w&G$o+8K`^IG7v}7UjOMHBFjSg?#7rW^C!+A>JUjYl? zzqCgUO&Y2=?8$y#tQSLj1Rnx90k!V<>X3VOLpXzGk~xP4s-xgFB@7$)Nk8-8Vhkz; zDa-tL4udBQ+Z#pmSdE$bX1 z7F~L9m5vfh@c%xOzu$oAp8S%IC3MgK&%^0X77`YQdIHW~m(%LWg1!Qdj*eBH*S5x{ zra8g^@H^wV2*J%;G6 zSv}M0dZe{cFJ%%5yfa>#AkUP&4**hJfKnB=8lz@y2T9+tCy*WkvE@PAGQhT!f%5&osD{ZC)rfJY z3Eyf$bUD;NW{Zc~MxLeX`)HMLp6=A5lq=qwY|oEI%2T^odNMHz=a6i+ELwlp`?B{;v#vpThH!zVG>0J%{ z#(ciESc&-DhQaP;P8OV#@kXj$92CC;RaQfW4@tyTk37`{m*|KlNH8KG+K4SJZjy6se z4rESkm%Eb)M!gZ87KIsjuC-(NGD+*L*UMd8D_%xJ*hhrU69%oopg;Q_3BLz>T>R~2 zn^QPD@wU2v;+Z`hnz0bsB6EK*pPQbHl$7w{d|hN~;I#wI3&*OtrsjhS6_=0~1u^0!yvz_cHkjlr=5= z+yyD26!P=4eU6vSV=`>`lA4!}l11Vnlm!hNdxk3jHm60(nk^6CYW2wekR{+S-4@0k zoTYwRlWc>6pL1EF+EAJYE7z*q?dakTI+1T6=@0?cK$XD@-P$OC`k;3Z{Cp$LK$6fA zSF8(Nc|;v$^BqlFLf7$rL#X;pZ{jt)aEGI=TC1%s}W(e?+%gHdz3ud3Vsq>#V! zi%|XxAeZEmaB^t=S!s$QfZ~~d044*t(p^LeNtwyLPK3u&raz9qkC6vEi!+bXBqp<4 zU|CL=m~gB6TzxldTi<;1^)p5W=I)CDA4PqPft_ymS)C6F`xnF|==*oT+l;lh*7Kwv z77bV&EuHi7HtKdsGCzHS4ddQp9Vi~&L3JNw{6bJhqmO8^o$iEA=6#_g>ZO?Z9S#kL zsn&8D`Fh#2a*c&F45)f6n{)5N->qNU!=jP<-m}^^tij)(_K{~dSq!lvzu1W&>PMFt z!x(nK{45HEthm@&?RHSzhq}F>C@!%HtgFC!_<6eD*x`D+nY59gqD^V6b1*!XgzPyrcQCy}fu|C@)s7=i4JFEj>1} z&k+by{o2QJL_y>VYEFmR7@%OdAVCY$t6&`v!AQv3dm2am9o#MR@2k*Tg&=ZPCJ6)z zW;Bh@7~CJY>^(lB_$tW0ovAW#TMs6VNshrd_oh-qbs_y9>@^e-z>m-Ul@fsO`}7h@ zcqJ6##&bO`Ja6ku z3Gt!p29F@}Yp@yI<(OBZmm$y5!`?u@Z}5lLO)`Xkm4kNfLCWjO{*#bq!iC#E*t{}a zkp!ky;g#7)xLy0hRm>Mc!gMF^*$SPIA*Tu>p6^*MGw-382SY6~ct7+4DK+A{kvhc! zJiZ!0SR<-Yqs7A8_e}8KzMqIuVXVX5W6`0HFiC$UxvqzuXHP4mj&{gxzx)fj#RxAT z_yXb=*=ND(XM9;olkRhePZA5DWD&7z`MqBzlUni0@QiKbIz!Q%OfC)_*^0=q)69cK z!@+wWgt>^a^XZ||_hCQg5e|#}t&#kS&)uQ;6;3Ll`=~W)kH!#zA%|&&l#I-ID^B^F zVU%~D)Y%uV08nsu82{s|=gVWL?6(Nie5UXQy%8xY4t+H-F?P|gF~-fifJmaa zyz)MZnLu3F#2gVu4VPYecU%42x8!jMRO76hWj&4vU%m6>p3!UHTR7j5VX>?U z3tLmmNw^q(U1j?b=e#yD92sNBP8oF?RGruPW%` zlPO3F&8&91nJ;o17Zg&__Fv;kG&DE0`~!LabOhl0AONnhZbUML{HNc9et?b;7%|^0 z7|%We_Lacp)_yo%Ub?}G))QcX=FUacp98EQtQm~%$P4)eq7B=fJcW78#W^* znrDw@gI&C^0ETJ5fNdLqV3EMyBqSW9YMIxsn8t)~W^ zsSsinhEGsDzgOFD{(WdhQORndo{^@4C31*n%-+zMlZ!OqJuvjK%rhZ)yt7lQ!`!-pIk8P2{)c2U9p@{PA9uhElOOuM^Gv=dbB%~%l_3!v`(&X4 zLavDxBZ;sm`)pABtv++t?Nhs%XqkbgxH!CR>!n(N)L`O$30g4QA+Qkjbkz58(!Px& zl7U7U0IVN61{E@RrtQ4|<}!;jTb@CwU>fKY1*R>@*7vt6l}Ta>nbOIGbZXuJK;>eX zqiw{!=ag=A=SJq#ZyL%A&=7)ix#3W(@gv`x5e#R#*sioKslS{>W%Glrscic>fFb=p zvfZf?;`VKkxKW)SK&`7D23kx_JI`AHT-rAI{H3|uPIgE{>m+-{X)Kilkv~g?)MxXl zBFvpy@1w?Tvd_M6J>}bPx6*psY&DB~Bs}HS1J!F6#Ip%zD=dsZY$m7^y;o0`3o?X$ z{E;ai3k;%!qppSN40S(@3P=p|qy0Q(x;@jU#vDnYmP>^|AfWd9v+&s1p!09+ zBQ`T~FIv+RU^?zjbK6`_2oX2@&4@*HTA4^&-!>c7KI@gQ*FTk(f(-80eyAeb)m-n*aM!+y%5##oZ7^(m#c7a1plt zJ9D1V@zdB|2DpeHwvjEicCe%+5`f$kE+Q+zFOF8qupdX&8nhr&Lg#^NsyY=4=dgw1#)Tdn-XRlz#faaYXQ=%-KlS7$hfRwG|AZ= zwTkGirf+yC*z)-^WGtKwO=>;FJ?n|!&;cL_K7Pq_q5n#ky7vw zlevBxfmnOX&f`M84cl8{9Ia&WZCe#YgVrb&VVE8y=VY@b_Au)?cpeLc*I|+#mwTH@ zDgLqhv>jEcD#D_*vps77fb-eGup-Kcr4^wl)HnU0U%0Bj_BBYjCN_eY3;k)*u(C;l z+F8nGGF*Emy1tF*8Ym2a`vXt-&nAafHp&uOc;kTj@xc zJij{Z+Tq6PPk>%6JSB!Y!4~&1?7y!YqSV3%3A&I#~^>IOGi5>(&s4njqr0=7xNLmOpc2DqvQiV zLz*M~LAaYW@+CV0Gl&pwiJgagGIq{3fgX$$O&nM6fZo)(j1t;+kV$)*LYVr5*kd^(JR+XEg~;!;W#1WSUK>)!>5r^#-Qu9K zPDV@v2|#})Qp>inN1Y?1WEaBk`{+f*Chd+F{)RLPLW$?})83u*W4*%xL2Fiu#Q+;J zboqX!{MpRG+pR`m{<*hxd`P?N_7u=_a)Iu1;Zn2q#z%K@wn$IT8vJBD6wd4`_PaZI zfTJ0_uaSDQHf*JI@r}cj=$g>90nvDotuZ=Pd>l4Q$|Eqe>f6I0-Mcl-b+)jjCxkVq z`fZODeSNAlxFF%+ljHE5ybt|OdP69uq%?h4 z3|mHeY+yf#Q0AfhwXo<6(ksY&*LqmA1V?9jyWG+M2slg5PP3Irru`1xce#~VJt^@y zrXT%CaO7HM@~>+I&?Ly(aEubv2gM?S{)C)_qSBrt;$Jn#jpeD}JCh5L1T=k+zz*~L zk0#~+h|XXjDnn9~beDM!OIH#KeS%ZkUokV2nqD zkPgX5K<~H+zi$JSlP-%)^q5|=N82xJ@5uXOmpz0{>CKm#I9w0r)@Gvs?G3oPMzG=M zUa9wHFgoepD+o;`m9yc|_nN{=#D$)#>I_^~o(X2nZrEuA>)W$UN;bhUg9~6=>1l>& z;WQKs{0&DJ8Glv|7S9eZt7qP${&Toy2zW#2)tsX2&Vf{+!sMLmRi`cR#D+d~B2E{u z=J-HRDQ1421GVZ#lQ69v$tHs?cq-|73wcU|pggPf9Lw0p*^jKy zjV?@)KoOmJFr*bdv9PPQkU?`k#Vqq9z#qnFdS_|iApuO0@)Oz;n* z9@>*$k3y7w#)D;(ixJ|fTSfD@rJ*eOw$Pm|?b+xC{|pn2;TF279m`>y3{xk4Web+$ zAS8K=&awp{0;fOX6@HF{!==SU*5caJnL{WduGviGRy#TDaJk@`nQBb=F2+RLz6@gD z0=^AI1voa5px2(9kpM3z2IPig%0e;E6_jcD*56cM6DygIkbrGVKlZ6^<2)V@P=R+^ z&_jzt1~72w1!Le}+mzT~Dxp<{jlNvBWxkf3%bdoZlvMv0XB0^AR#`3;;bu6&@8a{;!y-_Y_krPZh0lBmj%rsa72ZKBb!G$4}p3 zlBDyr((Ri=p+qFnCcc~paC?f6{2`m!NOuQVcEGEH;Bb*>v!MlL382Dmz;3IDFjy>h zU?!>&5|D2Z5#ckfs{ZB(CRdeB3v3Y~J8TV)Tm2FH)%uK<-KFYj2h1}+^w`dbug{Q0 z2$a%hKAXslfmg^Z1nB7p?R(iH$Je!L&DV;GuMW^7=6`J_>5(~B=!|u^);wfKMCAZI z!>71LpX|iXzNBFb!`z9%7mUAO-fPg+)zV<1rA4~jn}(sa%>resE4ydOAt2n}-Jv_x1pG@uJ&Cq|bM0*+TaUW>X55Nc0V^C1;h! z;m}|Rc%2rxMAizpijTQ85S#j`in>!|L&O%LG0UJQc>5zB7!D{8xPo|T_gIxHkI-dJ=(<2;@se0Fpca<9R})ct=bdkd(l z)9rm6X-SoC5C;%N=}r+akPs6BGPaO0coVW6jbUU(hbrLN=W_oaqgWv z`tuQR)0 z=cFMKk>EO&VlAC6dp7Br@#Y;Lrh7eSU-VpGG?UFLzmb4V9Lbi0R^R3jB9;qkNWfY5 zWnm3DAL{hyHxfI8M#z~G^Nv@xP?7vNvhGZlR`@WV;yteV-4Rn9j0lfD;llCq{MG}) zo3cXs^!MnBwMRh9>|NklFwnW`F}ry034mcDl2R%%CRIq;`k{xCg@@q6B(t3107F6a zR@_g*#nv#=1$3;yZrI=9jX60lYEz1S##2~GXh8V2-At?g7v~y?6dkm7!{%AfYKi!q zjg7g>`%f9Yw99SD->)WiVF$XsJS8I7L>jTd2E2EK1=vs_|$Uelej4v7ta#%US++hDxxj zlzv|Bq15{mL2!5o38}7pqX0wOY4O~lgT^vNmg{m{l#iROj7o8cp`7HrQupnyUI~X+ z8b0T9_@cEg18>yWjbkdq^LK}V7NEacyWuD0{2uJEfV!cO3(t&Fl#)%c+x?FMWZt-JsO zO0Yfb*JHpY&PXY7<(un@Ma&3Uzgu+Qp-%Hbd2=!C+ZpYpN_0FY&}ZZ0+u&2h=*aCD zZC;KSYI}9%fog{yqBw9>4ce_Q`Uu&7y`i@c8vqg6 zeWye$Lh5j%WztgV@%ngOwtDU>J=Gc{3+h<8%}pNZViD?lh`x7%!4L4L672Mnk{L@! z(IC{Ai{cH>##n8{bcnPG)!B{lk9pV{2@>vtKX%vG-QVanc=_|W3ioFzGf5fXu+|I| z>P-|9xa-8K`o#%c(*_O>`cORI4{BNpp57*A_w^58bo+2MU5*){kiCQLJ`sdYGN)~a zyYk4ua)*FfShSH}@+Aa);Fph=9 z@_ssE89&ePQ9$D=0hLai#@MCWY2%m7)=M`bcw?6r;@~yItZZqtzLpPabIWrS}+b> z8(~%62lys{d`6eCo8&0o;@c#Lp0gOgdnCPA=d#Z(cQ=9owT4l!6(xCJdZPmMah+=8cElJyB+0)jA5D?lNFG3;jOJ8ctkVex~NlKP1h=sZ50 zz3Oe}Q3nI)x$oARJIl0$Gl(71Z>inAd-zGL3I$}opZofw^SfB`ZR>FFii(tt@^)w# zbSm)}G-HP{NgY3TpkA#9`cSe>O}>$opDo4vScF3`FoR2{oCw&@-Q3St%#i7(fM#EN zDEPt`*WT@Gq=Lu5*C)2R=M8>O`lfdLNXid+C0^`+6oXFlfs^_N&Wq&u0TO9H0-?MUeqp4u7qOUi(0{q>5b9G3V{83yJ`MYXNCB1 z7Kt3-bS^q>P|Rkk3VD~Hwa%%P|w)pc`{*r!pbdZPP0`c{Te(KZE+|qfo!8%JS zwEP_xWHVQm2aH}q8w+R8bJzB_e1}9nENpvGh0*=F0WV&0*>$UHrq--F?A-byA)x** z((KPyUz##92dYwIB(jPBG;Nwxz;`ZZ1lN6N;3lj)!n16lL!W}{>|@s*W{Cpsrb<>ml-51h4r?Hc%4xT!ZsANDz-9H za&lpYAppMZr7iWQ#txCJ>@4LLP6KrNz3vdWX+Le&l^v*6XM72-WSf;7c9}l4F|jJT zFOE-JP`h;tO?KCt@GJ-PiPWAylZa27R(GY@>IC2+7${m|t9+@#gBuZcbV2@!4HPPa zxV^ERKG&$S^wtz)QH@SNz=-{N=;@LW)agn;5+8unTI| zs-JfT_a!=Wng#a#OzAg7?^=aqAPu(XI?)`n&BLc+-hOwowTe%Rq*~!LpXC>aJKtZr zt3#Y@txW6q2E4<%bp{f`q@O|H_W&R5kHN=yck;}Q4VC7>k+(}|>B18Cr|80nJ~>ol zUf^MEXPxos`+2%Smu}yVoPB)(xi!R#(b0ZL>yuw*k*ey4`($MQnJ-GP3WrmL8+iGbjO<85x4Am4&CUfno2} z>;v#QuwvY;eOD~$L5tldK;|g=3mzwVzlP@&~9e5xlxKm)7lPo`{a zzlWkEmcc5Ky>5{dFM;$c8G(kn2WaKX{m<_LF1<<{Y>p3OyAN?)X#>JM)Qj-9vy30v z!_84ahXVgksK&>v~i>UmXn?RRSB_cc`a$9PYIgM&vxFt*=IF1aD09gXgKjHda-*%t{%QlHWU zSATGSyZeJyHF*W7%%j@WF1Fc|f&f+$w}@MU!TZY_KU3=(V$T}KH!qJ=)6uN`FMpWX zuyf*(Q~q?;80nM=uxyH%s?V;x1q}WiavG&1#?u+v*KGjcsqdZONw2ZRB7b%^sj znqSj)ZX7sn)d9cCpcxk#iMA%){{)E@I?Z3>%lwU5r7Jix$_zg*NgW)rTzZq+q2`X@pJWlUqf_JJzpNTeeop{p@f-O zLQy4z8^2O)IP)Ymn!*v@cX=E*uF`h=FdK$Bg~5Om4@9UVE!#pMy*PMSIja8fKd(0j z2gc;c%8{64;sr5qj*+ADJm|971<}L$NA`558t2LRD@rAI0ZTk-N^p4D`@1hrW4F{y>Wg!Zg&DrMN*r^pNm!E!U+#G%#|6!= z)sh`S*jz5lY=yG>59;doALtD*)n!n&5FL#`;}d>!tL6D{nI#^VvO>nyhQo7?1cwkz z!@j*zbhwEZ0AtB%lp;aHBL~8mF#OMOPdPfS0xI$x^hyX9i4|_>gX)S#~ zYg*_=gum+F#d_c~kE)smsHJIZw!PSCS)*kr@@xX6j3BI#)hK?-r!I_Z9c*AcfViPUFNeQ*X>fE3lU!NIzB(-Nkp=)bgk7}X)t)yC+4 zxl45Ua-!Fd#ekzJk;1n9E{;!*<5QLP1wv-1#@G=@YdXQl)Q}5XbTFZ{ZQofNKP-nf zS`QECc{B7gG6oNV3L_9cr$ck4M}Y}P&%v-(Z;SAHE>sPpEi^adc4c}i1GbabzM#7t zU?NzN5OK>LsO$vcmqMhh{ynia8>wtD$E^}zvet1G|Kekb{rX+9gxfB!T%;x`dJMvslAK$gk)vS5Kh@3ossaU*gf3ir{; z2&5#9h~W2$lECxTR)nn*0&GenIkH_fQL5t2F7`mYm|7^yil<%VEI+^^Lah_xnVah@ z$48GSys&EuJQ*3@5E1u`?>5gC{0ZY$Sv{??qHki)4JX7Iuf60+**v)dhVNa_M0Eb?BV~NhR)b^-$1MmJdR>iAyC-o)YDAaclw_wXA%GnWCPtR?OVisAC6+Nf zl3)1F^YU&qkGZ7l4HQI|OIcL@dKS<@ED5xXcxQWiB1yCypQoqSlcl$uOQL6TTVQF( zu0(W|iEZ|#rYNO`uH6cdC7{XENJb*UjQ|&kn(}y<42Ec3w*FbY^%B8OXRs6w1?}Bs{moC%V-YxmmOx);RSJs~hir2nc~sFaTZ}P} zFej%ZqUFbjnNDcf$pl~H8co}-AE~5t2qo7witlyGS(>85iYby~JtCoRJ9voat}kbw zqX3ar_Dk%AGm3a3z35RQGvibjOT;D~xQsc;f3;^9G-@R>>Mo53*k~7+*vX0rF^bZ- z?_0^8?lI;}UVAKEAmm}c<9N^CeHpFHNx$4c^tv(6yf?FTz5f6^DeIy>(VXr_MT)q% zILS@iB%TVZk-2Q*De_>zKjc!;qCNq!7egHX%7bV~OD?~^oH&xH8r!~dx`&rQ;$jZ} zYEEuJbHmAz&5S_3DJ?^gNJM*y89pt?yR@i!bI|JZzH5x+C-A%YL%`~NFa^uAIuq^S zyHzo<|BA%F7fqy^s59MGGl}-+%@+Fe>44?=n&21tsgayeaH_xvE_C&*D4aL2jdlRSHd@r*>g<3tBjEy!R6ADfI{eBOCx z?aRGHeve9J)R`I$hRPSb{O{tQ9O@SS+-nk8yPa_&WFjDN7Ad4^bFH&|->ver@5MO` z9Sn~biJ@)1pEo|$?WTEGSR3@EHvfKS|K;zW-a5AWm5YPQS;CgsOSWv7th2pm>uMLm zLd!cIpUd1l3H{NXN9-71p~EfXH@3)jPmHE2{yV&ON~lS`QDn7b2;6rQ9c{RqowQ9%@T5l0&pZX&p+$ zqLlBn-0v@Yu0-hRTXgOjxMS7Xe|Cv}+f#H|e7l1WX)A~3#U$`ir($Wm6^)$Fi)P4w z;uxKl=;l}3n9uN9>lw|>r@VoZPE9K71X@v;x@RJYrv+=>T%&jfP&6N%Pks7XpDA*(riSzMxu|X5=*_L6X&_KW{7Hxb)>TTA~@O z;?v@)AVZ8J(xLI5$dtbz8YWl7B(QMN`r>xsS+WU~8$k+rHVkRjUHTp1>Zz5IZjzw* z?#VDZp&c@ICUY6tyg5hE25EIHwovfDa~Kgmm4r`w34$ePV=&Eu4y8F}6E^XQU6rloeOe{S@Apcr2Dilg)<6lHQSiVNTXIzY@yN> zNLy$)!K*Yd{$wUX%9rNcLf)e?!mG8YClawRTN(oz#CGb&N=%ho&OYs8%j`K__^{6H zLw9%EP4*;gd8Tq&h7IbY2@7&ImC&Z_5@4ZAH)S{(KB28p(b{Nv)qWAzE#pL(DpIc& z7uWQaGP~2&)m7i|POjR8cBjS9?`^eG1O2`OnbQ{N)>#g!<+j#6H zb-L50l5FHeo>~$oP|dx3OIg|FYqs9_i&VaB2|78~v(*!>^GULEB=1=q-7=`3DP4jT zQT`-`O9%IrUZriS9+@yB7&-HNCdK0mPjX6J#NYjNsc;h1PeMvli3a4h{cyNZsmsxzP@C)PfK4Sz0^?etPROCk3HLb?_>)OPe{?rw7{IMVDz+* zudg{658CyPr#080pfxOBe}84NhE~qG*?tzFLCsB!wp9TG0ISg+vhK)>p*J8Ft1CoYiB5%X2~NRzM%*DL;l~Oh?|R zWzmwHG(Dbv7lhmn?z<*;iv6nSsrXhAX?B(_33Sm$ysz6O&1!!;YFwTW6uhVE6kJsJ-Lp9R;rY+rhc)q446f5*)x zQCS}5UGH8-*RN+sA$1J@!KlQt>{+3af8W0nVJJs%V)j_7QVts}`Sj#ldF=bp9RotQ%?`gSnblnFxZ<=XGm%v;-j$vjEs! z3yV4OG$EUE2v&D&UomP4ASKnNc$P_yud4WNzhz#bU|YJ?R5{pM(MTSXfH%K&-h$v% zo_4)(4Depxe4IodJPJ5#adV66spl)JdAOuKZswy%`NJsuL5g=?|k-~yD8!ZJS1 zN6Ii!Qc`kMAQ#yKbA~(%?N+z;Bh$w9TP1?KZFOxl#6H74(YXj>uj1HVP$@&bX?Gbe zp1s6wcfx@>bET&SJ46oT^4w>9%!~EO?A1yrY@rHtt02H|y*fG3FiTUyylHcYF10CU z>Ww;g^gW~8gZFo-PrTA&KL9S=NJMwFes7v3OWu9L;j_kHx+(*)Fv-QaqhyONlb#dD zrq9^ICU(ipGz^5Sr|D~f*PU!@U;q6H?}$#wc*1=#>AP1xMmv6xz=&;dw!emXoc!{s z3!@vppW9AeMxAQOKYh-n9v!qb&em(FKYJA2MKl{X<{J8Fu~AyVe`^J3b%D18gZbhzSkGw4b+lGf z0~nh@tj%bz!Rw9zvnvR=S7G3m&{Gn`Wkwug1g`=2$g@5JE^2&&a|_~Tv<%nsyF7Nb z7xHdNYNSUoBn2(3Xe1A@x|Ccld~b>Smaj_~+;?JI1D8RWRKkNN8+W7|Y$=?D);09` zHG+~aG?Zscmc1ZT)`44|@<-w6V(mi1#45;1kixI{B$Yl6eDnIAc`$Z;pj zuJ`7P^8~>c6RC$bj%{ce_FVPg&?=#N_b*>dZH7jfP+s!$pZ8OIZ`8aGK_b#fgSGR! z4WZJkV>w6swWzD(d`Gzf1vmH189q|&&YxnM=8swK7F=J@uiU*7`6fte(QEdl@0d+7M~`L+nf^!0<;E}ggfWS z+~xT!#rE>Xfb5bgUV+>WffixR2GdqH^svMoP=_5E3DN`y<+s+WezTy6v>m%k-FfuU zdNhTDJe5o$Vbp2d(#q$A?au9ovw26xn1|y347fWp;23`53T&c zNDd5A;~q+2z9$G{>OTFs&+;A5DNFeP=^@7H%Ecaw``j`u4G*r2#=Y`SWtC^neNcmp zqfhU<(qCiMPI*|We~RE_4@+A_ME^-Zp4mecr#5255}VncT^If1WC^-~x!I|`7w2Gn zX(WCj3pqb`?P$hR?9uz_xZ~b?2B&G8WwSs3ab5lKLthw_oQ)GF$1W}Aek2~^3k#GV zhImn<$n;Est@8{Da~*MHwzNOh?*2G6B0;_%9iWON6vc>Z<*0W2aQns$d=V=ek%9O- zzU(jA&5$>IhfXOP-SZX|5DhYEclZOP-Ue3q9_z9+bBKZrR?@6+0Wc6->Dx5kxb3_K zt5ghwdD;}hlI}Yzr{h;ypCb|5OTbv17AbJ_O?TjAjYyEklh~@DOULP*>WU9~>d;JU zP*qFF%PHI~#BiYXYMMe+xE;+v<00@EpI|`28KY-Lik>=kMM9G4jWXlS@rX^sYE0E)^>P7v9K+cS-c5k-W~gb< z!m(XT_My#(w@lr-7)-9FaYr5*uwnKJGjUiHOWg*7tti>7AfzSEG*N+EUn#D+P?VH9 zWk1$x5eNeAIh+#2>R8RdhYO9Sj38}vcs9BxZfQbXQtoGnnQTOxvdeJ>-^8P9PE;_= zkZyT@ZW)lp9U?jp!PiWU3;xxRuG`sR9H>d8is;%kGO%NDwPx_Jm=pu}^YF_ln z4)pW7Jm**mAb0m-@J8@_IeZ70b4TO;`ny+Be7psI`jZB;o-`aSe?zJ@irNO9Fhg^K zv=vG#L8Spd?JhW4-4q^_JnJpuG4vO^xaABkw;b@4Fr!7%xOBk+AN|u5dMlYW;}O_P zaKws!$8rk)gylfb=SykkNWbr8w}$h#;u#cC8~l83nVHky_`0!6JVlQRF24u_fbv4; zCv{CHGX6teZ^`nGq>$SV4t5@PJcrw_HIj>g5!?!mzW>uE@sFc}{^1Ne+$qA2%nKe< z@9dIHKL@ohiFcWGJCYC@Be01dR6Ft{$|h2$FYs{|fCfU}>CB}vsp_x9*ngwZk=*#6ac)$AwzfC{?Fs|2sZyR+ar2(^h(+jq^oSv!LkQwp z3L39U21OmE4dsb@sSTpfdaas7C@PsI0dqaJscY)#*uM|tk*7LZD*I&XBRfMkAqAQw zAH}Yu;=PTLK7q$8DosgFPJN!crpI+1)Cb$`()w3r4KR~l=PR|D(D0RDJR{BQF;6fQ z5j7J#%fBH$9`Yo)&#pHwV%7BN;^^q8>~QzNpqjG8qd=iF^UzU74#JixUw6zDmy7(| zVGixd5*=@lh-NGT`#hSnE1t&JolMq>XmPTr9yqEtigcSAie4;Pla>$IO|Y)MxS(Q7 zqH?dr^nOQN3GYs<$ zZm#RSsxUbh{0xa$jhOq7>K9Er!Jq6j?BHOZt+(P&7P@q*F2^Df6TYMIFAT9C7JJW~ z$z=r2<>;pU8Mf7y<|7bLdNA*NF# z5JNJUe70|>G&GcmmDZb?@Pe7XvAJk`z*|6X_RcFLJW4Wg=5FV!&g|R21i!uqxrkvz z%P{fe$RE1uEi%_VMX&L^Ef*NRnxqu>rpY>51_j>EK2v#yRMsjgpVJj0eEOjMwxia- z=?9^cRgKyr8d`?p`rGqf=qp~MG9NXk#J7|S)#}&=+y=Vx(f$bcu43BMeSZ}>#u4k& zt>hQk6DQFcq!OZyNquviQ@3cK?cf}1vzp3#cbbOlj+|!t5AqH`-O~s~*g}jG+aSkh znMkFC6@}8yEBO3{3IU$M49x;2Z2IJG_QV&+iw6{@@Kf$AAnzwv@{MB?ui&M8T)0pV z;?C!>3m(TH8luw<$J7?~#oa!HIQpD{K*dM3h2|*5!3EeOmRw}xGi_XsY#zQeE#>L$ zJ8j_%VJqtV!RHq$myI8&ebav+)e$J&L|oz@3!34^El1%@=JSJzBp1vkT|G>uMolzG z*jwxEQc}4&UPcNn&pp%}zi))CP;fJxSgup!6gQ3$0{c#Cft7bd8p#iIuE7er`|}c6 zonG?3n&RcqtAeG?O~b;g-`^MSK6Y`*1LY@R*$h~}%gg`0(fqL$n`8~9PEBEX&!6N=%@BoP z6Wa+gTZGFXt54IuI^JU~KiI5ixB9mhU?Tj~vu6wUZ_Yy)i*}s+@{=t64}yaR zaahq3#o*$Th4hFdqd{9Qso1$%cMI>*vUqG%Sg<>7VN%bE=;P zfXQ*R8lt!7EHoKwSd)+H4=@2^!BNc}cGh$e!?FS#MFs)SVIg^e=1{2X_|SqT@(M~~MYl`6h8Jqsv9LROmAWi6&bXOJRIy>})1^Jw9>o@YoUCGJ*R?w? zJ4~OHxUg@iM(-ZCNtv3wWxsG?1-Wtx`??JIb2;Gd&*t6F?bmrfJe%{~xp2U3WTaYS zlLOfrW|4y0Q3^du~><>~(kF4*5C56~pug%cgXHd+D?2(((RfP2= zqijMrS8Fv+HMd$QPgLyETJ}(z6-nv{VC0_PXr;5!H@H?4bJ;9DKK>JQ*ZV2AG{AEC z5pDx;!j96P7mJjl3hTTnn=*3#5nu7aC?>w(u8E=4B}xuz9z$%1%A{AC%Qh@!^Vd>@ z@@~bd6Ixo7q>Mnz?pu>xwEpbC!Ld>RKBx^W6`q48o#}v2LtC2$Msy9PXmd&bfRw>7 zx|7yIqpErBY%aYyk5MGs}?9<7TjLpl57;D?vjTz(ZE6ur}JRqnMq^vCr+@9lqm z?0cMCn2Sz~+0 zY2X2s?xcD}S%9=3mtk@7;5BI-V+-Zoa@PtRN2e5hiwOl>yvMbjr};gAPA8RIEP1mU zZ&}bp+4WS%6XD<7+&p=$;e&}XZa5J;|Eyd2WH%;tBt*f-JjLZhbaJ!7x>X!{h z_1Kq`XxCU!jE~jO#K*KLBU0JZS*uMF2p!9%Tl$IVK4_Qt$KjFk=GP`V4C~f9UC~lY zZQ?9%eaC@9iROuhzytkf0pUkS<5M`a$0sYpQ5^ZcXuF7T_fH9QW*77t%D68=1$ zif|inffyv?TE?Y{$3i7aqvt9!tlTWVV|C{=zZSDmqtB^35|2uD#QF#0ozAabhKHII z#=b0VLSfe2nf$8Oq%(d-IEo|^w%K1F_+OiEINwLzHIPX3Oa6}jgwWm9RM-XQ=A zGX$L6yrJJUT4l_MLRs5H?hJ2sQJSGmHAPZ9n!k7+#A@9C^wn9^j)1?kH%P7G&l?*3 zn^tBv2dH{Z$EXw}DlM&cY$p8hK0Pl(P2^HSX(o#|UOam7S4I zoVP=1_%bi{ep&GZ;_V&$L%e4q$V za7z9D%Zs^y;=#@fmK{UNUdNw)VdLSqL@L?HxZj6Yg!6H>aVET_n~W?@!sUu=0I}Fb z${dvK-NE$fv?MN6kx@IPeShJ6qJ+C}VaC%%RUX35^`}QaRB^>;>^B)I5^zYx8~06< z`VPq!@&AYc|6Uwv)3YkbQ(k*5Ok2Q{eTlb^XlnuVx*c9aSGH=puR1x%5{h?ON1!{R z8Q>9%aSLl?YGq~Y*RNmYZ7Lv&rZ62XCf zk5*#lIS4(P_fL*z2t)V_jX&{&%Iz|>bI{{*+Y?YOn1bWbAbmzg#u+*~9m^CLgPrFq zZ!89*YQe;q$NuYwOhvVlUF{EaF_vnX$5vR9DwSa_Zs4Ci4mBOXw(BQ*OgP->XbhVuaTl5)#*^WZHEc zP=)zq*sikE?#WDQKqW*$XVHYE@?V#{G)UT%lz&hSX_e{{9i2v81~p7H$h|@UH0Kw^ zv!XCVw@&zlh_!IBviivekO&Mnd|*iSK6Wjrnv0LGpe5k<_@1jb3+9s9LpDFYEna?D zTd6%@(bd&MX;u_WB)AKtdG@34;4hi3@#J+XkGv7GDaTa{gY|740JKfd8ZFQlL7I#{ z%n&Zise9MfwhfZMeuC+~)p@`bJG;GhO71s!ua8!3XKxtrhbnub_x3-$I`|MB<{T_y z5s^Hdx_AOY{;zYKs54^~cXM|NdU0r-SI?XFvMG(ceYPkk*I}*RSuPRxEG=)koh!UW zhg7OV5r=lz8PieV*KKL0hnXaS+5rEl*c1TM1fu5btI(NI0=Y?%-;zJJ(!FQ?aIe4E z-<}`%)=TO3Dn=)D1X!ArQ*e9K@7AqvqGU8=-(hw;3Tn zOq2+O{ytTkcUW++%3$x?7cZ6{Am!>D=;ylPd&HruXW<#-&h|$U* zWg^!PQeYQJhjhxhjeFTl$SLhzna><0Ny?L+V2)zf9&NOA&`Q-mh>%N)`P*V8svx=; z&Cs4Jpm8t=+e{R3&??fGiRxqm&p-6(?_cpwgCt`Qq-s|S`wBrJR1G~4U+cYAE%jzV zH(EH4fLd8pwoJ6V6BU*|=AK2cF8(*_;Da1V%=AoU+Cvb?!n~ zxI|{0w@Y?H;94gZ8g1-VmU_VF50kOJ#Lu+ino>wDjm!3&F)NY|#W8{l^U3iSHI0RP zKX=(Td@UT@TsC8h=a_e%Y~6**!B72J0eDg@&^&cJ|KDCpsTiUf;m!h^xnircezpE!?HT({ah2`pq3bLsnGC5hv&d#p$7#jSzC%_dq!7+bsjob?1 z55~5eKrw$IYN7ln2{Ma2w68j&a1>S+St7Y;F^QdWgS2MDfO-?G+PWTvQ5pryhR`@y zG*Pj#8vtxQ6XEyS`FW!TDEnUH!@|2@0AuZm2^`zd#D=)EH(z+s|}x3e~;vt7mY;~4UYiR>b-A1Po7 zf%Z1a_cSsx+H|Y?&UgakCa>GKh5ISmX3QcYRXxi?Bml=ef@VvB1Eo0LXOG%n2`mo6 z9OdI|xqWnw`xLE+cLj?fi!KQ$R)O*fWa$0ky!blC@KgjeIp9U*?MX{~mix-u~ zUG)A$bk29(atVmppGk0Dxld-cFcej9)aJZLK)mDq?$3u+9XiJjRFeLF>m=GD!r_i< z^ufVvUImx8d6?2I;};G{+ga#@a_*dmRz#vJ!;%_=*qG>clqR{EI=AoV#l&j**PtWW zaq;tPwpuAaN?-k4{lVCJzi1&2J)3f}N5^qJBr3XI`?CtG4iKE-c4-DJr|NR-+~rbl z^ldCZ)nDVXu5X)B|9-tZc7pPIK!SQ2dVrQ)qDI|G0%_c>HpVTPrE;Gnxg&41HX_DY%?b%v_#ZL-9oDZ;W z+m?ti29*LxndU$^jW1a|K{<~$3emM~!YK>)29N7v?{9e{_u;ioK2^WPap_X7h!enH z+Lg8}z&;o5&UwNK*xQO}pcij#rUSH2qtmO6fPYYFVy{(b4>AL-P(=W)v<~d!y*~L- zcrp!!e2@H$jz21UHN*c&MPH&`zSmdi^&Wz~#ZHC$N)sMa-tJyG5kFd`PJOSq@kXU~ z^b7Cf?UY0?L?X5ysXKsL{f&m!!WT8=M-Ussa3$_LkT_lWHKX}uC)=J!UuCk^N+in~ zg_(u}SN!MZw$yNFmELikiJs4ch`k^)VK*aO;)e%G)UaGv=AFdyM})m0!Lba{C7(-` zw4-CPe01moDj2+Ecfg_A6)qc?I=L3fDx2jw0= zMyEOX%i7U|gsxgo-u-y`#ulqb%OD$k)3O3hUs!8F)e=}SiDYpTBi~v)PO{gOSpT=#DI}739T>T ziYH@0SHgd~Wd8PJnhZKm9vaGfP)A#cL%X#_ZWicIml^g0wTMYPQW3Sim=!uy?6>&- zeTN0>e1CoDQK1FSM(K=g!pugiEU6s=uIkRb?O&HzTH)M+8NweV=Yglm*ytUC^O}8d zu$nus5$NrI(u^0#hlVoA%H@%yZVDXQ*c*h z_3Hn6Rd3q;`NOss+nW}wpE;GgWWTvk6*8-S;pZ;oAc+@YMF`|nZ)q_baX!>2dGZvge*OQTDSj5iOI>t89EO~}9#_E1Q zM6CxZV5sm~CkSr`R;2xsdO7bM!o5rqE+!?_a8rs>!tL86_@8|R4^KjkP_w+aRCT$) zJjb)HiaL0-E5nyG@+JxO_O5Z`+vk~3NYw9l+Ss2Q?HWZ>=V@=e%hAaL8hiEK{zw32%*kktQ4y>xX>T7vmitq z=3j_-?A@dZ!u5y?@0{}pKKl< z#7SD~ZYyW7{^b|^T-+o%BrD`AYk7vgTwg12X3Lo;eDUETo(|>fnzYnApp9Z@I_hRB zw>^Ryl@$cthT!=_PELM?j7+vWSwaMy)vCbkwQ{X`dExWxcGZeDpo8{OPWG7~GRwo5 z8JLIyX=pGMfRM)wVDH+55fDehth*@XCtxk)NBEhPUieI2ras{kNC>Iv(E}U0-vyCb zl4w^uUhK^}IhofQ6oz302_Cs4m3f#=;7doQOOz55LsgqOBP>H!vj&>aN)Xl-Gt0sK z64h-bwl-E114ae`Aa_g1%e$QCdmS`7ej)Q*^tKb8y8_D|PA=9;&-^!vXJ=>8eVC^; zhPc;35I(tka8ntiY#UP@u{?fPz4zORsJSPz>*K=4$k1)mLqkJNpNPS1h+z2eE4$R2 zp%deKW`Qetov+o~iZ~es@dOJgw+|6k{5!3@(0i&#)n z=jEZ!q{8Xb9TGt&%4yQF3N<6~lF4Xjt=a%f#Im1zdr~GdI>te%_f49GG7fE;h3FTW zUqhK0DJFve3dOiGQXK)^r~1Ho2*j*TG)RF~!hG3!!R>Da#NQq*kQ4C(leoWW0z)b= zVjhq-VRKTiyGWKC>uAAMMN>ll#}6yQ6Z>+j_}K&AP*9W(#N$p$w`^MrP3%6omzsLV z+rp9OZ;us&320!uxmbac6d1#T=^%pu&}CwRTIMqU9q#!f1SDw#K+`3D&?B~kejlYK z#3D@I9ksFnu}j~1+1#?`VkL6lpeCKS{bH#f)~-utMpzbZhB}L${s%Mlacnl!rmOzCM_11$w5H;j)m*%1U`<^}Bbk zK{Z)CV0*Bga?)`}Xza^E@vzK)#l!x1K@8f+ROuEQ1QXi@ZqqegG$Y$SYvJHOy7IWc z;Qlk0U2Ffj*-bTlvxMDiRN^$4Xf)Dm_SRd?yvf$)Yiye8k*>TbovCA5e3S zEKa~(5D-&VHnz-88ger;hpp@?eb{Vy`x~-vCHH(rAhzi~xO0*n7c}Q|9pOLcYHstl zrNV&cFHF#f`~%7$F@dCVZ~n4dgy?k+pP?6^PU%J?knMn*Jy8cE$fb z6J`xW=`X~I1sZ+Bw8E0}=o zz~h@)mV*Vt-*D2kBH<)FZ1x#+bpNQdTXp3B`@Xz^B*uoXjrCQd_8s(6iGVjQ2Nzeq zQ$HY$*s{b>TW3NaIXNZeTfi{T03&qP-?yCT=uiZSsobqww=V4{X1(}hL;Sa|Bz-_G ztbv?rJAGOgDJ^@DIOsgS3`c5ja?C}f$U}rwL(`#PLfQRj;xUs7#vvb@f6BYI?NPpN z+wqK>liM;*-{%V>b-ucLoy;E$=B^qQ{)8w065kNvSJ0oFFa@tY2?WvcZ{NN(aq;@_ zoCWRGLqsQ-H`KO-@wcV>+mkz9N8n-+hqpwKkx`f}1V)XMw0_aXBt}SMfUn7ePfd^7 z_l%euGo*cDow*ghI~CIkW7pDy8^_0whu>39jF-MGwn@d?Rx6Y~ zYMtVh@UciwHy1KeYW3vL3_ZM=k~u+KLB{hm{CB**u{jTT%dR_UH5M-02}Z3W`hI1#G#Yaqi!dt66~O+s6tDQ3tHuWMH7td6u|?~wvZT%@Pb;bo z0_WBS!dnDZO(gqNf7#}%U)MX8n2`;?Em=qZvQGc>)c5t!`zXp<2vX~>E8E>!-X?5N z55h*3Z0H*Fkv2We|1u^fDmwaoq|@?^q0%5G4NbnBBwX5HAJ4}2#-%F{2761`8@#t} zvMD9!9n{tlJZ(Am{TW*`1?!Ukg>WJLo`+#yevP7B6e`Hn*S?|;|MxyWXV#5AHS0lzM74N_6d!IXXDKvz9WF(9e_aV86I%<* zi7ZR@!Ep_z@WH)*azg-%l6a^~*XV?cnOA75dEh4~zP1 zQ77Go{w6bBR_=`2@TSPW&X+uzk*~HH`?PqlWA}QZ`_1a(=`Dm)V=yY$X=0#8NS#%F zBMOgkvZJKS!j$!{i&&ksv3@i6eLiUenUD`> zZuVq&b?!Lhg1l1Fr;BlM8JU?t8h6cCOE@(^%-eeVR;$?YViYO8zLM(M@^1~6VzJo- z$TLqUo{$O?DdJ{gjv(q}{hv#?@>Y26)`U`vyk!Wz@c?36+I?pF=YcE6dlK%%cvn~_ za>bBj#SITC)&z9YrBo$omJQqgktFG9{xCWlYQt| zD`xl9flp^+j>_|NjwH>{e9z{Zlcsiq6h=#NC%_{`1cNTXaj)n#`$kc=KeLi!m?HSejY- zT6Q6&*%J<)$W*mV4%C_V+XJdK{WO@wI5;@;qh%p?+GF?{kUlnh9!)CJ!uQCz9CWN? za3+oPd7cwz_%{>D<~Ll?`ic;zx;Lq^7M`_RrAF=0LX0lo#_QY_+Eu=g{=-fUSAz$h zdD?66f7kdW$8N#E`HB$`P|s~go*h0KQb8I7s+&;@DpJrovX;G(HpS;(8L5ep z9VwqW`ASxQ?`|{Ikp>=%X#CZCkt~FRgexR<_hVD(xG`ff>Ft}?t@i@3tdUvm@26t1 z{gb4k+O6xNVXjKlw{PDTs9(DME&o3EywMJ*5Zh5lQI-EgSQdWOND7}=TQNSp)h#&_ zn#1`cz}c&7b#5x-0U?3$M?~Yz6s={1)vWZDBJ83nEkYvfE0|ZXaZgb;JmDotc4@M>s`#ztUQEl2J#7EZ zxEAkmCn}&C*+oS5Ga_y?{Jo62fqaC%Jvx*X{;o^KZ}g_TJ;|>SHX0LU zyLXS9w{(J#ku>50+h@~eY_~@ypX=ORaA+N=%HpJjQAMThE7dyQlR*L{g8N+m=^{<~iwO3_;8UgfPB_)goR~QIu63?54|Gjl*k2EF|T| zEwu!d{F57&5doK9oW;e(><(Jhf0GM9B+O@qJmeDd68ZmSZ}ng*130we zabQ(_`C-Sm7w6cXCZ9X;hHu5j_W5X~WHB!8W(1=IAhK4svI&T-J~60M=@8X2(6y&o zk1e?LYln(0=VdSH-4<0-SC?~j6=AyiP%(y>4h-PqJEVQCaEX}nMU-(8X&9uEb6|vP z-8l6Da|Z)YcFNzNQLFJ=4Hlz*1EEH1(1U#fmsw zb9o}3EO_FS9!Ea>;O|=x!G;eE9rlIQ|H^v)>2l!Ln}jhOhTF~0zJjT)-N#7Qj;(!P zcGsR&5?tEqFec^Q4n;7*=$j*qqA)W%_Hcg5`U(qOH+}#1O&@7+IArSbGF4SqS5ZTQ zawu1W$82873rfNiX`k{?LhabpbAtqVrzEk<1FjKk5E@}}(=43Mz~J$r%f?6!LG1QU zmU!9D5#6|hc%Xo>Hn4X-SJev@BbWolfC!evqK!B%tBT|95PDwPSzo#6h%@Q zQ6yw%?@ngf>lCuHonvIv@Am%wzMtRwjqj&E-=Du;53k3$$93KJHJ{h@Y65wE(#i>Z zHvf$txq^jWYnL-*7f$Sv^5~Ra_jggsi}OS-XC9>YPy;=ic~v*!AjX zh`XC^x|VE1+Xr4sjnwdoa8(XwDBPG%)%?yo12vJyxEa`4kOKs^ij6=kd~|pwbil>$ zELl$T$BH|T6G=4WAUYiD5*t2E7>if1hZQRdK>=M#{C-9XwWmmFXI^k>&9xR4{$P)` z5YQB7GOQ_j2dT7$NeCmTtSml5fEtI2cvN5emP>DpjFfhnyr9UYmjrXaj)>6pkya-y z2SG*%0t@ykR%y7r#HQ^`ovD7q(gR{$f-`3BIihj4*!ZsRUWXbR7fPs!VHgYfHyqO= zyx;7l!%1XKSo85S0zonXn`Y@;e%`#Ki0J~)L-3y zyhwKcIWXce?3@P`O3^;SO#l`Ijsmi+f2j00F6|#C-CuO*M&JR*+O+B>)mZI;j|U5XCUBmz3G3^Zzih3%seot&{Z?OD%^=l}K zqITuoTBxyAD}}R0NUy#fer`Wy{vezaZ?A2cY=gu(kdxtUlu|R^mV99kjw^5I)+MMn z-E{Zifp&Gu7Sg7M%S0#B9JiA)>+Cfi9BgVGjG3Un8KyHV6`hV}% z48XIbpC&#lwwX7ODsy$PwC1G7!NzA-`yNVCw!>w)eA{)-!BZKYKo7&>r(Xqnd@ zYHZ1XZwo=HB^f&uE(m)IOY{$gyWO@tB=6*!TNQk` zes2Gq;ESyYvZ+I>!#JXNz6qb|H!F1pkta3d87K@mMKN8MHIAp8juGcCJ$jiEReXy& z`0kpPMKry%9}-_|b7zj0P@hP|n}v>#cNOh23JsjR5JAcgJQ6!CFKV%oRxzNaM+$3G z)8F7RJ$Ue-wWHmpMT1?^{#Q`l;?G`bN+sy-P!f`F`>)7nxA2dw)AIL_;gvt>au+n zB?>EGX%!RXA*CcG%_tcFEm~du^r?yJwz-ptq@<*?2YVT=A|)YwfN^tq^mA%Q(tMdG z|Ln}HXGvFNmToET-W_4`gD=hm+N$Qa-f@Kmx>}isM__e}8r^Rc65k+q-dwjnABm## zQfNWwjbeO6XksGr4JX$Y|5cKPA8NeZL85>FTI(*Jmwu097 z&rHs;QAlQ`sFzc5Gf22`xUa7Ad-0S}?vEpI0yY{6rdgp_J3FKlqJyw>`oXq0stq~R z(+~m+u`_XTbEz-29k*68ywSQtE~5aC$Ir_fzP-IIm&@RxC_!frqEWU73jT{_yH`q!bBDi({Dx(?9>*tx23 z^YAIksZ~m5YPBF$$j<%y)BLDms;4!M1uNhHX% zhsONWJtbd*h~YXCyDzjJsh!lg$DQ0OLU39twu2e*JL|snQ&q_Ou zgBDjY=h5GjgTCMKLXRe8*qVEcuGtT5?gRj#3lMG%6E%tt%AFch5-y@25O-pB7*@98 zaVyM&*Uw;M3Tem*>%&S`1 za22_`H%i>&=lk)?b+fjmkB?+Uxc2*aZOsIdV!l3Dd6t$=N}4h)cy2alMFyp3ZhW(3 z)$C@vC>LW;8ZK%MlG|A*OWo_xaJ3FQE16iU4SxN5IsITkXd+wqG_9KsZ_Uf6pEjwu zE8GqP_%02RF0hrQQ!Rz(K(6A_fZx zdW1%Yv~<%{racdl(Fek;{1upbnpV8c>e0r>$W)Z+roUn%`t$o@H4B#Oh6Z!JdCb?P zq%<$({riqq5Az@)bAt5gDb4lC;6ldb&)nbv6^H%x|D3uT@@Bxf&!`)c#!;Tmv z9h@H?U4qP8v2imO_)bUiiFKxcK_2T|B)*D-q!|qYu$#4u0n1%4s>!7aq<1U5Mrv*viP$Y#4(8h4$Q)YP8wL24QPr(k&At-)-HEh{E#>V zk!t&-6@KIo84211Uqv!%>%gb{P3y2=e&k{bq(!u1Ft59<&*kH%V$p9cvZ>1()^7bI+pt#sf@2NPp$vN_^ ziczCjhV%83H|9pOD1Z%l*|L>|5Erv|VB}v*Lr?o8a2!j1xa>-uC;yH8pw6wm%1>zi zB1V$$R$eTYKmGj9$~{|q{@jeDmzzHJEPr?R%jizM3-216d*cRQPL*8TrPI~)Vu^!b z8$htDOzp^C#frhKFtP(^ek3|8$+;|c+4X#sKD>#V5Vwnpc^4+7**D_;@^Xbg(h^=i zRrqjGf7Q-KROz@>@nd{tvqItKdxj~ z@JP10{`2Q{sMj3ju=3$^)a9h@{4RRZIj`GG<8u2WIr*ju(R!?YT{!5CdxqkOf*=zA zt#Bh@UTmYM$ipspqi3N5C$0$+&zM}phI(7gQE2_wV*U0<`g%>!jw;le@&wi%Xds2R zAVMPh~%P$rniU8{Ds>@t>!6!^|K)ma!X={J4ffNq*uBuyOwdhUPh1Yxa z)fW5bWD^d;@Ov`#*n6d=%ziN4yk(JQm+0EwQ|4BenU`Jn=sG`x!Riji*m$Dg{rj&0 zmg0y954y_NJOVN^jS>^CT)Tq!jOG`kqLDH$BaSmsE*6p>4 z+umsO-DsuUP4#!g5N-Yxbu7a}0|)wbC?tjj_V7Bg^zK=~uV0f5t~AQS*ryJHs&H02 z=5G59Wm$;P`7WwY%=K)r$V7oSD0|DbZ(W>uRQ5MJdLnXNP&PrsA`H}rRlsj^1h!Vq z%#2^HWqXZfz`(%x`V;-@my3sV5+4v(Jxk~*tw}a2NVLseqa?%)BV#lfZTLt5Vz!~k z)y***4mvNWQ#$@IOQZ!2)TGo-3@!D6V!OE4x<(__{3SwfSGp`pMBOqEW!xPkQ7LtW6h;SFw3nJRt zh8ppYb4A^?=S)rBzQgiChfpLoylr}1Oujo)Jr@?qJ6cUG?aoDi-IvwjA?s&BP%H=W z&oC97JK8oY?IlU7WRF#9-gX{-?l(ti z7+CjGh-|Q@raKf(Z)1ZRtUYIZuoo}y!K38AMGnjR{!%HsJ}oT-=T)HkV5$-iEsaEB z;p5fta8fc{1_r`z>L}-l*BkW}qm9I5yjibw#Q}0^66W}x`UtmL%5Bln2q8D7r8T<7 z8`-WcRBM^j-cCqEHwg=1=$b(48>l*Z%hp~OQ{N7--8~?MoG~{oJ!UzB^bU`OZMtLL$2@75;&*y>a6 zS2o{tO)};v+8Yg0HDhwYm~V4@xPv|X{@0U&I(^Iy2}*)#tO7syWvjV!%$=!t)O>2% z#1$j@*N8~0A_tmz zvhHreLAewePVZFmDhZRzPa_reUV@7bq`60Can4v?TKG;a>ejito1NMLZltK2_ic zyaCzP68Y< zMn;-PELyM9)#d@H<94#iEc8C)C=c>JP7T$eN2>TU26uNp}-&XT}x z!D>uL=nEhu}lJZt(?$jKZ2K2@nrKycz|C`A2ff+UFI_5lMkobGzL+%i{UbT|=_ z$o%(|e6>g^I0k+sXe}&Q#1cixt}YTn=-dk1k7^X3($N_hSX^?~BFg`$YC}Ri=P^gw zmYJDhVj{&s35Rnuq;&^644lz5DtU!XvT52B7p4;QPFs~%e~ga&BFcS`$-lJgqq4)3 ziHDdWABSOkYeGQdFsdh3k$YuLIPzJlKY5o9|y>B5j@t){jXr67)v}be*AgBt& zm(EEKZb*mnJsSdk8MDGu7&X5K5=11~6rQ3?qouP?3AT2B1rf!*S07UC}%DKwM#Y_hdxBgJayQ&9N9Q2xaQXyjLSuO0hSG{#2 z9raqe!r%!}6lczuzIfh>c+Oye&`rWYL` zr*5uPnkgK12Goqcp>r(Et16CLE0)sM(G~z52sXwW$LXxDX~ix$suMsSuI(|h5q7tH zBztrZqWj^ttzE=!9r^b+-Z?V;SBui?g3KgdQ~Dvv^!OWFD?yW4iJ5?R@9$k7o*0Mz}OXLKa205ZPRlqUmsYXt9@IB0%20NJt>v+>0faMa9qLs_G?deMr~k z)yHyjuS88lmk1u%+*sw~GZ@SynGqE9i;o8ldCy?_`%3(C2P@T zs5E_@eX7c*{RZCog}tSBTdK1KdqK6ckLGmZ^UY&50!bS^2d>h-`JQsys>_9h#!(@W}xl&I)(#rg9v4aIS5jY{k7sNa_8_)mD6zZm)Bfk`8iyY zlxd=2B$r1&ZM;_?jAB0fJ<4_yz;_jll zlmAjWvYmAaoMPu_)@dtM5(zIOwcW+8RYlvbFl zZQ{>3IIEuN+Rnd&h zh_>#g6oBD=KE$g&8|t8JVSq=yFVWz>jhe9mW_W?`{Kw4oACil4I?tuNg+OqDl|Y00 zl!(Q61s=^!sEY!t!11W$F)eZAK!1n`5$zo-a%N^1x9Us+RWfbEWs-c#ucC8v<(tqg z15EU{GCfhRe>$dd(KrcsvuH2hZb=uSY=BSqUP8sh7f0RM7x#7_#t?_x+a2v+@Bh~2zCac$V{2ulnfVQ!^-WbEo#O%X z+z%)z5iYd0GM>6=Z&=BSeE&1fFYS9HL6lEj9BItMnDpejhpzSESlvmqoE0mr&%aRsK+XTW3hu{{?K2sZ$!M9{?atY2)lh}9CPj4*uJ;ea%DT^>qPj66o zq?=-(YaZx+4w^ne1ee!0p*ce)FF0Ee17dzXcsf(*ciHDsumVLIaJ=o@I1${|SdR8)nxh ze)`{;38(j4&CVhOci{svvNE$+szTGE%hQ$0HA}HVFhN2W_mT$jm>sj<+@^n(e+^k(P@_8kQq~LLj^+mj9)dL9 zTewkBQ=AZo_}&lKKfv3)2hJLe7HflbN*{ zCs5y7vb8+*Wj{cD`(OhXgy$4`4KcC@tXCT-jIcKyX}Lcdb2ItN-k;hLDQ3EOW9VIV zL7-Kia?8&CV$@I=dChF-hY+M7c4*^ksqwVoj@Z4YVsbrKhSz|{bz2{f()ry_!a(BM8b(pm>GgYamCEw4ynFuH?l5S?@za7IM_api&Is# z;c_WAH)hoRM3(7!(vDDgeiQ+8Qk7*np+%47@<8h$9t3F5LcTQC)lMsnDzd@bVGq*u z*Chv~i=Pz8#WbEo#K??Yk*CYWpImo;(ACna62hipK&{|tjZlP_Ocj1wek;X?uXl+Q zs_T{>T&Nv7TA!YmzQwgg#J1>x7n^-IAkQ;=>%L;}TrDQZ1i|SiHay~j@e5755l9MB zn*<-NhG&b4pziKaBBD>38IMOwg>mpH>>JX~lQKXbqfjXL6U`d0gv^6&Sk zIi5iTI)oNkk18CZzdC%av?JM(m;Y1^ngu6+V4O$MZ-M}`vGEmPf7{&>%uYzS^mC`; z%PcpwrmO9?30`9kTfj6_{ zUZNwFb4y*P_r!)~Y0q$VIlt1Vp@$_7Pc>3A>s+#6k=%4l3Kv&Q9lz~YQm7gbpa|4Z zMrLMDo_YEB+f(wgA-HBoSu>ptulK(K5XHOr;r*t$P?8!e(jHD)ny|KIu z$rIBzF!+eTA@K8UJG1%Tf{|1Tc-zuFXnv}wThk9R8#u=)ii(!NUGJ>jG?UUh_vm}A zKb{)tgvr(-hJRvfu?|017?{-?;p2OO?2KMF zy#rECiQ^!2kFY~oFI~t?PRKCKuW!}$V^xb%^1F0x8@q9~h8>7)$g&O&13iPU;! z)13vDW3pEqt#1)IjQt#5UvO4FQ0$uhsaTEjGFC8DQfjG(hH$>ziR#!-Wb7>aFl}4@WYIFVeZ7n_~CSa?mWi2H=eW~`>;fL~a z@kxA*qwV}-)DB*b?rw|qO|#<*`qzyA^{`EY0D*CfN)O&Hr9G#^)n1*iUOz7RT-I|K z9?1PgBK<)uO)h>~IYB#U;M>ch)YOM#fxer{s~3DgS|C3^-ze93D^JS(4WN_%D2Ssxx^D%1dW#eSIB=%N_RA zC}xuOHfL@#pOvc>#X3HC!y{Z=rX~FU%h`Xd=5Onhsco=QS6^EPadRbwm!kAy(|3pJ zzH}Fdd~}vDLux-)PC5)u4is;?pSKpHw-yOUtGcwO_j7pm*aH* z+hj+tRQgEv4+gHTN8f1am6VFRJli=#;ORMUp<)MX#pq_nDfc_>I9OT1zE{cavEAVr zLlto!_>K;2yu~`fQ4&B@5uWL-V>2A%Cr9BDUT4jYy)KJ#YBUnLvj(sq8lYdDaY67x zwQ}92am0=Ua&dWi=en}x^4h!4S*6S(;AKW-jR&XqFnV8b&$dA7`HmyKu z!_4Qz^}(HWd7o*`wYASXt6wgyydN^GTrpm!iqz54H5S?l%zH+%IB2(sq;TjOhx>r< z5xOicT>=!&7M0OE&N2aQm9%t$Tiz$=@X!6j+lViLid-8TF6F@8`Taf6Hl-i*x>#Rw zTDc?@Z>!igqs@yp%B?K4xhUr2W$Q9rHd1#(!w3B}9?_9hl3(uIR;PF4pF@UVAue!qd-69YOS%=gu zG|xZ9#|ety;Wf9kNN+YX@BAbYpSD8RCbrGbzkfH-TWWuKaBI{4v(i>ZFq{K4h}0}K zyN-booaCE}2uC;k+{yp{_CJV^K!y_YUwwRh_5Xg&f5`&Sp9$yqW_}|i{<^mlfG*+j z!kWjA!v>u!+h~8oiBpFLqVL3bf3R}>3UK5mrist|!LE+) z6GGpBV4AR|FdpPC_U{qnpoh>iPKhzX#Xylq< zybz#l`TGVF@qf5uOfUj8i%AGoO-rY_(aVGIATbh3@K9FyopL;Oe6)G=3x;%hKm!uN z<_s;!3?1Ow*1p#XU340s{`<`8i-BwF(VtV5}^}NT(^zR46d_DSE zQeq!2p~wwD06RqsJ?{Tx1XB+nYjs?Bn7CBNO^8@v0ox`CCW-%%JX7f-Vu8A)(YWUK ze?C(yfS1MhzmPA8CPH9gskbryXYBinUuo%J4`ef5jDM%?zo*;3NL0uGsMaJPulCR)eu{~%*DUe7H>qnk&<_yi05X Date: Fri, 10 Jan 2025 19:47:29 +0900 Subject: [PATCH 17/59] test(autoware_behavior_path_start_planner_module): add test helper and implement unit tests for FreespacePullOut (#9832) * refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners Signed-off-by: Kyoichi Sugahara * refactor(autoware_behavior_path_start_planner_module): remove TimeKeeper parameter from pull-out planners Signed-off-by: Kyoichi Sugahara * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling Signed-off-by: kyoichi-sugahara * refactor(planner): add planner_data parameter to plan methods in pull out planners Signed-off-by: kyoichi-sugahara * refactor(autoware_behavior_path_start_planner_module): remove LaneDepartureChecker dependency from pull-out planners Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../goal_planner_module.hpp | 3 - .../pull_over_planner/bezier_pull_over.hpp | 4 +- .../pull_over_planner/freespace_pull_over.hpp | 4 +- .../pull_over_planner/geometric_pull_over.hpp | 3 +- .../pull_over_planner/shift_pull_over.hpp | 4 +- .../src/goal_planner_module.cpp | 19 +-- .../pull_over_planner/bezier_pull_over.cpp | 12 +- .../pull_over_planner/freespace_pull_over.cpp | 6 +- .../pull_over_planner/geometric_pull_over.cpp | 7 +- .../src/pull_over_planner/shift_pull_over.cpp | 7 +- .../CMakeLists.txt | 14 ++- .../freespace_pull_out.hpp | 6 +- .../geometric_pull_out.hpp | 3 +- .../pull_out_planner_base.hpp | 17 ++- .../shift_pull_out.hpp | 5 +- .../start_planner_module.hpp | 4 - .../src/freespace_pull_out.cpp | 15 +-- .../src/geometric_pull_out.cpp | 25 ++-- .../src/pull_out_planner_base.cpp | 7 +- .../src/shift_pull_out.cpp | 36 +++--- .../src/start_planner_module.cpp | 21 +--- .../include/start_planner_test_helper.hpp | 39 ++++++ .../test/src/start_planner_test_helper.cpp | 98 +++++++++++++++ .../test/test_freespace_pull_out.cpp | 113 ++++++++++++++++++ .../test/test_geometric_pull_out.cpp | 96 +++------------ .../test/test_shift_pull_out.cpp | 94 +++------------ 26 files changed, 385 insertions(+), 277 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/include/start_planner_test_helper.hpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/src/start_planner_test_helper.cpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index cabbeb3435087..41524b1b8193c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -23,8 +23,6 @@ #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include - #include #include @@ -40,7 +38,6 @@ namespace autoware::behavior_path_planner { -using autoware::lane_departure_checker::LaneDepartureChecker; using autoware_vehicle_msgs::msg::HazardLightsCommand; using geometry_msgs::msg::PoseArray; using nav_msgs::msg::OccupancyGrid; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp index fabbd667298bb..9b97f87c933a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp @@ -29,9 +29,7 @@ using autoware::lane_departure_checker::LaneDepartureChecker; class BezierPullOver : public PullOverPlannerBase { public: - BezierPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker); + BezierPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::BEZIER; } std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp index 37c82ea904a55..06ff47224dd44 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp @@ -30,9 +30,7 @@ using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; class FreespacePullOver : public PullOverPlannerBase { public: - FreespacePullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); + FreespacePullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::FREESPACE; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp index d15c1e796bbe7..e12a759eb2137 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp @@ -32,8 +32,7 @@ class GeometricPullOver : public PullOverPlannerBase { public: GeometricPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, const bool is_forward); + rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward); PullOverPlannerType getPlannerType() const override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp index 2c6aec919bfbb..994d8283fe36c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp @@ -31,9 +31,7 @@ using autoware::lane_departure_checker::LaneDepartureChecker; class ShiftPullOver : public PullOverPlannerBase { public: - ShiftPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker); + ShiftPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::SHIFT; }; std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index d4f3953c557b4..0a6185127fcf0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -101,7 +101,7 @@ GoalPlannerModule::GoalPlannerModule( // freespace parking if (parameters_->enable_freespace_parking) { - auto freespace_planner = std::make_shared(node, *parameters, vehicle_info); + auto freespace_planner = std::make_shared(node, *parameters); const auto freespace_parking_period_ns = rclcpp::Rate(1.0).period(); freespace_parking_timer_cb_group_ = node.create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -280,22 +280,15 @@ LaneParkingPlanner::LaneParkingPlanner( is_lane_parking_cb_running_(is_lane_parking_cb_running), logger_(logger) { - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); - lane_departure_checker::Param lane_departure_checker_params; - lane_departure_checker_params.footprint_extra_margin = - parameters.lane_departure_check_expansion_margin; - LaneDepartureChecker lane_departure_checker(lane_departure_checker_params, vehicle_info); - for (const std::string & planner_type : parameters.efficient_path_order) { if (planner_type == "SHIFT" && parameters.enable_shift_parking) { - pull_over_planners_.push_back( - std::make_shared(node, parameters, lane_departure_checker)); + pull_over_planners_.push_back(std::make_shared(node, parameters)); } else if (planner_type == "ARC_FORWARD" && parameters.enable_arc_forward_parking) { - pull_over_planners_.push_back(std::make_shared( - node, parameters, lane_departure_checker, /*is_forward*/ true)); + pull_over_planners_.push_back( + std::make_shared(node, parameters, /*is_forward*/ true)); } else if (planner_type == "ARC_BACKWARD" && parameters.enable_arc_backward_parking) { - pull_over_planners_.push_back(std::make_shared( - node, parameters, lane_departure_checker, /*is_forward*/ false)); + pull_over_planners_.push_back( + std::make_shared(node, parameters, /*is_forward*/ false)); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp index ad42ccf1582ab..ec3984a6d9443 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp @@ -31,15 +31,13 @@ #include namespace autoware::behavior_path_planner { -BezierPullOver::BezierPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker) -: PullOverPlannerBase{node, parameters}, - lane_departure_checker_{lane_departure_checker}, - left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} +BezierPullOver::BezierPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters) +: PullOverPlannerBase(node, parameters), + lane_departure_checker_( + lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_), + left_side_parking_(parameters.parking_policy == ParkingPolicy::LEFT_SIDE) { } - std::optional BezierPullOver::plan( [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, [[maybe_unused]] const std::shared_ptr planner_data, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index 473f76b5904d6..6605d258a8d5e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -32,9 +32,7 @@ namespace autoware::behavior_path_planner using autoware::freespace_planning_algorithms::AstarSearch; using autoware::freespace_planning_algorithms::RRTStar; -FreespacePullOver::FreespacePullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) +FreespacePullOver::FreespacePullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters) : PullOverPlannerBase{node, parameters}, velocity_{parameters.freespace_parking_velocity}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE}, @@ -45,7 +43,7 @@ FreespacePullOver::FreespacePullOver( } { autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( - vehicle_info, parameters.vehicle_shape_margin); + vehicle_info_, parameters.vehicle_shape_margin); if (parameters.freespace_parking_algorithm == "astar") { planner_ = std::make_unique( parameters.freespace_parking_common_parameters, vehicle_shape, parameters.astar_parameters, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index 74b3fe149fd1d..bf2ce86b49bab 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -26,11 +26,10 @@ namespace autoware::behavior_path_planner { GeometricPullOver::GeometricPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, const bool is_forward) + rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward) : PullOverPlannerBase{node, parameters}, - parallel_parking_parameters_{parameters.parallel_parking_parameters}, - lane_departure_checker_{lane_departure_checker}, + lane_departure_checker_{ + lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, is_forward_{is_forward}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index 9a3e2d6b13db9..8350252369cc6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -30,11 +30,10 @@ namespace autoware::behavior_path_planner { -ShiftPullOver::ShiftPullOver( - rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker) +ShiftPullOver::ShiftPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters) : PullOverPlannerBase{node, parameters}, - lane_departure_checker_{lane_departure_checker}, + lane_departure_checker_{ + lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt index e28339fb51a6c..5961b98bdda08 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt @@ -19,12 +19,22 @@ ament_auto_add_library(${PROJECT_NAME} SHARED if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + + # Add test helper library + ament_auto_add_library(start_planner_test_helper SHARED + test/src/start_planner_test_helper.cpp + ) + target_include_directories(start_planner_test_helper PUBLIC + test/include + ) + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${TEST_SOURCES} ) - target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) + target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME} + start_planner_test_helper + ) endif() - ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp index 364d2d31a2577..e1a7ae455e374 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp @@ -40,7 +40,11 @@ class FreespacePullOut : public PullOutPlannerBase PlannerType getPlannerType() const override { return PlannerType::FREESPACE; } std::optional plan( - const Pose & start_pose, const Pose & end_pose, PlannerDebugData & planner_debug_data) override; + const Pose & start_pose, const Pose & end_pose, + const std::shared_ptr & planner_data, + PlannerDebugData & planner_debug_data) override; + + friend class TestFreespacePullOut; protected: std::unique_ptr planner_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp index 78eb72183cdf5..5d36c996cca3a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp @@ -33,14 +33,13 @@ class GeometricPullOut : public PullOutPlannerBase public: explicit GeometricPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const std::shared_ptr - lane_departure_checker, std::shared_ptr time_keeper = std::make_shared()); PlannerType getPlannerType() const override { return PlannerType::GEOMETRIC; }; std::optional plan( const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) override; GeometricParallelParking planner_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp index dfd972aff9be0..0316d6a14a4f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -42,33 +42,30 @@ class PullOutPlannerBase rclcpp::Node & node, const StartPlannerParameters & parameters, std::shared_ptr time_keeper = std::make_shared()) - : parameters_(parameters), - vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()), - vehicle_footprint_(vehicle_info_.createFootprint()), + : parameters_{parameters}, + vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, + vehicle_footprint_{vehicle_info_.createFootprint()}, time_keeper_(time_keeper) { } virtual ~PullOutPlannerBase() = default; - void setPlannerData(const std::shared_ptr & planner_data) - { - planner_data_ = planner_data; - } - void setCollisionCheckMargin(const double collision_check_margin) { collision_check_margin_ = collision_check_margin; }; virtual PlannerType getPlannerType() const = 0; virtual std::optional plan( - const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) = 0; + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, + PlannerDebugData & planner_debug_data) = 0; protected: bool isPullOutPathCollided( autoware::behavior_path_planner::PullOutPath & pull_out_path, + const std::shared_ptr & planner_data, double collision_check_distance_from_end) const; - std::shared_ptr planner_data_; StartPlannerParameters parameters_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp index 8da104940d327..1000437bdea56 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp @@ -35,18 +35,19 @@ class ShiftPullOut : public PullOutPlannerBase public: explicit ShiftPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - std::shared_ptr & lane_departure_checker, std::shared_ptr time_keeper = std::make_shared()); PlannerType getPlannerType() const override { return PlannerType::SHIFT; }; std::optional plan( const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) override; std::vector calcPullOutPaths( const RouteHandler & route_handler, const lanelet::ConstLanelets & road_lanes, - const Pose & start_pose, const Pose & goal_pose); + const Pose & start_pose, const Pose & goal_pose, + const BehaviorPathPlannerParameters & behavior_path_parameters); double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double target_after_arc_length, const double dr); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index 47eecb54e2b2a..cf9227c2387f8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -27,7 +27,6 @@ #include "autoware/behavior_path_start_planner_module/pull_out_path.hpp" #include "autoware/behavior_path_start_planner_module/shift_pull_out.hpp" -#include #include #include @@ -51,7 +50,6 @@ using autoware::behavior_path_planner::utils::path_safety_checker::ObjectsFilter using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using autoware::behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using autoware::behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; -using autoware::lane_departure_checker::LaneDepartureChecker; using geometry_msgs::msg::PoseArray; using PriorityOrder = std::vector>>; @@ -310,8 +308,6 @@ ego pose. std::vector searchPullOutStartPoseCandidates( const PathWithLaneId & back_path_from_start_pose) const; - std::shared_ptr lane_departure_checker_; - // turn signal TurnSignalInfo calcTurnSignalInfo(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index a089f6a8a83fc..6893c7d11d09d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -47,13 +47,14 @@ FreespacePullOut::FreespacePullOut(rclcpp::Node & node, const StartPlannerParame } std::optional FreespacePullOut::plan( - const Pose & start_pose, const Pose & end_pose, PlannerDebugData & planner_debug_data) + const Pose & start_pose, const Pose & end_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) { - 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; + 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); + planner_->setMap(*planner_data->costmap); try { if (!planner_->makePlan(start_pose, end_pose)) { @@ -65,11 +66,11 @@ std::optional FreespacePullOut::plan( } const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), + 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); + start_planner_utils::getPullOutLanes(planner_data, backward_path_length); const auto lanes = utils::combineLanelets(road_lanes, pull_out_lanes); const PathWithLaneId path = diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index bbc6c05725434..69c5c41405932 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -36,35 +36,37 @@ using start_planner_utils::getPullOutLanes; GeometricPullOut::GeometricPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const std::shared_ptr - lane_departure_checker, std::shared_ptr time_keeper) : PullOutPlannerBase{node, parameters, time_keeper}, - parallel_parking_parameters_{parameters.parallel_parking_parameters}, - lane_departure_checker_(lane_departure_checker) + parallel_parking_parameters_{parameters.parallel_parking_parameters} { + lane_departure_checker_ = + std::make_shared( + autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, + vehicle_info_, time_keeper_); planner_.setParameters(parallel_parking_parameters_); } std::optional GeometricPullOut::plan( - const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) { PullOutPath output; // combine road lane and pull out lane const double backward_path_length = - planner_data_->parameters.backward_path_length + parameters_.max_back_distance; + 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(), /*forward_only_in_route*/ true); - const auto pull_out_lanes = getPullOutLanes(planner_data_, backward_path_length); + const auto pull_out_lanes = getPullOutLanes(planner_data, backward_path_length); // check if the ego is at left or right side of road lane center const bool left_side_start = 0 < getArcCoordinates(road_lanes, start_pose).distance; planner_.setTurningRadius( - planner_data_->parameters, parallel_parking_parameters_.pull_out_max_steer_angle); - planner_.setPlannerData(planner_data_); + planner_data->parameters, parallel_parking_parameters_.pull_out_max_steer_angle); + planner_.setPlannerData(planner_data); const bool found_valid_path = planner_.planPullOut( start_pose, goal_pose, road_lanes, pull_out_lanes, left_side_start, lane_departure_checker_); if (!found_valid_path) { @@ -122,7 +124,8 @@ std::optional GeometricPullOut::plan( output.start_pose = planner_.getArcPaths().at(0).points.front().point.pose; output.end_pose = planner_.getArcPaths().at(1).points.back().point.pose; - if (isPullOutPathCollided(output, parameters_.geometric_collision_check_distance_from_end)) { + if (isPullOutPathCollided( + output, planner_data, parameters_.geometric_collision_check_distance_from_end)) { planner_debug_data.conditions_evaluation.emplace_back("collision"); return {}; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp index 42c5bead33604..a475b3ad582cb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp @@ -14,21 +14,24 @@ #include "autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp" +#include + namespace autoware::behavior_path_planner { bool PullOutPlannerBase::isPullOutPathCollided( autoware::behavior_path_planner::PullOutPath & pull_out_path, + const std::shared_ptr & planner_data, double collision_check_distance_from_end) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // check for collisions - const auto & dynamic_objects = planner_data_->dynamic_object; + const auto & dynamic_objects = planner_data->dynamic_object; if (!dynamic_objects) { return false; } const auto pull_out_lanes = start_planner_utils::getPullOutLanes( - planner_data_, planner_data_->parameters.backward_path_length + parameters_.max_back_distance); + planner_data, planner_data->parameters.backward_path_length + parameters_.max_back_distance); // extract stop objects in pull out lane for collision check const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity( *dynamic_objects, parameters_.th_moving_object_velocity); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index 4759559619870..8f4de1d3636de 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -41,31 +41,36 @@ using start_planner_utils::getPullOutLanes; ShiftPullOut::ShiftPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - std::shared_ptr & lane_departure_checker, std::shared_ptr time_keeper) -: PullOutPlannerBase{node, parameters, time_keeper}, lane_departure_checker_{lane_departure_checker} +: PullOutPlannerBase{node, parameters, time_keeper} { + lane_departure_checker_ = + std::make_shared( + autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, + vehicle_info_, time_keeper_); } std::optional ShiftPullOut::plan( - const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) { - const auto & route_handler = planner_data_->route_handler; - const auto & common_parameters = planner_data_->parameters; + const auto & route_handler = planner_data->route_handler; + const auto & common_parameters = planner_data->parameters; const double backward_path_length = - planner_data_->parameters.backward_path_length + parameters_.max_back_distance; + 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(), /*forward_only_in_route*/ true); // find candidate paths - auto pull_out_paths = calcPullOutPaths(*route_handler, road_lanes, start_pose, goal_pose); + auto pull_out_paths = + calcPullOutPaths(*route_handler, road_lanes, start_pose, goal_pose, common_parameters); if (pull_out_paths.empty()) { planner_debug_data.conditions_evaluation.emplace_back("no path found"); return std::nullopt; } - const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr(); + const auto lanelet_map_ptr = planner_data->route_handler->getLaneletMapPtr(); std::vector fused_id_start_to_end{}; std::optional fused_polygon_start_to_end = std::nullopt; @@ -159,9 +164,10 @@ std::optional ShiftPullOut::plan( continue; } shift_path.points = cropped_path.points; - shift_path.header = planner_data_->route_handler->getRouteHeader(); + shift_path.header = planner_data->route_handler->getRouteHeader(); - if (isPullOutPathCollided(pull_out_path, parameters_.shift_collision_check_distance_from_end)) { + if (isPullOutPathCollided( + pull_out_path, planner_data, parameters_.shift_collision_check_distance_from_end)) { planner_debug_data.conditions_evaluation.emplace_back("collision"); continue; } @@ -227,7 +233,8 @@ bool ShiftPullOut::refineShiftedPathToStartPose( std::vector ShiftPullOut::calcPullOutPaths( const RouteHandler & route_handler, const lanelet::ConstLanelets & road_lanes, - const Pose & start_pose, const Pose & goal_pose) + const Pose & start_pose, const Pose & goal_pose, + const BehaviorPathPlannerParameters & behavior_path_parameters) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -238,9 +245,8 @@ std::vector ShiftPullOut::calcPullOutPaths( } // rename parameter - const auto & common_parameters = planner_data_->parameters; - const double forward_path_length = common_parameters.forward_path_length; - const double backward_path_length = common_parameters.backward_path_length; + const double forward_path_length = behavior_path_parameters.forward_path_length; + const double backward_path_length = behavior_path_parameters.backward_path_length; const double lateral_jerk = parameters_.lateral_jerk; const double minimum_lateral_acc = parameters_.minimum_lateral_acc; const double maximum_lateral_acc = parameters_.maximum_lateral_acc; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 83c1d55c7d022..0bac50a37fdbf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -68,20 +68,12 @@ StartPlannerModule::StartPlannerModule( vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} { - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - lane_departure_checker_params.footprint_extra_margin = - parameters->lane_departure_check_expansion_margin; - lane_departure_checker_ = std::make_shared( - lane_departure_checker_params, vehicle_info_, time_keeper_); - // set enabled planner if (parameters_->enable_shift_pull_out) { - start_planners_.push_back( - std::make_shared(node, *parameters, lane_departure_checker_, time_keeper_)); + start_planners_.push_back(std::make_shared(node, *parameters, time_keeper_)); } if (parameters_->enable_geometric_pull_out) { - start_planners_.push_back( - std::make_shared(node, *parameters, lane_departure_checker_, time_keeper_)); + start_planners_.push_back(std::make_shared(node, *parameters, time_keeper_)); } if (start_planners_.empty()) { RCLCPP_ERROR(getLogger(), "Not found enabled planner"); @@ -983,17 +975,16 @@ bool StartPlannerModule::findPullOutPath( const bool backward_is_unnecessary = backwards_distance < epsilon; planner->setCollisionCheckMargin(collision_check_margin); - planner->setPlannerData(planner_data_); PlannerDebugData debug_data{ planner->getPlannerType(), {}, collision_check_margin, backwards_distance}; - const auto pull_out_path = planner->plan(start_pose_candidate, goal_pose, debug_data); + const auto pull_out_path = + planner->plan(start_pose_candidate, goal_pose, planner_data_, debug_data); debug_data_vector.push_back(debug_data); // If no path is found, return false if (!pull_out_path) { return false; } - if (backward_is_unnecessary) { updateStatusWithCurrentPath(*pull_out_path, start_pose_candidate, planner->getPlannerType()); return true; @@ -1592,9 +1583,9 @@ std::optional StartPlannerModule::planFreespacePath( for (const auto & p : center_line_path.points) { const Pose end_pose = p.point.pose; - freespace_planner_->setPlannerData(planner_data); PlannerDebugData debug_data{freespace_planner_->getPlannerType(), {}, 0.0, 0.0}; - auto freespace_path = freespace_planner_->plan(current_pose, end_pose, debug_data); + auto freespace_path = + freespace_planner_->plan(current_pose, end_pose, planner_data, debug_data); DEBUG_PRINT( "\nFreespace Pull out path search results\n%s%s", debug_data.header_str().c_str(), debug_data.str().c_str()); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/include/start_planner_test_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/include/start_planner_test_helper.hpp new file mode 100644 index 0000000000000..a1d294b279ff6 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/include/start_planner_test_helper.hpp @@ -0,0 +1,39 @@ +// Copyright 2024 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 + +#include +#include + +#include + +namespace autoware::behavior_path_planner::testing +{ + +class StartPlannerTestHelper +{ +public: + static rclcpp::NodeOptions make_node_options(); + + static void set_odometry( + std::shared_ptr & planner_data, const geometry_msgs::msg::Pose & start_pose); + static void set_route( + std::shared_ptr & planner_data, const int route_start_lane_id, + const int route_goal_lane_id); + static void set_costmap( + std::shared_ptr & planner_data, const geometry_msgs::msg::Pose & start_pose, + const double grid_resolution, const double grid_length_x, const double grid_length_y); +}; + +} // namespace autoware::behavior_path_planner::testing diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/src/start_planner_test_helper.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/src/start_planner_test_helper.cpp new file mode 100644 index 0000000000000..0f0720edc4a15 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/src/start_planner_test_helper.cpp @@ -0,0 +1,98 @@ +// Copyright 2024 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. +// pull_out_test_utils.cpp +#include "start_planner_test_helper.hpp" + +#include +#include + +#include +#include + +namespace autoware::behavior_path_planner::testing +{ +using autoware::test_utils::get_absolute_path_to_config; +using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; + +rclcpp::NodeOptions StartPlannerTestHelper::make_node_options() +{ + // Load common configuration files + auto node_options = rclcpp::NodeOptions{}; + + const auto common_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_common.param.yaml"); + const auto nearest_search_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_nearest_search.param.yaml"); + const auto vehicle_info_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_vehicle_info.param.yaml"); + const auto behavior_path_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "behavior_path_planner.param.yaml"); + const auto drivable_area_expansion_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "drivable_area_expansion.param.yaml"); + const auto scene_module_manager_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "scene_module_manager.param.yaml"); + const auto start_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_start_planner_module", "start_planner.param.yaml"); + + autoware::test_utils::updateNodeOptions( + node_options, {common_param_path, nearest_search_param_path, vehicle_info_param_path, + behavior_path_planner_param_path, drivable_area_expansion_param_path, + scene_module_manager_param_path, start_planner_param_path}); + + return node_options; +} + +void StartPlannerTestHelper::set_odometry( + std::shared_ptr & planner_data, const geometry_msgs::msg::Pose & start_pose) +{ + auto odometry = std::make_shared(); + odometry->pose.pose = start_pose; + odometry->header.frame_id = "map"; + planner_data->self_odometry = odometry; +} + +void StartPlannerTestHelper::set_route( + std::shared_ptr & planner_data, const int route_start_lane_id, + const int route_goal_lane_id) +{ + const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + auto route_handler = std::make_shared(map_bin_msg); + + const auto route = makeBehaviorRouteFromLaneId( + route_start_lane_id, route_goal_lane_id, "autoware_test_utils", + "road_shoulder/lanelet2_map.osm"); + route_handler->setRoute(route); + planner_data->route_handler = route_handler; +} + +void StartPlannerTestHelper::set_costmap( + std::shared_ptr & planner_data, const geometry_msgs::msg::Pose & start_pose, + const double grid_resolution, const double grid_length_x, const double grid_length_y) +{ + nav_msgs::msg::OccupancyGrid costmap; + costmap.header.frame_id = "map"; + costmap.info.width = static_cast(grid_length_x / grid_resolution); + costmap.info.height = static_cast(grid_length_y / grid_resolution); + costmap.info.resolution = grid_resolution; + + costmap.info.origin.position.x = start_pose.position.x - grid_length_x / 2; + costmap.info.origin.position.y = start_pose.position.y - grid_length_y / 2; + costmap.data = std::vector(costmap.info.width * costmap.info.height, 0); + + planner_data->costmap = std::make_shared(costmap); +} + +} // namespace autoware::behavior_path_planner::testing diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp new file mode 100644 index 0000000000000..79c58c37f0dcf --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp @@ -0,0 +1,113 @@ +// Copyright 2024 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 "start_planner_test_helper.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +using autoware::behavior_path_planner::FreespacePullOut; +using autoware::behavior_path_planner::StartPlannerParameters; +using autoware::test_utils::get_absolute_path_to_config; +using autoware_planning_msgs::msg::LaneletRoute; +using RouteSections = std::vector; +using autoware::behavior_path_planner::testing::StartPlannerTestHelper; +using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; + +namespace autoware::behavior_path_planner +{ + +class TestFreespacePullOut : public ::testing::Test +{ +public: + std::optional call_plan( + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) + { + return freespace_pull_out_->plan(start_pose, goal_pose, planner_data, planner_debug_data); + } + +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + node_ = + rclcpp::Node::make_shared("freespace_pull_out", StartPlannerTestHelper::make_node_options()); + + planner_data_ = std::make_shared(); + planner_data_->init_parameters(*node_); + + initialize_freespace_pull_out_planner(); + } + + void TearDown() override { rclcpp::shutdown(); } + + // Member variables + std::shared_ptr node_; + std::shared_ptr freespace_pull_out_; + std::shared_ptr planner_data_; + +private: + void initialize_freespace_pull_out_planner() + { + auto parameters = StartPlannerParameters::init(*node_); + freespace_pull_out_ = std::make_shared(*node_, parameters); + } +}; + +TEST_F(TestFreespacePullOut, GenerateValidFreespacePullOutPath) +{ + const auto start_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(299.796).y(303.529).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(-0.748629).w( + 0.662990)); + + const auto goal_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(280.721).y(301.025).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.991718).w( + 0.128435)); + + StartPlannerTestHelper::set_odometry(planner_data_, start_pose); + StartPlannerTestHelper::set_route(planner_data_, 508, 720); + StartPlannerTestHelper::set_costmap(planner_data_, start_pose, 0.3, 70.0, 70.0); + + // Plan the pull out path + PlannerDebugData debug_data; + auto result = call_plan(start_pose, goal_pose, planner_data_, debug_data); + + // Assert that a valid Freespace pull out path is generated + ASSERT_TRUE(result.has_value()) << "Freespace pull out path generation failed."; + // EXPECT_EQ(result->partial_paths.size(), 2UL) + // << "Freespace pull out path does not have the expected number of partial paths."; + EXPECT_EQ(debug_data.conditions_evaluation.back(), "success") + << "Freespace pull out path planning did not succeed."; +} + +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp index 726c9ccc4c5d7..4548c058b871d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "start_planner_test_helper.hpp" + #include #include #include #include -#include #include #include #include @@ -30,10 +31,10 @@ using autoware::behavior_path_planner::GeometricPullOut; using autoware::behavior_path_planner::StartPlannerParameters; -using autoware::lane_departure_checker::LaneDepartureChecker; using autoware::test_utils::get_absolute_path_to_config; using autoware_planning_msgs::msg::LaneletRoute; using RouteSections = std::vector; +using autoware::behavior_path_planner::testing::StartPlannerTestHelper; using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; namespace autoware::behavior_path_planner @@ -43,102 +44,33 @@ class TestGeometricPullOut : public ::testing::Test { public: std::optional call_plan( - const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) { - return geometric_pull_out_->plan(start_pose, goal_pose, planner_debug_data); + return geometric_pull_out_->plan(start_pose, goal_pose, planner_data, planner_debug_data); } protected: void SetUp() override { rclcpp::init(0, nullptr); - node_ = rclcpp::Node::make_shared("geometric_pull_out", make_node_options()); + node_ = + rclcpp::Node::make_shared("geometric_pull_out", StartPlannerTestHelper::make_node_options()); - initialize_lane_departure_checker(); initialize_geometric_pull_out_planner(); } - void TearDown() override { rclcpp::shutdown(); } - PlannerData make_planner_data( - const Pose & start_pose, const int route_start_lane_id, const int route_goal_lane_id) - { - PlannerData planner_data; - planner_data.init_parameters(*node_); - - // Load a sample lanelet map and create a route handler - const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( - "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); - auto route_handler = std::make_shared(map_bin_msg); - - // Set up current odometry at start pose - auto odometry = std::make_shared(); - odometry->pose.pose = start_pose; - odometry->header.frame_id = "map"; - planner_data.self_odometry = odometry; - - // Setup route - const auto route = makeBehaviorRouteFromLaneId( - route_start_lane_id, route_goal_lane_id, "autoware_test_utils", - "road_shoulder/lanelet2_map.osm"); - route_handler->setRoute(route); - - // Update planner data with the route handler - planner_data.route_handler = route_handler; - - return planner_data; - } - // Member variables std::shared_ptr node_; std::shared_ptr geometric_pull_out_; - std::shared_ptr lane_departure_checker_; private: - rclcpp::NodeOptions make_node_options() const - { - // Load common configuration files - auto node_options = rclcpp::NodeOptions{}; - - const auto common_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_common.param.yaml"); - const auto nearest_search_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_nearest_search.param.yaml"); - const auto vehicle_info_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_vehicle_info.param.yaml"); - const auto behavior_path_planner_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "behavior_path_planner.param.yaml"); - const auto drivable_area_expansion_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "drivable_area_expansion.param.yaml"); - const auto scene_module_manager_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "scene_module_manager.param.yaml"); - const auto start_planner_param_path = get_absolute_path_to_config( - "autoware_behavior_path_start_planner_module", "start_planner.param.yaml"); - - autoware::test_utils::updateNodeOptions( - node_options, {common_param_path, nearest_search_param_path, vehicle_info_param_path, - behavior_path_planner_param_path, drivable_area_expansion_param_path, - scene_module_manager_param_path, start_planner_param_path}); - - return node_options; - } - - void initialize_lane_departure_checker() - { - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - const auto vehicle_info = - autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - lane_departure_checker_ = - std::make_shared(lane_departure_checker_params, vehicle_info); - } - void initialize_geometric_pull_out_planner() { auto parameters = StartPlannerParameters::init(*node_); - geometric_pull_out_ = - std::make_shared(*node_, parameters, lane_departure_checker_); + geometric_pull_out_ = std::make_shared(*node_, parameters); } }; @@ -157,15 +89,17 @@ TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) .orientation( geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( 0.708314)); - const auto planner_data = make_planner_data(start_pose, 4619, 4635); - geometric_pull_out_->setPlannerData(std::make_shared(planner_data)); + auto planner_data = std::make_shared(); + planner_data->init_parameters(*node_); + StartPlannerTestHelper::set_odometry(planner_data, start_pose); + StartPlannerTestHelper::set_route(planner_data, 4619, 4635); // Plan the pull out path PlannerDebugData debug_data; - auto result = call_plan(start_pose, goal_pose, debug_data); + auto result = call_plan(start_pose, goal_pose, planner_data, debug_data); - // Assert that a valid geometric geometric pull out path is generated + // Assert that a valid geometric pull out path is generated ASSERT_TRUE(result.has_value()) << "Geometric pull out path generation failed."; EXPECT_EQ(result->partial_paths.size(), 2UL) << "Generated geometric pull out path does not have the expected number of partial paths."; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp index 05a9201dad41d..d2c7c60e1a4ca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "start_planner_test_helper.hpp" + #include #include #include #include -#include #include #include #include @@ -25,15 +26,16 @@ #include #include +#include #include #include using autoware::behavior_path_planner::ShiftPullOut; using autoware::behavior_path_planner::StartPlannerParameters; -using autoware::lane_departure_checker::LaneDepartureChecker; using autoware::test_utils::get_absolute_path_to_config; using autoware_planning_msgs::msg::LaneletRoute; using RouteSections = std::vector; +using autoware::behavior_path_planner::testing::StartPlannerTestHelper; using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; namespace autoware::behavior_path_planner @@ -43,101 +45,34 @@ class TestShiftPullOut : public ::testing::Test { public: std::optional call_plan( - const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + const Pose & start_pose, const Pose & goal_pose, + const std::shared_ptr & planner_data, PlannerDebugData & planner_debug_data) { - return shift_pull_out_->plan(start_pose, goal_pose, planner_debug_data); + return shift_pull_out_->plan(start_pose, goal_pose, planner_data, planner_debug_data); } protected: void SetUp() override { rclcpp::init(0, nullptr); - node_ = rclcpp::Node::make_shared("shift_pull_out", make_node_options()); + node_ = + rclcpp::Node::make_shared("shift_pull_out", StartPlannerTestHelper::make_node_options()); - initialize_lane_departure_checker(); initialize_shift_pull_out_planner(); } void TearDown() override { rclcpp::shutdown(); } - PlannerData make_planner_data( - const Pose & start_pose, const int route_start_lane_id, const int route_goal_lane_id) - { - PlannerData planner_data; - planner_data.init_parameters(*node_); - - // Load a sample lanelet map and create a route handler - const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( - "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); - auto route_handler = std::make_shared(map_bin_msg); - - // Set up current odometry at start pose - auto odometry = std::make_shared(); - odometry->pose.pose = start_pose; - odometry->header.frame_id = "map"; - planner_data.self_odometry = odometry; - - // Setup route - const auto route = makeBehaviorRouteFromLaneId( - route_start_lane_id, route_goal_lane_id, "autoware_test_utils", - "road_shoulder/lanelet2_map.osm"); - route_handler->setRoute(route); - - // Update planner data with the route handler - planner_data.route_handler = route_handler; - - return planner_data; - } - // Member variables std::shared_ptr node_; std::shared_ptr shift_pull_out_; - std::shared_ptr lane_departure_checker_; private: - rclcpp::NodeOptions make_node_options() const - { - // Load common configuration files - auto node_options = rclcpp::NodeOptions{}; - - const auto common_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_common.param.yaml"); - const auto nearest_search_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_nearest_search.param.yaml"); - const auto vehicle_info_param_path = - get_absolute_path_to_config("autoware_test_utils", "test_vehicle_info.param.yaml"); - const auto behavior_path_planner_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "behavior_path_planner.param.yaml"); - const auto drivable_area_expansion_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "drivable_area_expansion.param.yaml"); - const auto scene_module_manager_param_path = get_absolute_path_to_config( - "autoware_behavior_path_planner", "scene_module_manager.param.yaml"); - const auto start_planner_param_path = get_absolute_path_to_config( - "autoware_behavior_path_start_planner_module", "start_planner.param.yaml"); - - autoware::test_utils::updateNodeOptions( - node_options, {common_param_path, nearest_search_param_path, vehicle_info_param_path, - behavior_path_planner_param_path, drivable_area_expansion_param_path, - scene_module_manager_param_path, start_planner_param_path}); - - return node_options; - } - - void initialize_lane_departure_checker() - { - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - const auto vehicle_info = - autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - lane_departure_checker_ = - std::make_shared(lane_departure_checker_params, vehicle_info); - } - void initialize_shift_pull_out_planner() { auto parameters = StartPlannerParameters::init(*node_); - shift_pull_out_ = std::make_shared(*node_, parameters, lane_departure_checker_); + shift_pull_out_ = std::make_shared(*node_, parameters); } }; @@ -156,13 +91,14 @@ TEST_F(TestShiftPullOut, GenerateValidShiftPullOutPath) .orientation( geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( 0.708314)); - const auto planner_data = make_planner_data(start_pose, 4619, 4635); - - shift_pull_out_->setPlannerData(std::make_shared(planner_data)); + auto planner_data = std::make_shared(); + planner_data->init_parameters(*node_); + StartPlannerTestHelper::set_odometry(planner_data, start_pose); + StartPlannerTestHelper::set_route(planner_data, 4619, 4635); // Plan the pull out path PlannerDebugData debug_data; - auto result = call_plan(start_pose, goal_pose, debug_data); + auto result = call_plan(start_pose, goal_pose, planner_data, debug_data); // Assert that a valid shift pull out path is generated ASSERT_TRUE(result.has_value()) << "shift pull out path generation failed."; From f0d7d8dd2872a886faa956d755c1272d45f165e1 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Jan 2025 09:08:30 +0900 Subject: [PATCH 18/59] docs(lane_change): fix broken link (#9892) Signed-off-by: Zulfaqar Azmi --- .../autoware_behavior_path_lane_change_module/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index c5cdf0bb68bc2..b4f848e0809aa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -1201,6 +1201,6 @@ Available information ## Limitation 1. When a lane change is canceled, the lane change module returns `ModuleStatus::FAILURE`. As the module is removed from the approved module stack (see [Failure modules](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design/#failure-modules)), a new instance of the lane change module is initiated. Due to this, any information stored prior to the reset is lost. For example, the `lane_change_prepare_duration` in the `TransientData` is reset to its maximum value. -2. The lane change module has no knowledge of any velocity modifications introduced to the path after it is approved. This is because other modules may add deceleration points after subscribing to the behavior path planner output, and the final velocity is managed by the [velocity smoother](https://autowarefoundation.github.io/autoware.universe/pr-9845/planning/autoware_velocity_smoother/). Since this limitation affects **CANCEL**, the lane change module mitigates it by [sampling accelerations along the approved lane change path](#checking-approved-path-safety). These sampled accelerations are used during safety checks to estimate the velocity that might occur if the ego vehicle decelerates. +2. The lane change module has no knowledge of any velocity modifications introduced to the path after it is approved. This is because other modules may add deceleration points after subscribing to the behavior path planner output, and the final velocity is managed by the [velocity smoother](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_velocity_smoother/). Since this limitation affects **CANCEL**, the lane change module mitigates it by [sampling accelerations along the approved lane change path](#checking-approved-path-safety). These sampled accelerations are used during safety checks to estimate the velocity that might occur if the ego vehicle decelerates. 3. Ideally, the abort path should account for whether its execution would affect trailing vehicles in the current lane. However, the lane change module does not evaluate such interactions or assess whether the abort path is safe. As a result, **the abort path is not guaranteed to be safe**. To minimize the risk of unsafe situations, the abort maneuver is only permitted if the ego vehicle has not yet diverged from the current lane. 4. Due to limited resources, the abort path logic is not fully optimized. The generated path may overshoot, causing the return trajectory to slightly shift toward the opposite lane. This can be dangerous, especially if the opposite lane has traffic moving in the opposite direction. Furthermore, the logic does not account for different vehicle types, which can lead to varying effects. For instance, the behavior might differ significantly between a bus and a small passenger car. From 4b11912180be2a8fadcfd42889bba54e42cc9324 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 14 Jan 2025 11:30:45 +0900 Subject: [PATCH 19/59] =?UTF-8?q?feat:=20=20tier4=5Fdebug=5Fmsgs=20to=20au?= =?UTF-8?q?toware=5Finternal=5Fdebug=5Fmsgs=20in=20file=20contr=E2=80=A6?= =?UTF-8?q?=20(#9837)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs to autoware_internal_debug_msgs in file control/autoware_control_validator Signed-off-by: vish0012 --- .../autoware/control_validator/control_validator.hpp | 5 +++-- .../autoware_control_validator/src/control_validator.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp index 080e8f0e6abc3..b828c8d07ac49 100644 --- a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp +++ b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp @@ -25,10 +25,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -139,7 +139,8 @@ class ControlValidator : public rclcpp::Node universe_utils::InterProcessPollingSubscriber::SharedPtr sub_reference_traj_; rclcpp::Publisher::SharedPtr pub_status_; rclcpp::Publisher::SharedPtr pub_markers_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; // system parameters int64_t diag_error_count_threshold_ = 0; diff --git a/control/autoware_control_validator/src/control_validator.cpp b/control/autoware_control_validator/src/control_validator.cpp index 0c16fae065939..e0b9c7135e5f0 100644 --- a/control/autoware_control_validator/src/control_validator.cpp +++ b/control/autoware_control_validator/src/control_validator.cpp @@ -48,8 +48,8 @@ ControlValidator::ControlValidator(const rclcpp::NodeOptions & options) pub_markers_ = create_publisher("~/output/markers", 1); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); debug_pose_publisher_ = std::make_shared(this); @@ -181,7 +181,7 @@ void ControlValidator::publish_debug_info() debug_pose_publisher_->publish(); // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); From c47cd5d6a985df04f61c4499d90e6d273e0abdb2 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Tue, 14 Jan 2025 11:43:58 +0900 Subject: [PATCH 20/59] feat(lane_change): append candidate path index to metric debug table (#9885) add candidate path index to metrics debug table Signed-off-by: mohammad alqudah --- .../scene.hpp | 3 +- .../structs/debug.hpp | 2 +- .../src/scene.cpp | 20 ++++--- .../src/utils/markers.cpp | 56 ++++++------------- 4 files changed, 32 insertions(+), 49 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index fe1d18ea6ea0c..a8b7a670c881b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -135,7 +135,8 @@ class NormalLaneChange : public LaneChangeBase std::vector get_prepare_metrics() const; std::vector get_lane_changing_metrics( const PathWithLaneId & prep_segment, const LaneChangePhaseMetrics & prep_metrics, - const double shift_length, const double dist_to_reg_element) const; + const double shift_length, const double dist_to_reg_element, + lane_change::MetricsDebug & debug_metrics) const; bool get_lane_change_paths(LaneChangePaths & candidate_paths) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 1541846841f20..589f2f20ba258 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -34,7 +34,7 @@ using utils::path_safety_checker::CollisionCheckDebugMap; struct MetricsDebug { LaneChangePhaseMetrics prep_metric; - std::vector lc_metrics; + std::vector> lc_metrics; double max_prepare_length; double max_lane_changing_length; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 09a4216bf5857..88f58debb886a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1083,7 +1083,8 @@ std::vector NormalLaneChange::get_prepare_metrics() cons std::vector NormalLaneChange::get_lane_changing_metrics( const PathWithLaneId & prep_segment, const LaneChangePhaseMetrics & prep_metric, - const double shift_length, const double dist_to_reg_element) const + const double shift_length, const double dist_to_reg_element, + lane_change::MetricsDebug & debug_metrics) const { const auto & transient_data = common_data_ptr_->transient_data; const auto dist_lc_start_to_end_of_lanes = calculation::calc_dist_from_pose_to_terminal_end( @@ -1100,15 +1101,11 @@ std::vector NormalLaneChange::get_lane_changing_metrics( return max_length; }); + debug_metrics.max_lane_changing_length = max_lane_changing_length; const auto max_path_velocity = prep_segment.points.back().point.longitudinal_velocity_mps; - const auto lc_metrics = calculation::calc_shift_phase_metrics( + return calculation::calc_shift_phase_metrics( common_data_ptr_, shift_length, prep_metric.velocity, max_path_velocity, prep_metric.sampled_lon_accel, max_lane_changing_length); - - const auto max_prep_length = common_data_ptr_->transient_data.dist_to_terminal_start; - lane_change_debug_.lane_change_metrics.push_back( - {prep_metric, lc_metrics, max_prep_length, max_lane_changing_length}); - return lc_metrics; } bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const @@ -1185,8 +1182,12 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const auto shift_length = lanelet::utils::getLateralDistanceToClosestLanelet(target_lanes, lane_changing_start_pose); + lane_change_debug_.lane_change_metrics.emplace_back(); + auto & debug_metrics = lane_change_debug_.lane_change_metrics.back(); + debug_metrics.prep_metric = prep_metric; + debug_metrics.max_prepare_length = common_data_ptr_->transient_data.dist_to_terminal_start; const auto lane_changing_metrics = get_lane_changing_metrics( - prepare_segment, prep_metric, shift_length, dist_to_next_regulatory_element); + prepare_segment, prep_metric, shift_length, dist_to_next_regulatory_element, debug_metrics); // set_prepare_velocity must only be called after computing lane change metrics, as lane change // metrics rely on the prepare segment's original velocity as max_path_velocity. @@ -1194,6 +1195,8 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { + debug_metrics.lc_metrics.push_back({lc_metric, -1}); + const auto debug_print_lat = [&](const std::string & s) { RCLCPP_DEBUG( logger_, "%s | lc_time: %.5f | lon_acc: %.5f | lat_acc: %.5f | lc_len: %.5f", s.c_str(), @@ -1215,6 +1218,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } candidate_paths.push_back(candidate_path); + debug_metrics.lc_metrics.back().second = candidate_paths.size() - 1; try { if (check_candidate_path_safety(candidate_path, target_objects)) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index eb120e006a229..ef899cceea0d4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -73,32 +73,6 @@ MarkerArray showAllValidLaneChangePath( marker.points.push_back(point.point.pose.position); } - const auto & info = lc_path.info; - auto text_marker = createDefaultMarker( - "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); - const auto prep_idx = points.size() / 4; - text_marker.pose = points.at(prep_idx).point.pose; - text_marker.pose.position.z += 2.0; - text_marker.text = fmt::format( - "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | t: {time:.3f}[s] | L: {length:.3f}[m]", - fmt::arg("vel", info.velocity.prepare), - fmt::arg("lon_acc", info.longitudinal_acceleration.prepare), - fmt::arg("time", info.duration.prepare), fmt::arg("length", info.length.prepare)); - marker_array.markers.push_back(text_marker); - - const auto lc_idx = points.size() / 2; - text_marker.id = ++id; - text_marker.pose = points.at(lc_idx).point.pose; - text_marker.text = fmt::format( - "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | lat_acc: {lat_acc:.3f}[m/s2] | t: " - "{time:.3f}[s] | L: {length:.3f}[m]", - fmt::arg("vel", info.velocity.lane_changing), - fmt::arg("lon_acc", info.longitudinal_acceleration.lane_changing), - fmt::arg("lat_acc", info.lateral_acceleration), fmt::arg("time", info.duration.lane_changing), - fmt::arg("length", info.length.lane_changing)); - marker_array.markers.push_back(text_marker); - marker_array.markers.push_back(marker); } return marker_array; @@ -206,26 +180,30 @@ MarkerArray ShowLaneChangeMetricsInfo( createMarkerScale(0.6, 0.6, 0.6), colors::yellow()); text_marker.pose = autoware::universe_utils::calcOffsetPose(pose, 10.0, 15.0, 0.0); - text_marker.text = fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + - fmt::format("{:^18}|", "lon_accel[m/s2]") + - fmt::format("{:^17}|", "velocity[m/s]") + - fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + - fmt::format("{:^20}\n", "max_length_th[m]"); + text_marker.text = + fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + + fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); for (const auto & metrics : debug_data.lane_change_metrics) { - text_marker.text += fmt::format("{:-<170}\n", ""); + text_marker.text += fmt::format("{:-<190}\n", ""); const auto & p_m = metrics.prep_metric; text_marker.text += fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + - fmt::format("{:^17.3f}\n", metrics.max_prepare_length); + fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); - for (const auto lc_m : metrics.lc_metrics) { - text_marker.text += - fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", lc_m.lat_accel) + - fmt::format("{:^21.3f}", lc_m.actual_lon_accel) + fmt::format("{:^12.3f}", lc_m.velocity) + - fmt::format("{:^15.3f}", lc_m.duration) + fmt::format("{:^15.3f}", lc_m.length) + - fmt::format("{:^17.3f}\n", metrics.max_lane_changing_length); + for (const auto & lc_m : metrics.lc_metrics) { + const auto & metric = lc_m.first; + const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); + text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + + fmt::format("{:^21.3f}", metric.actual_lon_accel) + + fmt::format("{:^12.3f}", metric.velocity) + + fmt::format("{:^15.3f}", metric.duration) + + fmt::format("{:^15.3f}", metric.length) + + fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + + fmt::format("{:^15}\n", path_index); } } From 3c5ace825f71da53e41a67fa6c89cc316b1b3c38 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 14 Jan 2025 11:49:39 +0900 Subject: [PATCH 21/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed=20?= =?UTF-8?q?to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(?= =?UTF-8?q?#9859)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_planning_evaluator Signed-off-by: vish0012 --- .../autoware/planning_evaluator/planning_evaluator_node.hpp | 5 +++-- .../src/planning_evaluator_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp index 9c268206846d9..8c0b49ce2dd26 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp @@ -31,8 +31,8 @@ #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" +#include #include -#include #include #include @@ -145,7 +145,8 @@ class PlanningEvaluatorNode : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber accel_sub_{ this, "~/input/acceleration"}; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; std::shared_ptr transform_listener_{nullptr}; std::unique_ptr tf_buffer_; diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index 5889f15e48390..53319ffa4c1fd 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -59,8 +59,8 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op output_metrics_ = declare_parameter("output_metrics"); ego_frame_str_ = declare_parameter("ego_frame"); - processing_time_pub_ = - this->create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = this->create_publisher( + "~/debug/processing_time_ms", 1); // List of metrics to calculate and publish metrics_pub_ = create_publisher("~/metrics", 1); @@ -282,7 +282,7 @@ void PlanningEvaluatorNode::onTimer() metrics_msg_ = MetricArrayMsg{}; // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); From e12bd85c41f8fa8aa1cdc67b528d39c1b3fec813 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 14 Jan 2025 12:20:54 +0900 Subject: [PATCH 22/59] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20to=20autow?= =?UTF-8?q?are=5Finternal=5Fdebug=5Fmsgs=20in=20files=20contr=E2=80=A6=20(?= =?UTF-8?q?#9839)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs to autoware_internal_debug_msgs in files control/autoware_lane_departure_checker Signed-off-by: vish0012 From b5005b6bc117980991a5dd474924c4cb10ca7ed3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 14 Jan 2025 14:44:01 +0900 Subject: [PATCH 23/59] fix(autoware_rtc_interface): fix bugprone-branch-clone (#9698) Signed-off-by: kobayu858 --- planning/autoware_rtc_interface/src/rtc_interface.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 47bc278c30564..7fcd0596b6b32 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -80,9 +80,7 @@ Module getModuleType(const std::string & module_name) module.type = Module::OCCLUSION_SPOT; } else if (module_name == "stop_line") { module.type = Module::NONE; - } else if (module_name == "traffic_light") { - module.type = Module::TRAFFIC_LIGHT; - } else if (module_name == "virtual_traffic_light") { + } else if (module_name == "traffic_light" || module_name == "virtual_traffic_light") { module.type = Module::TRAFFIC_LIGHT; } else if (module_name == "lane_change_left") { module.type = Module::LANE_CHANGE_LEFT; From 0715615b684e1a8b98a560ff2cd9ef03a1232783 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Jan 2025 14:57:42 +0900 Subject: [PATCH 24/59] feat(lane_change): using frenet planner to generate lane change path when ego near terminal (#9767) * frenet planner Signed-off-by: Zulfaqar Azmi * minor refactoring Signed-off-by: Zulfaqar Azmi * adding parameter Signed-off-by: Zulfaqar Azmi * Add diff th param Signed-off-by: Zulfaqar Azmi * limit curvature for prepare segment Signed-off-by: Zulfaqar Azmi * minor refactoring Signed-off-by: Zulfaqar Azmi * print average curvature Signed-off-by: Zulfaqar Azmi * refactor Signed-off-by: Zulfaqar Azmi * filter the path directly Signed-off-by: Zulfaqar Azmi * fix some conflicts Signed-off-by: Zulfaqar Azmi * include curvature smoothing Signed-off-by: Zulfaqar Azmi * document Signed-off-by: Zulfaqar Azmi * fix image folder Signed-off-by: Zulfaqar Azmi * image size Signed-off-by: Zulfaqar Azmi * doxygen Signed-off-by: Zulfaqar Azmi * add debug for state Signed-off-by: Zulfaqar Azmi * use sign function instead Signed-off-by: Zulfaqar Azmi * rename argument Signed-off-by: Zulfaqar Azmi * readme Signed-off-by: Zulfaqar Azmi * fix failed test due to empty value Signed-off-by: Zulfaqar Azmi * add additional note Signed-off-by: Zulfaqar Azmi * fix conflict Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../README.md | 58 +++ .../config/lane_change.param.yaml | 7 + .../images/terminal_branched_frenet.png | Bin 0 -> 53664 bytes .../images/terminal_branched_path_shifter.png | Bin 0 -> 59599 bytes .../images/terminal_curved_frenet.png | Bin 0 -> 76194 bytes .../images/terminal_curved_path_shifter.png | Bin 0 -> 71940 bytes .../images/terminal_straight_frenet.png | Bin 0 -> 29125 bytes .../images/terminal_straight_path_shifter.png | Bin 0 -> 24433 bytes .../scene.hpp | 12 + .../structs/data.hpp | 1 + .../structs/debug.hpp | 15 + .../structs/parameters.hpp | 9 + .../structs/path.hpp | 37 +- .../utils/path.hpp | 62 ++- .../utils/utils.hpp | 46 +- .../package.xml | 1 + .../src/manager.cpp | 18 + .../src/scene.cpp | 100 +++- .../src/utils/markers.cpp | 119 +++-- .../src/utils/path.cpp | 471 +++++++++++++++++- .../src/utils/utils.cpp | 80 ++- .../src/frenet_planner/frenet_planner.cpp | 9 + 22 files changed, 991 insertions(+), 54 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_path_shifter.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_path_shifter.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_path_shifter.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index b4f848e0809aa..ee371f8592833 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -787,6 +787,51 @@ Depending on the space configuration around the Ego vehicle, it is possible that Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. +## Generating Path Using Frenet Planner + +!!! warning + + Generating path using Frenet planner applies only when ego is near terminal start + +If the ego vehicle is far from the terminal, the lane change module defaults to using the [path shifter](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design/). This ensures that the lane change is completed while the target lane remains a neighbor of the current lane. However, this approach may result in high curvature paths near the terminal, potentially causing long vehicles to deviate from the lane. + +To address this, the lane change module provides an option to choose between the path shifter and the [Frenet planner](https://autowarefoundation.github.io/autoware.universe/main/planning/sampling_based_planner/autoware_frenet_planner/). The Frenet planner allows for some flexibility in the lane change endpoint, extending the lane changing end point slightly beyond the current lane's neighbors. + +The following table provides comparisons between the planners + +

+ + + + + + + + + + + + + + + + +
With Path ShifterWith Frenet Planner
Path shifter result at straight laneletsFrenet planner result at straight lanelets
Path shifter result at branching laneletsFrenet planner result at branching lanelets
Path shifter result at curved laneletsFrenet planner result at curved lanelets
+
+ +!!! note + + The planner can be enabled or disabled using the `frenet.enable` flag. + +!!! note + + Since only a segment of the target lane is used as input to generate the lane change path, the end pose of the lane change segment may not smoothly connect to the target lane centerline. To address this, increase the value of `frenet.th_curvature_smoothing` to improve the smoothness. + +!!! note + + The yaw difference threshold (`frenet.th_yaw_diff`) limits the maximum curvature difference between the end of the prepare segment and the lane change segment. This threshold might prevent the generation of a lane change path when the lane curvature is high. In such cases, you can increase the frenet.th_yaw_diff value. However, note that if the prepare path was initially shifted by other modules, the resultant steering may not be continuous. + ## Aborting a Previously Approved Lane Change Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met @@ -1008,6 +1053,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `trajectory.max_longitudinal_acc` | [m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 | | `trajectory.min_longitudinal_acc` | [m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 | | `trajectory.lane_changing_decel_factor` | [-] | double | longitudinal deceleration factor during lane changing phase | 0.5 | +| `trajectory.th_prepare_curvature` | [-] | double | If the maximum curvature of the prepare segment exceeds the threshold, the prepare segment is invalid. | 0.03 | | `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 | | `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/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | @@ -1057,6 +1103,18 @@ The following parameters are used to configure terminal lane change path feature | `terminal_path.disable_near_goal` | [-] | bool | Flag to disable terminal path feature if ego is near goal | true | | `terminal_path.stop_at_boundary` | [-] | bool | If true, ego will stop at current lane boundary instead of middle of lane | false | +### Generating Lane Changing Path using Frenet Planner + +!!! warning + + Only applicable when ego is near terminal start + +| Name | Unit | Type | Description | Default value | +| :------------------------------ | ----- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `frenet.enable` | [-] | bool | Flag to enable/disable frenet planner when ego is near terminal start. | true | +| `frenet.th_yaw_diff` | [deg] | double | If the yaw diff between of the prepare segment's end and lane changing segment's start exceed the threshold , the lane changing segment is invalid. | 10.0 | +| `frenet.th_curvature_smoothing` | [-] | double | Filters and appends target path points with curvature below the threshold to candidate path. | 0.1 | + ### Collision checks #### Target Objects diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 91b296f8bd40f..df9491576a4ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -29,6 +29,7 @@ lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 lane_changing_decel_factor: 0.5 + th_prepare_curvature: 0.03 # [/] # delay lane change delay_lane_change: @@ -37,6 +38,12 @@ min_road_shoulder_width: 0.5 # [m] th_parked_vehicle_shift_ratio: 0.6 + # trajectory generation near terminal using frenet planner + frenet: + enable: true + th_yaw_diff: 10.0 # [deg] + th_curvature_smoothing: 0.1 # [/] + # safety check safety_check: allow_loose_check_for_cancel: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..51f3a2fc46500039d3a136d93a7918b2de82cc36 GIT binary patch literal 53664 zcmeFYWl&r}6E?c|;)}bx1WB;q4uRnA5JGSZ5`w#H@DLn=Yj9_=0158yE=ve*_mKB} z?^kvI-n#$psjXT$J2O2!Jx@Q~(A86b%FdVZM=8HkPtN-)l>hsiD=|h> z_5`xp^H3@&S$XwM+m-ib@B*GduIl0G8!B8+Nph09nY{g7pLIzU&<%2tX zlL1g<`0a29fnjEwv)k>5+5HH|hJ1qyKaYX6*yo8~!+sE5;1;dm;82W|WaZ7Bt}jy~ zeiA2NIYXd%UYktKZ=Q0}Q%}lnU2f_WmQEzPKV)p~z~R#1T3YMjnUG7E})iF?32 zFD(p?x@C&UIz_4T%zONtBA!(lzQ_Dex3qa0r(DORdt2rqR5)r+=3O#IH9CokzyzP? zs4vWvKlyA9z^oAzq@^E<6A7w-_QihxYaHi8Yt8u$ssPAB?DSu&!5J5S?#E2en?=p* z8j~3Z=YmW*n<+2RfA_tni~e2B8NdIt2+F*^H+vP;f+D{cWwY>b zkwzq^&+~i)lcB0to?xa0iSH~FgJ+B7rq-zp4DcpLtw#LN*dF4koiS-?-XXNb1?AG6 z(ien(5a7OhPy7*IR^&~q1Qvhs@HI3um`EF>J597U!hwNs=|n@2gv z`D>od?)3pzaKQ8C!AyB5(z#G3C#1&}x0pSWo@zWKTCNm?S624m0jFq3dKrtoKFHCv zs~Vj)W+zbTrXr&ZIYohaQxz&8g}igj63gm?jMtpsgXfL0^AH4U54$IQY4D_;6`dD! zu$xn=A=FdW8$09odp32*U|qfOd--&ug_E>gud|&%Y>XXa%piA8HA$G=XsS+}J%%ts ze&t6Bq*2Q&CBgK(pOR}7KCj+AceZA##j`Bt?xpp*LfY~1U}kmHSPXXDe)fuj>aLoV zF41Utb-VTS-QL|3z5&gQ1I>!|PhR*|O02)Nq@jCUwdt-8qxx<{PIUo9fH{HYT^&u=|@-MN*5kBF^iX(7Y4P*EA93bRkrNxPH#Tb(jLSZhf(|ZS?V$-J<`k1} zW{9!=mXd}R8`w-6iQj(}Ed^cmA{oAE{4~tfxN$k?L4N1)mEUrbCeP{VX0x7%{~}c$ zSy!CgDJI=P^n8OMUVtpSHt2Hxw(!Qo8`-gak-r)uDS!FyKJ$GJU}7EQ^o^@%Vd*o zyo0gjE@1R_+6FCx4UPcoZtY5@k zDpC^6k5{I+ml7AvmVgAqf6}qix*=+juz1sYpYf}*CSA0;8Zt07|w)t%}9ExxD2G#aukH%i)RikU* z6xO1|60PlD&M2rD707Y*Fa7*0up1*ca>8m|Ybo4{r+@zOxlDY`(n2BbTB^;l=-6WP zI2W;QSXr^3-hL}L7&XMj_&DIESC#t*winBrqzJ9WBC4h;a)+;cD77qzRxPc2e3;`* zG7AB_865LwDl?F{tF2ml`%r4R5fSy}D!aatH?`vRAeCaXJyW~i-BdYDEoppm+KuVB zz>f7cT;vU{1tD-Q>=)m%&yrgL@|05C3rI!yf=MqYsw^_+U2zl5^IMHi1^9+F?v|W5 zW@p?VU`p$1=si|B@Ejl~qku9U>{l-g;GBpVRaalfas?D?v=^Vy+UOjP+ELCJ-|&;@ zV}{2{mcf0*_lXT}C?i<>OFL!r9?oD@nroiIn_WfZ^YynZVGO+DZ0@%?zOyk`V_aJp z$OoZ2L-qsCYXVrc=@^XJZ81zH_ZGrbUysJ;l&g+45WFb#Be0*~1$K}cY^Gm{KM^{P ztsSPSmZ@p5K&^{OU)w)-%C!9&6To1M5u2|P5X!+kQec!-?)XCAnQKZ?L>jb=z6RqA znmfnw4#7jb1EU8)LPwvVZtc_y1FPvcVw-X2y{q$4qtO{%-j9D^um6vr^=R*JZVQaj z0-OBITDu7|?P5eK^3FLyj!%>J2CkOQ8L}(WRR|!d3M{TVLE%t+S90Wiw;A`>lIGK3 zl{}TuM0HeYgO;0bp}TDk*l}3l(?(Nq#LTKy)2#I%7_SGE7g@Wjo3y5AHfxg^{)K<; zjPd26B@)nAxda+nvEOkcOpo8#(!_h)U9K@BOH{WCIzC<@x=r!BalI6S37aiInNqZf zNfFoz9<*{IP}L~Uip5;*E|y3Um$b3cR2vO!xNj}0QMuD*>3ofNtq#MgQ45&BD~z#! z;8Q!tM8%yZ*7mvmacgSJglg!t5fgS(T{930nx`_aS3T zHI{nQXmB=`{_bE&9GS!QFLLvnd*56FgtEs^6Ou1N{iLZAT+r;lGuG4+)a-p%pq zDlcT%RekR0JoVn~c~{J<+qRzy0+AVqf7E<|LMb#SdVA9=Lb{Fmp3UshU*!)+zwaec z*N-cq4xi(T#*h2xb3bEUE#A6%?lYn3Ucd?x54g ze!~mY535f-4OhLe@XH?!9UX^mF{A6Uxz)Q373`JlpLo89sq6~27`4Xotd*{#UYV|+ z^Xhtwf&5QIEZ-ectsHA$Vde3Om~n0wgW2YUl21Q~e@s&~W0Nn|B5+-4n#u4*WlQY< zfiMX6<~~ny=DzeqF1)8V@teYH_r=C2@2#Oqyj85q=xrp^uO~2do$GC0C9f;_OYMAg zJ$#&-n@ce(L#I>b=Y_}&>O8+9p~MUiLX;dHz6+BW&H8=Xs`NW<_3rcH;>nKKQ=DJp zTSJhwm(W7;j zOkxifGrn0)$(TT`dvN>Zgf4!!t|rut<8;4{bD=y7&!KEVCVU*MABO5mTCef@$EheO zX)>jan8;DH8M_u{6PEFV%NMfDEX{h=fBE z9KNHiAkL04ubE`?xL_1E3o6ZKr)}L>y6qbLX{s0KT`@$LbEe#n`E7Hq`_8MMN{Fa~ z@L(QzIBx#yIQIOaFNe@L*4}G9U`WPmAadOdJh@#I9cu~Qp)j^{415m~y3B%5!Fil{ zVAU_11;zCsquphdW1|-@Hjba*_c8l@zimXyX&Rd$b{9$z#bN585UjW|QkY%|wd6eR zjBz-<_+Or3vKw4!~T`%_2zdf5=tD3Ujbq= zo;sZYT4KGPQ!Dso%JA9BY;MZ4HUh_5Anqwr49k&Ud=G{l4_6S3Q4pvfZVBV^>AMBr zUfWO(U*`I5&nRp;6!!OOX4Tq@%3g`UO5(8k*go!WZ)2uWoHCVZ7zMk;D4sPCDmG*Z zP-GWse>vv;dV=zCU+v*^W1h)=wQ>@9FleVh(*mQ`vHb%5BHs3Q7F2Acv*WPgM(pl< zlaw&?qwV1#Q|)R-y@@K+|2+(2!R0cB51R4dO1Jbnx}hgi`0^A54s=bf`*hDGb@0>9 zqq9VydUEW5`nFO(s2CeYf4k*za$?8ojq7ue)rLJdB{XxOyshM}?fYG)3iwLIq?6Ou z(H>;s0h~aH+eS5w#OC0Y{AZGzq4V3(t1w4On^n00rU`%yR}t$2gkP-;#c*Kdu;@Tj z>(sS}t?J0xVrh%25Ifd_d1_S<{nH5_fg2@b@4oEZgo;G}tiNYheO6lU)yG{gAs`gW z!{R|!TApI9duIxSO#_3seJ1y$c?o6HR8(+>ahGk~?&T}FzEd&#B4O!*uZq`|xyhhw zekD)8AYtJx>&42&C|WPTIdhk+S&5Nm*nl|WwYBr?UGWFK`#V$R%H(`&`$a<(dD@Hb$^qjM-|{>la?5hN%y--5GT6k(|I26bSY2W?As4cum~u%?VWOrV0g?89F05bg z;wXSgNlSveK*%4SV*Ul(d(w&jQZ3^W3`>Y3Bfr*u{lWeZ38BJlT zSo6*CrNk8bEzWNuMEqZwo@L6@03z{mRMYS3%kwI=H!pH0AHF6?^N0Rm%5=f@CTm`= zZ?DiT;d!tNeT`X3G0SNrE1Er!Sfs)&oFoT9gs~bMe%=;<`A|tfOe?D45Z2Bnn?+{D z*;77sD(jRr3Rl(M$^KhJS5_boP(!O9X`4HmTFd5qxvD%i&C$+O>F#xjXoG?PiE)S(WxpN z&yCbjTIgc`iYh7OObj>gPlh8nO1;|iX+-Ws7`E{q@f z)PT0J+58%WY(^}hCp4h^A0rzOM>aGn)83abt<7*iVhQ7Brom7XTX?*ieED{f@auYE zX2uagQnLg(L&Ua1&t-S4k3d5V7lxVMZ^tuV2z9zVb)qtjS!*?W2v_8qF5w?3DR~AB za6a=&6(l~qtbn${EII&0{l1Ma;`9!jUrg#i;*o{ILNKE}tLi?iDk=HeL70MD1M?>$ z2*Hk!KjDp~lluo`m7N{xd(f=o5-7OqK@MB3Qj^*s*nTnH2G;NNoO?y?v#W-myD_T5 z9yLZ0n;&x?viQ+XDLJdVo-sM#&V|e@&BKgq=Hkd?0LsN^tc*icAClb)S#(5`v-4rs zVZ?lEUcrU<7@E3>ttCo1Ap1SaA(UC7#sgV>busX z)JM}^vGEXbp!>c_%b6fWSfC;3qL1LZ0~;jIqyd3|^TFxTxDnFum7BDYv`w)HG}8Be zAaw;qGjJh(QW7{&K=oBWb?R@ZGx^-~_tOS@DcczJ*I7EnNzjcA+KrZB(1I0U zvq@|gNo)ij1lVdXL+(DEu5arY_Zv92MO^tlz7kH)kYY?lGWd!2j3#PA?4ioiQ;Lg0 z1=_-R@ExHRAUVyV8PsNTp`sQ}1D2mQg$dK|g!b+G7#&!V7^FpnZSZAUT9n}R1XR_h zgGv`|SXXo;sVB}X8Z4yd>Yau`3EhV8`|fH=Q{hzWPq(20;(_q*1t~4n7vvWWrVG^- zg1?i-YN6LA6`HmhXduNz4D6R3JlNbXjJiQU%t9<67BEe<_8(9M4J!`&x_L=cg!FtU z1lM!2=k`|6a6p1KU79sHIF{C`B0-^F13M%M0^vd>lGH3~Pm;`4^{>Sb>_+6Glh@{ha@OQ5-!Ew?6Vtzdr5d-pA5!s7;J&9N*u&&=K!A)NOe@M zP6upjQhb2UMwEWZ?Y=si7v?Z&nL0FcT^3hXqZb^Mt=P%Zsa%>rFJ}1hA}69jl02U` zkgGUMBu}u09So13?}7Hs`GszPgZ?-Nny_vL*2~)FZqFC;wMl`sn~gZLkptF&6`T4r zIr(4(mVycEpW4g41UYn=!wosK;;;FH{{vC5e2A?t4k+I3i@XAv@JQrGqG{=;KK+ zf^{`v@*x~Wo(Ea;s7-(Zi~P|FSS;H$V4=nZS=JWJf}<&%l*QTol`ER28;hX1sDZph^L} zpWC7FAwlnJo3D(9s}JIjm_;1~QxVxCm?y&Xz%6;Il}Tp!5Cv)s;XRw_q$(-h6r(4S zIenulwbw9xe)+0UQAzOJ<%~I}g(0%mqAfg{cD?6Y7NoR|tScFs4o<)Lk#^E$F$JRye4O2y)duHlVk;-rH;RoN6GDe#+88$hUqGs4}*3+YbIJJo_iwJZ&I9P2pdOIA(@ubcU0> zf#*=TF~-d52~np#rZ>HZa3MDwipzkK{PE%EU6BQ+Akffp( zcu6yXzCHkzm)(HkP0qCZjJXg<0ud1>sUoL9l6IXo!70}bAH}#ohYx$S^0B0vm!QTu z)cD0;=Y(<{E?(mm4kRRouLiyitzqr44EoX5onym1!i`?XI$*U5#6_=y^l=&wvObT4 z+@x?*2&y=gng=IXEnYBiOwC6D2seWX&!qHy_LLO($QJ{N`bAoyT!Clsh_bXFU;NxB zw`(F66$)9OrWNhHdmRj!V|RGx3fpiWR^j3>LSDUwLLHds+8JrKV!D{FZrIMJN@Lc|=W%UxG zriJ#*v(~JWETSedLvKub3;_HJj)!0I#3|84i^Z$*w_L;u#y6Ophv-;_m<9i|3YPGv z2CFjTL(mY|aQG3h13}4=C_<@$(__Od#TTA7zlQ2U>#lsuxcaHb%-TN=bxpDL`0KCX z#Bq-aWz-@#i(7<{2E-m{Fsm7ebD_cMNX+4;SkO$gte}_qVuVW}>9&>}7ZMUrbDm1B z?VkS8ty^&L8moU;xnYDV=NZ?dfC$>ZJr6B9a}hmM9!d@ON(i}7-DzYiUd+;LdmoSGmcx^=z5}{G{w~O-+Xv>p!Q?Fhlo(fs-gr0xkG0b?dFdAgB!- zdK9`m7`-{60*w{VMqUi+^fId8xC=X|$&+b>N0yMFIuU~O3r!7^w z#P?5v?}&h;fg4nb2eAP+#EUh^=yL7thSgBZ%@UTIN1GDH`-StDWL4Ebt8R(-uT(7W z&VTfJZ|fbP9NrIx7_F}hLSpKj2zEy@rSPr6GypJP2Vk=xu`9wUNG{?+nVA*gIC3=a z59uwuYpWgvnCB_6_e|rua?Mh*N{m%)M=H!VIy7bJqVqhv=#m1!yi3986}-@~pgR2M zXtF#uf~xz}p#oDt@GrRiRsw_48c3eY^GDj@HTMf#)8^UQ2b{MRyL5(tZA=fQ zkFEmk*WZ0YnZMyUwN7oigO?Ssu~@VJER ziW1kz)rh$JJntQ@Y?zZ1UvQ#~@f22X>tbv?8l?nkq7Bt-YW*n)E2^$ia()$17e^&T@rEvIF}TfGPFnoGced>&VcAUhRCfr zXdHaySP|2+CV&Y@_L+0H+FKsbB+#+r*PBqqZO(<$w&ycx$#G9`tS92vTDN5Pu8gkx z=IVc9R6XJKf4Fl!?x%bsg#e@3Fy&^TF7zMzfHTyez^^kJ;hoo4h?eJ`{=$s5OWhfy zUA9ph+$--3CK#3Co(oQb?*DyVsMxCg)&rjFnA7z{^DxVVUA{N z(_{|_{sI$@u@elTj+fVc=^$7| zM{G}>92lJ^08xLL^-hmL>zp+}-JNr3E|uG#>!QT%P9(On?vrNHG-w2fL?=FHD6V4;+|NqLLa1&W&ATMz`iC zpjxfZ9d?$o$$f>Dv`j!fod1{uoK zRYhQQ=&y_kjioIv2x6Z2sS^F^%(#wF=9o8tNS`jLqRa&Y<8Q-*G_6fjM>_r=@qm%o zn!0bsa}RGqh-T5!3=MnE&uEsY7FZ3$A`dDb0xR`98$5HYPrZ#OgHP|6?RsgP_)sb8YxzbWWv zCR$dE9vh_8(A_&Ab`QX+ZmvV-&#qjp)V9`mdJUstYvp%x6#kI!uFdyXgp<-d83DCO zUtHVkTYaoo#Ep$5H6EY4r%i&ny~#yQvI9@{spg9%c>lpZ-uDWWE7>Hr&G!5VRsA`N zU^PeL)l&7UL?>IX>TQ9Mj!ypE=xjv;`K>>%lh88GhN9FESEXUB1m*S)rab%NUIf(n zmrJW^W}VL~C|I6r>bq(W{V_Y9p(5m}e}CPcy;YIqkUtOx*fl~Sedv4KGT##Yn;*QHWvVcm?Z?$Z z;(W5ljvt=I>XlvY-#pW5462yzd8FNJa*G|AOEm~LpM+vD7aKkSaaURsw${aIy$vx7 z1N?9x!F9DgdIDVrYmN;ZP?}+-Uy0F-$*@=f+|;5Y^9iLvr;jKISo*xlXQsM4@@*f; zY$*#ruXQM%o+c|nu}!>|Eg}^%T#~(n0-QO9otNds$R$_VG#@B_ba#<7swhfztlFL| zHp9OVKNw$Cy+1(7t>vA$UuA!dJl!FI;aMhJbgT|NzPOZ?yMO|MJ6IYQ>xK<(I)V-q2z08$he`U1XKnQjscg3HKP z7y)}={2sK42t>naL!3ITgpW&fkq9hxU}{0q$YNg8s^fL1Px8{p4vT6edkWI$z$h~V9{+00+ivVCkikKBg z{bjGL`Q7)+?9d%u6twRR+U7hc?bhg01lXyRzw(pbY&_J^6pME?uqO>$AXYn-Xm(#i zSx=18pbKzclTa81|IXP+==c|}V@(>nm#qyk6QvNKw0;!$kxx5LGT1e_9y@kLjm~}4 zP=Ohu`7#1(!);814=Mm9N$av8goA9wcUUOZ%WOD9jsNi*A;42DF#h$Xo;P6{P2igD zFhGVNe;1@sNjt#rTj1d|GI4iiBjy5939_WYP!O8`ws<$3yB?A=r!6W`R60E$oIH){ z+?@Y7azbo8MLHs-uoO$8uxgVVewt&wV`KcVn}Jvu@>ygU<%X7^t;Dnh^hKfOBs{V> z`CCRaItDwifusQ8+MSafnWO?@AzFE~IBl{xYHQWW=Lzn=|4?`#0@#j0nzRwcb5u+t z^*g7?;vni`mBC051&?E!iSo1nnHs2AnO8&Gr9|IGU~y)SGCMuo5u5t85E@Q;(<+hw z0RM=T=Itgoe%|(xvW-+ueoAsQvU4220S{-BQ@j&8Bwn4D=j-Zr18vp_u`G@Es$7!m zTCxxQOT9IG6vK+6nOVi(eQe4vpXE8A0#edvPYbPA+n93SW1V@VnNSco1o3BUot^EF z9SuEk^ljV3u3r0IUMp9HP1kfu0})E04_j`ZdaymtlP}Ai zczS7c*!73!VKrPbsE+UA!_Knn2UlFqU&fMr>HV99pW9rnf+~+b(I*Z}@1HkuaR((s z1s``NuT=jI0R=&}&PY1uvfJrS1KRaY=v}e?Wj}5Te>a{fwMpi^z{icC=d(uwu=#3} z8wm~)>SRd7T#hjESoSr`z24Z^?t{v+6||C2k^CR#k|*WNjxzgwWV5mJFB_}}Bx#z1 zP-%?HN_k|%OdrzqcZ|5>;ZG{}R|@ErsAuCTLZvUGlWP>hFASA6GR}^G{dMR2V@t6^ z{Vv{bgX=MDoEt>+aKTsky^WO_VI zDP$Dy3ggkBxocOF^R^B=lq#3z8^0Mx_bIolGEy>ALpiODa&;BY4x7)G0NoW ziaU#J-eqwazN<@`3pu>51X(R_->cC_{XH(rTg(^=8>)`j_@v(t^`!abnUnafmUk{iF|xXu zrNs{rn98U^WIOc3&)BRU3x?AwiIJVfg zR2B2g!QzYwP-)-4s(16JloY!nDWpHK<8qGfoIvz=MP3Yj#%6o}YX2T0;fMg(@Jk0=b$LyAD#Z-jrt^CoQLjgE#-b;NQMy1Br%_u-!RAI#vzNzix15Lb zC2plsR?m9}MATu496EM_8Q3|~Cz$CC30iU{lQ!yNpQ|rE=WpYFP2X})?|_eM=7miG ztx+mYyEk;@$^3C!k4$zbn>RRy86EyLOAvKsco1OCX(k5!MJ`u0wap#2Nbzu{Z0M;) zBkLQz?6N;T&!xmrV^r%ebq%PTtj{0d4n2-gDq8bLl;m<7W(h`lvqmLl_$T2SubEdg z1)!j-oS8a1$oYLYXbN#$BWwD6qv&C1484mxSyOnpmU6N~QNuT@ZwgS^Ju!E1gX>c` zKW7T=vSN%I*4TA&up`}7IOX558u%^rw@d|%S8^USa5dyrmp2s;~tt@}{5g3BH zy2Dqg{5BO93#`isPQvvC#@6i0@3Zu%<_f!**r{y)CdmEjWdPBraks7m@m021_khcl zlldiWhwvkO-Ar0`_P_u(p_8vSDQ9MDs3B_*3cAa6hRW(<%M;}1_lc&LZdkkh-{Tc6 zs6)CwGzS-zMP2U=iZrFf5RDr3{rV}8#V$7RNz9|@HS;U~%9W}g<{C``&d8HJ=JL&N zi1TZV7kVE;UJL7{_2>gtYfaofaGWM>fHX!DLrPu5L4J3?9nF6j{)3|NT`JRxrkYLB z#)Gi!Mk}7xy=nqOuZy*hhD7}!$;fM!MahXbra#(ZrHh5^?_}is*#v+(N*pyY(=Hh~ z8=lO8VauwGG98otiu7S8cCwTtRdosR99)m<_m4D>2Z^6xKL$Qk>*`jlx__|3SnarA zi2m;Klj#+g?4|+#YF9`N3GiLMm4)6Og>0L)@@-aMw%;|v{onDTVnkmbDyb57hqp#u z209L#(=M|KN(Izp-wlw|!ds(UuDh47&PIabaO|`}u8s>@0Ag+rzPg5P8#I01!JTkG z19I6kKw>ocx7#m_xXsK~sf_MEYp(@%jO#P z&X2QrKW%2Ojr<5xYNS%IboSYyHE#V2U#XNGW)F~Gi8rV;h;3a14J?7#%pd`bJ)y<4wul&0B^ylq(pyPp}F#;XWMf0yVdaid+jiJW+}&b zHWYGry|HZ|ASN25DhGqdW~d4bDIox$!K}S4qH6V)HgpoO{ScMYv%rxZ!Cx>^W zvm++`^{St@8J`fz~Tg=+o7DT*gUIKmZ?UD&y!HusbW2vj^lE!(3@Yk}|{x z%hpcr&F^6&qh~!rVsd>~++WF{=$0H>aV%yzfEwWgnSC96A7MXIuJpn)m3FXcjYH00 zB^su*x_Qka@9||+6==W+N$4_LTfJu~acXi+fppKOxIenlOix94*@eB@qbwPuix2>( z`%)d;=6%WfxXkH`?r7K+auZ|Wef^h`5WNfnNgImW=$}HmUpQ{$N~Q{#Azf`f*9cZy zA{LIOCC*=8z~YGgZ3-A8-aL-5o>7)$#Zq0|^>uJ)+dso8L# zBuxMyar{ovS9@nG+atF(1Vuebb;ytep&lQ=I!vP*wmK$#^@A?*f~alh<6h$9s~4gq zlaG3uK?=vG!cB{Nu7@k|s6uW{SNw6Ynk zSYX00NLCf+diRD#Q%caQ{KS8P{+&pL?1Q5Y+0qR3KoFgZcHeEn4xhW>w4ZUNzV@iu zBO+a%pYhVA(JW;d&&W*f1${lA%mGhkm7jZ|?c&V9FrqZFX3ND8})WP5ko#;oKs2lA1os1uKD!73IVX%pY(YOT)P>jrS;t(;EHDYg%`%~0vHIO-SxDN9~_lPbJY4AfC+nF3sim-dL5E4jPuv~4%k$f(6JHQQ z&@9KYG(_eZcYB6*1b1drs`cjWd1V896=T#(@cFbihlbRfgY6gtxG>;|1t#DHWSrNI z8UyL1fIv#HgbxjAs}`te4%(9jD$M2jYsl}1D)`TKwo{$_oUxv^TAxrl{B}h=%*d&? zajn~&&j=sK9UnQ2J7MquMZ^+KYmExAAxPyz?gyFg)6Bgh+?gRfi+kL!vfrDC5mBB3HxIVQD?N{(lvZm1?Ohx-LP2K>WWXND8Ym_ z;rDa%>nh((s*S$%;p>HZ9W|B|*x9`o2&+@lfFrq^Ovf0SG3#Isc)+JK&PRT4;ZN9w z3QNP*wETgccRP)+X|k&ILw*yvT*Dru1Dy@#_VP|p&7ze^pzV5-#zNX9fvu|j|MTNOC!n@@oS<LwUbNhUj>np_qZ<>o8*$=uzz$M?WFZzW7$_Q7eA8)bO zyTe%43H`Q2CgQ{)*C%18YwH`6A_Gg-XUTNs zK1DB2e1B!4VCE!xFXyt+a;A-|K~K8vr@DZ+IwwmC*L_uOBF>!TaGB|VSeFQ;ZN`2+U}%R1(Vpt6PG zPy3FKoWCkw(1t@j`xM97Hc_rbyKGAQ*EO*==httKJ6!h(Ibudlon0_jpN@*I7h9=v zwsZ~#u=60J{Ms zSd0cqc;8QNAU}>$`4K6GXaTM+*Cwv~`<;UxfOMO2e)mS~L^B(ue8g7vs?4ddL@%oR zz2pQHOYWrDP8?iF8YyWAKJHiNoS^KER^h`G7KWsIWqpMzI*}s`sJ?Y#F*xsW>fsPWyagIX)TFyI9%L`7Wf@Q3}j-pimH ze0{= z?)TU(CIL`Qz}ra78KUNw`Lu|px0+yw`wO&z^FZi_Y~VZy>Y@zP{jkyC1tF{o(5l$= zk)8_UD% zdSf%d)iqt+pT(}cGlrM~cy&dz1JG@E@~dCh__DR1@rPuVd@ilzARnS7h-I8ltD&To zZ!`O*#)w}=Xtod8-fb3ZS{h+MnW3YUzM760iS=Kj)Uh( zJ~Qw zns}~XG`((#B>Rm{1MoxOCoBU!RduKhj-*FG-1Iv*winvI2p9^!l-goo4&RdDr z(t=Pn%PN{hTHx6hafOJ8BQACeU|G3D`9hN?&Qq=qsVAHIKlc1&nDl77Cm)^FF@5V2 z$AAzdPu6yRgQAqmA4);6+T&R=_7N?E8#%cvXvVpU88~z4Br8<%zP{!NozQ!`B?sHK z<)quEH#N|1AM_r2^Nvec@@cTOq$HM65s%~AG>FcdaHJNyoCi&4_`zD)`BJa(24mJ zIGv)p8D>ugz?<~0n`iJ=0geD*Em0v_!UjgASIK4ETwu50=47ODB6Q;4SoKRP#k@07 z8GxziSJv)_!9fpPm$f^E21?K$wln4yDUYt*zC&bb?0)Y@OhG)gGUoU%|GfJbM!Vhu zb$4{;EFtIllK|AYwYfhEazrZ+&_vbd1OrEC3aneW*7QfqD!T1sa^1E*dGAWwzijNB z{SJhgjCk&2zc?YF&v_6&9kO|azZ4N7s8Tz5H?l7tU;vF0it&AH*CeTu> z8XwLy@_#7%j@@eK0+9@_tdO2RIlF9I`Eq7cmJs)iulfag@<);pRZ^4ydO92h5M1?7NL^!h{IR{>iJ48P&b(y}MJFo*JQlzu z0a#>9b=;h|KB~NX*_GuJ>29u72F-FTUkhq()qO#5xwL|VmT`#W;f1JxBG?gKR*JEa zlZV&8hk$|w4==UP?t30%0?p8I?5U?HPelWmGq*OHE%Ob*wHauj_UxdK$mxUY$5|h1 z^RL?ccBx;`YDrV-^eG_W**cuCj4MZs=m<7wL6Yv`QrGS%<-3~dhEr~$nba!`1RQSt{DRTrbpw3Kl{U`8Lu{e(tvD0`$yyOPI@eR_Fs0)Dv z{zlblTiEK;p;$ja$tCc$%PKKsCtiP}$m%_UdCU&1g~8EMtd9=~KkgN+_Jz4zT`q~T zk#B{dTaF{hVu>xYh0{vwOQESb#`};L;9uWHIj;5pk^z7KTl9|P@rvsHHQF{V^uQdu zm%t(MM(yp6oRDaW1^t&41i5))<@X6wXciF?OY8B+a2&!E4{2T69r3-wPk0pPmwE+Lj+ko0>X^%I`A zY454Rr1D~~RO>SwMmxY?_WtS_8;f$cH`@GX?rYnxbhy*Wx(7xn*IKhXqP!GcggkK= z>`UeT_=< zT%SMf`cl-Ne*_68cZEcd=r&;H(gP8-anlXFZ`(&I3mn=pobrOGttqZLE8nBAD1vA$ zNemUGE+u*pP3|P$Ung9BbbMNDV`6bZzV{pv$*yF{cE})iz9AG)F1|FGNNF&U4sCiJ z!W^1x_;t--3zsq?PaW;6N~F1pt9>NVdoF)vj%F5eYJWuz#-;PeC!G(8&w*2wI zZ>r@LYTqj6Cddqb+>qh;-`u8$@-#0mHq-qa&vYgU66nH9O8@RzrB#3pWNL zjmbLM&)UygDQ&%c!Is*Zxfzy`o}8XsZ}~#+;)xpBC_VY}Y00mJKRQoOPu`WOsB()^ zU&=RK9FAy-21YlUIj;FUX;p9wSZYNR2i|A?okNP-`qS_Fy2j|Q2iB(E{xR~y&T$s~ zaCxs*Xjo|T?E%}p+QkpdD;;Ju*g#&xB668L#k3dn=&4nO04MUd5g`n!A-)piyh6y~G}h73sj zS-G2|^1UifrIB70h}S`F2Par_477PD>-=F-60kWBH0tA7FBqMTXANW zQ9kLL5xwbbv4_#=eG~Pb0$Y*A&SJAtM)!Q*WT?X19}RB|St}}Iwy~C+h!>KxaT|X; zbo(Io`7etJiBE*>X6p5yH3p6Wr0fl=vS=KPV%5)o9M@c(?fQbZHtZD8<9n`JOQZR?EyHyhQ>FUP0 zTsEF2!u{J|3R`weo0`Z6yG^Vw4cXm)N+H(OFEn36zrJ{7cq4fEhwFoULRl<#ow}K+ z;Dc>K_nK$qUw8(isw3lJc=WBUX?g=2a4nx?-AlZ0TW<%MVZ; zO&xowKKHB6p@Vtu&{`6XIE*j+J!u90G$I`$Nt>m3PW1u`BNwPpL^-0f%~$^yS8o{> z$MbXzLvRTY+}+)S6Ff)=5ZooWZjj&*+(~eUKnS|{;%=K@iv)LfcYlZ9|GB@sTwL%0 zcBZGhs?MpZ(>L8N$xV~IW(jb}g`FUWrAF>9lbdliU8Pf| zTrqRA+bi!MhU;D$$nzdm4oK(;HUydqg$Y6Q`a#~vmMA0Qfo#vj5N2N`7pEYn zZ%5k{j1`1l_#|r(!{pw={!Gna=)T}_S#^4l zhAb%LkmB$f1QK!2+@3^j`!%493fR!vj_|3yPi{wTx-lZtVtmVUWcQ+ULeH-OCVSSJ zvD(znLYjun*wLexY;U%7&o!KG1h$=sw$jkXNwxfQ*86-A=wrX{uS2VzrUX9<$A{8 ze-3dzfjRr--a;&6;Fm$^L$PN->21Chw1wV~SgbBdljs>1p187WI64WlqyKjFG_xrdJ5?! zmXqIJ%~#(eS1>T+$Q`AX*wvlVWtnH<|!OazR=Ti~n%-*ENpSdmpHt6?#xhH!J@m$8<$c z2LrTbxP=HauvnMP!Hyse_{hljDzW+x-!)EXNXRAp&qz|4R>ymBh?vkH*2ST7> z!qmlzla#jFi0+kwQ{LAiOL-fVC?34|S#3aSRw706Rp-R+wn}#P)@CGz?`=1m@5Sjy zFJ1JK5CL{eo;B&VrF$2~V;h6@D46 z^lgR^9BEY02KjbkXn}FC(6_p=hnA22y~^v`Ugry1Pg7h^A|}l@tgeL&^5?;=V*WYY zk+*ND0(u|j&|=;vyG zkfR*=pdKyVk1o^de}ryvOCymRFmf%~_V-ZX`qT*J<1FF z`DO(rE0cI5xiP1 zsEKwRPD(}1M}@hk>lti3b>qY3s`!nxl_(feib6L}T_3IkHjiDlXA!i^EW^GaWRa0T zs~sh7E(lG0Ho9zN^mhbT^~#(k?c#8|Qhr@{uri7*?ZZOt-xO@|smet!!UZmUYij!x+h(;dPMKuZhwc`uvQsa?L@_Zc<=>Kbc^Z**1|Fs7%)Ln9lUD6#vAL3zOU?GI^r4Mwa*7 z9v~wwh)fJg9w1$QzOa7S4bF89*mKQd?mAK@OXUeusQvUXnCqKMqZnvJhG!w$`w!LP-6y3_(uERsphgNT_VPo2rl;QB&v@`AJ%df~8J={`k>f zTDbV^h^WHVa!qWS%kP_#nuV=nvgk)Dpo4eK{P|2)F=Sh4I7OszoE2QsWc$=J9PioA z-D9s~Y*sEbbg5iv8pAl2@kMR3C^w+{BjwU+qBZtJX@}qY?$E6cb*;qS%3tt0hK2Pv zu67V~-P9?`qdo(~9<2mZ+(g$%`)EXruhkDUxGPh5A8@s9?v!4}~c{d}o?Xm#x=I*E4QNi9205_Kx zL`(op(;wQ7r#!1XU*67i_D>!=fYX~Vtgi_ZH8H>*6tRliH7EVOSAB5jE~>M|wuoM2HE|dEjzIIxu@3tEyM8W}7z|(#A|o4fNXNaEzS50v^P_7>6-oEJ|K+$9eHyXGz|4 zQJJws!>n@)e0;Wb{uS-WJ%AcF`^3R4Ea0x-`Cb2|r`U7rtwiu@-#EDxK2IAz z>}G{KXFb7YSjjSWw@~;uq4n)unX{Q5VdNB<$4q%BJZ#Ijs;a(wF&!F%kNnqLLP;+K zBr9BeV$LHzq7NRQxYej-i}pPpiEnydZXRk zoV>NX9mYQ=)k`cH$Yj{q4BoM{I6~hiy7Tn8QR}VE>@Z6s{k?PgaY0#G^sgHZ>V86=%9=re-HW%Dwp)Id&~f}9G1FW-{jn#*hiAXKH}h=NgbD_ zpJQQ{XkPlm`_H&6t^QWBy-XX5x z-@+dmQDoLHg>S-8(=@mVLe!kM`J_+_tgBt+G7<;ycfR=fr%$DgqdU@OYbUsCItT;_ zik9Hs2X;KI_x@w+QYpY?FGn$sUA>77_$sUeYBH2&2;;`=0tr&oaLIP;Vz$1Meo1<8 z;!V1jpRA-KM9>;TcBGlmgfu8>bo3;9l<~IH$w>>yHE+kP8zR@z?);;52WYpgo5cK6 zd>IEX&K~N`7C?NmVP4I!hk-^3A}C`MzekF!JupLp_LE9{8+HdPUS=DZGEMN>tPH^qfeaKme<@~_|f6*=J_F+R>?zo`tvfXle;uo^Ez3> zb>~d&F5znQ55?F^38#D5Agg|GjO%p}89{`qF-*mTUoC|R$fl$ic7*CPl>RK1Jl_ZL z)^YM9?F9ZfT)jsdd#=yeWcZm15GR^md0ZE?G1^g{s+ONe<^|@0u!iL)hW4kuc`<`D zD<}6zs4EO@&ov2smfYFMKbgzeKlz(V9FelCSeBPk2xH4|^}Uot;wDk0Uu4HkvZPFt zwi#G^YrP0tx2%xsz0v$?EC$zk-(V%T2=||!^r8i?E7SF>cpuXN+neO1)P^QYC4zA~ z?k~4inMDJe`_Ee^V29@Nt}gyYjY~`9U5rC!&cf-`L1ug_clUK+JCK3sXF52(ep4ni z#!uKCz9=x=w5(`K(EBV}#$r>IUONq%GFO`f@8k@eBISK{E)r8NfF4FXdY_tSq*fY> z?^#|XAsR}%ok~6)F87~aU2VSU<9R-zdUh5!Ru4!wFj@mfE+om@)mN?fG;eZGCYI(u zpy5R@?Lo|ibw1vU6g4aMmTGYwFxqNOP6!f}&!yz^lyl;_h>{Qf{`t@P?>57dHv!Mn z;<+tm0FwHA%5^7vOXpC)E#}#iQZfmg z!vB^Razy^Fid zl3I;97c8x^>7SFhN#o3xRVj2qFl+8X+rBg~JGsLN$Hia)y{fc1Qn7bt0jmOl_xhBf zJ70M_jZtatrYq&y9;!t>fnc*H`y)^}0xND^?X{gy|Dk`dv%e)9uH0C;%+Lr){3BSwb!KWI;m;*UqOCu;VZHf30Pq2j}uE zC&|GY?;uen+UkKkyU!$fDVQ^Hzq1SiKp}!ss#Khv0EVY zg*>tKDl&m%fehkHFI}QS8zRkJ6ks6#CRG+NE1woWKGDrB(>u&EGVN-;A3ru`A67>z zRpElUUJfBeHNDb%3+68lgFi21knlSVDd{6&mAcl`_BjoIE7@B;-vMDMtU5gG;hV6; zc`)WkO1b^pBRW*cd49Hm6m~B6#Ta?81~vbCD1?AgMRF5>u(D)GPWIQz7)2Sdb_L{= z=hLM`-)k)oJot>7*aoA__O z)Z7qcI~lJCYYsAKmbW15Fdo;Vn9Rm@5xt*G6{7f$@P^5e|&tFmu{pQ-{b!H>rH&vJz{9&S zB~z?cO)%EB%4RfH7_=b{aZH_FBbCAdwnb)4JCc2Y>}VhERA@#N2Uc|b6D!xEiR-HT zE<`DNna$j`*ih?4VCYzUm$0Io#cKc&R7wUSA9?mh+jX_%!;w0dOhh|1d@9b`&F*RW zWe?Tjl8GSMUWXdX&w{#yu@D{+n@YQ^*y$?AXb1!s0YUEU*7w{KxvKtslYS3}1;0|E zmLV1)0iL?PUY{&lY@uFCsD+*lMvy+7&jO-3pJ>T{_htN#NlHif(*bu{q$e#ubY{c~ zuOxp}8&7kP;Bpvw=5Qcis43z1)4m&#q7T^f={VK#9=Ntr;pAoBU|_!k=@&?toj#cZ z+1Y^dJ=KT1q;!`@;YxWLnNV7~ZCI6VX0XGtop#_Rr*O zj!lfM(~8>Eo58_Bj)qS&NgA!sHND=2i6&MCPNHq6RYayY(5$WoYmyS zZwkpWO5I}7AD(x{ML!~%OqGYg=RYgHtkQ+H?`cLW?;G=Q;L_3#cDoPkc!qN~ar$uS z7nN7uh3Ijin=QK?(Pe2_@qZ86$60vME^OL644$>9#nzN^vm09*2kb_yZL#BLjRjsY zTBx`Z^*-(qdVKiUq3di=9&Tt9K4|gnTVp%TJNwSUq;80jT{5~QfjU^LYtbdb!jY*< z=V8vq+o0qMmnq_9R(qQ#H6qtKJ725@Px%!mO>c#vp`oR(M`So&PpcYwON!~dU|}+D z-w$}>Y@=@cnuQkb>Z0}I-$qX778eRtNVbjcRvwXjokco~Z$k_hyYnvYyl-j`4+ZC? z#=le2ipQ=0lEiXoc^g1?fZ4*j$&1X4iQg;%t*FVI=9-+xBTL2b4~zW4Ba!Q+#2Ht7 z$5g~#DbQ)B=>iEe{@cfo^LRnS+>*zt@1;um4Mgj3I{8#QP8pC4 zg?(p>;|_Xs%6u%(aQdW{I+^!$2fB-VleE3gt5 z0!a_XY~h_{SHx`)H$fVN5*JSvNFao4=8?F_sSo{&-bU=bsd#-qt6uxj9ivJxbKjCf z`)yl1&ZBuPD;FBzFVd*hBrlY*yVhaFvo*qL1FqDogl=obZ0~2rq{(6GHC;9J$<*>u zY<9AlKhVGK`xyDM;ozFK8(-$^o~ndXy&;EkhrMC9@@yo7 z#e=s8QT8-oYrz!S$Kt8!aZk=NS$0kicyurxP(V+TnL1UBqQs+HS2^a>6jSuT^HzkU z?tC3)<+8QMm(Ic|=<8PJl8V4n0PH$0vY2qiW60zSFJ-fKpBo}xOZultuR*KPKxF)Z zITK!pR@Ee`Lj8nyOO=Iq|2teL8S7q*V6P}@W=66DS%q`Uzsq(Xw63fCH(w}v)0-i5 z9@G9)^bu9Bb(PHW<)h2{>mAsYExOYTCE^|Dbt%kBoWPWIH9{4^s{D!xYGqTX1rf}c zXcWX0lwDeaTC_@RWr4J;S|^au23(#b*cYqM-=XKVY0<$oY+HgJyhFxY-jRv#=14<< z2_91f#^3BxBM}mAz%owaBz331WU5wtIenQeXGoEnCpv~*I}{>(ma&j zsz+ElSxxYgXvfYXGhfi#+VsSDy-=gy ztbP6tK&R21t(Jxi{^0?VIlesED{_kdG^N+s^z~Go!5S1Fl9Q7LFq9{?mqR9 zeXkvPg4ebLnhEqaiCF2=BCqY;^7r|Q$EkarZtG3iQ09-G9J`$mDdwxny+sZD_k~Sj zEeQVB8P3}b@f)p^4ALjP_42(Yb8>`^2D4VBAUJ5-HmtT9Xj+h1WNa%VD9iQF&0NhK z>gHG$B$ZOhtYTyR3_^rmojAtFtp8-kn6Dpyrwj%*;2c&|Sia@cu>gu4<>uyiZ$vqN zc%ZHY3YAthwn}rVmH(*HVEG9~Oa`el%Rh*bz_y1rNUXNEP&Grfx?fWT&$P7F3kkmB zrHN~C(lW;NMx%)vKN~>r`}Xb7nK@(z@5TFY(h$KD9;J4LuatnwgOplNP5En@B#rrS zF?HhAuO*{FmtOLVrJ1;|g;d2=YCuLru$M4AxX;soX_^GP+83{v~Dndg@n3D%* z5J>7&iAS-#rkPS<=LdZlIj|44-g5qi6k)@q^%uQ&*AX|6v5R_*Lx#KWA;v&LDEoDt zu0YIR!u{Xi43SqKwQP7_UI>~+kWg>Uq4)Qn6HzRMCt}WRthQvLB`$MHF|;5HF<6hg z5&OLKB*I&;00=jj$CkQCK)%TS!yY`vrJx+_GJ-61f6_o5{|5<4=RpnaVQ0z3bIjPj zjvJzy)8lD8Tn7WDQUW6QwTC$MdD0?byBpTj@`vw;-)n0=@AY&>$-6p99>&LJlT98W zKOK8J!&zj++fD~hvem0axqzc|{?sqG{TOAL(QD$MtYLq?CEqf*5t}Iq z1~0QnmfUzCg?#e-0T3|^hkl%_QUGePSif`bC-G#z0 zwb;BoXlS<7zha%RPM1rS9Qb0rbjX%}AiqPwt$=8{GANF>io{v0DZSoo=}o?nGiYiJ zqaY!l?y?Eq_CcKF2B%HXh`j%^Su-=Biok^*XUV5aZ0hBXq!JVwYhf@mkgs3%JdHsukqy^*I|eXWfiN zP7~vFQOtj-2SiRj9m-6T`qzA3&rv)r=vr)4Vd4vL+AsNGkDA8s!x z;!Js!%Wo!IiLcDDk;G@6{e3G)Qbi%n)_>;94l_HPwPHa@ z9^^BETf3>%`Zw{s=Zb&7KG?$IcdDjWq<_QYNGt#yAaA6Awkcnq)iq4(faA5W`K(`R zQW5LY0KpKUFC;BIBSjc7b+z&G;}fb=&G`AAjvr1xAvx~EE>$0aLOIxRJVjtomwt}_ z>pM()c&8~wMgElJFfnzUwHC_$cZSX^6LUBU>iS42HUr75PMpDl8TvT+i6PXeEIOsb z=V6R?$bvuPiYLSWQMF(FdoLRGE2js*(w28lg#sJ9oPPOhLVi5ikSUbDw>cO_k_zN< znpy-hNk_ErgRDs#981EY%yF~7yN`Q_Wz!=vS_!LCt=ERWiE_G=nEvpU>7bt&fx~rw z9jHyK`+<|c5TKwIR0;2c1&);RiRWuheX$#O#3aUqDiF+qx>kPlx$f~TI$%tD{9z$7 zk9FMpnF+sE_hAf~ynuRYu-AnW*^&RGTE5lPp*a2!>$Abqm}=!nO(`|g67CQ2GE->!3I7UTf4Jz671p#gDpR=_H2 z*h4i4r66I)o{e$J`FNV?=Lqva$S@SGllep} zw@TYyvV+GnC)`3bL|fX5K3jZBf8LTsE=@MgTS%vtAFQC5fH)Xcj870(t^0|`U;I}s zd-RMpqQ~7Wu|DYhT=gyM()cybe#j_2bJik=1|3G8h>WxJ#TQks1e z1ig8t^H8%eC9F6!RNr*!fDA_g*x={It&!L%bN7jP43Obp93L9hhOr{+IBzuREYg<% zM5C55HpWvr0aN^XuFUppO^BvcXADsF6WG}$vqJ1*RTvSfks*|y3lVzegTb;)vSy^z zZe^TyufyTUm+5|Qa=k-N;%$tJcAPK13v@x6sgGp@pVd&bEVcjM14kfF*PL>Y!D`Md=l|`PqLVM6Nc?TGoz5bG z-qweSzei$XOrJ#fdoK@j-}mHx#aV|G(!7!Y2_Zp71@G)BSrOG-WhQVw+vET}ogO~7 zbs;QZMYgkludyasEjIrMTy|NQyk2!5+=2(r^{@gT&KR4n_L2p#YhE0|u5GztmiB>T z2h@01aF&DX>vJmSj|EP5w3WK#dD^O|GZk~HS%TR#DL@cP{8bB4f5kiK|c@Sq5sddBp^KkP`TE4ca9Hg?z8`)$rb;Z+2>X|jDZ*`}*NksufHaM?-} z0>^LKe)1YPh-oQ{2+4&R-&Bi6nm&2-_b6em%gB*KKZHZ$KZ6WWU>?<^G&;&Q_`Ad? z7zLR9^=bosERCOe)2(nm^LiOB+uNT<7ew@yR|X7`QWrTUfppoq%vdl6>(wsvnBvy0 z+_B5UWu(M!BFUt(9r40wavF?T38r2pIZn<$QrAzc&(sGy>e&>qD8Tn4&wm-M==-9{ zSmkE$9#3FPtuJ=)O|?OQg8}8hsI22P+a#;5aEDi>U5%o^`$4~UTccm5<0f2$7pzq2 zyGPf%8};PYE#%v%t~qM9-Qpp7nO^0}Vw|ae3@Ep=;oD7Lh{=)f;#lN&a9Al*~azmr}=9f`ja+ZSak10>=LWIO$N?1Lv12{<} z^+2}PGxWed$i@~(yI<55ciM?=A*LK$FgoR(u(n~8a9824Ut}rd)E?+WahFYRL(MvU z;)@LhsmI9yr!Q1=)1$TLBC|}X<&+=(7~bTG>~}R}w{B}?Qr&y=N!(gP$&8H*jOSok zsAZYbRfAt`2_IHPYAT8)5>d?_ok#df6j1~?c=^KgTLljpd##n6Y!g5KIAj0LMWx1% z2?+$YDiLFqspx`N^Z$HyyDzD2%ibu*DlwEXIPlbAr_T+j8c#I8tD8U&OexGvHtu1a z59VO_7+!OuOU-Rj(MT?9lM&EZ)s|>rPr~cc+lZAup7F4o1O&YfkxZYgQ_mC=MTf%>A^>*|)J#M@c2Wu@b+_Is1E$KokUueht z?CxQ2WU3ZtnTPb&IPs)iZ2G2G$r7&kBv?z`!x8_{sb%%@1;Tynj`C2y-|Bfx%(sh5 z{OMR;1=&w86<%crNNp`)!_yz&ihsrRxJm-RgyY{HgUr!MKhesY?^C~i)mDt-L&H`d z4?(z3fl)52AuPVC@51uV_Ip1sWAbpz31_VKBP%QbeII9VK|Bs+#L zq2$TMjH@X^_%-$gLXq?rxcQPd9jUWV@-1rib^Ptm*%vpsZfIllfEPnUSPMJ8H#0}@ z+p9yl3L%_dgSNP8L?b8vtudn5ngzI4r~jB;r5%A;e|6aicAx3U%ly00zc0_rP2SUa z=YI8%wRuM3Yy$HS>L}O-YTkvWSFG8U{JOGl?7Nro+OIjziv%xYY4X;&`N>0P%_7Q2 zme$AAYmXf7(aGYy1mIX9w8lGCI>gz^elC&w>cpzg3eX=NoRn-{TBbkTxPPy?Nk}eA zSP2+?yVkGJjjldoANMN@j1`gL;~Rgh^a6jIjl>$HU%-XN44vaLX>E&feK#Tt6=E;= z2&*&lfAEc}Y`ye=!6xR~nWa*NhO+=Yd>g8wccG4%GS?q2bm<7y>}4Xsdx>g2(<#(H z`oY!m#2)#<+%$2cP6lKQ7r2k+WkxT*%>!7uDg~BD#F@$WnizI)TOd_cF0@w80zxAS zTyfs7f!wuz%(HszF2BHlm{BSX2gSN&s(-_rl=P1n*O+s?onum`a>Sxuqfl+xylC_U z(C-m93da0JRFquDj84;wR+CGONsozV-p~vY^vK+10LSJp^UG9vuON-jG50z-LW0d@ zo}O<+5ih@;4#S^`(<1El*}l~CrL&|LgScmi!_xm|X$GTJD~kfMG%e$ND#yt=W`u*# zz?I5lCx?;Q+C-OgZ9dO0OFp?bYY+sC=3jp5S#B?t`H-2Uj0y+6*NpIKIHI+aVq7I> zxQ|N6GZ>Vt&#Q2(_7T zDnx!j7p8;}_$>XNU?(L|-)CChncx!_9x+2Uian2fx*SPevTO0ZI=DkdE+`=DDVho_ z5#sK2ehM{_Z0w_W1=Lk=GW8pUdh|GfZa^>E6lowN%mmjL4XEX=eNF_LFS5z0(;3d& zl=$A>2UB?%pQ#@e|BbqoO6gVu4knG6rnebsBlyP!NaBg{O00OULzIncL{e~gi9v8%a|G*ySA~j@b`_NwvXZsgE#of zdK-%Vm`X+YBv4cGo0Sk9|g z`?M^UUZy`M6^Ypx`)}X%Q}GvRZDWu6dpc|pUN80d&j39%kqg&>?>-=XN3Bf;go8fC ze|m=utEoco4G!}fTWh32rYrAY0n7-ym2JvfYmlv5(`$IGj?hn|_j@JlD_4i{xBWgH zh~&@PpG8McL3KtXS*U1e_5_=2> zGo`|J9pgv;G^oG?rYUFYTxL+pjB$0YpVrM?fLpm6*2%fcjlnex34U||ZDM`o;S4w_u<9mTV~V~I35kjs0wA`xR`-|o!3C!z8nB*ZcK3ECB#*^ohCsP>$-I|0?u#}CChltA`3 z+kR`pk)30bB>GJ4qDj^AU9d*VLixkCvSaG=%JS17o&Mj`^AR#<(5~;?S%W_7sRGsG z-#3-T9fmmvuqL0DY>Ni6-#gu%U5JQqJr_FfN7W7{+%agpD|5R?>LG;t&lDCf<8g8= zxV?H?v}AG7b{G&qOiI4d5D!SR=P4^V8Z8`Cix#d-pW_!f&E{8hupOw|cEEtUS#?gr zTpP)~zA*w)Zte^F6<^)`smjXd{Fw!Km5c1M3+vF$kO8V2VU?vYUxo8`!t%+9eiRK< z!G>s{P$9jPO0EVY|J^QvxHD*%@!Y+H@1Z0DmNRvmkg;)V+SX>7PG;)8J67s{VVLrL zX5Nm#{?S@k!|-P;KEvf<&?prD^IPcp5zXUly&tn{`qcQdN>|^;_<$VWR>kp*?hgvG z`)?tQ;m#8{4Q||gC*GU(;g$>!lFY_*hgu+L@SV?73gs}Uy4AeUJ^$986M=~jI zKW#UwXR`98wTMa+$0A^4i^X2QH?6qCaF?wgt!7UlDp((4e7bLI@R9C9BRRH#NI^k* z!QxlDdagc3mG-#VwVfjJ;_=|055TpLZD5^MiHfl85i-I^i>OzSwvBxsPR% z3zz!d|M4i@Q6$?L2C3=O36b#qyUVwQK`)B0nx?)`#{il)Yk9z}Rr9At%hbCHnZE3H zSO^dGUFc}r(@+R;{!GQ$SLtH1^<9=U3EAJx1a}erS|y@}pAo#`%~%k&8*_~1WlLvXL$apm|fh?B-c>AzT%4|B(8dk6GNo~C9?XY@A#g}(lOAe(Pw zaDrregJghgitB$k?C+tLWnj3{pKainNg_ZF&BMU5Qq`f`N%(f5unmNVOvk845gX(G zuDKSH&;)?SYz2g;DXrZz72p~ND${V~$~O#M)2of3?WuaHY3Jv*j=|t??0Ej2S1WMA zoFwl9d@t7Xyk0;9X!ObIllLi(gCW&#ywkJhvtF=Q`d~!cF+MQFgd?a!+rB01c6O@e zmqbp^8k>o)&&0JeftwVm2SsY0GV*vXI}pUzfa%PfG_Z!L1_9~@VAH`46VOf^Ut+#f zY*4BMDwHoEzQq3oS2K}rQbhAm+Gga~a`5c`n+bXt4uFyBw4$Jhi1$C`8G-)>g<36T zu%qSd>@akZzzXmO4^f!1K3V8YTXwxz_byt8w^UF?5~5Lf!Sc2XQ1lG3Nvy8tEF+Z8 zGLFpy{!y-D-YG|?;N^*4I@$NG`rVa4<_y5s>5nmr!-bi6DI)TNciw2tSjHX0s|kUC zAzba8ZQP1GGH?L>PXH?DcLiZ(wU9TTb5e2I>NCx*JF77|Satq`P(ly4-2Zi=b4I2= zN)fr_A?%V#>CE5uwl6e#mFaa&#{bW(Wnpgijt(KlKu`GYLxXl7c*{%Cz5u5UVm2dA z-g08Ux;FGP7jG_@GjD$+8p^UGvh(fYbotpRtBDEM?XvT1K&e*z^#3e11SkLJ8*e?1 zX<%p2SY>_2f9ph^vrg>q*br>~R;KT9ShyKfB<=)FsG{zub9|4^E z&(fsHg#luvngA|sO^Dvzt^peIpc}!=>q)&+$i!&bm52MseO+Ut*>lW_L;j!&Ku6iH zAm4&)1Q)P7-Ts<9HxI*Gw5UvdY%&d=QEGbWa^nBlA1a6)cp#9*dtjlU^I=hyAM`02 z(A%$Sg4d+H#l-v8cS}B?j8iq_VRU*O`@M*PN!>&gwO=!(1Ihr01Bp2h`Py;`H}@TOYm0JG7Uc~-owUr5552paG9qHwnads< z8!IsGj+?dS%z37Y_kJTCu}dx5aZ@M5xg#yx%o6MtQuam~ zuK1SKu086~;r0D0uQr3M9GW)E`+ExUTS~?_Ndh}fpgT!dz6odF9u+0fCiPx3iP-;6SF6~(06C?^men=eOh*m-xUbG=_S)}A z;^9Iq<?pjA^OO^PVbA#=tUCqng3-_# z_1||g^qv+?<#WhzeM$nHj%rT2@|JbVSKxI69ABDLE{7>Pr6&-QrOCfpcbv9u&G!+d zo>0Cvi<0=gQ&5Rz##qC>;)vQ}IKR4({&#D$2fdNB9=$oxg3QfqcE{l-6Er!`-hP`A z#*e@mD1`1MA?_N&Hb>$$$@&t6@G9rUxNL#M@%?{mc8mQMSuU0ky5UrV zOx+<8B{9V|<@iNF59Fg`WUHB*^@B^$TMp;ttZn!9h%HkOfDQR$H0NErHq-CS*?3tN z3fnvZPIqt4B=^5yM6*+TR%*foTucEF?nML>85$kVR&%zU;>Hgtonvz;6y^qT+EniC zS&quJDIL_I7-3*w3Zco2c?C=v~mE~6K%|H*WhD@D0AFWM_53>wqv+* zh@sB<@E}ajG7=}x@qODFnB%L3m(%2VR4j6|YkVcnejcHcUG%u>^%)W@$zF@PDx zXG=nYcXB_%PA0(j@2;|f9)6QGJEYszxD9oI+Zar z=iI|RW{R*+mqEb*e8Jf(y(@4TK&xxYWu`A_kvD4h4MQLwXL!pcA1-6*ljP_oe}RF z2$G?-|Fd$7L_dR8CzB(*@z3Uhz_QgwM591NBPOvOk+)vINnE;4b9)$G610OCWQ_=> zf5|UrKAZpw;+?n2m0W5f_jO)g2f=SW{9<(eo#Y@?gaO7J*YnPM`wFG8x*xdUq9X=?YegjH3#@1;ou14l(i#82S^G6#IxvWD8JD`lwHU+&NUa_jTkEGV8^f%O zi(D+sr=d2l8`)R*Qm$Kb{Lz|MJP%rJ#M>4ZKyL=+tue%foh+bz8+UI%YK~q4M<4z9 zJYFr(*G2o*c~N4Gz)|%-zYLuUWJ8sC@ucty$iSd~W6Yxq$)>@}Doy#%k&~?w<#52K z3Gpj0drO14u{(Dj?QgD8fX4woN4=!eIY})weI(Q%*?GSzdFVB7PPd~GY+ap0xy)@- z#F--r1%e?Qgc@i^0AvpRbBpU|zQKwp>GXmL=XeM)yg#J0lM(zc_5miy$$d3IHUbzxu(I6rm>LXUyIXPnlmc zoR2M0SED-WL0D&c^xzY|3FbdV+?3YA5 zvJHKiz2PuV$agzg9LbPKbF~v#s&!H~aFTWl*00pO{Ttit9)iBHA5QpH1h?ne|2Y`T zuitFNyXbIJi*j%m`*gb+>FUA5A!y1HKPRE-Y+(k0sIH9xVX%gx!bG`avKkANW6t z_+R>r?P~i0C|jUVp)NgRLF|vOHqwBf8uud|)ULR|ko*5p^|_{v=N z^8d5|MJi)Ze7_`Tv;JBI{mDxJ?Y3R{pzZm}*?vgYW_$m%-GoyniCi0BNL7T<%SwYX z_^rGY4GM%}ujY@KSEv8}BXxN_+^V|T-Obvrswgl&i8 zC+6`qqwNa8%HYBxZ1UQ_dQ)jb_u@R}ME}h)SYVE{5Tc%Cr2`!~)d^UIonZ$&c5H#q zO;)-V_y|)7uf_KGW@Jo)X`7j69!Z2IN+@T`+QKZ+X@8`|RweJ#S@i%>zMp zc>*h{if6@pWUm^vF+wWT9T@LW+&fj%Ej?LQzOzd2V zt!QV%?aHSu=d(?&01_z3^XhV$hq^quAa+jy4hxya8@Oy`iFYyBr8dW!t!$R z+Ux-aZ8rDH{S5`w?{-fs(DAGBgX{7gVaG%4by{Zb_VYu>)A3Sy>_qkYS~StbFx1P& z<@?w63qrs&=C+K(U*xMV+yJyg%9T)lXUUh|gINT|1~|%(xxeKvVT-6G+$6T)qc@xf zaZp*ALR$zOBvIIC^GkZBWJlleQ^9k1@}!o8--#Y<`c2=PuT;JRi6z!#Rxg>EBcWT{ z<&?YsWoAcrw&+)%cFtlLtQ0mbVk@O1IrP7L$HUAC^m89u0~p2qg!ZOZM}@$J(g@Mp zrXrjon1_~0XB+}ITE~@@&DJGAkAK+uN*-xXLbN$u?~kCq4~laGwlTt0?hXPml!C}c zN-QI}qR^c`JKw-)`eD5t&lGE?$}cru;Uf@gGf+7sCRH)8uQUnx#0uEhOM*BP3GDET z9aSy`VA0hvynH(mBnD{nv~BCi_Cu(#N1kAVR-1%YeNPS*bMJ zmcaQop|n$IX2Rwi#W;*S{hAq28${EqcVXr0i6n!o8@#$oQUda19~!j_Ny9aDlu!u$ zh3h{|4SzoeUiI9if$oT@j{6A>fz>Ql)>%Aj0YY)+pHjZx;CCQJUPGuEnb2t8Su+h? zYFFE2)hW?nxc9{c8t+~tfLhvOc0b;4;cliO*W~f}VA0Fr*R>bZ&GCJ^d!klfiy~nq zV@u|6yECMjLGKIwhYelf)-v53A*rA)Q-se<76;zdwKH&}2+@6jH2sg2hX+&3AL>q_ zdNGfz-Z*d!yWW(aoAQxU^)X}S@O>%me*2QeGqZNJYRysfGB!2;zV|ZKviYZBuH5Zg zv{ysk76*R+8l-R#Z8E}m^!mRDMHSQb6i*Zs^o2#x_E22V5dSrd)^iS=H4Ty)mr~IW zkd31yeoaUGI#s|B7YUv)7){WX4PWbF-SFu^I3>VL?#K?KRJpaG3=pyXwuG=4U zE_Ln&i{`=Qth%SoE{;c(OYPSr5?N1T48L}q9D8ct979f$rtr+)3}ZM9;HM7V;gEkl}wp z5v&%I4c`n#^jbylh5elx(Ja-1kiiGZCXZK6z%K7^T;w9bV@@dgv4l50QYw{PD~}~) zo{w7!x|hv)R%o{TA3~8|7Z_oQiGtuiQiz388lcEZ^_EVDexzFLim&Jh_9?6VUVE@Y z)N!>f&&WMG6?{cV_L;%suoAWioxhgoL78}~QQ@akM)BNxQFinDM&ah&JzS;!l5AB^ z#CE)4FA-LDSNn#&WB^sb{a}MjfIHSto4plJMSPIg0eudMWOQ^Knl1-Nge+}i3qOL{ z8HWm(W2Ltf{^4WC-F;(&Nc8hIQ9$r@QAH7X!Tem9askuHzn>FA|M(Cyn~-YqO@|x4 z%`5YH9(M^mtSwm!Bea{>Ww3kRjp{wr4tB&5RAM{}-O^AtrJSOqw#Ufahq(ZG>y!Bg z$_cDuwdrZ%Cb;sMbBl=ZB>Ol3+qv~od+q;Y>Mg*c+S>Qwp^-+qOAu+4?nWs=7`j`! zLAtwCN(6yXLKFDqKmlB-@JEdobKB^vkXq_i@$-TW#uc`=Zg_s59R3zf{iP{!a4D%sw&3V%bQU-JQ=h3n6?Z2HTnKt z7kHg0K|-DwqScF-C8ME_@jofVjfPwNwQxZbJB&mDc9%Oho5)QokrZ|vd02S2F1fO} zV+dn>!M*J=&l{OOBoRl1f{~l<;c_XSq5m;T&sna%mgc2U;_CBj`k{gNWyydO%~D^% z+`8^S4;2bu$%emcUkFl;vD)OM+dt%WUG#0+xPaaN&|gF)1e3ATlFbg32~9tX?l=n& zT9k~uyGGENnz`c=3ZLp~$oJ$|5rIeGT@(!mKfLGyX{qBnnQ1x%PEy%cLU-3Yd`p>> zr5qE?9f%0ptTKW79Pser>Yh8Ylm{f0p$yYB28Ugv^N!EN(U}Bcw0^OttMW4qLGzkE zsyXHLFxq=*=w~7nygzw1T}vk!B`Y3wF*enf(9B*PWA7|Le)N+2hV7HE2YMJy3xO4` zy}dnVRM%Eb?V2}t-~)W^&6PjRX1p1>WXzbIXPcZc4--$5R`aXdLN&wIcy>-)E*COf zxjJ&k@=9uP(|gpGpDzVwQHaDl2i;JT3QYAqbbC#iYsaSIi=v-kokc;}yIw^k^vpv@ z<3%AEvu%I?rec$sQ&qdAbBJ0xrSQ#0MN70z+aV5Kd?JXbDuXIr2j^YZwJU;w2>C2g zchdLuPO$uZvNG zo*|-)Qx3O3&w(jnU{uVL4ugFift=KPcIA#)OxDKJ-TvX^a446CLZ>;)ge3h@hvReL zatD}0fCv;WB}5GJZ#{Y-KI!${<4jLX!k3zz_OV39EpEqhl8^t_D6| zu0(OPkAV~Xc z%bV%qwoJgaCmGs%MhDMyMhW_RBx!Eu&bjW7;1r-n(80%d!~((A7pAW4-LI=_R*y!B zd{*0E-2Y3&+t1TDK2Wd|jwt(h5bG2>a8H?PB|EE^=4xxu&g@=!C)8K+y1V zXFu~6CWwtZ+DV;SIcct{X-u?QLXY>gxQV05)WEp(5gdo(k<()=P>4q)cIo0*I`31y`0{-xhYNAcC|S&KS)n!2h_f><5E+HC)x@$sp+h`8YZ$2U zY_bYpv5|NneMQ7IH8v+N2Gy4KR-8*8|CfQctv+tTCl!hXJ}(9v`#n~}qYh_{zOeOu zc%MEqmULCcHhXSRfE`8oM!HnmU;^6&24aqsUI15m4LQ-B15>d&2Hw%wPyB~anRl$6 zR9L1()nqp4y{@G}#B?uT0)xQS{*3k*9dGs5^n)L<@#nOLy-P-ZRPI#lbN1ugRSk`J zB|k&C6LY%2PGx4+0Z+hw$wc@qUUNrP^3L5yZy#hydQfMwt_Exd_}`62>HcXnhnf%^ zx&#nH4pYZou3<+FEf0$7RHcxPc+^evt{HZwD%KzNAlP5zG>5D6AuAdPCY~UAV?t0a zwpJc#w@_8tJI5LMJ?X7&lL(>{(EuS#7G%X}kn6Qu%H_~L#7@T-1fEzh9b)DTF2Y|* z1WB&V;(MR00{cu9?m7I~^$|==#KL^6dlwP;_FkCi@2+P2@{WMN3?3oVye%@Abj@_D zf-l7rHj~6io4qnggPKRp`Boa%AY2LA!4M=mwV*^g|1Kz-6huICXO4wSAd#bWHe&%rL`Td!`jI$`+b6nB&Mk4_=sDG)RjkNKi zyzaQaI&@l=HpUk7(mi;d`>JrMt&Gix0+7bdY>ET{p-OM+skWFJ7*JlKu`W(QX>X=s zM&~^~LWi*z$C4xwou`5GyHQVcMNI{|Wug*EMY)o)<>ETR=lY)k9H^$$fCe!Wj%{X7 zI^4)Efdr3*t!>%w#^UC2hc3s-7~)D9;^q!MUfr&9ot7g4+hgzwdtxZJmbEwbBflAm zHJ}N+nGe8tPgSjp*+5_Ok)e+Asl+*eaXr2G&IJMcSfqkeN2ZRn?^t2Oi)inMl6?|1 zY}yCm+gVeK>*uB*5?dt^!RXD4EKF8sqoTxOHYrToe|Mtz^Q0nXn_axENRh$N=gelY z{6XF};QZh_Z=BgtmQR6-Jl8eGuiABbd3|xQVyU2Pw|A;7=6T5HP(V6wkPV+utk>-1 zq(56+Fv;#3b_zn3hq{(#we3_%5 z9EJPLJ`QZm8OS(~41q$AOntGO+wQo&OE@#~^eeo31lF*v)Cw9$O>HXUMCm|DXe-F3 zSe)sp@$wd&q6Y0$-;_y`&t-J19a~ciw(hRRaf>C9nfSCOD{DSnD_IKN-hUjEceGAS z*%mxz74{GkLpeES@_oC$p?R^P_Nxa$O7eHD|I zT+C_uL{7vu3y>Ggk47-P0N^BtK39WyYmn$7q{;jaw8hFxch4hlGK>x6wBC+dJIULW z(4c2aSWE{zfyIXA4|>iUeHgsv_k9ud*9b4e1DzvWkY|eYh1O_K+d<#Ac+WzjDT%fa zZbM(j%_^BZg2~A#o@QuBs!E!bgOiht29zAPM~+#yNi_*W@@D3x>;8`iIKt?!XsM`Z z(1PWDKog3~vxhe7X+a-s!|C39p4Z6Phh|>ls%Ze0i#)#=yM(K{6|JKZ2FF67n6?#U#= z=a(o*KGj;LNL5Ng@=%KjOPL+N@1=4YDu&lZ)Dfj@&u?ADjDM17zz!pxmCQbp4!^%2CZXfGrXhSjrN-N=utDSzu$FXNY3JTl3_uBMadC<9=KpMvO}dV)!e$0-i>ph@TNpIGUyiF{22emPMJd7KyyNI0`s*2mNn2JkviY z&e+a+jq^4hLZ&tjm_w7Z#dNb3b$`+p5VHjaN=r?WHh)iiyEaDZuMs_@?l7f*OCa;~ z3x#0!Af(CnY~^R(+QsQnF9Rl{#F9@qRXGJX^s4Iso4&YDJ&cfgm%Qg#k+w@+@gNbK zl|}AF*<%!Ke#yv)#P22*aJ2*jW&ES@m2;ZKA?Eos;E%(G9nkn1)*CK$Jn)z1-ewLQRciXcg8WG-hHKlQo8qN8^V z#ZLOP*Wn}f2W~Z1dolUZ`zJIXQjMs6SKmi9R-hW8aUai-9(iu>l(>6DfM4jPE z69jwH8FsZy%*4AW6QfQKa)M~jetjwHhI&tfIR!jw>pHBR2Cu}V3FxsH<3+@Yp)@Aio#Xoe98cd(n=C;7mKR&s>WY!4PD2$@V#O!~&S{(7K=7Rxmt1~%_etF?~Zp!%3 zarg@8X9xsk)0ecAr&S}#l1JyH5Y*a3Q#Ea3pHPV!a+S&t93UHwBn$VJOjt?>8R+!< zC1j3e9v0c#&<4=cOt9Wk{N-K?k?A-^ZV}dR^OCYYl~JvRFo_zyQd|Da>PR0c2d2=D zvqfEqZE`L(B2r`wN#(j)qV3lX=hnN$Ad-jbwP*5|CO6C;_SMbWo)i7KZ(Pp{3GTP7 z*Jymuj|89CrfVYPYKD z(*NGHszd72t%2K6Z_nW?8hB4`emGUgq7)0i+qJ(#2|Qm-=b4|;Njt`1Vwl(Wjjp7I z+oq$SAjBz#2~m-3qVU%4t{3ho?vBoHQHSXoG2>cKVilzc>M8>GQjTYn4yZaM>`NWh zG36LU!jix5$EOLw%_2Y?nze`-yq%S&r|h}eU?YaYr3_w9s-og4Ic`;Zui7rz_E_Ay zU;-}62$OSd@D{Sc&Ih2X>X!FrM(0lSrX!!Ms;&R+>6-}__NUf@+JJ9v)zy8TTKsTC z{UT*#)EqF^qm&&9xLMc@+{`v{FT^$v^^5lJ^|hTcs*9E3z}T6HHv?Rj+C%WL@(Zae zJD%1n&gr&Od!B{As3KEt@R%UHxowQoSgsic1WVepfsizRXX@{8I_5|Eo!1j&oY(|Jtnd~&PLe+j`HS7 z^U>|NCy)(sYR;EeZ!LuO$(7$EN*DItKi}Dm4WLFiMrDq|b3d`xA6y=twG1!gUh>Y* zL{)c10izUJ7sl{IKN|1QBwrE?zpdM+!B`<`b}v5lj5tBO@>0lb9~*(IUbr9audY+;ae8jzIIdh1#f zL>%Q8WhUUL!}}mK_-F;i$NxkKWTT#4!7$_R?sw@f7=K-APL}}?$f6d?_;Vj?VipPg zPv_l*R)o|i&&#zKghTD!&zG?=Typ&&y)+iK%2!upXh`5|kM_FJGH`oJk7vf6uub_P zO{?bd&mSQ}p$sn`4zLgnu()@)FRzjqosxRg-ZTfHk1f1>SQe3*OzrU`-K3|$&kxU!I5Bv0JLhYZRKq1uL+ITPX_BS>IZFsHfuOd;ZiiUjT;C$#&K-aw}{A)vGUYZV& zg6@??Gce}xL9xh=gB~)x)s0oY#ir{gtu9-9LkTKU59O)%C_?)WLX3aq^-d5r!J@IaaPjT18gMj+RtC*5cSRQg*!aMAOo_5UOK*7qj2bhb&%;5cb(p zjmIQ*pTieyGtrZVu}#|Xp-^5Sp6I(B!9b#2wZ~~XX|4wy0jQxJ-z9TO>R+*Ed_#QK z9h{Um^)uFn&XV&Mu>-=S!HgO*BYKuLX|k+x)R1 zE_R3XLrK)|(OV5*6?sI=_puiU30uZpsUHmPnbeHTLwV@(pXMX{oHh(;h#G#PGn!G< z{cE)Q*8b%gJvr`L*jK8H+d^manKcf(-cApojV(6$kpQ;?jz!aa#zX`_SS7j2h_cA{ zyJZnD>vBN`WQn49reI)gZWqWByO$V-!xj%#?I7lSsIL5^O7;pgHFeWVig((68wTDL zK#F^^@JF$>_0y)jKVcP=mMf6;P6o7@&=!gRC_fY&QLCT&vUpEnh|!34bMj4W7lTd|6>Vurqre; zL6*?S$G>}Hd(qOD-e;WG5FW06-X3PaLJnL%L<28ZN-++Q8>C~mTbhyo^#V|_`y3CE z7=CC(18l!)A1VGEZ|(UK>(!po*0*Wi+D4q9N8!*4Y_%np&e7+I$0dgmVY+8RD<_Sb z`ZuuHcq(lC%AL7(i|eG7Ut6ww2X3ZC0d$>i#9VDu-a6L6S#j^7Ol)x)vuUg*KW>gh zQv!blHrW|nSNKpaVjEjj)anXAxT}Q5OOVjgWlU4W6Vhh=@UW zYLj-((FMNN*|e1Hi=b1JA(jKh9a;=u^ii`aV4=KiRiQacEwSv+>MQr>xf}n8e&T*J7&P zlka-v_Btu@kaw@HGTz>v&G``Mc9G%dpb$_Elr!Vrz0x89VF*}5_vPE`dxh3Q9EIHW zKw2)bljLx@Z-CRE#}kE4ZAnV*ZU5Qg*UZRD>JGpY2vAWO^Gb&``A9;ZW0ox9HrzOc z!{&}rNucm^$p92^00=1XP^g?B6x&*;J|*LOr_-&FfoSq~LfDW}9M87O-A>;@s>S8f_p z#)v8@1fQ&1gsGQ2(bV7ia90pYK@erGFfY^W)KQZRtB^cHmhin0zFqRZ#mgC(R}qeC zIDJFz;Ts)_sX_2`vDucQtL(SE%_8LmT^f^~tb_(Q)!f86Jab(Ho@9~iG4i6R+mGJ4 ztno8E@m`zv|64_NuadXjUhsbxxMTp(L@mYqxRIV7CPx@=>C^+f6A<0WQ`T@luJBH? z@UFSx_m3VZgc16-;Dyp7k31ZHvU!S}?7k@v$;kYK9$c*Li4^Si4^FqjZo19C#+rpy zA)SA`GQP<)D?Rm$5OKEI4DW+Z=*?vDsq(QVH3Hho~$ok$`_K-D}T z)9;Bm-8It{L-suv&6OO9oq$`FN*Z>5TMozFn6}SrxBJHIm2P!t3TMpg@8e(;+HK%&{T~#pv=7 z6<(3Su16hG!${Rc>-0O26Iij3J0R*lg617wC0oeJLTRe~a^iT#zH` zFhx|mgQViO5*cM%GG>#9ySFCodyL-dR)u}qzQ8*!d&~BJ&M=mPJjIwsad7;Sf#fHs zhC{=4b&8)xyRvxYPobkl6R6mTOo$tNUk`KzI8WOhTg98t!=t3qV=H%To9C%1eEN`e zmQx$ZSMcAf!~)3q2d2WNyPYvBd(tuz+6!ui*)5uXM2J=4E;iglc&etkEf~cGEBk+N z7{B4PeCblR;pR%9Rm^F@PBQFoXcS5yalSJBTnYqg<3B=56J#ry)0x= z#%r*Y?^xZST>S1%0#sGStFyHn$s;PC--e-r)KZ`fOlyzfz=93Rl85J0i#=ueuP?gR z5130gbFqsMLvd1Oh&bnMgizjrs+O}bjEi2e9g6!OxhSGOPNcSTZuZa)6Jx7@GG8Muk!E?CZ#_c%x^owHJr*FM_#)uWoLp zUHHE3y8M;Nz*U%5Ewkm}c~u8`al2O&Xx&~$ zsFiC&aT9n=t6p{{{wzB^n)}`l>)R$y%_k;P6aR}*TD&vGEf92*1QyUNvo+MhZt*OZ z`m}JKOA(X~T3vVu&pfd-o=5-vdq^KG?}!VbFYl4ztnEdv9n11@n)J$8teNi~=eCEMFu-jYJ1miuwMNGqgOLYlVx?beG}F zadymN`d7i{uVP9<X>;R6-3V3L5grQS$5FI(p2EPdQ~rv7mt_GYphBbn)-6taE8_WiE#EwLIV@ z2x-^>LK(epSC!U4`_h!=x?E4d;n^S(WLBGH#J9F^Z<9wVST-8kOrF=PT51*WX*o&e zP!UN30%4UEkRmoe*MQp!SnRdYJ~QQ)(ycK5hya_ElTK;7_+3fpt5{Dves#wcot<+% z>J;|y_FP^J`&wMat|oXXpyC{aA+sb+U2S0YDgXj$rtIluQJk1U0Y@a>cl<ewp;#ohv<_mtDS#I&LXm=YmH+(t(P#A!GepY3gQB20hq&h2yz$?5 z4@Ou)3bj8{=@o2)2)}04y=hfi=Z}RJMJ=^bn*n$i+^vUV!8_Z?yYC+SBrzUwG^Ft~CtiI-9okVVxg~ zy9aDv$({8i|wQZZ-*-l?S$^4epat(zsjzVZ#R7c})hHQ+&3 z=W5IHDL=U_Au+%};rd65hjBW1KcWYVl)DDgVzX>0jkCCqdDlWny^TwO-ho0bfXQSQ zz3(zn-1O%`Q?YPiNpjQc)dR(3Mc5*-}j@Wl*a4J&7R?qpIb4}cqsDEB8(Ph_2n zg`yu-?q>gmUo8flHp=%)RWx!n93EPT@8UAp1+}ZzF6&IfTgcO`x~jF)0Y^J!20oQ*~zViy*F>4GeKjCB& zk6~ob^|(n?q@UJ9ID05_a0&T8%OT`XF%%U?#%b$ga2q$-WgbVppO{%h98g^kZQq#n zW|PG|Xi7^Le10kbn`()O1j`sa^i@_W<{pIdBqKF>F(mwWbSGJXqKC z67rEme8~wli0{ngIr_=N6b34KEP@*cqf)*>>u~F5GBl21ro;@T80>*V@LH1jPpwI$ z?}gWGs3BXn&b@H#&5?zP5I_6^FUiS2SX{(A zM;JyU4@hzn(ws-E>>X!#Yed8X30O2sWBJ$=kFk3CtegXT|1nfX7;2sP6JNf4eYCCMqh*UN_|Mzc-_y*4W8i zCMZzyMEJ%oa=HIt8jnDqRK%{~-Bp*cQLQFofy^7b39<|)`-G89>7lB&*iDqqjZ}0? z&GlcDmD8&9*-B-0Vl$L3}K1rtVC z@yyrts!6EH+t0TtbCDl8NhCLmH+m~arpuDILrBBQcZ#jA%>nJ9x0xpK-kToHA~D=l z%l`4^(?wQ=rRd;^UG*FV5Jpn%8m2-N`>|_{(ScQI$d*JER~!}LE4I+`OOF84xIO-L@Vo1Ij_4H8FI`iiy*DW07h+BD7+q6oT#BY z%2boPU>7;qbV@7q$IsEtYVz|snwa0w&lL62*%eX%>TQQv`5>>ZdcA^P)lGTYEQvGG zx%s^utte~So_a{fMwG;4`psGL>_nO3<& z5h9~+i@fswDC0Fj_P^`C_*`jjxP=UvHeFnwnG=hK&MX*Yge=Ee))0RZbz@|n|KrmF z#jl3|vqUSgRM)Z<8dnb)p-sOvUiUx1%YM<4&CG#9o^h|Jr5bEm^6dUybtLPaE00At zqD3VNkxd#2eO>k@a$u8Pe8hYNnyJx^T=)vPta(-h;^6E%f}d-G|5dyWDXfyP^D+^I z-0jOP^>vTpLE5(y81FJHmbK2PG^03AT$5K0%1_%jpURXTkf#c1U-->dj>T?cnns(3 zbctaNk$ncd-%cXi{rc&CiNc8doHQB6FR}u|5N!!jpPsf`ZanHvf>+*DEwDl9)@h7U z8ns4~>F0Jx#^nQkPpI2GJ{=zym!{}R;{+FdB7TU>9ETwjv4y#@=xOozY*|U8f}N~h z_?S+S%iX3YfW4qD{<@eV11i%BwT7?{-p}n>TI(~6P1C)l#4zWij@!owQHi!J=_%~a zTRHk8OfLT~oayTggNzb|${y$ps4xQmQGM>O8xN1GO}SVHkj+CT(L;47Zr-5j&lnQ> z@@A1bksQ~uUzkhl3L{rF;WQNM{YBw{!1~NF<e(oXID=F7+Sjym%-tFMaT-SLTZH{= z2c}dc{Goi4jviEgp488@>I(Z=(Fe$H*raNdb#g*R^b;TutKDJCCYL%oND&vm3??cM zCalw8$1lz|TXP9|Xis`VLvar1M?4yf=A?UEH5Y^s$TM>LNsR)^l#Z9UAKW z!PRCVMx^?;HPzWv`@l@E{Q8?wsy}kIe@TDvY`x`VKMMqB0KDWs?*Xnlx-Nhv!DGvJ z2>q+1*o`Ohab_uD0ldN^#qgU_b0cD3&B%6}{wwR5v?B89t| zVaoZb=5?sAdfHbrW?e0z6 zo{Y^_{Ep}Y3)<`gaj@Zk4WBnM>v(?6wzee|50|PbmDXv&59gj>Eu~nQWNO%PE9+#h z`2Mb0&Wvm#3tP+KA9I|K#q|vC49kw6az+zZ$otX-fqZ${n)9svNlLjxFJZr1meM;b zl8>JdZ?Hj{YzNsrUu?7GT(TV?$KsZn@BFXSwI5ufTPN@wwq;Si3Do-<>)2tbt{_)a zuX^u_N6T{-m3J@vphHynO$uhJGavT-X3L7Rf+}L_xr?(mV4&#*x5kcNvP9Q}B=O69 zd12n4?Qol0#7D|@g6PB%~=u=FKSD+d0zjeTc-n>k;Fu=sT41u%N)w zFTgj*MZVE(QWM3@;WV&u8&A~E?Z@R04cpa7vCn{jl``D;sf!araClHoYSbYgtntJ_ zRPXcS^W?x5>VeA)r)S4eUmd;_ai5;;$OK|5Gu{3f8Y6M!C^Z0bfnaFo!;s4qYy~;wuI4%MLp=qxBo@k% zbn=kYp7j1|7W5L2RQqWx!`k@N;GvgA#@+YjsYgTJ=Rk*1UZ2>?Q|lA4OoYe1_jpRI zmwrJ6Iq8``Cum{tCO3>$XU)v$NZqFjI*9^C*aEHkuuhecA7v$VjA4B_#Ep_E$YcNe z(klN)JqeL17;g>L`Q5jWMsA0oicVo6|{c@A~FcYa3f2c2?0=e4FLeyHNb;1gQ@{F;#HUD6s zLzw(}{W(9zK%sKQvTse6uoFuFxQCuwE_CmvG}R1AGi18WwXgBoT)dCeY2tdm%(8Rj z$EXnsSEPvCIHn4ziS%)k7j^@rj_nnKhtI+^jcdtEB{)QHRiNuBW1lP&nxQLB(>Hcc zdjE2-F1Ni_-Gg7=e^4peLDyhj#eqYY767Wu$~nU%&PD_End~{iyYpX(o|MJ<_Bx|Y{_1EsH-pS-3cGD^? zd3^a%X{g7WD3hO1qvl$U4JsF;562DD#m}{jFHxz>Ykd0# z*s3cJDb!F{CfgU&!+f{MzesjY?n$QG;97{z_gCy6eHxgzE#;V4qTiKsh;pi_EvmeR z?(OcP0W6=Ydgb(C#;XtY&m3npVM*UpuOFyxd++q-@jghcp;>P?n_17%5dHYhc)6GO zK#PUv{hVK&ceR)Yy3bX9$_TdUp}dx}%wzUyChxDa4)Cbcf01M)c9T+e4zx^)-3Vl& zdhR}=Y+TKWRL3I!&yfZYl=4`!B3Z4#qjqIyOh!uH19A_fs!Dd=&+N)SQk_ppA%-np zC;?XaTDk6cZnNo6X4ENc;Sz5n!r zvDhHn{XNN9M9+?{gcS$ zL}?u*=BdfGd~G*QPR>G91CTvTKQd|%vD-i?My4GzC_?lmD{)Ls)7a)FoM`>eA}(S^Ueb|GfSa^@C$P(3P|QdO*`kJOEMc#Tc*hv(@m zZrziI8l!A8kq>xylqYRb?le1jOZYeO8)OqhQs!)uat5x%k_1mNh|#U(8ig^cb=(D* zj_TNtZ1PK*`bcc~eV5-EPe8d5ahnkxDRT)TS`yibd8CB=A}tJ?6c~@5KLvwMlWjNZXJITo?KqL7v27Jp!=KG;4+;6dxnWpK zz0RXhpIa`?3ejstxeK|%8Tb}qF@ZVotLtfS2t}&NMZS8UV4~CkN>m9R&~m@yBsFFYLxucVwtM zKE2_%uuxQ7G^-@ep!pxV3w$1)xqmnansq7HXPGYtxwbdALsaC@SwJdJ?b|55u$sazWK^$dsSFF|1-MUqv5!JiH?E zKS4{kHBZmYw7@V>m@srg`4C!~((Yh#v-Y`t`56R~ZBNlut0#pH0A;mth2_0?&`?pq zeSEbS(H?)?PpP~)->T1@XC3KB0|^de`ixeuu%CLVH}Md^rcb!AA4~RC1Ib!A4w80! zM=-ri3~7%-FQD6*?^xwEy);mNl{7d&#A@}ZL1PBr_Fo+$2Hk3O6IVCIgR@QEKqQ|t zZ=yV%x_0(m?f|6=d39gYG)@kboo762H{Y(v$WNIi>QoNIdTU9+-AUdYfM2)vx8yz! z8f)dky}J6?6|Z3wRcUi(45xm1L`WR310lf=Bzn50ArL~k7jn{C3K^y<13P~hF!Al` zn=QVASf(-di%LfQ_dL|_ooOVD#2C&m{N~wcf$naQ7!jey-)Z&^9mbPctnVt`l1LD8 zlfT+C!>NQBsk;0vWXR8kxchV5UGgWDi(>y(E3AKzKD33mDeMocphUNv@5m|s6yT%-&0ju~(pM3UKu$`cc{h;?ML+blkix5!%AV>iORj;J!6G>uW4a+{U z)A}!4s1cBHi?-3eBZTR&`-fn~4S{#NCdxN!9(KNzl7Wa**p#B29C13eFH!=XKVp37 z`3Le0xYlQyXE(1f&+mMmx?WGe-^9{21Ks&9sg$;kzVo{7!f|+%6ES!YQ>actcS+N@ znma5)15@s(p^d1ETuqESnzf*25H>u<3N>=jcmyj*mxwEw|5nQjdJjpM8V3odoje`J z?JDf*o(Y8czW!P2X{x>Lr2@$ilZ?5Z#%ma&5gsKt?pMmpfksNPXZy^dK?nq7MrKuU znu<9Bw8zJ<4|2i`#Iv(U5`n(!uR)9Zj#HqXx1!DJunbC>%q(ud zv@V_$xV|G+v&tz6bx;~uPt3``u1vtYoM(g#0{ML0L4p?+! zWf@n(tJz@~=u`NPFqhXMaf~wHrI1}`VhjJFor~sxVGJ2}a^JfRroOIjZ!a+}Zqfy@ z+%L3vix8{EI-ry~Y~z1~w#e+{sxLnyXdXQ|{KZk#87#L<0u3&6;h` zBFkC015$c1Jn$JIR7@Vt@V=hXqhKLAd9RqltTl)8$mS@%YW+mg*=^enKXGQ8o7dWE zzw?**HWP9A4KKce6o_NSRgDHTF>|!2u13d?ii?%`sQi!C|VvIr}|E1^2{i(Bh0u{{HT?YQZ0LvGW}9-pin~_B-N-=AukiM7L@L zdECAa>v#E=l_vMh$im7yt+4CMZQU~>>m87EFwG$Cl;&{ArMAuMvZ_9A07Y9Qx4qn0 zN%6abf64Iva}zDb<=EksS&!xw50Rs_DPwM{7@*1EvM>J9tw6*>P`G0?TAwhT%t`!^ zHQTaIux%XC-eo4SIvM?WDYB+pbhXWxGLt!Bn*e#vrDWP5sAx{osMgM|s z0RbbPm1U!FK>`NJ$f!hGv0psZ9*2k@$HBsFE?>0E3MzTJ)rTnQe48@&bA`0hubl+H zddJL3`^md7-e4p$LIgvqlSWqNCu=k^Aco;N*gPsO_3z?Jnu=3RYBuZSs^czDTH@su zpGOYGhpeHb_X<0yG!2!)SdpHMNb8W4jmKywUF1)r?g#u}G@4?x^2x5nI%b2wf86~aS70qLo}&oS-AZ-y zvkwmFIo{Z}p6^YLw=0|JEN}VMn&H^neek;8t|s&9esRZHcs6o*`4(l3Gf*_2`DD*-;|%T~%3?ga!Gr6Zpsm#gvfJpVWU(OS2^c{Hf<_Q| z^b(f%6MS2A(G_^`s!x_+OR@P0YpF8`u4#0g4xi@qgbE^VrnAh@y*~PW^hh(s^_CO( z+0(B)PDwEah(M1?l&_PGgV&{Y4l}Jq^dvzh^PXMg8QkAX<%{D#sRQbJdoN;xd(iUv ziLM!U+ttk46;y(jg>rxI|NRhi{o@|^9C4iEOBK9^=}*r=V#@*3cxf7)mgC=5J`*wB zRu*we~<*~<-)rU1PTE}7an2$}_UoMQ0(pO;;0)pY#;5@}TX>ZPX@YGtE-(KzT*;&MMdPps@!Q#^oP^43#c z#~G>pAn31s%#xDp{d0{j<^e>u?)4qcn>{a{@`kRYvq%mUlld&CJ@>~SoSdEtSWZLB z&fsL>e=9q(8o+l7{WIm^VcM+UxX#zU5yg^nTwPG}yaZ3X-Z>HZt}rCkij$`jQmBOF{hKIoSCBalejgkUqB(-c279p8q3 z$zs3TUdz2b@S{OTnJ9S?>Oyj2D*! zOALJ34Bh#5cHfXNe&|KX%DrtF{Vv{i8nuNNRsJ-Ea~VXMBb}vNr_p~(da!H~N*I#E zrpjcrdov~H9vjP6U!4Wm^b2q7FwOlnIKU5JTHQ-+#}^_LzOtAwVtH0#&L_*O!EZn? zfo;4hPaE>ZAEm5Ht$N#8E;CEkXkl)3@A{FN&nxqPh-@V=Y~fbr{mDl)+(yLwJ8Zej z=qTHx5e~k+ZX) z2sNIh^mEJ7Qdhj0p12<|^WLk+BDwdXPy(dE!aV=p5}UrTU3K@4KIa&jEi-2~@&yea z#wM66(XS4D-+8N{>bCsT2(?ZUcuDeOL6+aqGd{{Ffv>)VuoHx%P+VM=(xN_ngi5egr6SrMmFD;-b?6;e9D+FgTqk#v0R8Eu@wzz8*%BS1oe7*JqC zE6k=EnI7}}CV$?TB+8NoYG-yr>zH1d{NoH#6R;5qfrs^<-Rv^pF8{PhP(J7?Uj$9Ck`0vzM>W?7O z+}Bl%C+3o`6h6#B2P=1H;$C)I*A`Ga*R%10?<0y-NVG=%hk4T$=@Y|pU*3GU)oo<2 zdsoE|`XWGq{)ITsR}AwBV0upth>joB|Ki;;ibBXp=yxL{apeB(a@L}jz5Xkb2G-%JPh0aoKr;e(ov0y!2 zka;M!ZDz9p1X7tZ?b*cTBQNJ5@bO~n%xm&sEXkO#>Oz!PO~dW*{|mzdJp2;4fTmeZ z1OR|(vc#^E?soN^BYd5E+N;0T*!gg~3t!m+n7{=z;fv2d``?f48zcVlr=KtNA)Q_K zW;+doI&_sg&6|KA}10Lqo+NPWa^x~sI<)mbZgMO^p3SHv!cJ-$5>#UjoZ#sn@X z)V^Rd#j)tI&t|ik^=B=4a3-&Z?RNBi_xJZlfBjfk6V(6!%H>G?x@rnvhpZXJ1TLy4 z1VKFx#kGiKfvqF70RSwMWtFj(*wxoc_?oI8$ONv2%?&?8r-q=p5hy|k0&)=A005@R z61%#)T{Xq7zE>|_JicApVf(dI8MxL8Hxcuuc!rh)ogsmTwHvrp4VRE5 zXdHVCo%*;q<+0CW+UbU0v-`dlho8?`KDPjXwq=Q35oO=)nyR&FubVHw`g$~QEr~lz zqt24Q_=oM*izZfe$p|zzw0HqaO$~rNxcJ9#Xp&7>dm@wp0Bdlh{`yJ}Ujo+* zb0f|^Ypi*#xmx8#2arLAz;!KSVQpVj8-}!!Oeh0@l4OfrwcqWU>Ri)a5%a@Wl}F|QD4W2Qk5DF* z0l>9oiCqzGuQDET%{51X3xIS4u6hY&LKy(8A=8n1(_P11B76y40HpKk<%{_A`SXYn zxY$o96UqRfFUyhoh^OEcVZ!T>;eD^}-~V$7TmYmaaB(R@+5Y>eVi^D>%e2ba=~fy| zc^x-*+DqU9ARU2=(zF)JBIZq%MTlhpTvo=|6=AJ$j$`3V-~u2Wfs0lNWjj_d0XT=O zu`9w_;}Tu?61V_JN8o~Gri8MH`eT_DOaR7YI#NHzTH|R1E&$RIxFC-fr^+H6_6KN9 zrX%%ZtTi4cZ~>5xzy@;$1wc9i7f>22m^(rl(26d0MU*q$ z6;bzEqre3~IszBaves5GMKYik-8y6TWA#JbT4O}ntBnE|0O<%^0Lu+SSw!6{m_iwl zO{r5}o&K~}ME>|CZ~>5xzy**?OSj5|GT>ZF4_%P Y3kY*Xz9Xxr8vp;8S$x@Qq=RsK8%D5cvv0 zAUcqWyo`?b*ZoC97t6UU=8L1R@Ab<~+?FqkO8In|(p1^frW0K?xGB7pM&G`Qx?gh% zr{>KDM=i6=R|VGRh#!7(5#Ik~=M~=qlbFc1^YQ(_Z?7_?Tgv1xG&npck*QX>g1F+e zb+w8}Cmq@=n+*DOR2;$R;(FB8mZ5yy5_FfuN+W77E&qRGl1XGA0T2IwV|=OGJTv)})ayPsDd(n}fRt&CH0$;%&I2cN zoWeYjN4#gid-LyOIcc8Mav=rn?mR@@l&1I$n*y_MR3CXfxf%9rDbmfIm7iO!7PuiL z&tPwptbj=eD;q)i`29jZ{^tq&vHz5euQdvtAc?<_(yIqlj(-q@l^*r3?3dg>y+_;H zoH+A6&9AI1Nto8SNSFX7_1E->MGlmz%cBIYAGNuhv0s<|%dX6QU`~zLti>-5ENAqJB!}#HO>mMeT#b z_j3^YjO-kptV@Y7t9*%IVyP#?&&azX;$lrh|BSpd75hFRZy{DYlF^Rpy0`fER^L>^ z+414_YG>kakigzD0$Q5?%`C!2y~nja?|61~O4pXP%(^%4#Ds4sonrHk>1w}X#7-x~ z4z0}=9OnL(mRz(#h0L-Ij8HmxCffj%Cy;--yS{&3)BSTo1@ zQdK^0yUC<6#qxki{YS&l(k&=KN^Uu*V=Ic~jxgOe%n4~mUH5AkSmx4qrP;LR)7}X_ z4hRic9c1qMo$r{JT4ydk$&oprsva7oA1P9p=(*eWz7?rr=LX_65R~@huZojAW#lkj zzW$n!0#r&#=){oH2wDe3Zx$z3B{(|kb+j$*;Fg#fe_3P}QlC@k!ad0(4beG>|H}!! z0&h1f#V>o91xk*#vb>fvOr2oj%JkRYwzc(H@L z*?&oCHenA-rr!o_yr1izxq0B!FEcQuUYyBoiw~kE9M2wmF2BgOzOaM$QRW$7=>yIz zseUPOJLN4O>4w{3w{6rnR+#%aW1iffvdk7w9|}@%^z<8-gJ!jN1}d%))<8lifVj*_maT>gE^wS<1d0O|kLWs-it6V*XPe9pF~qmY zWXr?$z_hYF;zyW$!k9sN2)6aIH#aOy(I&FOVM(G^{9bsn*7sWt3ZRh5Up#XC z?zcUe*KHa0!#_->dkpAd=ch8shp^1+q6C;!Fmd)TV<}sI+8J5+)p6$Ez22I<_?=uk z9CL$v6~8xapUG`2Og17?7D>Y`;0F8O?rB1~s`Om`j{SDF={OqDGQU3j9d3T_ru0s{ zZTO~{`r0v`ajA7KXpzVCr)|CR_uR>)8|A{SgNhS^@rQ5a2bYQqINyyLb55w5oQ_Bz zNmMto)Aj9nMq9KK@GnlDmxYn>9V*O&po;<3jx$T_TW)9t8nzO`*0!x))i)^@DK|bQ zOD_`!zT05QpgqHS#=%iU+TKj-l`X()N_9c@13Kkc){}pJ(O+1IB0ym%ia#EbGV0ZS zHNMd3nmip9-(sgJW7$zi;Y7Ss@^h1@HgjninJ7*~UMrp_77v-8t?N*ykByj~TpNWe z0ou02;$AmKX6_c7g%@2i!}L=`JOyEal4 zCZGIV_oh9tAOe{;d~H`TG%=d9x5$5E0V8pQ$qJ@Gzs)C{y@(ZILG~zqQ?y-;*m};% zMn-Y;)z=oQu*>zmZF%4g8Z|BL3|i2AX%L6QWPJC4V?Sm@<$N$zxKNlS3T--5ltlapdFQ9U=Y>q~mSl_VwVo5E zmK_91iALm=M;FSJp?S~6k0xg-s-Imqzn&WY>iFrVCIx{;4!&5oIOaVmV1|W&)4xnI z`6cVKQgNaT{GlIEMH8)3ihzVz<3U>dF2aaS0F?xP^Ui&uC2m`6C{)mt)xBYXRkwdX zRajk7%)qI~1BJ_M>GygFMsN>alHzZtaBum03PphzT8%#fM*GLSFZVCUn)LTAU$%rG z%smWPijz4K^WBt(1)5*+mfS}TxIbD%D;31k(i9*3m2J|5J1v_nU7uOD32>`54$6k84`i5jhI)k=S&M3II4`SB=?%~3Ks z;xaQjqIPNuN_G<9tY`BYEFrR+UDDD_+(!X>s`Vt5^$z^Qqo6gP(+-o)ED_3L zA;;kgA_b8#dsQ#X!nL}1GCh$->mK&qx91#)t?SMaSgT1w4|SBANs$yqKap`NMqjqhn^^*Htz9*EqZgjm;5GiMSm)t-#a-u={E`qq_rP;Z=_{V zR*A$F5lG%_!y#3-S(j4#_9Cc5NZo@o_X8eO92}hVIp<1i!l)LZchzXTYrZ?As{FR) z7)2JaUo)L_3oTu4?{j_e>M;|%h5~U@$SINpBY(A6vM>klLPOJKI1j>$HZ~H6h)x}X zVsIJC7Y>eV3?-teBAvoicNb6K14gFLyxyC=Fjzu3AJm_51sx}hnAT=c9KDXU;KQC! z&k6c9<$Uj1lUlstpjbs{zQ#tA8y}>U1yoyCiGv@2K?nk z(#~hbN=I|-Xlo{i(qV~R)Xj56{_=b2a)$~se;%!+Voxh3#@~y8jo;I6CN{B>7PAz})lYB+Nnf5hhzX(|w*4nV`J=cWGK?6@_-pNuf5HmWL zueqlef1E6Dubf_1U)2RIp80u2LMMOet=gaQni!cLibNj>c~g7ls>)BIhixF3^E5Yx zTOfmwM6AQ^ydnNK_5)UIzu3xc_sYh?uuj+BUdBL@uPvn?%yupxF7rm$gTEVtc6Hrh zpZ;!LVFQZ60PzeLAZ#C)U?na~dz=yt_7#Xf+OkI8Q;-=hRXV3A4zX&q&rneWiG4=O zUUsVS8yuRUp#e z&b~q7fjC<90V87i9XbSR*zaJ3Cx@e|;#d*hf%?#A8kUY*6cAmbRgB z#`gg-;E6PFfay5i+PD^TO3yOx>c5D3M;oV;5Lf%y3Ja40cf}%YC;7!(ogV3j*49#-&#s#P?ZO_-X zN(q=!(EP;-79_^Dm|7|jYh@2Dp?c8?-zqKeXw=gqtY_j)AA8Sw+v?=^6iz99rw1f? zI130Ah0sdmQOO}per~2K6rD8UdH!Kius*TH)Kdwm*rUv}-|d+kG(75=9-$|w$c(Ar!MA&-jl20`;oiStf1v|MxR%Odp}NsM4R>ab&+ab% za#OCJ<_BOszCJ0VOdsNW<+7$QuL}gQTOUIF2Hv+;>OD0x-Rnml_@6y%ZDgkyL@#fV zKnp0UUX3pbB`nuV31bvNJ!SU=G^Ph$jc*=YRSO1;3~qZPKL>ma3`kdxES9`I(d?H; zi)%PWJbPG=ECrY*1H~&pzPw!~1J3d?N0i`S^YS9UK4eT(!O!(5taAN3;G&H{)HeRE zT0a3L{k@1Je~^N}@J9cP7UgolY<_9Q6NJRUz#z&>M)Ab?$8!xIeMn{O>nxz4?V++N zC)X|Qo1(k%N~{P)7#$l;spJR#(0+ct?g3`-VAA%jJy z<)H)AGAv!Y$%CmCN1go$kTW;(JFEfVT^Be|JVs!v5Ry)N-TcM+tl)-a7uS{$Ga-ww zk}V+D5fG?#N-FdRF{oG_0TerBcNKKn0dc^3BK^QpCP;u_wBCO4z1kbR2L>KYt`n`Zpu2*gD7jW?13tQMHNx4cla8{FAWIZap%& zT9|IxePk(?)<5~9qqQv+0*yXLmsD<<`xM_69=@X;&)RGKmf`U@@TSgjY zLFT)U5tcA;51y(jqY>fsbj#EA zwXkJ{6BCp)aysh`N1G>X=#W{Co(fj~q_M14L;EQ5k@^D9=##6n7c_--*i-HIqKomz zFQHxY;p{i_?}qMAytwP%WEh}B7t#$XFL=8J_Y7@2XinaG(Cr<~Okt90agdy>&%KCG zBF0z154BI$qY%UC=8-2-FfcIoF7-$b}wrK3G#ez{fh7@81lfMNcnUf@2@1YxkWExa;3VS@^$ zPTTQ$$$BQx$Pb`v zLFM|$Y4qU_?y%ZvUxspI<&R_xf*`C=H)2^;4leFI0u)VISrMoC3kLl%6%r6ub?uK( z6Tzqn7WI{16UBHI;bk+G2(l{=1yLnBWyz)QH6866eq%jVIc%$h$w!a`S^gG`YyI5% zR~r6c!Ng5XeL)7)H);v#65;)$rVK0Wlqz_T?K20=xvTd2ABZmvl|L4`esP;9H5+vU zff&?-m3tV`YoSqJ59r4!GSyJEDs^r_+J0VV4L4I?P30+fHf5E zX8_j2W9G$kc$bFs9P1-v0>KdDF`g0~wqU&E^zQwAj?)P7c;4tz1ou>Pf%1Gu2c0#LF5xpumZqR1 zO#huJ?$rvR_QXr6JCH`Uq(WsfTJh%pe0H%@k4)ZAO-Q#XBr$|Fgb&e))3%|npG~(o z{nkiT0MW4Q`Fcgls*%Z#wLdF8{l{tWS*Brs-3>0Huv3!E^C@t&^X!fSM<%hdeNqDi zGr!qakk|Y3uz4IED;8X%l)IaLZXK4xLZ5KNT&#ek#$@l`e1`!=+>^Lmd zer#&acuJqW#+Np!pu?KbBasDjC=urhTC+#<8k>f0`6g@Ap3P}4&|U#F&RuV3|sIm5Jbt}1?$g;jrNn9Fztg23syxCNvJaSx4exqu@(O8d{)ThN zUfk)0>T_k-+~0@%t=x7DB%})LLOj56*j~J^X8GeO{$bqZ4Qb_`pphEuKxCpod~t3O zVxhba`id&{bF6q3yd5%xx2!|5Z|5`(Dd&1$!mPjumVW}if~Cojl$76{`N)rH_IG~% z3IDZARjcu4z0T*WL;wXYjRf*ENT(PN( zcE@_oSSXmREhErvj1KdlSD62uTbkdXIYHKxhy*7C7wVRyqB1ylO(M?NQ&}jWX{yrW zq6JnQ$XXs8$gV+Z;qDxUqi7s4j4HVek(J6irMhJ3@`H4-rDF}TFwKE#&K4$C^}qe7 z7->AVQYR*yz!gCKf|=r^D0^0g`IM15YZ2XAMcA;>dki8IwEj=n2YkC&(`<=fI-DC9 z=07P6=}*!$&I!^P<-`UDf860rJn9;?vLL{QyKwJAFOmk+$s@9&Tix=Y;xR8~mz=8zDi*`Tq~G$Fs)U!je0VMR(S&A*eJEL#;gm7E ze0a4rUD)eT{5P#=h#8k;F993a-fH&T^q5m(HHlORJDXhe2?GH`ONfkPB2hIIk9m4* z3eQypySm)SJH7l{N`}=NT;_O$0*e-|RKeg>JXyM&k)B?3Iu0_(N)rypa!3)8;}B|n zr1rE?L#2vKzVO^^U<=O-Nhv-SQVCNsswgM^D?eByJ|7g@&TuRya+*SgNUmThw2LnK z8Qu5Bm&wtu5I>N0GFDSHKa+8Lp_?;@4O&Bv22zI%I?Bx1iZ6|O{zUbhZ7y^fQfS6B zZDh(X)KL;u;neSdtuLkng4GIyr>jEMBQq+Cb{>Tqr=Yzzw-MW9fzz?6c5Zic>Q$a==I2jsNw1qU2cfjc?v_b9uRR^RWL~ABi$eTkHVqT zs2^gI$*^^QcK*I5lX4}p#Btf`BE^$6FVdFzULQ+%NcJs9V|90`OcNJzJ#iMSHg@6z zf`r;c{sz34Uw*nft}^}Q(hb6-#-n+ZlAQdcy_;L@nXEh-ILwLyY-Ug$iu~g2{aBh& zS+tSuW*?%$215?55?Q1s6luBEBFRs>!d^#)-}iuxzd=%&pmVajyGidm6+${hrnv%w zrME?r>?+QoaCYpEE31rLL=1!r;Y6gNT5~Z$`3eSdX$n>Q1mVOFWC_Bmcnb9C85#JP zNJAcYk@WejvH~UDT<pavjA*iZHCjM_1|ytk?-NBR085mqTDBddV= zL4CS=&^P^4Z*Tz}2g*=w@^<0)UXu@H8}dLKfi1R{!hmpdol8nUjYTu#5*bew%zswr zddWZ@%)d1_^)Bwf5Hwii-n`4kfLX1ErO%Al&_0+Rj)8Z}kYMiEq$39Kr)M7hLxefS(Ob#|!) zm9qBRa;KYNCW~DouXhX!!aWvBQN(_-DnsUK~%$WLupUC)u3xInd`H$ z>^ME>f~i0Zv^B_l9(h}KGW&Io?&f*+&xRbM!!k4e67J$cBmIWfLvOIOGD>bBJt$e0 zVG^AorIQ3BC4zUDdst2xVaUtX%da#F`G36tH@s9s-T1xL-NdQocuNtMV6{D7a>kVR zjgD1aY&QS!DR8Np094o^f4s@O;(n@9#+@Mk&K3zP)RUmpEwzj0U`qWM%#_E8p676Y zPsPt%Qx;VusyfEiJ*DNPTk7!LeExU$r~0C&lTFZ5OB6rNqb=KuTA71dp+zNagwe08 zT$Ed{m{0hwE>m&4xKQnu!;dBvUO#88`n=4w<)hmK-dydpk-WQc1m#YlR?z3jPZa4^ z1>>f&{JKJzbdwFaf~bhpmJK9#_F1`9kVWRaoZU5DLg;>?DiIx@gN3Vv@KQOS@6ZJ) ztm50@=819ruWk7sg7Hk|snS^3)be=A;4-GB2#$9Z4RIeUDrEGA>{d#}i))VR$9YgS zDe zjYz?%dw%CmWY}z#m{xOm+A<=Z5E#KX3K>I^LM!0MM|nBc%q27=JHu$ET&vHV_6W1& zv@yu__+zScs{C*5lB1DT9kmS0;0=zt&iE9KEk1E3b#JQeF{f-ZK5!w`AHo`lMF+b} zaquVmEnztI>gLlZ%l8|N4d%C&2(9g&WvOlz8_EY;oHKvy;7CqWHKy=dd0K=zf$T8U zY39wdKW9UOTlkIQN7K9Sw2om5p9RClfr{HF#*m^vapZaGcss~?74{+}dNmXk(irGK z7)k+GBg>1(2-hJWx#R0j97JShH5#V9VE+mr=#sfsshGDOz5oRU2mlTl$LmKuM0s_T z7imoES%|^)5n;Tj(5wr7C-nC_vr4w1{vW~R_wV_P9j#Hw>gJ#vHP;SqGYR> zKab$ytFBiyR+yDGc@u%fzQY(~fu&?{>@SoB;u$wkEe#d~=Ywlha^J+rD>az@#FwRh zMns`fgf;UU>Zl)Gfpp?j3c3CMvmsm+#>T%m{gRQbC>-BfuBnysrc~OL_6p|*i~GdQ z4SEK`B->xz0lYS26{=#mJq4^ZQBwyayIPZ#M5|JdUY9}|sdHk^jw(|)JXT#(ldJS( z8+qu9o&M@@^}ogp#i=<$mXqVTi6?4nyAAAmIlnx?%?IWBEd`s2S6+@CWM#YbX5*bC>$tsA?iQ-dV9dJdKwO3KLwDvf;r!~+QlFEYk-ux02m2oV! zI&DWl=^~uMJIkJ+;K${8MFmx$>=Qi}*RC28*Z%OMT z(Y18!`H%?$Q1QUba{LVFtg$Vb3I@7i;=A}DFAG8LAHI7UN3<9o|A1zX93|!BiB48S zu)#=0MB&Mr+K9?>U97Pdu${ud3aoCP@`iAp=zMUDy0JyLMK~)KemH)9uQbf9=Y1^% z?I2vHfe8y0G&DcUmFMFoJ7oXpuroDJGkFb-D_>|@{I2?a!^W6Z{#(mR3k{c0q7&HhFq zZIU|aeAqQJ&O(9|P|cq{l6==3=_Gm-x;NUY?>I=)EiJ{xBEP%%z$}*>{_PuZb2^T6 zRo3;hEK)|%U;ryaS-)!n+_T56;El8dC@z1a5>aZ=gdX;7L%P8z61SmTLvW2t4d17!sq7i!OWXYD(TGlm7iX-r z*`0&l2rZ;6&Srq~go0%7_z|r}&na{VJ2#0}_rk26BM*wo$_O-sxpG9)z3D#}H^@dZ zOt3(mxbQKXWphk#+=}F90|0@M^E`FWwFPeIQ;h~7UNFAHEzJr&%DlG{)d>Y)0438~ z#D_qf)f%TSD66P07EH=htjPC=FKOKDeL1ED3mS#=#ibf zG9mUC%Dj>Id^q+hpIsHGTQJt@owN<*8x=V;>JAt5QgW|MoOEjrXgbG@V^jA_f250H zP~+z0|J`yP;ug^M#rZv_Y*o~Go(i5_LVPt)4y(EIhi>pHI`qmQr+JxolXb5S1&Ezj z8`5&u<^$2#7P-XcGWZ245SeHt>-4u+f##-pp-=o{(DHtS+H5rahR9U)XFRaE_Lhoa zqhp8ahcE3)3=vfF*g$QR(aq*~h6jMWf0=6^)qH64Y9wNbf-=-r` zG?m#C>oT!SW*q95 zs&nFzw@kqX>SaTQ@#0^JHrh6o7z3p@rhk2%5on#^y1(^c3AIKYs)uL^ zAm3>zr_b~!gI_!NS%56e>rs*EhK}S|-$)wRc-E!lR+&`IA zXDN*KsZ9@H{8?%mdijz^@tF$$DO@Q;X;ky~jYPztSOI>~YqT#BLzS=xG71n0k@=bt zuJgEoMq_GiGNbDdBP3yp!wz9ZTzWdQcH^ z{2XI+rT!ddNc@pytEN0}Mi`6Zu+HYHHD<7Nbt~a?@6)m`cHJ{ z{RsVw>U;Yq<#Xmu9~UBy`LRb35=Nb5>6;EL2OLl~iJgNV2h1MH4_`^p+|el|YbES} zCUVepDolnqPHvjxt`?8(nX^aQIy-JoI(oRBmUjdE6&uyalq$kYG)|j5v5*Lz4Jv8a zkb*gH7c-7In zJ}Vq}b1{0t{qPreLUp%@sgtJL@dMhhb--tG{-=V&0c{iu^Z%hF7}R)V*gP{*5sW@i z`{CT*I}!G2yPQ%>AXwt>G=71Sbf+GPn<;AhUf0KaZKpi02L!w-mMkiyyu8xEXHF&QXPqtGV!*E$?dK83MU9mJ8;%pXx?QGf}(s#=D zaBcSBI+|20kRUmN^%=*Yx}hL?3fD%26*fv#X~lU~uj^l->;vlXvaKq3T&7JxQrtX@!xmMTp6*{o z20tNjGq+j$d#(wWC2*ND@uDul>M8HkKs_GKOIjs9sGCo2rkqaQa_D!1%*2C2xxeKU zdST^OG(6K8^2G`+oUSub;>Baykx!*orgw4N$76OwK^u|eyYol*Bh`| zl>ancmUrj5ZpU4|Q*RXTr9cs#8^sQOUv#Sit#s8@aJ=nh>9O zCStzqq!UM)Db`+XA7WR6XM5K_n`j)So z6YBI-cr1>qR4AkOjkqrBqAggu|2+9bya|fLL>xa3 zPyyf=<_kwUz&;Hp(Z@dnkW8ZluK$ce|2d4dr8?Hlqk2GHIi`H8AbA9+%a=`ItO+a9 ze+h#a8eo?h7^>ws{~k5x_@eZ+mo-hl+Nh#lJZRK4*)`xQ5wnOWp0@;5w_InaBpiXm zYE?53%g~}g`@1>RMD~3x2go}+iY|s{)#k(KmR8NgiUH-staBQxd_EyygL>hZ(44-^ zUj?jJhD3K*l~iI#pigg1<-ga4%3m&NWc_Gt&u^9_rz^|+51h2snJjzqK4mdM$rz!^ zh0cuMZ@NxmdRVR9l-)z;iWK~B)+Lu7?nsuJ&s1It8w_urOrPtYv@BnH_}^SfJ{*Wi z^~d%3_}^}D!yWXURy19yR8=|3IaViFE>E^P?kE>>0%PeggdBqy^n3NW+QNmnIzrzo zY0w?n;IZsn9H~ikw|Gf)jY{3(#Y~G4aM3TBE5z+<6g$%ff4 z2VJa72A*6id2jt5;2gaLC$4xMi(T2Q<*YtbNe$dzO3HlK=|10^Il1J@8t~2oGcl3q zr=RSk++JOF+}XhbstS9{NGsPy9L&0>QnoaQH}S&h55@h$X#?)KXw;10 zdU{A-Uu8%=1f5)L(KeJ@itBeekXEfe>7={n^-mviM$xW2H*~KYseUmp$*xi7plH^_ zTT#!08)|mr)rKMN)!XGO;#9qile(nkp2>a8yG^0?s5&K$mBW;%tNX{}0RwEdtIZ*^ ze%$tR2k#o;D5>i{vsES9wh4ozR78D^tO4U0v%Zl!eI7&Bd;(N&o_j2*`@a&ck9{`6 zf`Q=2gUcXNEuz(^jw|%+Hi?`>OgnZgBmh49}?{*3NVO>FwdyizxKTg?dE77D^Du#qkHj5}h!H?HbLD50?7iPIS7Q_cm zr5dOuNu=a_PZ1aZw8}tRJB(l(EP~Y@5NadVe1XDb7e`97<|_jKfhSG#G@5jG@A5I9Da2cy zdBacHn_T`fKFmlxcDOq4@|HFPPkh7xG|}VS`oL)-=7Xa>$e-+g0j@kSujPrH;WFvj zfZH4o&b_=U=(xrlP9;Gl;lc#Bx*ZY(o=*v#oMy&pYFl{v;CGos`!mN85-Pc@vlBMC zZW26fS3OcqVAe&iO}hxIzHJS>wrYZgVGgLjb!ra3PGh3tO0?wA?|d@AT+hHs$6bq5 zZ$ajBWG!Tn3xraL+oaDq;J~lRWnX8n-Af#JH+)auc@6My;ec({z^kRvYHd!Ti-2%2 z21eq>N_PZiHH2~?iFRP}kGQqIYC^!{)DSoPZk&+vqRn#d>YyqJ*Q~`2X`mmMK3dlQ z;V(U#3^Cy~!^4D7dl<|6iBG0qqf!a_KcxrjgF_sOf5T_m@333_Hwiet^K@u;w|!@+ z=EO|7W^l@G34PgMdC4O6_)=|T^ul!?dH%c_02s0$Xsyf6x?!u^0|r-?IOcO?$Dz=V z`6sr|k;7+abMExbZc*EP?ghSzxKZ(RZfVd0Y3Rdc-PM$SM~MEYSx*$MWR$}kxS)D^ zg4`j%4l9|FVgQG_A2;xz@%TWfBj!4d;7~j${w;G9+%oF8=tYL>+dI66zN822htm`< zJb8q`>lMLxgm&KtQ6Qm+n|?+o1cHVWbRXWCX@f}pV6V#c4>4D>VazE1%wpTm~A0K|->UTuA@WnTtF4o+bL|vV# zYcIpB|79_^^z#T@+NCad<`x*viaq6yh!pm$4_!Dt0Z``EMB^jHiy{=;f)B0%3*uhn z&ToQ0e&AjMluY83-4;(;NK|NftgAlI~1)^~1KXJ+bO;Z3VhH9q5&=h3nP%E>dlWt zp{m8+YfF}s-3SK*lQ&&zb~Li!cq`1ShrQ+g^VeG^?+#Ix+HTPgC4%DZ$(&{{(`#M! zR;k7Pd3D9+QPKZQQz`W`C(n`(kB-6@y_Wl;&XP3$An;WtQQC0Bzi=1bK5RC#8yFaN z*Iko)L&JbjzV;O3Ci4oK&i3&GU2jQfMkSTX35obb7KHu2li1Ui>26h`44nsDmQ}UK zaA$SI_N7??8nRpnyunMW#$aNK%@j8k4L~sK@FjFM2}DV<$$^tLI2I?$Jk2Mk(lPLQ!CVnwr#ipz2Ct%JGA?MN&u_}2C=1KWNT(vSnk7~>wUR5{%re7k*^%zFmJJu+)m%%4^Rf07$7 zasco@`jXxIbRAvt{_ksl?ac1-N?D8;d$N_kc?|)NOQbogb9Y#7fv7^iP5WbFdJNdA z)-o<7`;sIBNndWH{cXk!x!xd{d=+uDIBOU$3XlI_=j9IkeYGEUxk{@5~aUPK`byYa?4%@iM;Vmp)!h^B3O6x3rY z8=I$#?RgbuHBfsDxEZ{O1ZlEKgfS40*C=-I`J=?A0Wa*(?ByDybF(Fp7u@ zldslKNWC8)Y@U8|b}@rE^z}~sU2*DOV&ciJZO<}_4=h%5y<~fed$@E#`8YR6d zcwZZJ_GH>5Yro}_LT$WQNJ~xDUQ1EBw7-2Yg#}18@Wf?mZv{w6NF<=)($K|DBL+eE zHyv(GrOn0lZTD}>GrEAVWnoML9OpjL2@Q%ozT`-#S24}%beNdI_f#PrtgSmN(~iG< zZrMpu+~1CW!MTlOt>`2?lWel#&XRt#t{+$a#Jms|6-1x=#-t#{kfQFiCBj9L{?hyM zVt}=ROX$X>aWCqP4LjzHhMDy5p_QElOdzYuyex54JD3d$#4I|+s5cb)kgdWk4*p;& z{V6jC$W<3MCE>c;^M!u%WE}c~S1aSxIt6%^bK)3*o^+#GieZwb;gY8EcZ-tOKUGF!q24J4n=Yior-I2H5ti7rYSO^F+o^%dL zqfIniRAMN`hEI=G8y3KlU;0#@X!YAH0C@AJkMw9yN0#oGHUptr@7?tH({|K6-Z?|Aio^ofSLIQmTl z;F9U|+_ZaH{7MLbvRecf6)|yeazdK8D+jadb+$llUK?`oTT3Z_^t?EY+)>Dola7%V+!%xC#X1i>q--&o_xkfHnh1af-@-7aL~T5 z^s$f-MKUvU_l8&X`PZ+)h%->$me%MULEXuiX#*3(ewL)8)sf*0!38rZJsC3dKv#r1 z%=dUAxak?r9E5wwMW=jgj3EwlF69@*ll7N1R;W)vbtQp#?(9qSMb1-CJw$FD=)<3Y z`m`t6S5zG;-s>J?fQ6w6U$!b&c7N3gi}(=1=fwSIB0gehgRd&1T663;mVdih5l`_r z`sE%}|w<7=>1Pjfz3!#AjJ3aK^OJdgNwN5=8}xFW-}N1w}dndiGjmNrH^Tp%&arUeN* zz04w5RTJ{na<75iL{Bz9`Iqdkzq1(*gxZy){q)(t+oUJ?Gqc+c5#^e-Wq_}*jMejw z9F@8}&KE6mw}elq3mE4~q{Oxzc83`YxKG77R{`XO1md#$+SG0!RQ0ImPAK(JDw?@Y|w zQa>xmv7d&A*bbKkhp@&7VK?lJS_E(zRGBAwAl9|(%HF#|vW1e>X}k)B6PJC@^j)s6 z$cgG;bC)OS5Zd_zj_2=;=&?hDWAL5b_VXE?C=p-M10F>8XLqk}Y6B|M@jasLMMLb$ zO<`gifvn>VRgbVNnZlRDy;pj(CD}Hf6;;B377;Fh$7;SC?e2AFr1bo9vOeG%MdrR8w? zcImHBq*DWo9raty(V@CTKai{523lFNCzqHg5Xc|*Ph8-=#;hxG(xzT4^JRig{}`WX z%AEKHQ4X4>b?H27ZFtdsk#H~@4M!#)jhHPA&Wfggfsda+AaIM!>Tb#<89*Gy?hG`| z&bN@fEPBPh+xYptyVUdl^#b@i1HJVVP-GP>DZWn7@*iq|&ySRu$?~QQ0IXo(@v>|5 zWT|abP{-L9+G54z+VPQ5rr9XMLF5Uv;R0+kWo{>=940_8gOj5;ea=H!zH&1BUPsQ!=f6{DZVhtgxlMp%sqos9#XPd z;>pw3PgkdfLK=c%^tAJme+l|pBH0dR&Xmp;0GFbS=4e*CD02TwTM0my@GNRb^hJCY zR>~LPo*qK!{>mOmAp0NSc(N<^w~Z&qeUp*quT^5cW^{R1#%V`-inBwOEv7<6=t0H^ z*%6u)!{r>nA$(ga9O+*JlBZ-DBgE6xW`N&BuaQ|0tUcNsExmo#HY(l`^mtU0$U*bD z*qU~7QM>V7gE58i;kdz)$o%i$IIS`y%8GGwh8)#k^G>05bT?9kp9)S$j)?1g;86LW z3@LFj12Hz%Hv810-s@1#2BVKHObwGtwZArN40MmKbK)9H4RkrOKP!;L`AbHQh_;@$ zKl+v_*9Dy)`>b&hmtxO1G<_Bu8goG>8r~-8JF#%$2posLF{m{xsnGtpK}JED=i(c` zx+`9EPGP3zgq)Xdq0NtJV6=*Y09YXGhnpt_hY_={a2U;~v+0mBiNyLh*c`L3cv522 z&m3}i_g}0?K5yq8njA_8N;@(l>wYqF8kJGwaT$$`@t(emu-OBNpmT4WMY2MD zj@*}-o1Qm1I0xAHiB_ypG=@TQf&Ssce|hE?O;o;qp|EyyYklx0d^4EKavE;fCu^1V zR&ey^Pae7A$gU%TXcT7hm%RMi0LuzxRf9Qsx8V*o{;9x|82{{6F{o@|3$wqAKj3*G z7-Hr07?Nm@o?Vnt>rFzyhe;p4ol&$;##ANLM=cAc?^UTaHQc&4rllFIVKi8ZYn`Zj zvtyEE53ai}Q<(e^F-@LdqR5vnSEo?&Lm|6J>BY9A1hR)3*{|Fl@l-yt^UmS-^i-Z> z>VCqahN68Dm|NtO6wHZ)I{l&XzkXbhOQy*rz5BENn{TYZ@NZ@!NHjWcr4Zpo@b@th zN{Mv>3d;p!qm8@o6DFVAJ2RUVB)>RAT=QK2J~x4_clVMx2g1wzU5@ajZr3qsxT+=_ zm2(;oaK}sNvYPLCXDW#^hcwpYCEGV#Ag(y@GhQc+>_zYRH26dLXy(UF#}j_i+N$J$ zt5kohh@w^Q8IA92MVaUie;duZv}0)(ub4XS)?a)b>xy*??j9pi7gqd#c>2nKsJicK z5F|%INZ95(NxUWWtu`_c0GCPQQBh^0B#@ss3Vo`sflneN-tyz?FIZHV@2Mfm z+@z)HKiJ~3@)pPsprtLi5+#8tlIz%izNiXys};j9VX9#oQG@lys_QA6*0xNO&}#N z@MNNa^!R3tD0P=5ipi{$M)gtbx;Tb{FDQIr@!>%tJSMSj$6cD%R|q5S~JAh7!oK;cWKp}tf|uyD>?i#Y!0 zBv_$(`F!MMrudyw*i`!dmO5g;2mup6 zVZQxwa_-(%Wgj8^nLzwH@3=l)`9HOWizl)r8Dlb=;y3f#ManGe9!}ou;l{YLu(f;F zm=*6EtdTUr^<{sRMGF#lO2nz?J@$Dm8i`Zx=|zx8G8{6lxkpDPA>A>j(5%$jS=a(b zt&>gY&Z>Sh8+*jnBIvRqlKbwO45M4l-o_wtg^P3O{21j6&KsB4os?EAi59_ZZm@EK zj?gW5Ca6K>R#gt#>@WolLdRfqpY8`vHpF2Zy6ULnz0<|>FpuWwHr8~6IDQ)snh{%F z?vaFHnF^&dg8tgrKt_es;NG|5J}ox<7#)LEX*M0iZQyZ|R;O}E5`pAQfefetuC-ou zV+KQDtAEf{hs!f!A+q_;gu8Cpp~{{ub=Sa%_FrJ$@h9=3jBN}vZ>oFa#(25uf<*W8 z)ra*P{SsO2KdT)<9xmSGS}@r#>EAs!ri_il=)X-|csawWv9dSmmR9nUA{1cO3b`-X z+-N*Y=AFh~BFi9v0*2Mz#m(v8>WmUPEXx*c;Obd zJS_XBZEIr>-lc!~yHUC}I~>2F6MmKP0>J2YPFMEImf@rU03FOiZxGEA{-#Cpfzk3K13YTv3`yb>0LVQbQir>HC+Q>CBK2JNtsJqer7sSYS z#VfzLg_^GKqhsJkGtPBc;23mzO6cvp^|4g9t~&so!xw=Z15dpqwjAVNzQ&YbI&2T7 z8ZmGU(X13$|8l@V*NrFq$X1L;rg6ocl4P^&Lay;=c$6IFh@BHEg0$>UFYq+^_kwQ5 zWmN{X8Jv_G0`ZHeWsBaZ>tik%{DIj`*3$R@uRFMusg=~jA&uA!f2*?Ql4h|%wYPU< ztuY+M9&+??lrdUlPkGv_YkuuFZ-t4=(-|-JOmlnKM91|b%0xgEQ$(Ms)^KEo0gWX~ z1KY@2a@WOH#@3=l{97>@lJ148{qj&&wTKiQ1{|hEwnU})Fl`>`!(!3>#Kn^NK~>(o z(3d(bw>)(}S$Q?o$)=e*V12nEAH~jG`IEfc>9!a$LD(HbhJOQ3EG#`9|1t|Sc*d-_ zo#5)Ey1stN%gNkfQT-zehdcm_F_ph(V2h!=LT7WL2c!P=wdJl=p`^$f{z-q_O*ky*Q-)WeHhM2UXyQr z%qUaPSsgolLCRMz-F4+u%?P&J_6uXE{jX>doSm35al_V~#;&;+h1DW4*NimPH2y9o zu|DVoVv0xS;=%IAu?-Sr2HKfr?n~NEmp{d;Ue6t1aItdqoo|2i+Urui9-j+S_QdF^ zP?S0;YG~P#X$;+VgUPlc)N50<&mL&Svwv_Q${4EH`u@U-9ebDlM-{9PgYGnG`eAhl!RB zdN|r+rfowmG~zNmuBG90_?<)EGB!zkf5fV8rQR|s`xI7qbTS~%zt(fqG;n%L+l0Sz z`=0&IiL{x+|zN({=5?b06S}CFpFAr~Vy_{+~i%f@ExY;^M8?Uj@_i!x~ zgDusI@8GZcjk75>aiNNGc$Vj&h=jo3SxWa0p+RofQAJ-TwD_-HjL2q~=6-8a2=!ZE zQ=_sUkgvPxq6TI%#PKsV*MfR221~`t-!4k^)yQKK^Dp#r=G_WH-KwNOyuGnEH^<2N zYW6lBp#sQtW8uvN0Ms$2apY4|Llb6;Sd7u0jTzH*NzKOKMF@c9UAyIPJoV4(TWJGf9fR<&9Z z-UIb4nBmt+-fWFo(Q^N1K86T2Xvvw2x$kdFI*1~nOoF9~&C(rWhr<2l2BZDuBo4s> znH<)pYJ$tvF!Eyk69L_xu}L=-mjF0f`l~5$dhLf?1nbo{dZAZ1P+yCcrwfpl{L3gL z5fUJ_o*#W-E+yNpAwtD5WM zM^k!eDGMu4TR)R1D;S!ZW)MZfl8yG6u%v!^isSg|05g^xWSMf8zH(4KCGkLrpV_=K64wQzh?`s&Hn( ztCLKPg3zz{ssqL}5`me5!~;^$$jX6O{5dgmg@>|RR)=HYV?%F>FuWtClWnzJ_+kF|AR>2`}~B*J%RY{q_rfY*gkXj;Ar5y8E*RA0klds(m0pt z6~X|MWEItq9214#3iyHTY=ba?^%)IpYG%poF|$~u*}SPms!;N15kq{mfvV(%p1#dv zO+|s`Bocwpb+*idig11WlSSa z{2J5{u*~>DUD5fXMqbD?>KB~qfL}1bJ6&dG@b~L!?V-Yes_y#+vZ!Ir+ZHC1dQfui1*V3>B-}k^L&P3!d28y zx-3cE&lNADMPeoeFqtaMGfeGV2@&4D%d+zfN?9J3#QHf|xNVVJ*Jn0GZOFZ?5zZw! z4j=UCTRR~cYWy76)6z;#p1vNN&fP8T8W+_MAu%*zkG-jtH383ut0Ya0Kc(J}SNDJY zGwiocJPXkW%mj=I9YV*lu+GrYQ{7H@r?UGDbI`g#M#Lat{X5h`yf-_EwOUVbd02Xr zE2KMh(sx2Vk}|QKjx)zHE+|3#YYg1WT*->0P(zQNoO z?ETN)*VYW$jkAr9rcXz@=V10VrZfS*4%O18@y17id-*4OQdM#h=ci5G2kAg*^MSFE z!{v<;@9P|4?hAXXOJh~}CL2WVyLHeR_V04pFrbd@Rfk_Pf}=67`J0bU9AphCP`!o_=#|&nDpUmo zF#i%el4W?`J1!V#7O3 zD!IVj0n6jQ?hE~m)7XQ%GmX4H5%XB@$CMUn=9u-j8J>dz_qPwQ$ElnytP%N)jkQSv zw&ambk_s*EM3TOG<9yvl^VSTTA|%x=Hu{OV4QeJo$_=P!v zx}9Pa_2-uV1h`eI%v{jotf7|DVfs@RtIsYd&A7MFMeJWyd2Wt6|3vGl?@RNPm9j#4 z>hi?pz!&#tBlp(QQSqEbECfjRnH!y&O!&dgQjM1z?89<RG6K#26U-CJdfVDR)hxL^O+;Sd&~p+cz-qqWuryS)df#s+n6Yii$ud8rtPhqlC|+3NRJsD8 zJR9G&B~Nma&~l4R!s|I+P28^|ix+ftKVO}Gsp)Kc20$yM@gwA1oRH~E$J^V<3FD@C z;O4E%Qk&oyNIzg`~5)-DE zioF=#C(eL9H*Nu7aIr`U?DWqOqmyx~F0i*7HWd^%>hv{sUG+Q! za09UAcwMulmE{vCH+VgfDfGC*Csels1HrCvqsIj&Cx&9__lp@Ym^fj!JRh1cA?f!p z`sw>}VZH0e1A$NamD`gVU7+!>|8;=3vVO+pjA7t7NxRy-fJo&}$cnw=d1SUhtBL3B zW~%}4%U@JyVZkvj@}=5)f0_gRcAS>J6;!c{;ZqOoMFkG+bPcWAVFn;7&T`Z;frP83 z6UC%6HgARLBz<15S8W7J&8VL7p2{IXfu@wCaMaV&vs~1%l4Rt!E~OQoW|XhD5DJ)O z(Mh^-`AGD+DMc`|vf3Ywplqv{eJkH{&7nq}PkTc#sx9=job`8(0XNFL@Tinp$CU?K zm(UsPpnXGbsohFC3BqIU?ZH}+ zCX4V-e@jo=g0`(Qzc~G&T1{IzXbYYvI62`RUbdr5hmogennAflbCm7E$~V3Q_-Lc` z#E@zH3+qoH3rPuAYe3gM=t_E{$x&{WMPOpbmC=4}yG`?O1F5`3uq_bCVyh zCw#b%JqL|)ENZnFzA_|ezSykVI{mg{TXh`^PQ3Z5iiI+2fgAgcIff?kkf5D0ZPt2f+3VT44fgK0@wK1%`-_zly&&cqv8n^0aGbivGRUxL9UtqB%-xExYT&^o z3#Kp2udLI*?N~8Di-A3|tPiEZcn2J#+WGUM{777$DF}oF?%Hmdr#ZbDzvdCLRrRn%uJRcm;)-J-)rC z7>Z;OYJBESNf}H;3b0H*+o6KjjI=8g3u0@3FQzc_?A*CirA0O?!`^yMY-NzD>q3e1 zL+q8s09-;mX073!qJW;2Q+l^r`xbvw&*IsZ6aOr~^pEQ4lv`SH#mRd&1v1uFH&^1B zrN!Sorn6?yBuz>GvT5Ls7Fd|MrW$Oho=lj?8OmygbnbGi;qV$UHuL8CC+)LuX$=0x z&^OyU$gWiV^)Ul;O`+*>m))k(xpHLyGka)l?L$XyM~3KoAa`(fz=GSiB^p!ir_f9= z4L@_luNy4jNf9IhQLB+Dn57_<_2aUvoPfk))GV9ggXDWMU&J43Ifk-0x9({1`s7-2 z8n4YUHc)(n$Q!Q1Zv?GKX^+^i!`I9vE|^eIl)h9Ur7pf^y4t3n&47kYexpT#t(gXbz7;d|NmJ zeq!FeuG%vYai~Yt6t`02QsHdeU-SR?IUZtP8U-Tc2(SZfe2S;Z1YIVNUz@f`I2wY4 zLU^I6@WI{3ZlvqW?v3SH?WuC;c&0t)C&sF2#O4*JlzFmWveC8HA0@G3I#EN)9R(lg z`AHdGlqG}J`>jg;9!Mhm)kf-H+UGQiXk<&B41Z$h5XcbA^^_H-|HLTF*C_t6qW^*~^U>+e5p9QKD=iAGd*(t;1-Cn^3ZA>5se1JEX>cY?S%`$Mn|2eS1EQ6h6 z*c38t{-t8tjMd+GfkIM-sO!2}91{`pMMAG_wigA)Qm_+TUCpk58Cz5v;@gDBq}9s; zF6?~xjlP|vzinN@$Rj!GVIWcTFQ5U-n^Ct_Y@@R7`FYpI{Y=YZ`9)SXP1q&2VW&~O zI4k6+MQzP0NJv8^nS(1Pghed^CR9THB8Z9D36{ZsIcZT1LtADlMwXV!Qoj1j71|El z3oQ5Sv%^Q^Ivj3Fc`zkRI?n45fvW<1a zpV*vcQ$G5?bHk@XFwZYaIZ9r_gK@gj8KWi92b!?Cq!mg1G6S2e*^Moe%1_!qX_rg#dgER0UigEL&v~`%%j_p#8X=3r5+wd&Z-}pFXY7%atS+?aJ7pG^HGGp_L9GJN4r9Wb>mzE( zjdFeN6$j6h=Pf(ZbI5Y-0O|D(k3x}ft(&>pqMBgdEj<$84%&4M-$E&}nHDQFYTh)~ zYad2pkHP}XlkoFGj2F1%2#>j8uP(l0_J8`#`V4t(2%!vBEE{x4ao`C zGDqR8saf?z{`jHIAYsepYj@#zRHO7>*ny*ET)8W{c4=!axXze-W_BquW65gE3LB}$ z+EnecDo+tqfJRay-CwB?nj2s)iusN!FWhimEii-y1Ty}W@Xnw7)f8Sjr$(e1v9Hn) zYf2}SkDd)pbl54R5pG4XxHN$|Onr?jFaOhNpfE$m*6KceSAJ-@(H9?a_5$hBMHD05gl3KPQ zKVcniy-Uph(*k_A3ZjWfUZ4u00tvH_3vavF;?4$TDRM82s^>1?U*geD;Z1gff5_p4 z(@b%2+&)|C8ysV8NuA!`mnZ~S>iT@$>8y63IXy!+`|OC0rit08 zCS*V=cZ<^6^~IOmz?cyZlIdkXQAZfz+^k`=6{MRdw7`|*TT?cFDEZp$dy!lYJcEze z=>EOR%G1-Mgljb2WwI<}e*-HK)ngVi7Rm4j{_Lg82H_z80;sEaf*x_xA`mJ7Cjd)9 zFni(vu5?Aqc(qIaLH=O@n|lFPPJj3PZEXCz9PFiHS`~n^lA)jZVE7rr(>4|QzThfT z7HbqUhZ$?MM3RWQ6AY1K3z5s8vJm+qf)%g;Q~f?UOjh3{O1cSqm_*Qn)?_quSQ#_F zqi%X!tijrWC~`uhK^;*LM5lzCnt-}A-%6p?{p_J0FNb%92}q5^d%L1X#@dmP&o4{@ z+L?BnqHBQLBEUGD2-{rwt6Vm>wQ7c)dO7%nQXRjm9Wlf|Duc?8VjyGyE=)mNaNHf4 zcyHNIyu%J)_FIP}E)@MGBN|n`U*AIqzyGYR?QUFM{d*?DQf*u2V43u@dLo_xiv@$8 z;F|g$zJqWLKL=4f`=@)cm1S$Hj5;zSRvVt)Vq<^78dW&X_70Qng*N$Y*a4w3pUm_x zzMs|lzv8lh>t^1}cwh;<=xDD3E|ZLMPBXc%!x6_f(O4o<_5}5GR>*?LmrAof7)%JN z@&*o7y$Y%vaC&{Ggpu`b1a{%dnO<3_>b4hgwyZ&*X}I3VeydYt;&?jDhpkZ)(qKh8 z({U3>69P0`Y6LqzbrfU;L4Tp8Pc}u7uX5{2YRV(|RG5#xNnh9*_LBed?C2;ATAde} zVmmJ?E;SS(T!4*+bc2b61SIG>9VLiF{@QWN2>%3Y#Uc$<(BPsK7nk@(Ff*0WBh!WE z-;m77MBoQN*~-zow9;owqbiA~AEFdLkDPa!5Ay=IB(wfijpPr=_W#K}8>LIsXu{4) z?3qMqL?Xd*EdQK?NWOhjC18jH!VcUEVE)c$4h_KlU`(0)eLUTyaPd=<^l$95E$-n#--%yTH>V2LxQAH{T{b+Aap%H937D3g8HGn?No2SaIn zw?=$udq}<9++M}5WX+eyVZ{=tjWNl2M9z#`Ua%V}z2MD87tsJI4~J8CZm^D=c&L)o z6yA=%Bwv^-q~(cNn+_l6U;dQkVyGS7%4_Rv0=Rwyod@(Ed&HWut09v06CPXlodBr$RS0VjSnzSp6th!0r|D|e77>l4T;8F zsOZH#qX5o3x7iUF|Bx4n_{-TUJp%#4F^H33PYyF3wDb!m$-H}pA>e^7f!6x z;Zz+vunYYN4Ry8nmpt7CEn3hv7aXxpu+X&J0zU=#M@DC{2s>O}7&%TF8x71l=*NbG z_pQbR4;C-l1nq6vW3>j<0R9W6!F0#pX^k7MA55~?J&tAXnwr-swB0dt#%5{#g?Uny zQjlQg(d<^i*fO~sVl-l?%sbY2XloEH2JvW$Spwt%SV(l$inGKI7zn^D0YdNsulGEg z3_%?fQU?38B3;S3J(0i!xB$<3FzG|lI>EOKG!eb}rI9c$o%#!7x#3?btStAoWxcHe zWRTf8Z0AJu2c3Tz0!9G<{1zsY51K|pS76qp&G&V+I=-6fr9OT?euIfH#BG-zGugk( zXcQ_t;sd%sN&GiR7pd(;-NJ*7B{RnwZ}DCj~Ru zN{<`wrD9ZN2f9pDr)%$ z>zSp?7PoL~HSS?>htYfV&sL2 zV-*>bUnqik7dy0~m_geVp09Xu*Q*yvsZj$%^Kn5k(0qL6H)sw#W-Kf?%|8QO_}_f< zlrUbDn5mXK8bkG!TN%+O`T_-CiH$y`dZNu#-7IPv@m=O4>YOpdaSxE$gCVP6bUM`I zGz2%{&^E=R0s4+7qzuqKwovfUf7IP&#DZwf*PychcntFAHY+1>?CZMn776^Xj>Bk& zW9=M`NhX;e@7s!|k1a_`Qhd4Kb0ylvT2`vAY}R>x>026-E)|-;^VM7DA8-urXD2kS zBpkoQjn~FVdetiUkx7Q`6PGZZ zwjEw3-b>}2@J#z!ex_2#rEnOg2K8*<6kZw3y2#Nz45ji7|8HH{+%gryXm`c%>M50W zreA-Iz8`#uuv5shxU-o7`{~7h(V^VI z=A20zGC8UGFuh}Gu7Sr>bnGKS4Y>#f53*r0%+ONgsDt#fNEVUiFi|+5=4pw^Gr2-v z;V-6FrnvTFK zKcX*G1z(6^&f-zbXwqLdx0p+4lS>>-&Z*80&f=GwG%B}O&}VaX;}7Ynb3_>H<0BRF zD@5Efw^MX?whHFF3aEHRzwjZZFH;746l8olTM|=J)Lcaa8uKx>hE$p7R(B~G6By$s z1}0tZq4J-m2dJ+fgx1U>3eLp4$Q=nG8Y@L=# zZbhJWzikUEINQ-WiHz(_@E=<++cZ_3 zg-buk5$)X5^V11)CjFom~0%&3^(_=tMi zDn7-UV|Bj?jJqsz+~YF|SMn|1i5l7(1E;<|uH+Efp^@_m|E~5iz#P95{G$M*V2%sT z0)6O!WBc-{wTd1~pp)rG)k=k2@GB;wu=f!m+4urz!H(@bWM4QQF2^NhuvFn>XPJMG z{>~YPd9~Oolx68Ub<$qY8mhEd*Fe8HSEjv$jKw=6gGZ;gT=`JPM_ash z#eXa^yd^IL_fnrIxrw$Vgst;>GDW(Z{Gc!dCh@dkd}iiJWO0N3|M6I+%W-=6VA7dw19!uTw?Up&j;=He-hZ?ze~<)Y(&e4Wq%ca*O^D9g!*OQFp)|h=V$D~ zS6O5H3$Gq+BhZHr!8ui*z9{&z&N)U%}#w0D;gn#d!|?Q{%$mf?6)hhn#%*5Jzm)79lQ6t6@j92 z!F{R3J!ck!i~?~M#wUXsbk9hK_nF(`+VNu4+OXXpk63V3E$N8cJ022Wzb?tJdO`FDFCx4x}2@y$Wx;CnRF&10y>{o3rH*nn$VD&n)OQS z!WwwvJmQczr8v@sll3ni1A`grxk@Y&;!fd9BM)R4iPe#KET27y<$M*%`RZc( z0B30~Cj^jmm}>;;o8t0L%ey|33bYV>wlskn*ey3q1#YQvS&3}vXxEI4N3xf<7NF&; z_xp}Cg+N?KaYNSKosW{e^p^%;u%a6sI++N%^y5$9X~?EE@D9Jl-Y*e~kgBm)VK$U~ zG#Z{Cic(h*&PV*b|K(hoMcZ!&%LDb<@CcN5-jB}5@=tSF#HH*;!;4;T1^=zd;9XBM zF2G2GvcM= z6D*x4O))_^SszL34vZ_A1-nUPF5OW*!MDr0Kc7}3;f_~4!p!bdf$?lG_D;2G>4iJ0 zI}4xZu|Sc#zLiz+iu88Uk@rzUkR9MZ0hnuv^98$gnq8HU;k6`{7s`}TUV{h{|GI5J z%*U*-=)9bFq8awIsX26fl?fQKGw|%UsT-{HWNi7RThqQjpEA8o{lPn1k2KrHlZ$j> z;ovV+Z55c=)Qd7E6V`M^McPl1YDBLVRCuMg=`Rfjvb>f0JpKX?f^b<(_iqq;XIMc7 zPu|&Lr8RvZtK1GVMOD8d%)9)+6z83RO6DdBOjRJ5DOPWJs8z>xeSq0cL%DG;ecYgU z`tuupF?>8HmWhf|-`6nx>^m(mb97040&P1~DDQ3I>RgQ$O2q+|@SxM4PR~G+wi3zs zECpy>a^2rZrc?u*ww!v&FLxSk%c$Pj+l?wBL6*#Z+U9vEKx+Lw3q~4JL`#Aq*D!nE z4rdYFQS3|`Ix)7DaoxHRGaYiu?12t!mTtedNb@LjE;q~_Q3fNN&lkv^3jQ;x z%#vSslSS3B@k-gNr|5b*pF zZQpA`SElu9HBlO8^vbF&9IdQ=2mlUvSu4ey4{+x(MXI_s&5x?3&Gc;*Tqpn5Jf@n~ z_SF*o6>5rn$#4`m_t)re1PCI4|958YsP+I|Kz% zPGSei7RCnv{OKtix3^o~iZs`oZt<%pYA5QcPd03fy8USj=V5!6s+>=!?vwQNujG!w zM<+R6jH`kUMHca1L)0mN$*lmBkGa>4paK4nrLL}RoUg_^X-M*|_ugG!+|inOK*ogV zvFPayUW*>R*^{>IsF41)XZ5k-C;@$FjOg?4n|hvwdyiM95nn#7qLW3G3>c2oJjmeF z;vuh@cGj_)-ZnwB?{=$Ipa0dQOK`8LEPG_Py|T&p6d$weyML8Ah%xFWAb)vfy0`%A zkMePS|D4P5*%kr@Q~dPxsI)9}NYFE2OPoZ9`hpsGy(Bhfbu)Tu?NzbL#p%3C)%2Z6 zmY9AdKt%XkM?JQf^!Ax7~d^B4k+Ta_lEJJ4Q(nz9w?*)zW;e=ZU zL4{a?+=9^S2c3DUo{Lgp2&TI&C9{@Ww2sT|7IJ-wDOjm6Aky#M(UMhQsDk%MZym4V zFAMeHSL0~H!NSuM{X^tdb+C4(4(pnWy*dn~{ErYW9;6-NK!DeExDo7x7xS@yP#d~L z+9?&*EAtxJ#)A+WKiDL&5BP6x&>e~{PSky>;rmD$?10n(&0=yu4~(=~@WXYtn6M7J zEZE!-zud%#ep)@W_Gtz^e%=9?h6SYSkQi~m=o0Ezq%at|38@?fnzEjwelu#e;&_(y+Lod<5& zCjvc%FZo9`EJt^^?;#u6w4h7$dZ^*OeVfvDs`%Inl;Hvmybs1p*AmOuKv3em+C}C= zs633^6^0KorqL77W_s-cr&6*U=1z}ZP1AJm@MKL+g>){AfC|<+5vM}=0e5IgqEBp3 z<9hXojMj)l-Dx=!{MLGpp*bCyC3k9fwj2zPzwTL=p9U5lG^NA*ACHYZ9E#^Otm(qv z-#lxt5VQv>d8EiHFaB_B%CB(88j?CgJ>w}AcZ;AJEK|6hY(HcS%8vHO|qjPTYbs|spTflfENRnBn;|o_WE5`kE4uD{AB65Hr*4V4aCzGHWJ3RvJ~O*hLS2 zR=HEGj7y!M{3$F(=3ix7BVcd;xHICx%O{?sB7mj8R# z#6~6(mZo97c)d;KeVO3h_8^YYuN)*O- zNmAktJkJ2&0mnC3RPVe!(H@M<&>Jkto__FRl-^gY1aQ)ecfbz8`>eU_6q`k~@Jtk2 z;0Y0F_mun9t(MUyHPOwSlxQXFZfI{8E8$Y7Jnx0Xe|v!`Iq;+HHy-T)lw}v;i9(Nm znedA}i}r`xv@q)fRtRR0sfUB}ihU2aUf>W}Wi{K(nW2RHkEWRSCq{c#k#-lm1D;yp zT;{hbWQ@;oGMbu^ymN&G;j+^x`qy4qWck&%_?^&rF8vC(f>#&^rI82Wk@Ivi zpOGJ4?MAiO0HCn@<$via*Hrk45aH3NHUo2Mss4g&#btf371(g)ny_^#z^a|Tb(~kh zrCv92UW~%QhHbT#vyF?}JIOKwQHeRlZ$1r{&v(HAazOfLBF8NQuCnL*N5SykE$gULx_!58yi3;R!->VF){f#2|=YMc9tKR;<$HMBY|E$#M z11g~TZNG*BQ+vx5lbt1c5!M>2^`*LV+k_K$@VWdUH~Y>SP zuY7R|)gCm5jmFteQxuiW84_gvuZP$=}gzEP9u#a|*B&;fxF@%cG0 zf=oP=Z^Kc+v4Etiw?{#2UNtAkc2#B14Uq zjrZc@W#m`;DO0U6JuU(Ej;1>C2c2%1@S`5N-sAq^k}vV;R`VGL!=C}47UE9~3{u|4 zV^iT*HqSX?=&EO`h*3JOfs5lGC?*q$NiJn`XQ57*Xkm$px&c1Z(Tl|rmXrO4*ZEau zgRA*o1MHSAbb9pm{kDP0)dGxvD-$oz$rF$e(Bkz-*exH;9jNWwLt9Qe=S=mzgnuZ7>2uvvwxl z4Aq`H^yvPawwIIzJzAhzw1Lb)+p0A#VW6C&A-=UDT`%LiY9e?}ehZ8c3cckd=MA1^ zO@a473Y6}GSiCpd6^~Y=K83A-I%vJ(tWk% zK_xFA-&9Xra87>p3=7k!07B=OvzmbaF9UUyF;>G2S({sXIkL`^3H83>FoJ^jynvLQ z)fG9da)Q=`5u!l@1;i)fN-Qc8Pu|8RC?$S3X3!OBH>z;7O`yhii}%2wdPqnmp>^u| zi|daAJ-L3aRx(HlVNSs7gin7I0CaPc(QxTptz$LwYFS1as&Ri->-vu61%#>?v$C1RD;XaeSOBgBxp&3 zYvVB_^2kewKPH!La#_g8!3Z+;^G&yWxZOs8^y1BVB|r3hPOZjEX0zw%v&HSp?60hR zbEXa!NbC{(O_abj7Fd__J7731`GY;B|TS&Qs?nmxaa(Io$ehG2}yc9U|>g zU2mu>@aINhS@WL*#Uc&}r2?%-9@$xw@%LAg^^9a^Z}JMWfXF7ILXE$oNb1d^JrD>Q zE_lJf0as+x`VfZK*QFn8>65Fl=YL`^{bF+|Ol}BM3jn(hFQ%cSS9$@+N9U79nr8R` z@R3`8R|E_?*6XMnT{d2_B%NRV1zzd~PUu|5vWy6cEKi?FnFhEnD{i+9G!+M=EN~_e zZ)<-Q!`M-ikb|EW;pd4oFwo*nT6&DbMbO4#VLx?>Zec{O<|dOL{y!~1UbpbHZ&fmP zQZIn`_|irBpv1S)R~DS`XL~cc?|Ln|{ZSGhRvuz}Q4&c<_{`Cr4h3AEm0}`54*p{P zaPzf5S*=vL4>(i=!mu~lWSjdj0BDD#2k7`d=K=N!MwlX`r^~IqJNC*@rGRkBq>)u3 z4vIgYZy<^Smba&?2}}s>Sblb>U2-lh6VktH{cZIqUQS{+k$JPmuj{@RiMLIXVn57XV|4Vu$tW95ZPI84}172Ef2F40Fi&3QXev znMK3jSODeOHi(vpgX57vpcAmXLpzOl&cLD={u||=RlgtMxYyN_i*6mrS~F$xsa=ND zBMn#+6%nvt2o3yLCuAa3e%iR6C(UGh?EVQ#92rhEaWDdId$|G_5bbA>iUK87b3l*R zoP#aJSeO{<(mlsGWR{#=7r+F;7wZl9l|}fKnosTI5lGbvUp^@_9n!PeN;5>}^qg&< zcxa3PBn4ll{iW|dXF9=$|1yAt4k2HZ;dy&_q|K?R_s!cyApZ9r5*T#;K7-|zn+{vj z)Bekz|Ek#=p!8lEd5>-50Lbzmig>sf2gLDbr{4=EpEJaMw>#&8&~wec1hWgZ&d%Zk zpOS2Rte$b%*d1v6e)1w_{kM}x>NAdg9sB$@j2y~>B(F(nPp&`$oYxOi8lvy~=B8H8 z%jSMK`;C52h>+H~NR2<21r+nrNxi&r3A_vNR&~^s0H_^S1P)uynW_U_E>vQwVjCdp zJY8pS2Nvd}*(?9K1v?Mh;=QrjGlp_9`m^%KJaDi`M{{&>Izjy-$~u3kaxj04o~!El z_gniG%`y)$TsJ&=&d8bZ81=gDpBRa%1D4tVT(f8`&eLtx@Nl3<*qjy+$H@7fsq+r( z@@oe8$!WbhD_nKY(|qc?r4r7{sTlI-QHIcYFxa&GhP{qAkilg1Wz9$tRznsZ?K|DG z*F2^%gTK6yisOsSDeWn@x3B^*#S@3;@a3IJ-m@uVB)WeDwkDmR-J>e-ee=i1q$MSD?PCb6O&N0AHad>jTR1 zoF2RFBrFT=R}q9)sAPyf!y1~eXHsTxhl~7=!WRjd5X2db_)CC0d9L|hCl*}k9*Vav z65>f^7?-C3yvg6)sf3gxfN`bg5neaDU+lgZD>xu+yww|Mh;IKrGmzS>+;S{-mM4a? zL?|eHg{kqcD9TF5C%ZPX-mv z_7sZ^Y!C+lllDE0ET0!&)G#N@n_@K=66ZqPL+;*9GPE5phAeu*FNj4U zu_lJFZIgMl<$4(@#(9TW|IYKp%FHBA2!HzH#RMFU$8Ffi(SCW%0@C2w8M;=j1LcZ7 zp;Ruy<|Om-J=vys4YTLzbO|tmuly~~(PjC5S2!>JDpEV3n>`kk&icZv_nnaRGvz20 zoENPfM+R?yCRsYzi;~pAjMDXsML3v#uZeT736g9!87`2LMP=CF<7(v)`}ioLHwMyI zQF*Z$VxKtD80dPVFH4oks8t{R1_!O2I7wsqT{0zG3ERIm31zHm@+0GJtZE@kvRZSL zIxQHDv+RnU|JkS`xi~jg}W*0y6RE#q$XkvRnq9!*MsTAOP*xJ|j{HBgC`y zySh(zn%eL*h@HTlQm;hpiN(m~G{GZP>ddWayp%qa>g&J-c@`KPt$#`$!?$ktyj=Em z8*3=gC}Q6EC>!q+?@SC`$3bs_BsKhOaa-a{uS{m&HaZfilcT@F|M1 zP&jTrGr1`fiBWoy2`Qw3q2iyv6KeoV*ypr}VU!o*G6`?u*i*hR*-^*KjV{<2rx0Gh z9u--WM-8XTPGsUvdrnY=8afx74;X4>kbKG{gJu75e-oO;5&AEcX5a39AtAJW2Tr-1 zxH0A!5IR=20NU8IO$_)#LZ;s&MKa@+^iq^x2T-vHXTBBa+wuIjW#y&4IA_bs`5Ed| z$pL0oZjsnDO}cgB=KAyb2b-R`7L&<8ny{FDzgVG_VH9?>WP#8amCAoIRsHG%>7L3) zY|Q_LyEGMVuiYDaT~o98-zuL=OoCCUtL?z+WONl%qm^$cW3~5?@9X(jEK<|?>;yaT ztWh;Vb?PrREv5`9a^;y*NSC_L`!q$D7(H*5IZm;=ET#)KfbX86{-7IZtUvyHG=RY@ zP@i`FC+dafily?(i|Hgrr5f}Ap>5Cq$J19vRrP&ct0+n{bw(p}2A&D{8WEd*K9YRdku6QbUMQNP*Jw>ro+j{Ov$Yj%OJ@~- zlet7!%TwhPz1)16B4or|zHc_v3YG6H$-fKZD+5bF>e4vZId^_jtp=T7#@lBIp`kQ% zCC!z4&!!viMRpylcmjK_$e*u!Wqtaej|rk>>Zp%IhfjL$QO|7yIcEuleVaN@Xk|}{ zcSoWk{Y9E_j{vWL{=;*-R}&v}BAm|O9c|B*k_)jNqivYR=J52SE~L2$&*2iU{LX*5nCWrOj1{4fYPrEBea|aW zXtKq@yQ*Z@B@^Wf=nL2^V^xq6WzwM=Z<`N$&aB`W)AT!)?JfrCUYIjU*VN_g%8OLK z_nRpWE<5V~jDy&bND=2wo=ImAISH>JcgCDamswp7BQ^n(0zY)z?X%R-@1(y;11ge6 zt4X4im@N!pwM8AS4cT;&>Qb=u^|J$*>qj~auccr&_O#z)9PnEBnJc$QPKTZFn8<3;Q z#qAd$0=9*ps)Cq^MaiQxF&fVEZ2u#o)8$EDo$?LV(S2@hkv=`=D0lnSV14_|$l82@ zSM%d(yjKu?h1`)LYlA_PZRw=rbUmns610=ueXIyvlJL&1ZsL!i6q}RrPIZ#5^Y7jF zx^W&3*&kr9lsB(Oy7)IkUvEHNZ5Yeg@8l<2DG^!bI56<}}{tFo??adIs0=rNZrT0+_XugXxYs!L^6i4NjZvN{+}gK zsmAJ_SLjsCkQpp?+2$k>>z8p_g$LNPg?dolus+|gn2)!zbs1^ub*pY#UD^GB@POf- z(V3rTqjpfw;rJuQPpszLxnTXyScZ{ZsCgcdw?9W_u~qoOjA@eAqoM;nlYuC&4>f#BZT9Y<@~ke#}*R? z34{xA$AvE{u$Eq4T1Kf1_8&*Y_&8LZ4uZ04W!POy|RDeZ1vQKUt0k?U%A z5~AF~@M(z&(=Ty5*8gk$1#TnWJ^nqks-(|SRbA1id?Znw^X-Wr8Lh-_S2L@ zrdrB?_#1D`WSF{{FAAZh1c(MHf$L^lf2T_mX%ngkHBU>k)WWQbYNiIQNj=dO1y9~v znXx5Ws~uFR&)IaQ3TMellA~#Evh^1P>(EFNrEpM47rw9S_(DTq%v%wC!bKVKqh`^( zL+=ZZR~ti6r~b<@tbP(qJ%1Hc6&{VGKZpsIA^W6 zKduoiRRjUEZo^1^j>aEf&(;Q;*|=vQeK7PaX8$VHsfCb`Q6}H7oU&HGF5z#`)3b5h z&Y8dw=wb3<&E_i8;5eDK@nYVN?udZSxyT~dsOb#m*?x7?vuWlQkA|GMLRAmq3>$}W z{c_p=th|5*hY4o1i>6B1Z^tNbVo-RAp(LGSD0-0?cms|Rr8HL; zN6kCix15jOdYvW4yF46|63*WydEJf7;qSa(jmtTpQW_KsaC9eOFD# zw5HkZ;$GO(uOmipmExY38`#A;ycoWqM}``D>THpSaAkFRGEQbW$p2~V;&gEBX;n!Y zgxsA@Il;K9v8BoH6XxV^;cYE0363=Gd_$S5&nyRxv0-a7vVI-!XXw}4p5sU(zt73) z2+!H$QAyldNXEK$-bIa6inl#H`a6qrgtvOpa~5`mJho=p^{o;uSS(RfdvgqUO`Y8j zS8>LSRUh`d^U~2$mYbA3o1J2hPG_nQPaoY+^^va-Pj=f?(+JYUc^|SSUh&nOu^ufv zgy0;xcj_002-b}al;C@%S>f|_h#T_*XMfbmrEGL`nv1mrth~`_mrN^-qc670>6*~% zl;r-K1FF$PyQ~|12_gSb;z};I`B97R%eSYu#og=<@8I}S=#DbM z&i2-nbbYrKFO(YPNYZYj7lVtN+r{v-DYI{)v#y%{xMcBB{^=$g#^_Ia+f|DP7dN~- zwwBJEX-~LFa|5)wT_fTnQdY!=h-lefKOB=!86BN$#q+ll&aP*lvWFSvg_=}~-_iZEv)vb)8-Y^qS*C1FA*d5rJ1wRDoo>nhg?!eZ z`}%R<@be1PoMfN&bVueq_-R_~1={>&$k131dzZ`^)NUzfZX$rb!pBKJl}xkC(2ik* zyGwu+Pyk0aK5T1yZ+3-Jj#gxx}uC#3j&tfN{k)BZG9_&rq7 zd7iICo>*Rg)zwfo!y6*t>OD&HO4X8i9j)?{?2)>~qz~%)vqmHvZZcd*gbS zwwKC?HKc806Ed=Pe+il57+w^S3@s-(&)VTir9;{3BFEXoSx(*4J~r0&@OEm8xA9tF zU??Q_+?!G61~gNm_3`?F+Ytqqk&VlFivoUI4( zBZh`U>04gS`<5=R2q%4Bhr=$nz#Da$rdA2Dw48}U14I4PnF})ew&n9-j@R5M);lBU z4QbLEY_FBdUv2alF11<8<*Dla@Fp$k1Rof)SEHd}xJ6jdG1KL5)wiSvEF^%y1>SFghW7XVlTNWtku!C>OT!bI18*3Zd zTK|+e)L7X|oa_Hn0+!0ME;K%!tF6>WsNVIQ=3$upaVJ#U0Kd(&YIyH(c}A$~>9!iO zRVUeDC<_Fg%(#J8Qv~@6*~awxO+110$-|$}X9)^uUC8*WR(w#}PPf2o>s?gs#io|| zTP7Q!tPWF|l)JSp7tj5dKC)3C%dd_tzDL|nKH_s=AMkyO?`s=h6a=y%QB;)bDxMRoO#o5)wSD8F5Be&8oT?6W0LbzZAvc%7dI}T3A z!1)a#$_#JqNKRz(a5^cGyNX>u%vjmETBi&hX|MGqCWFX8f*-2KtPZ^H%0{p;$0)OZ zCgr?#;#%(-w~HCU`5*<}5e9Q4pLmvo!vn9c(l}884zpL=bUZ!(YuhtMmMd=CQYzixRTK1mttV_pDxj* z%%|t+@oHdr$HeCBej6^0khdimMn8qy86TKJ?5{|a+(vS2Bs*7=l$zp`8K{}N`xa`3 zioZ)byHg8B6aj+})Rc*CzI*<+CH>2OSuH8iTUgK3QjBHUmN_HI`H&EaR|BNv9T}Xv z%muua^>e!jz@J`*9>751#fG_jTNqE1jZk;8fft?_c{oX zPuG&uPrqOBJ#>=?Ecj9t*zTNs(D!TO;XX$fLq=qt9`W;XBq@D2tHkOzVXm8(6&RUA zcXk+#pyA<8KamfTBNMA{*@Y8AVxfUOK8$>6wUQcR+h_LHo6GVk_+0(-xA0clw+Zw) zCFQk=ZyM1>T69Y@cDR<@Zj*T&mWh`59OJkVP(Gs4T-D40hd8*iVuJ}Syg%=yzu8zQ z%twV6SS$r}onKE2G2gcBjj*Prgktktm4NUs~x)`q6cAutQCm5x`K%b0N= z(6K+c2VQFi44UfMRQz4OW|g65AOeEh2%IwCa(lI!JP~n*g03{imGmI_Qqvse(1~A;3Slof--{nW%j}P)*hcW zb(Ew>XH7a3=E5^~&qv&*8V4V1nlcAOv=x<~Fllt;x5&1@=)fK^24SGCFA^B2K6Y^P zgO5{M3Bls*iHove*0{lbLaM$3-Umj{ouN3mh%EZ*g|F(b~OpeOT_w1+-y{e z&Rw|V@#fxxwDY=|azrKU$)Sz5B|%5ByEx&c8=T)9&B_n!nzRp}xiCB|>0d#xST5tl z+1-{(t)qx6(PK@%DcoyXzg(5mXq&t1 z5j-fm!C(26Vrx$otg$35?+5&$gI$6>g5`Cc)p@AxEwwg(N^d^gXM(%YEGnJ|OyEd@ z`!u-ifM_c_~qc|TgKW~v`Si2Q;Rp;iI^m;om47onWln+Ib z&tUS-*>iWlLRBVQB0~=~xBK00?Mli@X2#(8Qc)Z11`qQ@CtM9g#zI;Q`6ac-%%Fmy2 zH=<44g2pD?<1KZszW4B_7%V+WC0xE+(Js5WLDup z=>C(Sp&VP{KYG^R4~nr4K7%v^BQfd@}@9 zq@g@4V~;Y6;HNd>!0;Pk!Fl!6uB8_h29}iDS9vdEImpZ50t;W&YG5-mLwOqz9nar} zh(T)Y)1y=aG0g_ohKlKPsc}IJ-nMs9fh*e5wt@pb9s6*f3^UTs?(lhXwCtb-sD`|b zThh<6P?iFUxZZdtm3c=x(hAoB#ZqyW5*jWrmPG!D$Jko>#tDhlqp$Q2jA_PFFF zB9Fh@u^WZ8>+>8BGB+^wojkP4d*emFjhw<%MK0RVzzPwW4)T{pf0a8CK_w$*M`H3j zDNGO#nk~aHG(>N`G8+3r>>ED!gn_{oP3Yz*ntY55 zEDm$Xt3vl|YtZ%>lTGjlTdf0!%LTQ_G}I_(MyCYo`h+y5j%Qh0J!r8HAl0FBw4Cuc zniklWcydDeA}FZ*;}Had4Vv{s;hPoSsv>o>kH7)b_g+r`H91(Z`cBTHOpOq9?)~~ zK=Ix=C9NbLx0R=HwTjJLDmHeJ#Vs>=!`L6oTh-GNoBF2X(n()W!IAm=!}Z%A>A3}& znFf(&>(vg%8T*1K_FEM{NPq$5h7q;1V`6@T4V%D6?$JIwK( z(d>(f>5_nt%f1y<`0-!GCI#fya&&ba0I0NSO*I#7H5U~G@qk6DtrSBnhw+KGyJ3W5aD?g?liLB(2Fzin(~;k3uco#YEzk@};cFvM!}MLZyU^iuxr=la zrLadhqPxr}CH4|BA+abc-Ap6JNY;Cl50snviv1Z#`wfiy__ALy?7r*|zFBz&{{#1a8Pir!Fkl!D{$ ze3vv&|Dv74v=D$GK2(vIOfjs=9dMU{N`uK8+ zM@^Fyb zKpdn7+uoVo-Cu8I9OC71%0oMs;>N&aN){4(Lf(SBM{i%L`-y{KWi7wNWjS?d8*7lF zc(0$&^UYpzp8D&F=Y}7>b0*+*!>>oAf6C&MVN2Y51rFTnov5gm_+;*1k3SE&uD2Xq zu2Bh>jVZ-~F&d+=(tS~!%9ohL5{qIx)0{cY^-?u3yN)5Fy9-nu=9Kv^pZ)3RD0~0W>+`KyL zheG368(dtk-!T5Ek(&7OF1+iFNS41oNQxT!wyrD<%zr6aj5w!Q(}cXJn8r_#s@!Yx zaCJ^8e;xVac*8IGeh=j#4B|kaL@>0i!pG@cL%qe9(-FLfTac+!JuPcnH7;STWp{qC?`sdME* z2?*N8#xP>42~Wg~L90;}`aWNkY7xhuxmS00VkF}R=x7WSZVAa`I)j(Hs}73?yjn+w z3YxCh$u>8WELNR{k(OHx7NxpIwp=_7z6SKJpr$rZtNfyF?xU>7w^*)V-25r$rwH+X z$o4*CPZSR5qWO*Ja6Y;;*)c!M#1FZr`iR$fG2JUIcbr83&5(lmn6LI*^JbP#?cp_yk8c~NW5#T9^ZQ@d>N0R`Z z0l;a3y7me^omao@uV#pqMVp}$s$^mQG``9!M=ZyHDry4Bf?#RoOc>7e!%4^46iAaH z<{PUr@T;5FjMI~Tf0`lk=&uyz81uQC9KURT_AWLzkfz?_4Sv{KXDQcp@FrtNwCswu zQ{@|R29S4@V{WozE?zRHSNNB@^4P;ko{l+;Npr(D7ioHnbUFe3;SadHI)lXw91Lf6 z8p`yjgh|s5ye*dK@SYi5D^{#zxot6z6EOwEKDB9UrZubhTVzWyQ^jfx3&rV=x$~d?hwyN5%G|Flrd14!-0db;&(+>bW8N>m5ThQtuZ^FXFqB3j z+`MU{xb7H0D6+h^vz*$rKbbwTO94JF-l^nd@L~wA>q|*dch$P~6JXnL=m@^Cl9ew( zbISz7BqDd+f?##rD?jvi`Rvq+{{g{rkazk*zffHlQoLur$$5ntlNj8n+gbbCW=^}-v?9~e>dd9@Y2KQo=4x=t!F`fquXEbtq}7Ulfd*shuC~V z-B6+*8a}smkX1zb>O!*3=9IFx@Ul_0ip#~es^>=gS3A|V#0+%LfXq(pr|9$v) zdBYB92@q4iZSjR_X?b+*&!VE#BZS#so&f;&dV6r{x-B`_^etdZn9e@N&|B9Sze%1E z#86&h$z+!sidvZT_P3KIU^a08CfX z1ORHuzGcjSxNQwd#K+$lKYmxt-&noZrF~v4L^`0zQQ( zCwoHO-e^+EoV~Q37TUv7Iig3-H=ej_KxfdhwXxbZSI_f+2wbI${;5l?2EnF>79ygn z+MLVfG9wK+^HswcM!H%=r~Y-DfMDqx>B3ZFu?W<$Rhrk6;He=E9P%Swh1sr?2Ba{X zzl{(QVg}RrdcI32J2qzICGG!$Bmyvs@!x&|Lje9UoBMWPKcRqEk*5MhzA~ihibM;zmIWSi)TZJCZTixy8q*)e0_jshYhbLq~`_Oum>mTqSES%ls<*jHECfzpajS$%c>Y<<4T?54b{%-mD+i_KC#IRCy6`?T)9%QUg zPx`6&oZxRKDLR~}kv48C&%I73=o#|K0mkGEy>@xRBoHigSQ9yiCjo0ENz1nm&>IbR zdju(&m#YCEt7AADV4)hG?txd9ULDLNGAH{jpm0KF zJ~~4U76aUPS?$gmK)`F&crZ}n)@nOi|epPe!gLTxIk!MNp<8~aBehvFgWv%>)d4R>oi7(dKp zk`b{v5AU%yG3%s1Cbfg2r0ugggkC1h7`R5EJGg*+nHYHXV9k(KGF7*-22IwsF+O=$ zBE#2}pFx6evX?V9AxepBWMt?=f3&m=XgdfizkI0inBf&yOolXJ`y-*X&8H5<72>S1@69sr5; zuKP3|hwYFn%OX2{$0R2!&1JyHsSA{+0xmOa;WY;@ON4~OGMT9Nv&CsZCxo|dX@ycu z;+&ViL)J65;K{>-o!ZL1;pe}8yk5+=vN2kxx}8r&th_2)zB-*bSA4iXeT`UkW&7J0 zJ51O^sJ2qa8|BD-;JlZnIN-ZvDPU)S6_hcwmS!m*Wq*XBM!Lj1&RKYcqtVV^2X?LX4+N04ztdkG@ZCN)m@@r%ZkGX48Y&&F ztDCPGL+k4{i7J-X;frG$!A~~ycH^sb{qg=`H7BNEkcIo!J-d9e*)_~_&xaW?2d!uz zYqRZUv9tRNWCJv8lH{=}JnvY@6BW?d%3sxWgcKBD2l(h>gPjTrjs(mu21Gz!IEG@x z6zJ*vZG`v~P=jxoV}2}kP61*AtLATPWVb%F$CiY$r)F%q~)P>#`moS->&`c62^p7&NHh z#-Mu?TN9n!GmtpPa+*G_Lkx>;zn#b?0(HSs?PA5neN6fzs1nEg*4!TxtvuZ*V}xLVjFnmp zga*9}8(sdH5ShlQ1pz=^Skv^@Tag)?LguIFcopaZb0`SxfVfENW725!m1FSKx4knv z5*yQS0t)i@)Jd3ybFud-9*hLVbgK);8}m)&9YQ5_F*U`^)s2GoABm>G_G0;Qm4cyW z%+|(G1)ZJm`@xD++ZC`II_@3ZnIKUCv@kI=z4Ui0|gug07dPK9A{1 zL84fFc$Hni03yUb?+$VK$e8blQGArD!uU>0+j)gUoW~==RdG4)Y~FH6l1%bg$Cwb> zc}3M4g2nLGp#jz35KC+z3rZtMdg7jIGwj@S1NP3w+CL84coew(T=aPe>y!NQtTv?X z@%!D>Nx+L&C4||r-{7@Tg1_l1%dQw~3An0p6BVuO?CMxrMkExk%nv7m{K_scLZ4k7 za_$^bSnhOX@Mx1Iexw^PJMqK-yRVF5kW)nF=EUCJ-2vrdsl-gWvIRk8{WszQ>Hi5C z-^elcj*|C|8i{t(H1z9LKLASKd1X7X?C6pIeuaMv8p!V0xI$1#fM~sOqWM(AJdror z{5Mi*-1aHi&A2w2SwNuiTm~zt_^iWk?|#2?%cbx`?+Ld|Q*U2eE;GG*?X`vH!-?1R zR{h09Zg%}Lw+@AoyXK2*5Gw*I+lfN*tORdJ93IrcG48Q5@$Js2nbIe=K=g_K1iAisAqL$kq_H@e z8tKy7##HrCgRMsxDXRiueJ&K` z=6Fzq590P6kV7BKwAu_;#hHuazkS~g9JvBWNV&3+BkJMn}|fJxM4OO(TS zr8x!H@u4V??TtVCN6Z3TX#_%=h4sD(xBR~GN`{c?>yY5sW;Kz?OgvaXeGMIIuT8ch z0#yu9?Zjke;&4T)pldt(vBpa~*CS0NZ!0UsS1lENRnT&k66Jkiq%#-(P{7(kvyz^N zo~VXd2?p~#@m>CTkn?Xw`2%mcRp$`@RtZHGPbcP>6}^HfdSzxuhm`xhvK!Xy8%(b$ zk$jE z?2kAr>2G5{$oFN&jl2G9z6PPwfWCaEQ1$;PnTOQm6rRRHeYohu*~&c}!oIEeJj|!9&bslRdR&m@xkGO#*G9*EOU26pL6(g5 zb}KeR{i_yRS}Huo@ob{av(EzuY&bN*Ysv|Mu~SeOV#%4}o$?*3br0 zE{GJCwci-`d(L<=_V&Wxj<$rkv%nz(H*3nYo2$i&6APbE&TVCwsi5#fk~UQBA8+B% zS9tnS3%u%rk2ow8xk+RuAT1VjlnQVhCXw%V_(8xh^}&FSO=pp+TLR_b_U?|lQM$CL zXS^)0YJLIzA1Uf@V*BJyzUs}&r=IHlQ9pq{LJUh?ND$S;DIz#E70l9qv3Dgb|RlYAAlSVl+GYb{%G1k>CSFSNG zX34GKe=~N#FdTX^5LV!lM5OlpdN$mly?1i9Av4yh3@Mn2dc|1=Smoa)QDi5gAoJdw z- zL>%tzB(?QC6^G^ea=DgSVFzj9G~xgKaHjV;d^jmw@^{L9Ys@!sex)J2oj*!@g1$lr zW(tTKLRF9KbvS4#TM}OOJ4EqyXcT(mP+~JtSSZWOnr_!EtbZd3{F6N^F(jf8$Nx63 z+h!74m+q>q^{3zdw!hW9We*5CoHyG+hnTiz1L7yAu9%}&7KiOqp>>s&ANHc3y6Tf^*Q<<#2?mSgHenLl{Xm8-u(($B^_Fk-m?8|^{gB5S4PeM^$EQpcKpot8vR3y z_4?zx@*ik@Zo%f4QyiwiVb|{tz*!}I=JYvo6v*-qtc=m>TSa+kySV@MPPz0s%X+}@ ze^ve)xmO+bY%r)?p}rro9$e`&NPBkX+<%7ezUs@WV3IQQT!5sNnK6yhV^u2lB!xvc zK99hc9M@FXRUSgfH`xB@Q}TA81h6+_u6tt zc=YolrKL&uCh1+y>jjJVXBks|PLipm4t zRpYW%`M%R0bW3K6#}|0~F>b2g+f3mK!1xCiKS3X6@oky{vpO9JE?S?bVE(U?r{HDs zFmU%J8u3T04r1H4=%g@sY_fOfaTugA2}J4e{TV#d(^W7xplJ&c#oz(|?reyU+5sZ? z)7)hu`3yqQZu$A|JW=l-GD_nwj!Tl=AxTMZww4Sz(ie}po>ht4|Ln!@Ej z-Gi^5kZ~3(tvl$dNAIyle;E1dJGd*yhAL1tZt$}hRp8V@|NFPm#c^w&eBPG_?_JpM z`mm_I94>70C9nj80!GkVPAzM7$ec04fB!sY)np2y6%orjrfZ!$@yG0|)uuxJv$*`$ zns3N~Pt0o2urOjUr4RGKf-|1gT$Yx&61->FYR&DGpY!5xyA$1|p_;zi9#pD*QIY2J z%0Mv2#Fj-_s0(-X`DG997lebKBaxCptb#N+$%z8C1hd}UYckIaNm}jjb!u48j8hYv zKU`J&ni$gFuU{gZ=6Ju&p1XOLH+`8<`()_5ZazdU zghM#=x7WB+@N<{ASGic-$IXTV zWGi@~74`t;2)kjCdmXQlNcD)EyjDtOX8#hR=S7qQwb>;_cP_M=WJ|`AqtSLVpUh)R zmn*|AG;AW`?dN?|ESIo98Jm-Bl~t*Hdu&m(h(#>8GB|ks^Sx4^XbAAWr{ChXBlR=kZaTt^~1qwup8+;E*cm@;1^s#m#r zab}D0uHpzi6ASML7G99Vv?l-DtA_8s3#qO1qSr`8_5pn%0uECKbnNc05 zqS;D9*}GrBhIYPK{-%VEgS)=O-Kr>Dl$ee+7*0uvl7<~nBNHMi%`#fpr{@(fHsZI< zPF22Tn%tupx6e5BESG0cu@~3czp6sb?UhI*7(#AAlG$t`$(9^e5@M8xeD09k%88iM zSvk})=HtKm)-Xl1o3}Vt(qYnj>=0S^KmO{G2p2(X4MRd~K&vpNEBY5MrB@PeQe8T3 z2x5MAx*CYrCfNDEZZ@fJN08wX_K1#*ypX=ejEFl|tXEtYav_ z0xS_9OSGLP&@Y^=MVwL$_7Mv>c#g_wUNe2VeR4BF@N!nghtxW8U&0os6k_E1yj^}y z1{{ddi8adJNUX`FDv|iVodAHNYO8YT(ofv(oWtt-zZG*7%&iuSO z4c9^UuJ&mM=nW{GqwR+6RHr~O( zB;_B@j8nuyB#08okZI2X)8cLEem+w||7w{4pZ&Uk^J)oR#R6kmVfMTu9UW0x!mxPS zrgtWW8%6nqS0p>6>mn?&M6+&?UCW*L;$(W8(pV;a9n>2bUgm%fH}uq4c8rD3FNZNT ziHgECMO9$G6%7H4Hs@&?6$M_L@PUEVJq0UHWxQ5Q=^WMO0&LI4t{B}^d9Q3|*FcSG z`gC#*+_8BB7V#y1xqo+MwLHgOKfJV5U&mu_*zLB`?vYY<%}XWdt_*^fa{e%jO%eR7 z+*sL;V+VeS^$t7~>VXrB4MZh{s5Hu78HpWA2NXB_$1mRG#e|>~^c6zA8{R2M@H-GF zBIXPDnu5F!@;ean@I%0sinqV+K+Lj=h;sq&%cd9YmpmH(={?iMQuDFa?1jZ9tz#|; z9))ABGgr%?=t!!n=$n&Ka~p)dOi!pb?ne&V?+ag#Fvi1+4;~<9vxkjg=bH1{tR3=K z%2GDZBy%_lsHzHCV^W5*f5XBRAk0KU$Nz># z;hw@y{H=>Hg)0Q7E*(wh2Li*&LHv*`!X!SZ9Ao3$qo5Quk64MB%~5i0$m7LN3>W+T zty`MyGU5GLYn_E*DPN=7B}}5Fm&T=sh#{+6LQ-i&%|3sk0aMq=>gIU*Gfef>aQx89 z<79^HH-Y;35gX?J(!Q`r{)hFkfOL(;!VskV3>#|xg6#Ql^o&y9-7ls&p1Y>ew!)`l^oZG8O>dYiOSgwXmuP3|9KFQnh>oJPbGSjU{I5Ee3EZ@*V_%XII zS9HXW%f4HIOALQ!v7xeibn0PeRd8Wu?s&hdt$6Vqw?hj~o=hC$`}*B{kjQ>M|Ht=C z#&_2-GR(Je$r-5nCB12x0SgXah0X#dV&}!*^`aEuQT<*#f{x2B+@f?7Do8*BLH}Ev zs~raHUPDNO)tu-0z`;>60qN1kF|~HyeYTu?YBop>n9rnr3jOm1S>oNb=`qzgFqm@b z3a$SS+c}#164oHyy89BY!0uqn)3lrL%N9~WXwhR-8n6}0NLLFCc{g#_1Scw9ak^?k z7aQRfErydNjt!9NN}hi2WiC40A<}$9Jet@hpbR{le_q+SET>1v%;9{V3E^4OT^9df zUOP74`;Gmb7$ykK>5so^zPs+!Gcuay2d`NyWgF(wOn34y^^X2()6uTaMUJ{XHLQmI zoeRG_omAs_=9;pdDicwS1+yuqb{5b(T1b;55;@vhL2Tt4v=A+)Lwp&%|FB^_{JjIS zc>BCeK`+R)Ktx5eKPP1P9&Mt-^7or?JOwQEyXUb;1$dCltYO1XaubA4VK>tTpzQO1 zg5l;4BczQmQSnL(*_GwJFlYCznsBpOz5a9{e>o6SiucVAfAAhR@^YinkxuI(eX_i} zXn;Jjz{PN;*{SBUGJbbWa2N>dz+JR)<;0wFbPoeX>RjGN)WnvFb1jbFI-LqrJ3}9_aS1tSQu+z_xlk zH@;6@x=U490!#8n?w-Yg6SxKk!VCEP3{L?EM{y*uEJxLzyY>^vg`qRDaxYAYFRP%k zF>=A4>ty=nrqJdc`F_`2n6_^MaGgnXI(%T`rD#8GJdv?uH0ql>KNGFWJnm>6$aBRH zk{13%tfdjVf%&U&6X<;$TRp!x-PRiId!Ef2M4*Mv%1Ld8DCld{Ir3(qW;HdTfQQNa z5R#Y~(17<Dl;$yveg-OImA( zA^O#kO!QQSSXe(giYsGQz@fB~a2Q*l@?4%`pDksu_?oh65r*_PW+rCRAMz|EXm{nP zIV;YM;0ArT*uQJAz?LsS}?DMZch3m9ij8t@b% z8oJXYU%(Ly3$`ifz9Ba4(nHc^>VSK#i4$*Zb&VA|&6v1acN^~SkWOD2tZi)kKsf&W zZDtZR=jT+A(h1qUnnYDFo*jaYb4x2mrnfliAnv(6Rs|HI-b_Cj+F@s7XT?6$2N=B0V>lSxE*isLUh zv`W}9Xeb`h1%r&@!SyU)_Cyg1KjJ80)kS|`F_LY-y2~d~9~(lY3l&ug{u1Uso?Mvc zJ+jqqQXS9RQ9nlnNi?OUrUl-|TCISs!`)kY_T+CsBxn7nOl3~!#VOhkSh~K|1%9~;PgA&f5g0I6fr*Df zC8p~urY~sh&IAq8>fqT({S4X+d)_2~3ePah79;(@*`!M-H*+{L`8?gv({#RMdJV*X z)@!)fd)Q6Of0tFJ)Q}G74R%H3CYNw&v2`2**l5sfey4#0Bz58cRe$Z;ve zZ%eDFU*4ot^ew~IH=YCjPna&5Fo$9+h?lB`CoF~2cVL?fJ`1*>Wx zUcw`#NIUA=E`<@M5klIMUbZQ%BMvFWR7}}3>fc~!gE!>z%by;O-}cMRKW?4tWI0nM z84-vtnV-NO9GXelMIBW|n!J!#QYi5}mH)@`cv9{k9l<<(L~x(E<6qWMib?F?yoz6c zBV=xMfKRtoUs~VyNHERTMLSbZ zHIi$rP zB28}My{gym4m&;J3beJ{UFP-*HSeAefPhs%2mX$bLYR8(BOY;s~?*g`1Rv|(GgAI=(p-!ejPWLyjL79sg=5!obK+x#CSSWhX!HK z=MAj5g|Mib3pRbYPZhS26O9h{2Hi9(--^%eNXHf{*E;3E&_~`+ICzAtyA8kztii#~ zB4}f|X`G$_=}#hj+;hH%b@~6@4erm&)ns$`t=EQ2OP+V3nFWl(y3vnsKin4(K06b_ zTe@|l-xHQ1JJ^v>x7ER)dYs6uIa>xR=Z2nS21 zUmH#|>9Dg_u<4gaFMD_9ND7%q;Z9PS&S*z$u;mRU)1!4EXRh}SO2WJmE?%i?pQJSE1pwsiUtTXa`z&=s!pTW1$GVAphI~TEcN)j+G^s&3YjaH}IFP0sviq z+mCxt+_Qf0J-ZfySRGlUT-6*tu^~6t<@mR?^Z94@KsA`7E#aS>#9_xA@$s4`DCLcM zWYM1QBw97vI0hM0_$<7+lm82QhT`+%YP*^oXv^K$>fdj)M>UjIb};ZU%;`JzMO+L= z5Af~?YwX}MRyo=XIX;@G0Cja!PJ3D%ccjxIQ|ro)b4O_R8|u9)N%weIQBmPT#@fxC z^ior}qoT{-~hM`T;XL<PQ*)0@hJZcWsFVT#0NDo;^#yE&FACs(16X zVk2i4^}BPbvB~CE=B#MJmf+=x(Giu6MYVyWz7p?;9#&SBm5qe~0Rhe4005xh1i9y> zb3ZioNU6Q{b#h7r$+4lr%M-sS>=u(G#`?`(+tz`g6YAbme@9)am@9ciDQ|UJ2fw@f zvA(5C(w+h1Uij17BY&RgUQ8%To2@|4=wNHHjQM`>S$sWf`=%&QJdrM`VL^+ZfN0Wi zwAbd>wo$k{7i?LRCwKd~Ijg+DL2vI`cU;SoCo6c<;{wfoj{y-k?|b$5N0LSJyQ&Gh zDTz(NM8qRW3Tdb+we^+}`@LB*>e1@{(_al?MOpK(Xz4eBKW()-O?D5D$Edu8%!@Fb z$A_j^EYbDRo&1+ocOXfzZSx_1=?SEfk%ux5*Rh4#8$(&~jTOQ-?DB6G2#fDvQ8u|K zwd9|v%(-LE9!Rl40vA7N=ZD>tL&d-qbB^^30I>5t)9ZHD?Pxbk7k!O8J)eVmFRm#3 zjh2Iu?k(HpPugZY9QlhZOvCS4WA&!k8c_wp@Wbw`VlJh3Qw7GxA}>Jk4t>+OB7RmL zO?iAW9Yj+9d5)AL{3=oWRMKW~HPuDxa>h%V8V zk8O@hFXoF$=gZn3&|IfRwzOBu{Ys{4g`vMn8Q>`q6-^Aku`{_I6=b9!sG*DrPY5fO z@8+*wTMwMR7~Ts8T$P7=y=XLsHSsgDq)S3K#bfWz{4=lEZuUv4%ApH>3;+Dg$^Q0> zN!&L;_>Zfnpb-lt;~=4RX{omIC#R&?$Cd0_5gU^#_1}yge$rrcd^&r5JxF%4#H3;- zg}H|9#c_wgSq|M&;6*RTapt9g4#B;M%XI;Bo~BMS5!**gv&LIYiI;i+8J9^vv)&Hm z457V)XVjr2(5qiDupE>A4*-;dHWu;;j;>p`gG~qS7un3X5`VbFy~q`Bb=qo;*j4ls z5*7~q!y@MFnrqAvDb~(SZN?RIk-&CqnEB*p4xid|sm32Ge1OZyIl)uOpdNa4FSwUz9c1&=f~{I{TL8?e&zw**L&pGXrNB1hSfE@OI-sn2}|mFh2Own%{tDTxu< z9Fd!_@h!L>c1!Wam_=$H7T17vHG+i93uCVlA4CcfO*BuM(4bCH#}fkT*QP-m`35s4 z+@#r8bW3DN>S^X#)O@Mcz>yh~_tZhNg_+S?@Q16}#$=IfQj;9$h9v!BEaDybKIsL9r!rjF4xkX=_NdJHo`)DaNGZO^wA17lKYELG^UA1k!MLDGRAel-%z%*_?qB~|UXJ0|f&`*fd20XBl_!4~2C7iQB ztP=Thf2KnZX5SzAPZweLLn&28ubl+KSeTR2LYR|ob|t68RJp=xzRHx?%9=?} zx8>Q34)LQ&+M1@4L_ zKCTimRwc{p$xKCZQfoVz*{InBKfMXY9_&c&PcT@y-AcZ)l+tBxK;Uh)s z;sePZ7H!lIrK#QGCmmclu3RNz4e%OmR(3bWb|a5R;h>dd7ZU`KD?`dfo_M+U9Wx9p ztf1IQ`rI^yNkJ9HPX((x4LA)PO3@Jm-JJl7&$EYiAxD}ow|-VyUVX$0OqZu9fx?+; z>fke!ouc3Jx^_dl=i>=5REfh(j_(qDYT9Q1RAl?lX-F6rhE z)7ZbBrn`aM+_;dx@)X-OJ0iz;w&Lhj^zkZBoq@%i9qyV52?2!jK!3+W4C=-i)i5-{0r|K7 zmKpbbHF>8ZA8N@CPQ2B{hQGxPyS<)kz2Eq(4*Sso!>kMhnhskrDued@ltaBP3c_p0&7yQ>39`MLjIlJl~J(2n;Rtv~9~Lsom!K z7s})I`M{L)yi}_p6V8*ybtCJ7B`QJ!w5aJ3TJt-n#4Zggjz@&T0X}qO`K~;U+8{?qs5^3E7!h7FB&@0zuXJ(&eZkzk?m`Sj zeonid8b`sG;|N02RG-0_^P34Und%gr+5Smf~Dz~X1N#NVZuy*#>?tsyZR17CdZD0 z#%cPS42@%&L6+e;H~}M{$C1p|-1!}-xqo;sp84wD{LEC@9FEaR^}N(3`#8s18pyFn z{#+EaE{wKEn^W%R)%f5qXpEGBE_+d=uA9RF9|%l#C<_Nww4|i5%8FrsW8uv3u;;)% zd%j7xK?wReMUPdF3_nE5d9pLuG9v^W`Jze%*Rs_S^HB$7{tp=d$P4SssxT(S##&jR zKmuWkOG`8-^X1}C2?x^)%+*NCNeUC32Qt-jX5AN};5_OoD-w?|MZ4OBk)))keWSre z86RZVIaVP1$5i95lY0~IR!OrrP1!!=X#k&81yy}~WPU!>5eg>llEUKkmf7R>K0^A!DVvsXAQNs>)}=>LiP{(CD@N7VIlR(zh(=1D?xk#-<^=3?6*uiPo#o+ zyDl*%fqf7G1r`7UUc?@~;?O}VXZrX)6{F(o=6u~DOf29CweKrOlrcfQmREUT8Z(29 zmF3qqfUg;wO}+kBdVP&K`|q$eIB^7q-}sEU!VDT#zK%YQ1OTG`fmX1#s#v9Pq}=?> zmMRI*=_?qCKUqPz&G`)Y)AY3IWlT;KfCfR!&?WWJiNT~lbEIDC6JkPO?2`hQlZfQT z0VLP2{Ke+_D`dD{Jd2Yb&0iU5OVJ+|Qbiy`baPIO}+dzT0yDi=E5ie;0k5 z4O)>jMA5IVdC!UNdUsfqS4oD z-#=Af5wxG8mDEeEln6tV~DcIv=7W*6nNtOF|Wz54Oeb%HUTE$5%fQ z7VB<9o`4;Vr;^n~K5QmzPm=SPc)M?U@yrgbN;)^0bnacFIjU2L6MVFhv2 z8bCQVv;!-<5Zn!GR-sPy=So~kF*`HCZ5$5mlovle3SHd@51IbHfEqpX_LZjw&__YN zf9}72Z`-`Hp5QKM)=V_?tUYv$FdQ!FeN;nHPSfKOY!r3t0zX>x&}%m5@JPn~&6Ixz zwwb16Lkcc8=SuioAxP6m(uQcVG<1eajdkGtjq&;sjitxxT`g6f5gYCDF9M;&m$nVRUHs5p24ZkM6cR4aLO zNC6!hC9ALnrqr}DW2gkF&=c&OsoUu8ANc9^C182pG+;Xma>l)ShfmNoPXL*rb@_ZT zuZ(cVdeKT4&X|OYSh3VMGKY5m{f;& zihg~0Bk`*UR)CHT!D^{nC4W~rL-iqm4qVA<=_dA<43%&_3q{Wgl%Ev15B8kf7cY&(97QLCmqgJ*MRwwwb=DFA zfa1Qol7ilzRCpeEW?3M7D{R6mXe#SmQ6nIW6V5(#G@uxg{eA3l})Y2kHWNJ;eyH0A98%KizK-mnC*?z{?0$`8fTT zqvVckXb4mUjd=e9D}iVzoYPfi;xQp$>$OA<7|x*u+otRA5^wvY#&th=>cqPPo&4(i zKeomr!TMneKU1Hxt#Q?5*QJ%id%c1Nfbx|Z zn7@r|P$?Bab{&N5L`ZffQl8rW&J&9RU9(1Mx{o*M(@CyqCGy(YzO4jHoqnPR$h82= zSJwEOzdhs*5fO%@fY2j-(kjE$c#09BNZx1+?KUg$9`bAL%94;O*ir&2=aRcK@*Pdg z-PxAS-7O9lYThV9;iPEDxhSwh1M(OyxX8I?fZnFo4<;leheXa;^YdXl9w#kX?Wga! zRtrebC!oQ<0-!=bYr*65OM@aiWo&jP!SkYZ=;X!z`*r70mBdR*hA%hAJQKq@H~T&! zc|=L`F8n){e4W0Sj)oGFaU$B7Arlj@&kAUQ4hN8eSODlH&q?WMce-dPPi)2NP4%Lz zTkd%J^ai7JlCM|JZTa=Tx(_rzfUfeJU{-?4r{)WEvV-5dxzIN*|>nkbJoEk^o{9{+iTTpwloFcCo zYvu$0g#^uaiQx-)gX1Lcadz?jcUGP%)r|{f7X2N%L#c=qNQfRK2rrd9r~wf4UX26( zI6+t^g*n|gJvt1k1xfLb)ZP8hH0Tq3vB%Pj&Pm^$lNLobL{8`~2t|05AF6`mw=e)(R!tH!5U zGw=}?&_t@sOhy-hwYy3&O2X(W{LA=_{|F$da4D zHg(3%%tj#R9Jr&|aj6d_6Hn2p#%w1N;`gr!0pMFe_^>kV@MG^()XwEmao1ARPRO|F zhDaiO*1&ADShFlEH+$Coid_G9GQw8LS~}v2rpW4F2-e;&CqQP9=MfK}KP0i_`gKFi zuf}miem+H~E-w{2u}$Aac5cZ!$Pe;}T7yHfmwx$tkI9}H_SmaoH*{)dOI!!PNS1!9 zN5JEThs`8-Z8e5?Kpgn$>dc+_rPGvd1T@@H?PmgLP;10cN)ejo;bR8W@)x zdb-!>U48UrmFSV|DvK*g{@k9r_q)o6K%lX3u5;=*8`uKd&RcJuSyqDha@#JpQA(Pr z%jG1+>UWjC`|}my`3?thGb5uysKV7fGY3?RRGym3mA(cE9h_^_BG8KWC zzi}8J-*jgGdH%+eok)x_4aVO}M4yMh;nvBl`)ZA(8GX0Co+b*cib8}SFNU5Qoz8ro zyLy~*859KkF5@!&ImS@y7GT$6bCNU{3LT`TF_tG6zYTFy|-Nm3Qz<0n6Iab!oZDkz0_Y57}H#kO@M{!b3w)8q}27@c^(-Nx1`Q5jQ> zS&}K0&WL_ohN|r$A~MFiw_34UwvV4aIc?p|O#Ugt942%bqOHabd2z1Bj=0zFPwkK< znap?hos1W@g_^(1@X{O|{;&_ukhQa;kk8YxJpfk#7WO>&BV34M`wSQbT;TN zy|z03gXG?Q$WZ$@|G6yX6`H=sunm#TxBTj{-p4L;1VvFrE(DE&hhA@dFU_RaxZJw; z`1a9}s6fXs*nnzc>ogeSV`)UlX|IiS;7{oZZaP~2@a(%^n83{nuuvx_j1#egGMit; z7;_?ppJwJ((5A&$$qnOc=M*9t0%du=3?h<*{J803qXVq9PAMT~LapCO1Hn8Wd5T&@ z&L)7J9r{9PZgN^?(%Uf6f71I;>5$qpHK#KCj{UCgf|Gmz zWlx(0clcl+f0OGn?eX-9ZcH`?<0olGO&8{LGpdsKy(S{|9`QQ?UR5 literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..f834a64867e6c0a62b37609f4c5eceb01361a9a8 GIT binary patch literal 76194 zcmYg&bzD^4_w^kbWN0L2Xk$P`dWMn?5fmgOq(y0lZWuvAWWWHF5D7t~k?s_f5RjB^ zkd$tC?|{$u{qfuJ5nANV|FHJe;WhbIt8Rgc_TGrD7?)dbJRl`>P-I zE#DdOi-h!6>J$75kA@S+q)qX8@dy|h1^HWs6B=dRyU&iU7avy zC;Gd;-)PWf^`*I#QL9$Jo8_{EP1*su|D1St>L(6u;X1F zy5+=ZkQPB_x7W2^b2iV;_vP8(NphT>TlM2wF>hXdQ)!y<_9RYyOt4$4Fq5aj zU-0$@^iVJi{PDf+EyWlYFXty+mgjM*Z|;m zKW%xEcbngu_L^#EVempgS^l8XX@&1WldOr{!(Y937AvPuy$*)7Zbq)L{++t9fnWXTzn0e0hIYHURCv#4ng42GmCv zh739nj?HxRNrq1xp33CC_U_FQpNV^#w6+!F%Ex-Cs_y>%F6dv?-ACn~q=s=F$+v=V zpAwe&C1Z*R7z!WV{KlbUdxR}5`du0YjXzv28=a88$LbLvom3T(&*Z~4O?JJGWO=3R z(A$2NGM{qBIG3kMNyqXEjSr-?K-#8BeHwa3o?Iw3_pRd~-onH9 zlmb7Jx-Um$uH%oEU+tUSMepw?QkS6>tK3ZwYMj=`4LUy_QPaik^6?hA)vJPUP*5P~ z3x=heLnznBnrdtx7J4mEMEH*T@xhl?VZB`rIosRbbvj)WnGW|M80ofZ6BphE$A~0N zYxN(}rygp(aw1U=%RZCK@3gQRXep!!NS3HEm8N^b)z6>(R*hg+4%;c=q0zBgdH+ea z|6VH3n2rN4o7h1A^0BT|z|1X%BoDTQW9$Zhn+s>wh*n6tciKdd0o1lCe_i?f8EJQO zw5{n92$*E;)R?aIZz0DGkHe27z*XD^_fzXdb9ZS*U$(=2rjRA9x9mh~+bGsMu}b#* zZ+8qR=yC^_TcX=EdSo5dz6{u$DxG)_eRx;bJ7}9W9`P%dGWQ31eA^XXnMa=EJp=CA z{+jJXi-*aPs4?m&=EP)DXheXSbp}qsiTlYab1Z+|&R}p`ntqiplW|+4$EI`MQH{wK zx`lMF+Y72SVRP%UZEr2;92>fCd8$;Gh5VU#doG0eR^ka+1`TN!B=w{`Dsa|Fv!w!d zzC!I>EShWKbge`noz`%q>FB2S&M|grry#LTV0fv_7ig-W(X}tstq=_0T3o^|$)wTP zXpgi#{tM=1Wj}wA-G-Sh87}6jb>7~SJZP@aCAJD*Dt%3YS5RUkF?;{bmB;R1?Q7yV zf9NG95CiWsUi4#k`1r(7sicg`Ni7*UTpXDy^X=JatrowqHc1DSIZEv(-lXBy^3{G` zuio9Y*E2F~rM>AQ&VZ!*jD#x za05N(=JIFK^J_8kp%kK{pL5lS82k?)r^inNurJ^7S-9D=d__!mrvw2QPtM4f?*fnZ zWCnp&2fI*OMcCH|WGj9zT4L-a5OkfgCPd(Oy9Z&0&@G*h$XgHS$`(*iT&W}z<0F;^oy z={aYyD{sG)Mq*nV5o%piMKMv{-d#eU?@xg_?_kjIHRgw@iwo`ETCUf4+9ift6?;W& zI{a_!L_2)y<|=hOPg5y9%H2LC z&f=wpu&x`GTlf?%1h8qP!w+^x-ly`|j5zN9#>SLJv3z>6$_+3NG_6%1f2cKvxve#R zyDO4QSN}KX`RbLSOqA;)y7S`=`|D>Tb!Q(99mKyBf7tKIayi%xU0au(xU0FziuoQ> zaDJ8q#R3||#;92-kFr*jYje538c0aR<9u@`>*_%W6(II6OB&3~OZ z>{$Bj3H#uk)!(C|IS1X+5jV_6(z67O{r@bZ(588FrW(m`IRXKXPyPjqalM~?13sGn zko#WDapzift*xl4crjI7@HHHu#Jk$-I20ENq#HHCpLl9c__A!K9RZlV%X^{@@Ghg4 z!H61FKu9ENx~z6$Z#ivutZHzmg?g61!`<#_k%mO(XtxMUk&w{)4{;4b_ob`WO*QJW zgySnpzdn3XQozqPbcDWf0S_g=bju+tbpluW8i}NnW-+5()ZrS}DoDttItr z`AdyD{b%QgHjy_Hk2!OSCYF{<|mMAGSvddD=lJ|u-?WohWJVDOTU*Nv`r@6Sjd z^w#5JZTg?}Y;U`=ufM((9U7wQY+U~)Txo)IwjXW^%*+J;YrU%ixJ?egy#BK__l;;#D@gava+ z)%+RQ9WPr5U3lj${;)37v389J&UQVjDvGVk$bkfPj=;vSlKk5M$r8R-8PBtpXX)v! z&q5-c-?9-#;fZ#g1AHBjEA#4 zhvh!3asMh{IWv`Ubfm`f{=qK0_Pk?X*=O`=i`5rLb*4`$s8dw;d+-&6pL(4#vw-CN z{nmQjCoG0>%HS)`)^x4NQ&rRA{Iwl{xe8dPfmT?iUpx==kOoH}dP!_4a@t0jc*t?wx2zt{EO3y~G>D z$ZKG&ZXM!+#62zSn&F6v*I|vo+*a4^g^`29J2)!!Z3dC#$-3~Ff-7c1fwOL{g4KOt zZk>JO=Y1m2lG!;hV?5{MK98w$ofwcBezD5*U-veQQ!~vr402r`XO3i(AOh9`4sV(u zIB0n41=FBi`mr5Yp7WfcRTJNsrCk`7D*q+N*)GT`={@wfnzMcA_h-L!b8C0j_zc-z zVc+Ua{i=8Tbe~`h9L)=6>bL4O8&R)npnwX~9tY1>ImfC_f!^m@$PQb8c;?;oYmYUX zQ{;)qq!W}#vu&53RS$xx^S7o9^eIvdY>RDizq?RP<8yV0uGc-xt_EvdkmJjhCWvLjd6 z?MiQVi=yk+)cml~L>KG|nC@ns@cPd`^gGg%8ga!0Fz!ffP5AS0Y=&nGS^V)hRMv>6 z1Xm??OAK&j&R)j~z{=lK?w@OCn+`5AflQvAX`TmLet$Q?+?W2~!=Y-BTwxekNcUWSss^{*HStTa4pvIhYYsN?$DAE*)io^* zAFAkD3v2n^cQc~=1U#ukPwSt@S{!27s~g2HDK=Pglk)n9$@O zmj zGC)c*$+5VqY)|(A<#I@O`SQGgl$4ZvkgSi6-~AxwJ{t)|m9IZ_>2RCR>FlOmp(#l2 zk(tR37>_79T-3Enkx3)PyX1K18k`Gkm`2;P)dD>7HJcdJiw;wKz?sqPpk zbC_^nuu`k^FV0Zl`ufy1JSUpbfoio$*#2UF+{G!7=C4T}>pN6Zl)g<#ZKZ&RWLN{3 zM|{XP@`^W_I}=`cxJ%(jf~A)n6%sv2*8AZt!SKd zY0+$*YVn6@VRl2q4Kn5^=vn%~U9TiX(e;LSj!Za~ei7=AAqu5n*(Mjp{9pzjlbnr& zw?5+xl{D0%%bi^Ip~k}got${m_jm0K$+lRwWA75*Sw@Gvv7M9ZlWTt7tY$#PyHhF< zdhmhB+s7opU-Nm%SDw_4JU&5}aVjMh_~hX)h{;YrQCl+YHYSwPE7tp(tmq6(L%V** z;%VBD8@<5cnw78HqY4hPz$%J?V%`<+j={ypnTx2-vCK?kY9FnSjXiRgEA_{DXLK4g z#dqO1P(-u+j2j9$_?Cxuk z4Om4<*7dc|k<)`9kYaQI0Ds?I>f)k}clqce;KFJmBq-9lUVY4>_q48m&^FO^!f$m1 z<-hWN!6m0}aSY7<$~x(-j^5gjbyh2KZ}uDmxNyOjx-sZ9r?ewJ^aQ5GJ7VKwp}I4Q zwL%I0x?#3_2gz4S5C7PF*@g#2<4#@IZQBIbMQK>A1!O@|F&(svbQc-c?EyK4>z*N=t^{o@gr$C)6L==AHq-ROWBSZa$uJQef zg$>ya&&NO~#_+BfSuBbp#bAEsJlil3P~ z{$BNpUd>dH?3h+*2Cjfmt4HQFV(lExIQ&15(-YblYPA?;V`fT5cj7@bbp4qPwY>4x z+DhI!q#t&AX*0<{ecs{x?|NnzE1fOsu-r0Fmi#6grPaXRsL z$YvAUN%^V^ffRuY4WUs@kKG!Pp%yL?!mi18*>lTmVYxq)SGbpDh*;8q{D$uhaY*ZdRXIh|Nd!lt|;9tJM|5dovg7x)&XUlBDU&NqtH~PuPg0) z%s8l%S3Ktcm0l?b5{KYmYyF|z;p7J#B=wQ4Go5-F!QU!2k(E7Yf*T$VZZ6hb$_IZX zS7x4~r7E63Pv(r90Dw;sM<^2dchR4Ga^j2wFBD8r=H?&_T**q;S=Q&R zyu93*7jN6U-B>E~nuJwBQM$h4eBGdXPn$-bir~wgRoyCxprg)dSV;BO%kl7Y8(a@5hnT&oOpf)-wATg~C?t z)c&-5%6Y!ih)MG^wnu=R(P7XYVT{u23y`I_Tw=FQ2K^Tc*t#ShWZ=+y!8HYgDizdXE^*^v5(^e%3%ge&kq@(i?V^xV-ST~<7C^GYJZk2C-uKB%kf zYb(FeI6!x%b9R!ISGyr!^iP)vk5{rH$bk4%j!*Ay2!(&+R8^WGet9o6{E7Qlz4#BI z8P?sxP_}&Efz>%IuhZ7G*$+lIO|R}3F0Z6XA-Xi8!FRlgf7~>(PIOoc=Vgv)lOmj4 zmU4r`zA`#^K6-PLBz3jjhYE{NL3b4dET>+rIizx|tw@d%FB=+r7T-6lT89u{pdMfoVt@56=mT2(Hbn~BMTg_Q&+(%t$ z(HDSAE@xS*q-Y6KtqZ~~?d4CJY6cMK)HM9tqqnVPZCG8HR;8vs=_NG>5UKp?Uz2uL zba@fNC2j>g{e(}EFOq*^cd^5SI@C@7{o&`&&r$)ZmkR9db8ps(qgcIJ)4n?^%PT_a z1#g1fXHY?@i8^PrqQBiTQWD(U=lha5e+YeP4C~KJPF|weqiRykxK^n3dXwRwAr}ob z*z{_9P~~jo2QfdgvrWp=3JEJ3L|Mx5?~iBwKz>$4kYW&Zv#BQWwJQPyvY9ulJnUWv zDZXI65u>ITE40{-+lozWezvK_RG8yJmVMQrtMaR_&Iz_+X!T0jnn z1&-ZshkhX?NBK(~8LrK=y1XN1Mfc@<`emWMem!5D^K0JMefZ@;(rTha#U$kQX!+hM!1o2bly?U0O@< z2jiVXx-v>#ziDSkc5mYeM0vw-f^x-x2L$ZXzsl0AFAkV<|9wN@hc|mOqw#X*;411H zSCPVj?sEH)@9)Bsx=PIBE?-`lhX5JY=57`&g!&;IB=3>XD;h~ zj?P9B0A|2XV8QYGFW%zj1=Dmz#xF)gTAa^!4pA-AZJ`ThY(A{Elv1= zi+qUAToT^jjU=*H-&(r+ofN)@d;FCZUPHN@b8_shDWxC${BPrlfcLS#g+~|NGp(Ln ze|bIXmh|mVOpHVs04#rvD6o_(u~+C}L~9d8WR+qQEvJn?;!_xT;caenMidhY>0+pF zG?KnR|1t~P`+D>-`RdNk&424Y1UntPoj>J!g{|Usi$vz~5FFY(oWaho zsPQ!3Cw-eg=KN(ysfou9(XfMsu$vmK-Ou+!ZF-@4siPlM@zZ*}fBitr9s=kP2~#&_ z>}9nXTZe}~o}x}{el&p}xn8@w8gGv}NW7!kANNdzMwLjq0T^FTgd--YH zMCGjaobs9A!Ea4gtchB22E^E4?N|YHE>!x^X>b8fh(pa}qL(y1toja*UaR41dz)|e zXg3`+rL|^rL_$A0q6JDQQxW{FSe%j(%+u7Vu#tE?AOj&sM_`rlY;mSF<0i~we!lQ^ zypmpjioKKqBSw#BI*WB_|71kdL0&&lz`ikpUL(E@lG?lN`Scpu#yr}h) z-8uT}qD*3}yt5ABvjKuFQzgCSs zs}NShf0$>ye2@r=uHmK&-HDBgfvwuBX+Ex4u7LF$YAt0WfywwR4!by&5wND2UkQ2i zY4mUkLB^VqA&|RNfJFKx)N$N(>85E%Kau07C5(O}He^HW*8%CA$RtIQNl>}yo1Alt zshD?l#zH1(AfEoZJzC`56tH2{T=O{FEO3ft<^PIs3Ax;INJG^c_p8(2Pe9Abx2R9}@NOwk;}yy`7%`vX$}7 ztG&hDhB=0aj(Sd$kp>W+NO+S-jKqa(dA|N8X7z#=L?lKn!srZ_0?UsBe}d^I zz;4M|P3AzB;v9P8nt~-O@>30^_j%iC=4G$B{JFSfJ6&w01*>*&F86tX!G8;~rTS8w zwZkl38v7Q+hMF+ohXT>C?QMMrHR&1JOP9rIJx7;|^)M--sMYk!CjShGlIHjA z5uHPqNQbUx>`9~94&;_G3Zn)=)yAyfy|0!&PpsZE%db?ND;agGelNCuyHzxLKF})d zy=(tj;(=@SzhdxR^TYuu<-LmDRzG}awBoUrE}2S2>f-x}toxC~XI+EPRLoRcZ5>iywZyy(FaUERhI z*D;sf5KBX&{GeR_kGi&IH`FwrBS=&j!n?J43p6N%G0tDpfT51sFu6bct~*4fSC~@J zj6z$NG)lPNZ_?zTG!lO_{;h(h$FMFqDl}1-DQ40;9o;6l6U3rE>EOyL0PF7DoQI8# zJ4IDp_9r?M*cDc7O$ss}rgC)2c>Ye+mJBG(*uN6ybuD+G(Rr6hJ^aylm0L6z=T>wF ztPauS_-_yuY&kkQ4Fm40WuM+$@%s5=QQ^sTLm|Cl&|OKE4B)DH`>e8nfMw1LCWtW^ zJMh>qJDUsm24j z36ry+XL{<`{mHca-12GO1L4KcMcBS7~mas697p z=h-~-zA$Il5x-C&puybrIAy6loA@aT_c&RSg$IaIio`vm7fimUpmtv|MMhy@#jpFR zvNt1t7PrmF6p;o6Dzddvg`QPd@?F78kiQNdT7;$+-17^9gc6^hamwo)Myj6u^)RqQ zSA2L)Gx-ZJ+0p(wS1n6HY`84aNM#iJCZ`gcS;n!KGI&Vnk1ksn$b zg1^Ndz!PGhn_P>UuKAW<9wjho#YX&+D9yWIF?+)I+dCIg@Ts$=nz)yzYSJv0MlUTv zje4ms9hp4qUNaavF4Ct9kO)2M8Vgpw>ODgCgj(VR9HB6+aV<_Gi?nliI$<%N(W|0< zbxhjvY0>_iqd&In^z>-Zh&<|x0yUdg!Q!tKNn!OZIIoTMweY&4OIw8adPHPeRqx5t zIbJ+1JUAUMCD?Eg3p<`v%qPN)-#(s8i^>}Ewj%2r znXejhAMx*H(l2z=CF&hCC9(qrJ-e?o^U++)k&}~+oOJr`Y*lW16nws}U#5mYWzkl? z&V;5jIebWUIhMo3Kf9@}ZKJ6nwSnY{FpV0*nIzK4@Ow*1f$*B@)wdVG5B;-`G?sd* zOhY0#S)g`lL$5-W{nN7N-^|gxuZG``XdL?TgHJr?grbvplJ{fapdwWSw15Y|W0@Ln zvOf=~TaAA=cQ81YZ|%+Lv)sR35!6+;O_bVu15>#7Y+jQisK2o(WDlyX5bP&R_?-rj z@r(}o>v=PWwihhf=2M8-EGi2JaqK~y{$AI}Z(cr=0|GXay5Vj3FYL>LD9~}TV*TQlpg{G*`Hkm|(Aa@LZ)0I+|@q&;SI z*dYQySh2Hrlz(lx(w7^ys+$hV&#(6%7wnGgf&5u54Q|&A5vh9qxAXI)jGRDi5S?IH zhfxb{{we&v|B0hO+4gPi$CJ%&BpJ{l3WxQaDcLW3yK(nWLe!`tpPO8bY4GRRv0)2y z@fEH+BnLFljn=W0AiMa=o2J1#?GhR_P@Dp`v-d~#PJIk>WzS`obkOpTt3+@X-2BPA zI!_`Xd0Bki=d2NvZzV}U&1@YH$XMf5IbtDSZ!Ta4K`_qNQM1q{lrd|Oek;2k3b{}Gh*;ffHu6j7d{$4b( zJVc_x&2C|jt>e%2r`PbVGx3=yH(<(Z@y)Wkr}wRTc_`YyvcIHB3YgahdCEwgciq&! zF4#U9$_SKsqM%mEo`vg{3FegOG6 zyo^w~N)k8U5IC_E1f3eVY^rxumv<+j?aSQtzq1SX`XqPTCypyYzwE{bA~=wZ8j7bO zuUpTy6bnD#}Rx$ds~b}e;M<(JzkG6+a={ z-`8ktivK9lH55;Ew6N24lo}|A(`cIAx(et!FW8!v9XW>9UFn?W_WH?^L$*B-@=MiH z-R?Ssm_JSjj`MF1kA`h`K=jn0XEFxsnhce_%7gWh4`CsM7rN&9ufD<4$w&9XlRrXQ z2X;lDJm>`gqh3v(SaF+o2q_(zjXmdj(!Lxoog(5_KK!AdZ{PfA*xpv|xhYxz2}54_ z{?Ud?{mc9##Sw)bUeSp#b3F_Ka2gvtfc3*PM@6Gq8{gi#Q-tD8AC-0-Aw0h3a;Yru z(fWZw!fS^|&v)CA=#xK=?3eEePFg(!%}#;0_c&sB&s?6oC(3(NGthhBs{V|($)zCE z{)a~KY3C#dS-gb=;(%rNoTr8rZ~t2VI6_aiEisu%&Oon7{X!28b`DmL;#Fbc8~vOG z5u4Yd#Q9hs9JzgFG{SGXqr{)Jo{b2Xns}&Blal#2XB>3%nXmtsSjtZ_e!i$+ zA?KV#FcDqRl;dR%W+w>?;YwQNPQBWA`uW;Qn!DIg7{01IbQz zkRRp6;{tixyM=SDcS1Jvh>rHuhAxRVW_QWdxd7j^DKZ`fUZsCVzB^DoK3Fgp{kJ%p z2r$V;jzZGxe@e(2RR- z)O>3@-OmL1)1Jppoit>k9~L=-TL%+v!vlrTds+>I^ARPE`-aA& z@fjc07Zz0oRcw<3?9@?%#h(|K?x^(MMX0Ygj`N$|i!p82t$@yj54(0Q$7(goax9fP z?GMCnzBe771K|u`DVr$tuqR~G(wf@IDL*D{Ml{-Q+v07wr2%eE788j_VJi8r1O%nM zF)JBO1RE~QZl$Xi8CBRrFn!=XAw%Da8j**l%{E zMYlDm(V2#jgT)e63jLFXXKiThWqc{)EJ*PNI8`+5UGZjSV^X7`m?Li;s2U6S`=vNV zyK8VU9hAGt$S>gN?)N!oDMI*6Uq&OyO*bS^&T!(3Db0@-APS-W1*c>aG#QST!PZBn zkGAU0d745(?MKSp_bw+%){+Bj=pN+}+X8vK2*s2~xtbM!Lj@J?+PI59blVBZ4^m{K zbtXzyMPH^x)9BbEq<#*fcvr{v+TsV7cO%)}tymA?N2(@-;{y&>ftuEru&O@c zIVuG=E2g}39lH@07aH}GbvXo>p8w#7A9>IyKN~|5o;s>k4|?+VZa>_Dls~AMTCu~g z)HnskgJrV80sR|o&j_BsA>4Sfx3FulWneA8A@s`n$q+sTfMD@);KidT%^+Bq{Kfg; z$0o*Hdd>bv0o5-Sy(i^UVz_qiSXmM^l;&Sx-fV)Jo?-BTH|eWM_!Q?OR-8p|-H0`G zDH-TRw?HZ)V}HEsD*Y@sSkViOpd+2eDr0!ps$|odKuky&kUwr*@`I^gC!$8fpNHR7 z{krNBAzu$RHySFOcjDLWrGryR?~uzB_Y&1;n;4q4D(`tUEs}y z68aNuSOeC}skVMwsgJ!*cHhk{c0%lbfK=`EKTdSVaEho~a6-t&2ebhuSDIpm7%L;bwDUrDSq#AHtnRNj@ zz01R1Iy7gA*Ysrj2n}5dt_k`#^vGq3aN3!58Vajx%kM zBtm23$vv7BI1-%5e*Uh!;B?I^;dssmKc6b#gfuiQ5=@=|Nb3izNSQZ2M&c12(CqU& z4=-|Q3Ck_;oHCc#zUHTxFyVXmr?$q>OJF&9LeaYZL)m6nqjVMTw53|$uV}O`7&p8* zCr>!>&TFy8UTi;1_};%x$|BEsggpK_lGLOKaTPHwuJp#QKkbKs_1+7=QRzsBwg0&q zq&4+UwK?3*3M>niBmH7WScozjAPyO-sK*RGzc%gUQI6;y z!}L`B( z2mu=!9AQBt2=2T|UiMx^_ZZ>J)%I!DYt}J~GJGv4DH+r1{(IH>a%g%@-RU`4-fJoZ zWspLHi_waTY5mj<94R|_L|fO$mEVvGfRA_8i-op3|C>FqM%e4RjzD@xgd%Zx%OSPdej7NRp4Fs4}RR?hM*PCh) zXjFt1VugZ%Q2b-v1|oOz72~rf;oSsYXZ;1Nk>Q%YvbVbn=64u$edxJCDitT^MWHPI z;M6ZVLZzOAmsh^_SeJcpkwMpyU;zXzhn)};7j^jiL@)rb{{ld!5t@90;c}oa{L&&$ zhT`p&le`>c9j|ir?f&dx|L|VzyI{X76=#Y{+9V-RTck-5^RE1|>`1@|Tqc8)CJqDD zWMcRl={<=}0(juCm@)GqCa53QKxTdeJ4Yuuq6If30I~S-?lG%^tl32c;w(VpTiu$} zuuGf4ZD^Px=POI54C`so0dg3vF>+Be+(MFH;?Ify4Fk{`VWs^^(rr#5u24mu8*%Q zpix4aL~tpP8>0g&%P2ZBniTB~&3wq9H!o^CA08zVGyngYh7lqB4T594yjha^rJ3Ir zM9nszpxW$I>1vcVK(A=h z2*p`N7#%TVT66~kD`&pKt0?t#7+O2zWgE_7rlwThK>K80o1|K|+{26Xd!h$|ukFL8 z0UbwhuI@O-spPY0^hv}foPr2GcFD$#8=B!A)TC&w_b-il%FYi1z&y6DTE(d&IzXdSsHLzqYJpfIt8<|Vc z-tl10Z!p%UJ4DbM|F-6k*#Q_Mg#YY=f5I9jEo8IukpWp*><u6MI&@YmcbyBcYXbSm(XE6W?C88FPAU3@jYTQ#g>ey?t)N4^%!jddycdtcA`I zr;z^@8XrLnH+LW&=xB&C}eqk`lpnT0|x@9X^672F_<`o~%Hno6>Z%&3-4zH9h~AmCu4< z0Q-tV2|fCG=V&cBm5kQB6J3zdB|-#GIEaOW4uZYd{f=?CXTg*pFLDxti0I4GBZ7bU zatcs@lG5+8wrBHHsxZ&L;=yQD4%vsH`zRT1UVe#SQW}A@zWbyPkKHw}EL{y80VgX( zR_Y}wP>H`8@gsR=7||eFp?Qix5n}ieRngI3AZ$iJ7j74WbJ2T{f6@4he3J#2-*L>l zv(xR)n?#d06-g0dp4Mx|HE8}0c~Ezrteys{?@ZPUncXKD(VhlldadWCH$ML%L|G&I z?w1^YboR$=GqFd}As_4|F4QG2xnema8lU2z#nJRLWrOA(4^KQHe8ic=-6n-&a;S5G zIpk$*#Ac{J*!x$0X_lyu(gckx?@rsF+`>5_EIi~W$=uNj5nTvzHZstXIbCKge~zx4 zIX2{1p5UUM-n zJt_pfU!sp(Osxy&ug4`ej;@f;KY2<;8u}_xwOm^EIcE(K{A$x*IG;hv7oH@E1G>xe z^JA^0Mf%5ftDLNg-$ItZ7(*qZ`(Xe$=-I+O3Bpc6U}ary$V+DtUg-b6<#*B3u2qj$ zS%|g!!ZcqFNO|b~fGF@7YCeA(GvB0WF+~!|CXT15+qTYiryO+E$4~o@L|jl={SO@# zIHvQ8M#fku-f?7O0Y*mKNf64B6LA>AvbRv;IHn7 z;aW$+6p+@XVQ=;XsmvUIk(~ThZg3Uy|8BPhMV6({ZV~Q19g?H|CYn4H0(-0-%GA&5 zU_bTquqMM$n`a3>GJ7|+irHP29J+w+0i%%_D_>9D7wX7U<-B9SzA8qnQfB z!OCY~2`0#OmJrWd%SRP8cofG=byG=HY%ee~V1*ayhppEHq^u9}uLatiX+EY+&1@*N zC1#K){SLwb|9@}1Il8Fphxp2*YGGkRn(%-G{LOa0AUQL&*FGztuM0-qy!p(Ywty{H zo~kXETV}?4C_Dqwnx}dCD)&V>ZK0AyxmAoN6qVfOcL_zoB93|hQBMB~VDf`*ec{cV z$_)f?*I6`RNkuo~K!9dH?%AI<1XD&)q@|8%kv&mBmSEOz%^^R9A`o9 z<5lk@e}~JSAz6IxH_RzJOkIRX;*HD?YR$@kk#`u2yCT#tf|awR2tls+?Z#w5z90WK zMA^*}0)WI(=0s{YTdu_^F{2*_=Ti-;zu^B3Dj_%`2LZC3tFKMIza^<){DPe=VV4|r zMYGZ2_8|K71TV6GOc_NL2i_6k>P^CnaIZIGyCe7g9sA0m&sZ8W4uAjh8CS0SL~huM ztoWZl{^Xy$X!srilktHN16S^jsN+Yz$}1yBHO5D>L@hiw!jH8!b8=v_I{k$6OzNDI<*5C|{ra&P0w{iZI8a-y~rP^ME_KReU2@7tsGgD#EuM;>v)2T*4ULSq1V}YN_W6 z)sm*J;AK2O2Lf`^ym>|ra#WjMO%I#wbCuXRG>Bw`t?n9vITsg*HSf1@jsgb6aAt+( z6=!};QWTj%a~a0M&0_3CMpAVPiD`v|@=Wb_m^}}d8R(!qd^6mFNs9oPW;W&PV`e@B zLEgo9l96A`xQJWj?qm3`YQIK`p0~`KM=5gRf<&Sm|7qsOa$2>7@HFuNTuG0`>$tX% zOlRLb+x`7HoE&77J-43aPSArr#xRg8nO?v`^Q1&yzQI9sqYiMuS;LfHY% z-D=`)-kbA9y=Rqm<$3Yys{AvQAO|r%g|6c^c-PAtq#xidbKdr6S0I6DNXgcz)IQ4p zw$A8c>)zbea4)0wKjz?Medz{AM>zYC0eatPXi^vx3&LMr<+`%0!7e!Ymtzv_^y4o{ zpY{#fW`kU4Esxg{q@_3){K!TR;LoMOO)kG;P6Dkb!uv8Q-w*h}U>6>45gY}?DN&_! zRHaRKnsYhns*WKQ37E86sjDByTDUBQYpHJxU!!Z1Rk_qanoSjcP3~)?zLXdZM=L+h zdS&*kr*3Y0U_;mE7dwlm(9DeEc!Zs$EEgBR*_3M!;P@_g#=s-!@HT|{0QYbLas;tXg>t7RVt zP%MMQ9?EnB<}umK?6Va58jqSo`58NKPumT&t+=S2Q38JE_>pa)4)t|$RDFm{rt7g< zU_GC*(IflkRT0xtI{+Vu;Tf6i`aHzUM}%;IiZs|3FEaiB79X<6S5R3aKm$=8=-}cD zSwgJYH3Q95MEq1jRd|Acw^Z855oaLL_G2H)GNc<&ikN(a?~6ga5Wk z@k_pfrVQWudJc%DoT>f^nIIv%IZ5)zTN$D(@1u$eT&_DM=x$D-M1_~?=Z#a%`QcNT zddf$Fwo>`!Qt73KO}Cw#f0y};<#-3Ja?}0m&MsZ!!yO@UAIXYdo1dK)8OL=+ev2o- zJ_8!OPYZTS*8H3;uHaFC{tK8f8PMx_vQ%vWyASl)U~lE+X`R8Akmvr{$pkJu-4T`R zVu2*6CBthtadya&=Ramk{G@j()$V=@`^9c(B42|et6>Qq%y^MTveqQ1Xz}Z3)pceOXE}YBBmPdpUudeCs~wr z^r848I#VCAgQ$xLseA!NVs`N;zKK$mg_pA?t%5flUU_L(vAR3>KL*cn37Wi$!Ow(> zF`|p-J#ff&O1f!WBo%xZ{NDp8keE{<_|6tmcWsm>pqq6Xla}I*zlfLwcITbwIyu94 zO{F8CKJ}Wue@tWr?8C}@&UQcc!%k@XYM%Iz?Yy-7U69k_bv|mJWJyE z!e;~7H0V)-suBJG5aIk5@gqaP<;-AazzGB5bUQS|?`O%Nx3$ZaTm{;txKXK#dpA-> zl-bC`>)-nea)-6lJnT#HIUMW3q`#74U5}g6u$eMr%PaPi zC4k3$uv0&x?)C$x|KIuIly;Bw|6}XTqoMx(`0-)v%UH6{*dhS=8om<$pvZ4fG`6LB5|n^8WM}D$f?N);+#q0@`{Nll*EIU};J{KW&T>?} zR#eWNYarsu;Cm3%k>&x~hRmQ3;){G;ZlOtFDcXQ(BN0HQZQ)S9!D z^M+2EaGYV@v&SKhyRtwpu2?CzhFU$+SD|&Qw4b`wYqvfw%)&E{0ak#~ka8%bxt+w@ z$w)rK$Z#7}2yTC-LP}vU!?RwAE>KvbRB3wGR{}E7LO_Q61|&A&QAP}rf?OIj@2T!l zRQ28yLt=tdO-#aGTR0y0)zEOvE&=;>s}u@)31}%s`Pysmm+Jjv75`}NP(2R-;iF%+xfRv#0Cv6<+&xvH}#i1 z2^@;Wp~w&!Mb<^~!gi?DdX6|Oq_8QdksqJ`ocizV7daU6YkDKYCb>)D`6xbcJi^0# zC$Lgzu<n&9(n6;kUR<8&DtAT+1Hj3Px?48ScKRoPKX!$5%2 zhQG7zF88l>A;$82d8V7QfA2zoai^3iT_+%oSO_S83Nsq02lGHa3j8`;gS##!=4!3@ z(bR>|T&7t7hyCD$gsK9Hi(BL-C`#?nAVGqIf7=+eIL`P}XJ7zcT#*e_l0IQP z{S(Wu<6kGE1A@#qDZgBI*gSc-`Xgkfdi7d&V8*9R1=kQBC5QlTB%iw8=bQQo_U)hT zTkrS@Xr-x@Ri~zF3BJ%4{A1_!6szr3tbI3Qq_DVnxX|vYyLOtB&0O+ro6fSD2>am# zx|?qW^aa#zRx8EvPy{2t_0G93b9cF9eaoypSlHMow25$#caX>Pew;k?4^(uyG-Bpb z@^Z?X>S}@zRh<3B1F;Qak2#r4W6#4}VM(djgbnA1Lc@D8y>G9{I&Us)6v`ghO3B$F z&&A!4Tw-L{5^jkRHaLg$DilDe%}DG@iPcz!3otL$#q&-?epbf=mWg?rZLg!wAbl># zlJrm*su=-@@#4b6A`bnsYNEH>iY5a$g~!Z3KO3_UYg}h?B!A6Xa;VggOlW3}I2qr(AGPdRfde~P-R&b6xgn7RE*-}<**!X^WHutBB zGW2Ls^Cb7?UfIJPB$GNiTZlrF&wFKdRnFouS7s3BTEEwZm`&_1(FfwGeT||g?}QtS z7=J#Nf$yjF*`7lll`hKY*KK%Dm^^)1T+dZm}85 zR~19^Gtn4vBLC{>w$ndRhX5*@IZsc67`@MqtgLcyFL#q~?lBa~fbG|4s2PyA(DG$Z zG*{|f_(B{mptY925E#L^#4W^ud_I7LYJU1Ggz9%oh(vn-Nnalbc_r{l&4s5R6aoqx)k|LNWQ85-w6fa5O(htOV+F4hsqP z{++wPSOj#gn|tNxsp`18_X^7Sy8If*vKy9*4L_fq@luOD8XOwG9_gB+{I>a4&|)|< z;=4kH@H2)NhinqkoQh%S9Cv7V`BR9BJSp!;^6ZCMVshQ1o5GN|krS(SiKOOtqq0Sm z8e!zF>wlB>YuSV!J=9G}NoneQXyH8M?tVhcx9CY2p(e^T2i-If8jNFLPE0_nf|BcdxjTVWoR%(YAAd7OY>cD9}AVhR0Y) z*p9Naf(uG6u!l7RDZM|3O~wolE;*nGrzUPSHNGrs(TVFdE2cukj5+i#*YM=igVo`4 z3kgz7AbN$#XO(cNd~1MT8zD2ewiAjfM>l>H)n1(lDWV?a{IL8RXT7=*9w#0I+kf@S zhy<(gM5-glI<+XNwb4yJ6!SI7e)!)tZd7k3Zp}tClqTh0L?wqs=!#Q}R=g3?dP)Y< z3%br>htKChL1IQ7qyi0sK|e+7I@76%@$fC0N5e0Qv z5MVOp!YC<6ZftrEV~j$3NSZ4cG~X34UD1hT#gGV0{wHx4DfB3spN&Es^*R0y46JU{ zUk8(&{|xiT$V?a}A8~4!O_jX@0U5p4IXpPo0eNj~HPd*byKfOt1;#`;2~ zuAnNb5`xmo9pyed(Q`HO?w@)xgWG#trb z@>9h@>(Z8BOAHHrHr$XLW4)H(?v7vJ~aGMG6iV}MAsEh zKV7i7{w_Tj&0my))9cj8nM))}i!}ePAY=SQN>d~@{Hh0Yp8m(}$HCpNSUbtr=a4G3kY5e(W~ipYL%c(_5g9CNKL#9ors->c1~IGY z)$U@`(PNURnbhFwyjxi>#Na8Q$3!3X^v5J6xQtMOO=d)U0L?G1tA}56yuU++9bgk* zA~%RY^It|K?hhV2ZckMTK0@Y(zqw}$usb3}B7?7C6`5gU$_FK9@H}1UiAKO~IM|Vr znoY#!2qc6em68m`M24+Lqr*sHnM`dZ6Kn`J909l5uIoQ?iOpj(`aFLOmsbwO$R$0x zFMj*mz!xBY-3A+$>qv>X;|l_JSqhZAnkuV<_PArL5f}fD5q_x32ddOw#_A|4)2a_q zN;s!$_hG|3^5PW~y3>T?R7i<9 z@?tET@>hpy_N<1B=Bb7j3S-VQ#*xIMb8df@LqTSB?#kxTI6b-K=v+VIj~Eohile0J zhuuGU@BXHQT;l8$VO!fHVf(tc>(ZIX+b&4b>o_(iz~_dxHaW%5FxMPa12}T}KKEvE zOz_+=MffLz)sq|@ufPxi%xguQtjHy6?k3atFnLQcbk3Lp;+hO=`kfy$ruy8^OAi24 zo@4V7{&v#R-*2Z1)%1~X4t@_J3I{gR(jL!~4dda7|E+Ze@QH@XUgbzq?BfpcuwoJe z-vd&=Oum;i2>uXNNY4?PKliB}K1leBC%$dc%!5(bV$z=^(ptH?{As|zJq;^enjPMO_)Bc~?I#V!a;TvSihDP&F1a%@TxFagW6)c*9-CL1UR0@< zC<}7O1DD03`QQDKMK=~bG9-lopgyMO#?)0{xXHwqIx?FNRzaA-#?ms36 z+m2hFvF;>=jWSx_qXKSHe*VTA> z!dk9DhCS?3zwl-{O%jLeB>}DiS-{0>H}gbTPy`#S1(3n`93P$nLa1v_2xSsEoZ-G2RzRXk7p=T>&I&M zef>ri1A+t5j0X9+Y&iDd2^ee&jmct$me#leZ#fMuoY|aE&9ZeS2yhbR>qk!GJ6g@N zv3Z~QK%2vNV6M&={*5sdGaBI{74<@p_gWKQi9saQuCubnJBTc^AtPh*OeP@Tb9BT} zl@6{8UO(1LUC3ag6+BT2tveFHf4^CSTx?M+8g7m&#>Ed8g`jheKHK7jq%#_DQ?-Xj zGGkN-X&RG?A7DVv`iiA*t)}M~^e$VC%`-ON(IqORBk+`uX$qWgjETc*^0-wRAae7U zm6z#}U{Ks&G6)kkPy52$dhjX_gy0&0`i%&pZhWLv{>-ueECN$#&&ER7dOEQ6d_Skp zv-!r#)qY69l`+8PNU+}@yyY@np1|=^m1>4?vLo>feTpldh38R#M|M#nt^qj0Cv#0q z1csm+J@24%dI1nFfc7;;HDyn~x;I5M2(^AP5`hG>n;L5UB5X2WquEB?{Hfx> zJ?Z}*SMnWLfHWu|ykNUX2U7^#C%Fdvs(-mDo<6B;=@?FUKpb0!6&^MGgWm@I3s@!# zuSh{yz#YD9EeS$MXK9JKWZ)R0mnDv}!v=KG{f`R0{=tKL;P+$IrC>FFSuOM1^VoGx;hKgOP*IXuJ|GuNTtw#Sc9LCUo$~6CcOKefNNy zB#ukRRgOyZD7cNJaurWB2q?P`FU8&Z1E*WRDTUSgB~Q&9u+gZSQLi{ykX~F2 zfJsgO=HCSWq)Q_LM@DkerPkx76z(xeTuqt?Z|%ZaoAhR*Lo}Nh^@@^nN&7yV`U8I4 zPXf&9j(Bu7Jev3iy7AGAUI+PKFVLzt*h&TW*^rJjh`rXv?R)KM>r6rDM(0z~Q;-I@ zGD8`J;Jldz9aaSEWFY(u#wC%kafeLIdB86P<9~X38!#)xhKYs8-2Alj6OD#`ZO5Va ziCcfnSf{t>L&#uX05j6kh!#%rTXYwXP3t%w8?GR|w@Ki|%4%IL1Pr^zCgY=2bRNV$_jAH)?^u|E43bmwz z4VaMGasd3xB~fjkE-MZBLq4o3-1U+ty-|0=h=zJPrsavxO|a-a`X**y&DY(3hsQ)8 z;`Ej9@^H?@#8d3Pt?h7i3T`^5IfSz^!fX@jt6`gj4CGg_r^I&BHM9cEA0N>Coh9TziCPMiA>p#w1gh0bb ze`KTrgm_a+|0BcwxU579JS*a|4RB#28-h*IM#HZcCV-vqAlB3xbSDls?sKF1c4r!r0R_ zC1rfRG#KKr>dG>SKrgj&994-eo`+B7)XB+OVz`XjDTS5Rab;Jmr1((aB3+T6_t4NF zb{(t1HJ9jp@;CF+d>TjfS?o($WWGb>>qc)^<_e`zV?GDvY1g@PUu<~SKP{c#Fg^N~ zl@U;}av<>VqmYfGa7}`UBC4N5TGERQ))*-X0KM<^|NQSaNLsjz3FFG4%=E(~oX%&B zECdp@)3GIyV2_n3E}Dm1vrLW^^$~0Sl%$t5yg_uin(MO0J9;KeI)ki1l|7n2usht= zrxH-cmokuz`ExXgOZUva(yHprl3?Sfl+zT~Uw>`TX!(IOyo8#+cv(k}H#7g2yg$xT|Z5_x0 z5J=aEuq+||lpNwDkm5n(jR%n{;df&WGp~(SK!)T6Ut&^%34BlnWJN(80EHo@1EqG) z*pYt)#Gq7a-nV7p$Sl*fj{9f7n|?Vz@5KfULhN&;$F+xM4!V|?s-_-a6@9|v8yras z4T9X;WUiU$F;t@GxhdZek6E-emA?CRcySaQyn6*UFsMUEm*^+j_8ET|@8c-6Z8(OZ zHD4OS`{*|b3<6f_J`IZ&ClUu1aU|OLfMD`O(eT6^Fh-CE-lR&J{Azh<&?H?Dn*R|yMY}>sfg_zVQ@D&>dtSz?CRs0Y2GQ#Pmbde&K?_O< z4pZ#;pHFEDHwo7^LYbAbw*oc?r#{#eizp1C3}JNA#9IoR~p*c$6hR z=QTR#B_WLE+#d*w`9n=jPeQ~Mo9Beje{d3WxXzUI5%(sqI?nD~unBTST`jR&N-Q~d z{M7b=M5KFjAS3IpFhST!EHP$6$`_8TqjSJcq{8z~ z)pEWtaCML0AY0HT71k!Tk$4~`kBJ)bvRIYHUtRH6k0IF8!W+W&1Y7Zx1-4Q&a?SuG zCc5GnJIUcI1as8oX%LwkH)TdcA&eS~A_e<0+fL6PfTcQJFgHh9IHZ(4f`=u_9;#W; z_oR?rr(Katx-m>o50BT#Q8R!M7}}2QSXQKgd$3j+jwox6ShESkip_%n#ptcFxG2u; zn0nC1=3G=nx!~BN*%W4^<7q^WEV$rg2PACplNYx)>>GnzLU{=Z!0*F#`J17bj#4rB z#c`)CXL^SCD6sK1XN1+rqnH`tA+Jt)gB+{fG#`qaLY}fn$Pm#05SeU;+8m7V`JM!0 zZyUsb_eb2u>*^>*{VvGsoXC`r2j5QcuVW^pYjPAf3`*}O020SKLuUByC#?p0^P(^i z*nVJom(h(t>x||@=cEJMyv_)bx7ly4fz1+Y9(zYJNr&f4@;T z88#an_6Ww6ag910l*U_=Umb*kQ93?XVvSv#j6T1D;&6JmhLSC-@AbN0zBF0lKpO6C zTd}g980~hU0ANo1IRd*_X{}T?JZH>WXi;yC)#j`A{`3&4***YQl19A`qZx}VA?B1~ z9gD`5xdY7&J0Imeb0-*`LnG6uq47=x+27Y~#DwgK$%7=3!aDErh!hmovhXchWDD`I ze0Y)w7HI@NLpGp>aWP;eGPP~m+A4ShRIbIPt)jt+kyZIYKD*w(ZTH}=-H)^yz5D5Nq z$+DrTM8aF1%ONE!Tqh&wO!Zl)NsqNQfk0tX}9}PpM{K()p^~z1t zu4J&nh{~@$r8o&m|ksxA%0YvXaC{uhsfluT9@$|bP%=@OaV`(!oL^)x&THOU+dd+Mya4OesZkiBaUJZCT*BM@ZUM%dz#ww^ z8If80Wq*IsaT4;-${L@%B0%N}r$d>cm9oV zB0?!|&5_L~mk+;h3deBiw2QxY7|yX_M`C>9fdpH(8UZAJyQsfczGkTK#Xrw(qu4!y zup#pmfQBtk*EbKfS zf!_9w5$QD|n?dYhiO&~sviqz*)MjE<8)G6Gwr*|<`Kf3bUUReB^}-ZkjC=SVeT!4! zq|nEOZ&8$xrH_kTZ~=k$H}*cXRpWcmg=zz1{2CBDm%ZPwO#qR#kP=jlys3JwqjN?| z*JH%9()P5#rrV^(-?)PZCvY@3)vLqwj9c^pCoFa1{5UUiJodH2ABp*jIE|sg7|?c1 zUZsk0QL6Rg`nAU7RQ|C~>pkA87ss%9P=-1%8piS7WQ1ydbCm@IF%MEsiUncqu@CQZ z*!_mE{X^CiPhZ2)XtlLpv$v9ml8*QKq-bMDqv(?)%wA}nobZ;PC_7yCD_HD))F=c; zR`v?%J-u=pyi4HAzBC5YMv6UM!X2Q$b1;I|t_OIacb4JG07s41#uKz-bKbakz|lIP znpdrDUGUCoH{-Y;FaH4yReFs9H zckymPVm*Pzy^Cz2B^U<3m_^}!{*VpY)(%Bc^yjg-_9tGnYMN#E^(Cl5Rm+ExJvmvF zi7z=%lRkZR`Q+1bG=ZjUDoq9C9v5AmL0hN8V_2o9m`bm0E<7Emz2WBJH0 z-N{V{q^T-0B%j>mOecOPj6F4?yb+vr5eHP0Qbk*b9BUmY=jA~!18oJm^(Z;k0tROv z01PiSyvuk2T-ZSf_g@uQ8Oq5{?XXbz^ntiQGQwyBZmpm}a55p;q$|WOO=^g;H13v2 zfI#f3O*g~r+_3Ib6liQdbCErX1n9uBxhnl{PQCJ85eEQINyFB&jsAZSp!BCAt@C3} zBH5=q8;-=9fjrL>OB%(a>U4pO3JSOoZ#9ad^^{BiU=&-SsBJUrL_pxEt#^pn8h>2Q z+PEr-5_e)6iB@wX4u9Z0mCO~UL&bz(9>uID(qIedJ!MWKxq+>`i_Oq0IF~Rj0)pQGlGsQzXTKRGA|-dKHiR4j4VOPq832Vr)&WxMnWH@P-saru zKxup#dj!6?^Obm+$dP;gJ=5enKU57`Ky1%x(U&Y_*Jn_N2RmH-y}=m&jZlL8s^4|y zMgLb-%yCu`f-{HQRw2E;uj za?X%JN^~PzM!qZx85YBTLWSJZ-2GncEADQ~dr)FQ4ZmjoceOdA?52YT6GS{c?de!} zjvm+qU=H?w=t)U~d1NhYP5EfdXN6(euv4E)UyM98j9d4s4b1U9!Kc|wFpjs=t?N{w z2QaJ|LeHo%M*^!K$4z;tiT0%7^rW01^bq;I!C1S=flg~Eq$%lH^_AmGyWx2fag|Wq zvz%THY@XeaxRr?>Vd*K)mj3DK(wqOBepe{XG5#~yr1De5MX{$5-hwF6@p~FT`&0Pk zj#g!oyMUq?oh(;fAt4meUXs9CuS+W&3j}SxI@)}k*@AE0{IF+12WS5|cJDi90I~9< zQagbyBt~ns8f+%ACOElihvwfVh(4ZqVNIu&X1IJ)*a$@*VL~PKGUH=>CAuzp9-wBtXxo0YihTd4Ms>gw1 zNh7b5-LtnI_{w3B5zZF~aR*8sy&I8MSo=wyCH9yG4g)Jm;cr_h7m#mWD`N62136|U;SYy| zlvA!zKmLd0pZyCRC3uIXN7Bs(S8^NLl=~IVEV*%pOjjO7atO*Xg{ER?+uJK4UJpxn zP;DR0T=8)v4C@9T=jRrha75!k%f+bpsB0EcK0E1BaA7rbj3MK3V0@l5vONU?H_i1> z(B(loICu`Jb!yI~eU_6i0yhOLxO^{9m{qrz>IFLx?@t^^tS(%pK;+r5y7OsX&l^sB z!LC0AEcnNn1)D{jT5u5o+U^^k290(*#*6+3mz6->Vi9K@OJ>TAj0}qzlUe4B9aUxy z7L=AkY2UsL{wHf@DmnhmnmGs!&w%>n5kYk7j-@VzDPkWFeh_y`jAz%82=}s`=!<>+ zlu4OC>AJ9VAal5cJQ~DT)7r>09b*2f+HZx^&HsJ>%)+M^iJOL4zQ?ymmV7a!6*=nb zsrbbZ=Wa~&n;ZrK6*U?}mw}{{(}~|OEOwNajzs5x46sm?pPBceROt>o1XnPc7k9Y* zLDI>9_ezG%vm=wFtJR!C=B1G{$y_ZWBir3CMvIW5rs1OdkpzcsHNe~lsthLoS``O4 z6$Nv9ML(V|jDp}IpHj5HOJ&<`myPZG7+oGiOF{fG9#ofZE>ggUUl^!x4dqy1s7dHz6c^-mRuRs+D_E8S8e zX+vy<)ts?sV{@I3Z7hfyn&1H(CAoA!Can1ut3*EEoB;EOT;A&PW?b)gTyIcm{JW0Q z?VZ8uNPa~W$UqKYTn^s&-KBrn-v|6YK-L||L#%d}PoN=zyjPt1mCRm;&y_#11B#tp ztHHL@c$Qh{f-jF|kY4yTn_Z?ed(9h5+!F+RFxq1pwwrG8dtK|%5kkfw(IR}Kil$#lD zQB8TZ+>jpW7IqqFupQe4*<-}XF4gd4mu zhU}hF`QYlF{+r`S+YM_;#Yx4{Wst%>Iw!&jhiEaL8Q(pLY%Dx8g zWhEEbkZGV4a3lMg5qjcv`&G49o0a9#A zW7x75FxFb(R)aKR0wYw$BVCt-CU)k1-#l8lj%bLdsNHqveUI4p#N7!@GAr-pcrB51 zXo$E5CD*Ntp^L>|wnCVk_xtH-Fgx(qg?J+%zzsAn^(i&xuLX?)3EjZ%o=LW6m z4j_h?e9XVKlK~#;b5*mK`j&qksKTAF$r#Ay-o1pfYtYa@GS<6Ko?I$98dYppXfcEr zgG=^$jZ*g!IlD+h#8d@MU9vdi`q>=a4q*-t8|8d=yX~Rzq!t zHrmaPNXa2)mL|9zi)$}x1)mI%wd#%N9}8m*@3|xNWplyH0;S`RkTS-ukO55?wvgWN z->$c>x~6C8l<{LcruCdjWtGWafg}rB#I~K{^XEkKxsCB3oC#~;q5V#g9weEmQ{pVI zp4e_|{Hb(xJjgdG8F6?5C{|mq&}PlfL+(y){oeOt0E9pZ3J~uKFopH<@yNz-Yo%k(6^zIR@T6c3suTuNT_gdCO0WeW&Cpv8KtvXXykmvYIWj(pA+h!&Nu{dvcL z{a1dS6?1Duqo(V8hVQ2*mUUG@og41Mh6s_&+K`QJ-B7$>c6!?*?b&6V3z&8$6YlE8 zBj5gI3FfS?ddxwoSVq~h|4Gq$A?5yOmN7sAw85b`+|-7{(8zl73oHfVS-eV*7zHKg zuSql68%~;@bT1OkD)*$2zUnIg+2n| zNeuH?Vu(LLiJ7-)6U(l7u?6-F<@S$)cDR>4cjxn%=&oXlUxCj^jW2v4hGYaBJz6?y zkplK0a}-bzFx?@aC}Szgrtdo9Bo(NA9w-Kbz~II_67yNkFwJ)QG=F}jZ$$U6bam!#g!8{s--fK8#@JZOYiB z`QvlPMXnkhCsP4TvDLL~DHu}6beQP38b}hHX7+5uHJeXaz3~&gkf*_W<34(zgD}9J z1lHc6MS%L45h1x{;C|jE@Rir;yDjZya%1Z4X_J#?=B9(6sdobA-_hCrT@-*=feHy! zGyKIrKN>bhWURW0qv5<_r9l+o%5>7+6AZ|O;LxSI$$ywm5$lY)Kk}WF_zQmYZ`T9bxdQ zN!DyR08!s`paunE1XYROGmvR8(_7(SdqvSV+v+kl9o;yyZe>H*zE^FQ&1J%mnPUn* z3%jBE^!SvRNSmgYcOHT}&j#{l&U78dY&huty-kNWLet;<3TqTSZpeOw&S@x}+Lb7! zR=9KH-hAv0wnc8-KUoy@r6UgjEdb=CEZmr3IQ{t5e#9Vm=$wuCH&${xq6VY=%ROgw zjtJ652J4fO&HhR1$f-}1!Yxa%Q4Ye?b`~N}r}mA585x=WcADw5>|U;bGGLHKwCY8s zMJ9aqe4Zejo1}N6Q9UB=&8kwNo~Mt((Dc!_yA zNbvs&SmFLO+5LW`?bR^KU=2fIX&Uw@c^K3*->7Z&u__Y>2t>LOj+m)qj z|Hp-6DkUw&bBU3fSY`jJVrkBDC(a;qz2BwU>@VNpD$Z-b7KKhhGEW3#&T=RknoU~} z9$!D?5e5xakV3_pFB+s;q*xnxOob>akrqB1>sJg~Ws+Y;D4h4N3w8muQimgDZ+qHE z7>RwRNIbuyQ(D;*y!@|@0JGyl+C109yOKqqYu7UdozrP=A*?Ou@N=q z(N7Rt4ZLg4yUpk=BF~=W@eElU9O<>xgsw;a~a9gb?{$8`Ih#xtc!i|_bHgfsWbcbK>Im5`9 z!p}3gId`o2x%tUGsZL>~Z@?8g1VdENf|5dI2^B&Npwu-`pUAxb1#le zRRK59LKD;>%}_kw?|t#VUVt#pzxZ5w4W9GalP`|-IX$5VQd4j%Xhpr5NFUSsG4`qy!Tp4fD}~QHb4G#!_bk_= zRCfKckOh5?>X*TK-AY~YGn%3PL!r9c%Z?2i<*67W?WD4-miQqm+p!nNp1;Ahbn_Wd zdEpA`0Y+KDH#QV}CF4g&y(_8M2dE7_N8>Q-Q`zZt1_rLQfGc}wgDCSxtb1oSKfRe= zm_pEA-%k}3LP4Vw5Ef562GkWZ=?8d!d}!p_CMq=hon3wMkGw^FyO3vCOf-hQHUDAO z8t1hZ1H3VhfVTJf;>EW0oCbyG_^w*>+d~k?QMJz;e+nazj1*MD@;9DHb>`T7GcIV0 zU&E>x2g{~nf%t7&%S|2!mlZYrAmm{u&29fX%j;A(@%IsQfmEUSPlSGeq8_1&Rzw`G zX$bl`AfW7$2Gy*wZd|baga7Qqe{k_>bb%86&%7c7HrYj5_?8Rb{Q}RoD0X-wd)+^jHw5x4Ctci`zO1Kb%@?pP{m*QyS6r8zIPeJD6#J86qROV7>fIeE6ivS z&?9K&Dz0XJbyZV<5&h^_t(qy5I>>gH(o-7xGj2v>qj6HVo2FwF8@{C8bbt7!de5fS z`P4GgPaC8THtoPMZgQARl=&LLzAYC^4Q#WLC4DteiWc-Nx$RzYRXH7Oc=oT-V~@>fPqG>Ih1& zodac_$G}$GE~2Cs1(I61{h8_x>f}RmG_m-1eR&K8wlhC#YZc_zkM(z7og8M)=qs)Z zaLKt6|M>&=p8Khu9~l|3?g}Pi4WsebIeTBqjUg=Y8!LKlpUtwDW49!BetgHb>-aJ1ztFFA+Y-(Q zoFW|q@0NqGad9;So`{?<)*W#N6g58`e%3!%7lh|NXW* zs`5^#wAK2Pe2!0+u0dPJ%Ky+H`gQ*{zv6XqHt;BxPymS`L`jN8Rg^`K$<7)W=K8U+bD zJ`VV9e(Unq#8tVJjmhsbY6EvIk2vmLP#_cOvE06I>qn*}7m0j!Fm1o=h z_|l$+j@Ei`UPua1as1XZ2?+)44J7f0?kN90Ul1&a2U%If%O5hn1UDFUP$jfe%`n>+ zbO-Vt9Q{T=g$`j6vEg%NPmWZ!kFJ#6^SdM+B~r`3OFdb;G!qeW0sRf#xM5s3{`Q*A zt=Cl|AMMKg#QR^|->xH^eVtVx+&N-^ahI zqfwzJaSChn-YBN_p89rqdivd_0@vgC+uC=u@tN0;Ca33*G}m4Q9$30gEq_^?QQUS# zC~mvZz&7~{{vf}3kOunylZy0T7E69fNwL5>XQAHwEst(mzcmy0rmTj-+fQ8d+^s3Y zLwtwqVPn;*O@K3{1}FS3@dE4SjDI82b8URLZ7N*iDv~VrJs)GN_4Yoq-=9PF?~_$P z%oH7M$iMKM``RHr?8kR29;RTSh)TvP+Ntkf*1D+k%2=oyYvD+Pd-eX`a@XSzxa-#! z4#YVSLBb-y=#XDfl$O^{{QW$;Q-|jiy;f{@Sz}KG0)DTl?iO8{YpUDWc=2tSN$nVq$31eBD`2HjC%hTJ|-UY98{b~}>cT%xf8u5@z1WAz}fGMIL`tpRE>)9@^lZ(rA zC~I95xYxg{OZ*N(5u3U9I&JGmv(h*+!eL}v~Q z6iZIW^$eo#D+pQ`xB|LWlhcxMrmNL4rnhd*Q-`5ER%?)Qu5=c!Q=5H6i7A3|^LHbj z)^KMA{xz0h;b^$_Wp2G=EY)PhtT_X%Cm+!LZ4I9RMFwtA{d!9B+>tUk$iMO1derKH z>)|0kcL=!M8Emb)NEF)|sjHnEnP%>Twe7BFPHO!0qzt}c8tZE{nx$U>DYEr-MLi%B z>Flhmtp*1LZBKegxUTJ9`u@%cW&4QX>mwz4lC&{jwv)zK`5673T6pTZ*!PL*;Hm+2 z04}Y0bW_J6FH8`XmOFWPzkj@Df#VPTQ&ruDe7`9=9PsH{emTle#sZYC2Q)o6p`dLw+-LPX})QZ0`a z8E!W5P!P8qgso==Zd=+u@TOBZ#vQEHO&&8s@Px?>p`R+t&>nuPJMpiUJ7KvS26Cb` z;1>cJ@?KQm4#He#f2eF1v9E=%>8~F1+|lN282k}PcQSj>Jw4*+vq}d5jz65c0;o-s-%j#)I>%+D

iK0m$l#qKC>x3)aT?pbIc5iM&y;$h)o5D3u+?!s&pL&NV~-7~AlQzDp& z@vQ!jqM{$(<2N5a1Ud9Jm46(I%$tkC3VZmOIQ7$bBY*OvNS2=$UPf`e>)UN(|M(oY zoCjmb@rcg3;cHT1;XB;*S{~5JfH_06`*)sXJQ|fQDVc1VtlQ@VQDs-2i-zoHrslWN zhgW0CyRYvcT%0aV{rP1GQR?VfujzbZb)`1+x|ZT$Bzeml-st5?Xx~Satuy5Zv-B=d zt*ShCueGyL5l1_QyR_7>{zW0heX~eZ%Ot{Oy4&JdjxWMw`&fF$)O%|B54}3Wfo6rw z?qScH9VM3YejCMo$>!C;{o_YS;2fDXo1SL(s_vDtwnY@EB9YQDPhGlaGA~spfClim z9)0h<#b<}0AJ5j!ij`|Pkm&>7>&H#uzGS>~40dNU zyH6f_NjpK5M7bJeG6T6DS_IODuY9A^giX>>+#a!h*|E5JTl0#Si-O~@&mJ8_$AlML zs#P*36iI-HzgyHdI0K$E4~}M&m{QwK*80s-9UqO`UL{q=9oO`+agHlUoPVv|AWj30 z?=H1uEBSngFc1!HHjSzbus!$<-ud9k`S{Nt`tu9{ncUN+k9!Vzt9=)F0KX{OU$J1L!RrNjZTP^PSiw8PP# zmQI6UH{5(@!x}exeGX*s5L3C@TIE>KgojU}N;LIr&mf!VcY z!+ZA5H|yEvEfw(uWX0*OuowoFGxj`}Aiuv(4SsAWUwqXAd5 zx3`}ctVMNhd-l5V0s573qC%&w2b_=@qxT7ChGyAm#ky6f5j!3?J3?0Px7hgqW>81N zgkBAjhrrBW@%Wd8iw2RWbd~Qv3td=1!e^;5LsU3e9LPOenwua&bvr0Rebox{_2{Bl z6e7XZMdFK#p&$N6B$E4s$jO??Ban*!p+bNts38u7AiTvfLd{|GZcoZH_hd3SYjlL~ zTft|^uO@{LhkwRGgl*`yuRiKhHzN4sM3p`iaQ<-(m16CD!yFUH0D>1r{elV-qM`4R z&*&M&$b>1Qh>Ysp;iYBHHmr-f!9RE3R4RqOUqREx>C>c{+HhW-|T>zeR@Ek3Es)6gmaL_n3fa4`Bf&ZMZFMAPmD&YA(B8tt$yto3S3Tm z4D^G>s(l9N#rkKe2x4$4El>(gbcs)YjKACI5CM|_2o(2YC$7pvWs#0GtG#6!;*$zb5r!cXpAbQoc&PVez# zUtSmdF4v?kFWWCKjT%KmcorOLF>g3lrdQlccPDHLi3g#cOi&vBTFc&ZKFBW;y2^?R zt$MEpGp3BPqvE=jsN2#X=FVEO3+0;B{Uo{#4z^s{;|k*of-BQVC2ZUaqdTzB##Q@Q z7+0M4uvpYE7xzhe2%m2Q&f&I#?*h&OvXK;L8-;|sx7wBpM-DdD7MDE+_ZB!$NUfqS zBR`~coM3y#idui>EHIgS&nrL%uc+DNf6dt7q?|BlQRd`#(zT?M!sYH@{pYY>_4ZE3 zW&v3jW=YX(X|VaxZ9WC!xPQ-u^gdr43qcgi3ur{N%QbLeW~p-7Qt>h z7}#1&Tk!R``#dUMu=jfeMonYmK*xQe@OB)}Ds>_UEa6;O$0Lccm5XK<>|LwSL-#s# zGxW>Chtz9?h{NW>DF%Nd@_*DIo3lpthhSdWQbv8)<_|^snULf8Z}nltrQTOVY>LnI zeL~ZiWbe}~`gF_mi~Toxa9f=>U^l)a1U(%YUnJf)$a>f+2%XV2Rt}dWDZ2(;z?wL+ zMfuWoeyc~cuvDXI4M$Q`b)^@uCSL0CaxiM~iK^HfJ)^465a=A3YtP|i71KZ_^l;F_f+%cnW zPCxX+flVDhTD!&Ft@-zc>sYIPFU*9jMixFzb+P7_G~siHEKOs(*E`ZAyYn)@q=W8} zEPl{(P;lpG*r{>hn5>gdGRIa|n~%^mu9zsxCo;BxPGpyYt(*Sjb%()TySF{)k7TNL z#xq-BZvWs;7tGiF(VWYnYgA^oF`VZoxVJdDzX!GguF$VI#m&`?qoZiGBJaAd-n2|; z;QwU4s-gQ3yt>(~&?k2jRg@SS04vZe`e9mUu>W?&K5REut#duRZQhjaWI|8%Bag5& zZB{WIj;N+4R95%yn3_=*V%7;e3xF6xQms>Vty35Mt8E(zH(*I%Jq+!y8IVKXBP&W2 z7tM&C<0WUV4Pc`oct1@}U)|i)9bAQCNO$M2D@a%wt4Bm5RLkt4`Apce2pE z-W`FA09QEVOR<+;zervn0w&7mSyrTB9^M+g+*Q#`F3Is1hB@d(tXm3e$NjQS_R??s zU>LXypHtA$cO^@+vmtMglat3bKU$OUOw%A(iFRo+j?i(f-_e`e@nks?*(HCH6@JoR zPGVEmr^cv6nMfHR&^PiNgw7hv(Pw-6V?Ua=zyHI`VBa(p6-e=F#*H}O6Q9$NQ?&8S$4CBpZ zV7$J}YS`2z$J{sgsLVbw*Rk`>aGl-wW!8AJ54>^a5E2?2lH*3NZpC3*&{oBx zG%Om7abcIBuH%kNkSn==Q4Wl?O%w3GfE9X88@D1!F*5jlH|W{C%hG-^v+Hv)@#PAU z%DzWda9OXhd*P69|81zx!9ceF*b8AGI&QO*gUol2B0M5O6`m}x&bwy)F)fBIfomGH zx7sbz7;)A4qm5*yPwR`_!K!k{W(cR zT{G}ru;X{<=gB8eUZW15D5jt4u^zYQ3Fh%`4uvW>Ym?}I{m!U6UgrD15zWVp(<|<3 zm;sz5SQ)q*n{DjeC_Cs}vKS~nGFcT8dPs<8=WgcdNSiy{CJb8d_CHb2vGPA9G8*r@ zJ)Ot+?(t4i_3ZK4eo9>IaG(f0M1xeFw{_Q6q`j!-Ht$qxk>tQB5n)b3a!UQrv&DuJ zYLnj3v#Ii4Ug#=igO%97I*NF2O(3LJDb-e2&ks%G@!>sR5MK>j4`jYr%nE^o{dV8b z-C$hI1U&9x+%*QWMZe;nZrjA?^rq}Sn3+I`=-5KuD&q5_O3pXwqIlf#nX`m#17ieo!$E{2d#2okP7vT z?lBAdKS~m8*waPL45@wS`>DOU*1jGf;JIb`ayH#DdbFYoS1jl3%mxn+&rDN~8=Dh_dckpB;c93rtJQlu-1%{Q1dveeX;NK+(eFejBzY`?AGV z${#(9g`3ZCastj6An2#NIRQ6Jt!~e7@`FT3kGHiA)?eqGjrvOb^|xOAE{VgN zeg8R8>4Ra4`r8}eZ~j{_Mk{MAyV<+Rhrg1$l7VSFB{x%>4|7*cHPS8L)Ha{) z-B&l6)>(zl6O6YeI^VJyH!1KXn!er%K}ZFoZPNuFH&6{){cXD+>m6e5!+f;NINl(= zx!W~hHH`Al(tZW^aCyQG*Rmdz@=Q$Lf^US3ZxUA)7W}TRB+iHyc$5O# z+Nhzj(80wLFtQlO;uZcG0xvs9=OacuwqoJ^e(zz=H0`Yx4)q7xfIJx7FM=SVNURGV z??A~MX!+qj>fPL0O0_{Yt-hR!$piHL|y?Chd5c$_~>EJ^ca(VC}w zw;5q5E4Uo=$T}&lY(xZI;=X4BSFSX6CJ&ZhNl=3Lz@1U%{lw%X;;?}am)3U=t54Fb zKbC2KM(sdZt23iHeNMS2En>S9RB6Nefam{aNBi6Enf$uF;C!*svOAzdTUPdgqdGMn z*i0b-!I>6AIN9g>*_Ooyo`_+{D+6Z%&E% zdV1EyB@#IT-PSEr)LoCNBZ%$O%2Qdp)zSmZ%|ZOW~)OZS`|oM^CMrADomgBEmjnskRh9r3(Rs>)@b}!{7@-m!7GYzNDif=?(#SN zuDYLzAG-qC0w{z<<3Hz%^tnaSs!8B792NPzsS;8S0yc6Ur=XzthqSFuB&Aws|IFm% zWPcz0-!mgzQ6AAUpF&?=gb4Cg$J#ZUgKr<7fI0zO6okp^qk%sPw2B_KQDME3%)?#2 z{s=sEuHU)P|OpGzdT{m-o+u~MJi9e2T5j)Hyis`HjG|p(acE*2^~3UP#M~Ks z2hO(Ad&Sp1EO=WsdG*`IU)~K{ff|x|bo0GB<5=e&P^O<@60yZ)Xr9-T$C&Gr9uEDc zG+8EImY+*7ghx&T&r)^e`tAvZpFXwndeU^{MVkppZ))80diyhTAnFd`!#$k9+Yzk z>+Pi<)YyNPro_HESrGq_Y<6(tI3@XPq@h{VQl7D%M}a0zm&nn?&p&LYG39uybnlT2 zBG(z?eqvE_-=bG`+d4D!CAJwQT9C7eCReb2uze9X zfkaURA)2@wENe{t%Xa%LyksmH;Dy+|uTe}{Q3C+~4bA$JRK)dJj)pNjZ^I8h~whw6^(X>Uf0oPd2NvXcxq)XJ-D8th>0{fsR+OnMghX< z$QchZwzn$)S+fUE?@DJWYbm+{z`p%qe|3GI3iEPo<*+sI@`HN~z2VDyI%zs^(=OI- z3EjPM(1YUGN_G$HA+Z|jWAmH4XXPiUmB;69XMc1ZrX&$HP**(&R+P@lfm6n!TW&e;D+jL| zWxkv{Bu;5U2l1jTaB{{|okLMGlwDePJ0pnp$YDfeb?ITq99II=e#(2FSYE6;C(pw) z-joZE7+2E$Qib5~h-$jPzwxe%W`M+6x&;J=C#6~a`1Gy&%Vy@gtTh0dcxdh}lsljO zO9Ndazrr(Wq*`IK!A~YDj{&bwsJ|Db3RLu?yVD|b?=)mxkJReyopTNS;04K~KTd0A z#HY~l+Sv*%V#q>3+ff)QS{;9seDcLbMOCvZcun)1J`kfWrHtSIW6E&Q<#{;jP6`L4 z(W7qFzjSX*DBf*5shSo1LFnHbKwfvT9Y?n|CLD7q-2kYXP;)B&#<_!@1yiq-tDX7P zuUqVwv4J;!GksDFko6OxKELq&3#9V{srv6WjGYy|Ez7#ut20T&RZcE0CeAC5hM7(E zJIxnDpkXJd{0Zo^naRGMMG6XnJ387a*!Hf=RxIKbks7W?g)aZ&qP&sI^OO=mhnnQh z6`iYCLL3iszFL|bC!#dX@;c1T%L&w$acS0^O4=27^2_Q2IJ<$T0nAYHH@x6jhRTwW zSHcasx`kSrlddv2sj?0(fds%n{74M)3zUTtlJl%}`%LJ`-;;RWu>jUvyS<;#h`Y0s zjV`v85Hqw;z#XovQq9KUR4p;Pw<=g-;U3C}e3M=Nd|#IAO9H8siS{glL&I4t|U*s4#NDoA!Ipbxr|rQD{7e@=&0W!*#`Z?*?infcyjH9`y0 zkG=+yj`r7r{`Y1C;LWlB-mJ1)qJmpATgmZA}lKVKAzu)5x~#g=W6i(FZ|L!lk+bqkYn`Ls%%UazlC55zXZN{L>1&V61=4)tTG%8sv4nD z#U)-2#vp6Uj%Z?Cnv|#`OKN;uHdTWzJtyxppgHWK$Hn7k&tolT&t92P#b%239_@c%v=;45_ zqtSD1Eg36pDD^P2{<_pH4$QmK^l0+vUAj^aQs7MwgyQSy*G~;bK|sB2e9JmK^MaZQ2J z=*g?iT_|a~Ri0fIjq#zS6UE;H^?xd4dhkFT0Ttk2PVcZmcFfU%mv9G1A5F|VT}@7j z)>VkQ2in)2BpkMEBwSiAkyeL{|DL>M$jD2i=@;!1$WMY$IBB?uXt}{q@*%(+JqiW4 zS?Ajg%CY2A*`aYdU!BTK!Xhrf>Z=ds?-SUmc0jVI1^;JjGzq6VSU|WtE+!5D4+SZ^ zhin4e+yCzoi9gQeAAL6z!A@Ne&^Lq2>k;^u?K%A~H z`Dw|x-BI%0gOQCJrr4@Dt^HGKSn|$Q{DO>&#Yz0-31NHAYx_!iT7$zy1 z>%dKqIzpvODj&W!PUcg~-avxATC-*m^R`Fyl}=QVjP;RLPWXFdPn;m$=#SaSBrDzG zEJ7rCq*zUpQju#|dZIrOrT>Qw7nHlTHfoCBVwAG-@(KP@eVYKXPiO~;(MWjAjC&13 zK*zNI)=12n(oLLRdP^z;*#0(%amW}j|6$Fl^Sgo)`AX#?b%Ts%O}7;-REQV(bF(g= zrW+8CU=l!Lp7rt`d#Il#PFI$(^Wp2;W%t8xSM%G+D0vX_II){3lBnDY(6Kuy>O!O* zT?9Vd`pUXbf|e-2x$k-Tenr^`ZaujE2T8r^wsgD_4cvCU=L{FFY9!r|4=M5sT%#Yo z>g2pdw0vRoQ*N-DD3Jf*%RC@zI}S;OP-V-wocLc?o`p=%Ul)RvN=lFy!lWENSzFIt zt<7U}*4(i<6#sqXt9I{|;(%_H#>!xrQb~AlMR+BUO=RK_0wHK34Y1x2cGG0vzjc#j z2`MmeXf+RyYJXAp_45O}l~y}5W|=veQmh8Sr?Y{_g#EaK?)Na5q;=z!l0Zmr-8J@0 zP=j8Ytxzzq1}SEwI3E1o;I#vPRV>Ytnr`fk1a0bI!ap9`4@cB-;+v)=Wk zX+Gae6>NvV%aO#2T_W^P3F~kDQBQ=47337X8>h8%ziy8vw|-@(#^&;(EM(5~OM1@Aq|WZfm4)7Vkfmpzf^^Qmdt$ z5$BXdQb{}t?rL0ENjjk~Q7@F{O{PYUM8@_a{Kb4gBIK2Tro;PF#?FBt`152z2A>lP zrRlLy)_HSX2Czd!|5Q+cIaeg2H7X(A63}V9up-$3&+CAOwaF%dMN-ao=i8J%k zkA~+{c5^8C&(WW`fI`7#iPA&w9+fikq+BV|U_uZ05Hn2`cL(Km8yPXGuo2{p-Iq4;^& z2iT+}AF0Daj$r;|bwSM=QfoEx4Sc~)Zw%4v?|uNtPcC}9@As>R@I%M4pzO+uoDzz* zIA9>kf9ZOtsHf;2kJB7;ru9_|8RDx(vVEl03G1OC3^`VE-TKNEF@gLm5>l{F6F#MC zvZ*1B!C-02+Vsue$9(!|ZtUes56g>*lBYg3u1Cx(~o&NrzDvkldu zVi~Ju0zk)mF2I)27j5!y1gQ6~L!LQ@hLsR=&Taa`8WMHT1TS>+y(xt8*+X^jveqyJ zUPM>6fVBjOHW`$3{6{ZsI)YzF99W8&`NO2BBY{YxWvA=G6L@qzjQXx9P0^h*D23uC z&laY+gZqu~Qo1_Tmc;9V5`mjvli8It&q?*-mwMFgxORcjkdFV!R=O85di&FFtI zt>z0Bz+%FsdZi#0c%YvhpCYug{TW^Z3jQr{gB*r6``4T@IFHz^`GbU-*{|)OF0Cm@ z5i@UeZ-fk{D3;#m|3zAUG~n~79JCy^N~K*&Yv{9ou2%SB^oDFsb+iu5P7eS6Q_MZI zP=PKjss@UCPs7xuH4QvvTV_!lEA&`wD_jLK5Jx&76$1Z9sU6FUZ4`%uH=O~jwvWda z@RICrw>fc4b=ThbY#Y6jz7af@^p6Nh@+_zg!a{ej>a(TfblvtLdX`8@DL+M?8R9|E z8!Uvp|BKo+;y`AZ5&H>zp%n_G>KW5`*f?;jsXx-cA~h`^ntUulE&V75@sj^<4^*$r z@Q2hVsHK?tK6^=$);sxt`{BRG)`f{TW5u^O{B-{z1EtU7ULLZa)OP*9w+ z@P*@hChj+{v+OX$oKztNl660~z%t)NY3A#p@IdHu5YAw+gtb%h24J-yjI1AE1C9TC z^g7_$j5V`>YyUsOW>K+*{Aw3``g(JFvHE%vbl)<x8A`UDS2ckar!y zS-lA_NXD9^sDlD)@IK=V=7J&KcStWf>Yc7Ei!ERv?wEnNo6f*hLi@$Bcl_xcK+mLh zMj()Rz5ZbxvwC>|NNKo?ymo>JbNDcS?;76=AhlVrRWu4sjrH*kYSC!?SRvkVY3 z2@m9oV$}sz1y@`7f+_fP^$j@PbJ(PT_$S8()@`;JH0;nZtA@ciDFm@u$2WcU{J@Ez z;?hU4TW#TmEA!~(c^cp|O&$R|_##9I2@XzGy=WRaz&yPKJwMVc)g`XM$hv~REX*Z% zC4u6Zy06xNq&awfOv@`G5iuczhYEa{?hr!?S#?vLH0Qf?CkdtKtq!(Cs$Me$2?(-S zxo!AzsV0$zIaR_022P%#t%g%(;F-qkl7!O{z=n^U^k}%O^ zK6(BpD%hEOxwdbIbdzGN-Q0Qo+6um5(cb48gr(#Q9m`#rB2(ErO(+0ACs55D;k~o> zUSu9prxM$(CJ}aZCh@9XwkeZf-?ih@>N$FvqeviW!NLZ$#CTzo@N(mT7G|VU`a3S- zC)sisn%Zy?kYu8%r1|9_av|mminV*ROL}gA1c00+&0j2NSEK`Rpq9%0g+^~A>^wes6L145A zDNgl%8bgIqXn$l~y?=?fQ3W1^L~63cpb086A(wyt?*#0}*BnO<489>K)3agF9YohX^-1 zus6&Kry1DZ9#C(oUytSKIQj4YV&gd1#w9tL)YGHEU5u+pBH{Nlf>g5tlpH<@8REXn z2K-4CK`Y_n@&1^Z8)jy~-aA(U08VjHbAeSBe)iYsPBm)-g4xTPM~2UWV{ajy+3oc> zpo8A7e0Lss3{URQd>I4EIyI2%U#%9~v3^K+atQrGzX&t)mzF?0N4*$+z@gbizW9R& za#r-s*tmQ`VkQT;981tY`Kc$FknaHyg1vn7?+t zFClGmER?W|`m}YN0Re|GnZDRfHN(KlUD|vCR!--ivmQTPH@PLb0sD%12oN}F`iXBb ztQ!-RU6)-5YeV3F@1u1lP|@)b9fu^UwNoB3*L?~!QuT!?CBMg?&|+g7S&LKLK}4Qm z6=kf+GAksNv-6@-H1tTVnWQ_9Q#s6U!RE8fb2?f1GMoc{mcr4q#rH~j^5&{{A-!RC zr`T@E$+z~#T+7FiwSS%yrG%{XzVZ6Kn>bcy&6hpA8sNoX+SkF?td2@35TXIMwxEgd zbrqGCZbEzydpT=hndfQ(xpoz~-EgR+!M zqT)a?ulG#BsPy(js*E-22!LDBOGTy8b8s5hPRR|Pvof_FR%$S7?pqAP7Uhc%X@_Qw z#G&`R`C-UD(-J%{1Hp^Io;LutS$(>%(6w`@ULu?)sd`haSbad@>lit<_m1<&+dF;* z#-let0`alK2W8dT{8jWQoB#Iug_l*xQ|R^C_j{ZfK-^0wTS|YS4}<>HUCVrxE( zI-d)0&~->%!zj$P;R+WJzFx;b;{J>5;uoOl?B2{BxOx!YaN1S@V1ZD(kOJ@X%*VyI zF}o`wC4deg;Q;cZ<-eINJ4ZJHqJg)GcqjJRVdQUr}S;-MUe4xpQ&CnHGT z=c^(}`%Nq@P1l%FUCR$XZJUp0=AM>6i`35)riFCxUIW5`jx;jHSG8n0Jb8?g@puw; z6`W!j2n+4&V?+AUKypoRAwQrz*!32WAi%-q42K?6=n(Y_d0r$fP@zuNpNJdf!1p`g`5 zQr02^>O|P0>4vACeS)<>f!yU(qQi~Q2D|(KugdL8V;CXI|Lo?-<#^|oPWQ&}SopFaeU~lgb zM4sMEV&|itFi2knpk?P8-3eag?yzN~9U*a-p&E^f+j#QZUq2L@Z_qC|ZdyfK@@K7T zUlLo49FX6Y3Kg6qO(LYMP#X>{VuE>M0LzO@xYS{`NCLT2+eHUxEWsNDPAR}JH;|)! z@V|xsQ$Q-G1ym>n9F!f+TS5V?n?YX5J6HzO)P4^oLO%edi(6Gz0Z%?k?t@tiE>`;f z1{fo~n8Ug+4St@`l$CT-=hg@V$pFU+%7e>!9{^WYQu$cz5EHw>b=!0JUT63IPqZ(FQ# zBGjw=L%!(zT>E#?`6fjQ0ycX>m`0<&YaK@{-mRGDmMyreY2a%z@DWzQdEE#YMhA}Z zm8SQp@r{YmLJpflfnoUtc|PdS8gQYZhQ9Q<4NyxO-0X|oJKkv)nCmSd);Xu9GJK|QXBV`CarEr0pl4KaqKFPL6xj8^Ut(C!9<)%=Kt2Bx^hSsTobM zADthJy03wvI6V;;(pt?-qFBL9sA1UeNs25URuW?Q>#W@|lJ(|L+@1%HU}Jd1+RU44 z@8%xa@5_Ajm+g5l1RZ6*KC!K8nYSF};9$JBuGUS0$v0a=QdINjctu$mbJ3;+C?>Zm zM#!0mEC*@H>tg)NVi6o`n#Mb6*G|{-hXCLPkC2dhM$wB`81ZRWPr^A*S5l^5ToNkgbVR7=jEnHQCjRHIZGJ) zW)uE~evLrurc%yGh_?2P#r(b=8@>D~RWHux%4O50UNjIwK0339DeF z8Kheocxesst#`=P(b$qHQL}08t0?kYxU6mKNdhyJpAEK`C8wC!l%Wt1K@td&U{DzC z5Ighci=?P5t>r96q59uiQ&kN&oNS51^Mi{Ii40*MKy2y98`^@6jXK~$d=f5pQa?}4 zOhF`I`3*^`T|tD}t}1x=2ApgZwe^;o;b0Tn+{&SNM1DvXeG;i9h$)Cyh`hI)*c%Pg zs47)KK=wD#D1>H0^d`M5|NA?76ymu)R}fIQQ11v3PWee1{{$?pA=+fQ1SQ&u?uFMA zxAC~NA73k79MKfTXX}pKtC|-gOq%Gyx~6bn>nAnvbNW%8w3>;+A*<+P&SC$r7GTrT z#O7AUB^*1uik4A>z3VJAYssuWJ{z*TkcUSAVq-(b3D-@+OJ_DS4UQa@e3sU=)+B{w0*KObr@ASF9 z&5=!bG`MKhM8GOamK#^T_L&e z-bHDIh&c1?D}*cXDSk+x=1O|@Gvnh1b2s53g^_7ym1Q#qu6l%)ew<(B8<~_SI;{bP$PRsXA=@rpcpX-@bUlt{fSQ@5 z;iaqIpYub+U6;^D?YE}+Am#;SjFrc0A6s?m!)$dMgO9=B`Y(1ijpgzDr#f!?UuQ1} zx{dEnXGqSh!xR?A^*{c(c~QZ~uOg*PQ<&PGWB07Rt@=(RRqx+Ni1I<0M|wil)Uilq z7|@<)MvKZ5L4sTqA?74lHLB5p_h?Gm-E>jkiWBBP-IA!BGaSWfJJge9>G2= zrBLX~7n$f|8i2c$q_ncxqH3&DvuPQ%^$Wy`P0N`a64Rvj*3I zp$uq*bdLFjIKWWK4_e`kX=3Q!lg&@xtlqToM@D_AXw0>5Y(_C6Rh+Iimla6J?~#0g z>O*f}s-v~Gj4JALI$9Vx-BR(B{NF|uR~Uk{7d!6k*N+&Djazf{9k7PDhiPP^hh>2O z0mL$VG)?iJI>)+szYlzvP)f@}!lU!FbWyZr%4VYBR5ZL2aWQzAt1zpaau211zKaeG zWha)I?Y*;bKr@tv1<^bj&^NC6R^uVX&&7PVROb`w?<7Y{Mn->apIlU)XK6FxUr>9; zxw&zD037!A*IafekyWKG6wyd!<^p+nSEYOnIZUj@m!q9n!a<|Y{iel2DM$@L8oyA( z(!4AV%F^yw4&)laBpFN{DxqL#57PS!aT|HN1bj+Hy$EZ*vB{S&XowF@XJeAk@E9Jv zJ|membfifZnI__9t+}D}vd?+>_qE%wmHD}kf)*NKXtZV0-6VURo}^rJy_^<{lM;UeA;Q zqDd{6`5MCIDp#+GH&ORP0hy7E{WpuzF+o=NxT-4?jSRQwFX=Sh<3u=v3BlDt0?7C{J26z12Nh-#L|AM?B(>!!-=zXzZD)0#g5kc^7dg+n7w1S|o@>QP+K zu@hCu4R#{(Mx$!Ms;Isj*L;U(4A(#n`&ED0Pwd5C_RArd-hK*i=)klL6>^dB;a8F! zy~&(PwyKh1|KH#ZE}0RARxP#`+ms{fd90b%o@L6}HG-hQmyWRR=#204hXt7)xMTd% zQ;O#6W-tp{`Haol{e$xe=xoKd=7@sS6$(WNS-;=f?S(@e)4^WcgPV*f^>Fm8 zZ$~}~$A{_%;5lG8tNQj9*fcU0dXV6uD{5=YC;U;`(mh`UE~{c0qSwhI{Z9KIMvigE z23=E`nVTPAgPMd$|B;1LduM8~-=~|4GZhd*(0gcsmYkfH+D(1(kH{?>;RD%#;DPuR zrJ5h5+}Gk3y%@c2L>H3ZI(YiC{63|P_i*^OsAwdsIP-|-1#Wny-%Wkspo=qYnTJH5 zfD0Xw96#FT(W5lMh_Sw$HY>GL_tYsE^bc|;)u~aBQm1*u*6E)PO^rS~qm$4uT`VP& zRdg9@)R1P-U+TnrB$(*FYwHjGNf>OTTxv0;kav;qk`)(I1pfFoT`wm`kG&bLhd{eJ zHDy8ry<;`L_!79je9tZG!f8?;$J@lkTi zlRxPc6$jF=h-`&d+cLg|Tuf$Ag6(#J!`%Dff4-y}Vs2`h(DL)=Jwn9z;pTjgDM9{Z z7dI*MKb@wcuFOJ`TH3mr_8OMv0$w7x4j8F{@^NRfXtd2p8;5|BDby{~kK=E8bIc}q zq(Y(wZf%mwmkRq$%OgAcfR3$!W@neAE2-HaLUZHjI2{OchYf9g%q z5+8W}WKlwl1uSVvdySJ}_w~f9m{WWVqk(ohx-(nbQU_hwAl$e!kwp7ST zo96N6V@2wf#&;>o?B8cZBu?52CpA|6lg$VrqRk%U480*9{$JV}$P-A!)BzEDIXm0b z)U-ykWbqH)Z7__4!%Xn*(I;8K=c4rb75Yxs4c0I-`!^FI)FJrVt;@K6@0o8V0V z9gkWeAj_P_SBQm%O(--olTLBV{q9yUBl{^Yeu+;IC**;nv)P-`!-VGW)xM2B{mzqY+PV9^*)fcho-g%4+F8QCv`p{1 zMpE6?LqqL5-owHD0fA2%!a{9Q_eAMEMkUk!r74&{$5RNv6EMOUCt7 zIC_Ii0*EU%l)q5^iB^sNond@RK}STux_?-eLYe% za}yauE?a*LPcS4JwYc&u-SKF@{rE(%eL?CkrL}?f&9Qe@`dqQB341U$lt$V^#LsMM$_;p<~=7qa)?MDj3dNX}Fy3xmJ zI0J`%DNMwPwriP^#f9jeQ7zy!+=g)$p+7BkJcaqMq)U>Ttiyo2IzLdYATYtzsrr|w zp;2M`VAP&p$|YC^;`=>iXJF-z!&u{|i&I4=Sqy9tf2t><3?#8=bthB?V#Wct#3s%7 zHVV2_epMR$kcd}V`_cIbF%Ksi-e^UFzgD5nw%}~is4-z(VUCeH{ zQCNM%pPy$v+UIP~*<>q&9Fj}&8rvMkz>QoDkzi4qi1C5F)kyUHbjAO^dH?mC=vi3NXK^pR}ixGH4r4mu`TwSl@P&mD8cts z8OsY^2=}25=5nxQgf8`Rt{j$4d?kQhZd>wK|7It6({Jx(RXxB17?mxy9P^9PAoUSyZ3F%r!!6W3}%-28s=+1be1 zvwGF-e~oYksex{}DN`>2O78R+ocMfNvw3*)kB+CIex0}ySvh6iejn1zyl%+C^KenD zR)NMmp(i6@h&itONvllbhg1nap6Crt*A|O)HB`A}iKvWHciH9K&m`JN*iY2M3#9~N$EQaoi7-pn`>1SY_YX$xQxN5O2zp5e|hgk6#PV^^+q(zw5;_6HKMxGapRC z9dcV0hW3iGwuXSDxiV>y4WA6UN6A#IK}Wa$!1%=xCFBt5#q68Nfbln5Tw62cnWV#6 zjSGL&dF>rzeWghmD>3LpwBq8gi&r(sAT*i!q)--2j8iGw^-;DQgLrh1R?45xcOasS zN5^RTeK_LfAPv-a^VC@&8X7dp&GOTB`wq~dSPIBGO^Ns>_r@Nm{i!4z9MFOK68l$% z83{BRvWiAUuI4%^7qnYUGkt=|dAHsGKGFnGTwagjj13%HDL z%D$y#+(8OtNx*sQQFDs0l<1lJv?8scHqDTOkH}J8S9e_&1|+yG7O<6ve2WK&+&J&CJr@E;i|IK0d(!6O4nvv zLu;X}{%fD}yVl0==qe_eu2WOmEo)u_eH7{0k1Cof_y#ok`5W}C+>)=$eRNF@NJ82) zw$_ohajDOE9ae0ttkKI@d|$2+q|ePb@X$^eJ1NY}?Nv8a&k%kN#=fgT>ieVUDp4T+ zzrwEmW&YZTufo5t+FCM%cD;a{yty?6k{f~(?FMk}J$G~Qj(zOI$hUnr9MyGdQL_eg zKluzMj6LhiuGQcf(CORdJ50pZ;Rg_Mi%%Q^a!TwMar4ICa+KCW=X8{CEfxa04YjeqkrY{Z$QStCRzHzC#>19R$8QBd2quOo;Qsfm3zpy zVrYmE@IuN0;F5kTl@Cfr9&3YA(#PkOM%gy6j?GXG4L#gcAgjsxj)zn-Ofi0>d@{w87<75W5mZ^4lDa7DGNMNmtbb) zvdxSRYmWn(3%p^Q0@`t}D=E(YkC8JzM%$zMB$A48g10Rpc8XHNC2CvkJC&=pk@NFL zZlhxEqvH0Ri=3aQXCnYmQtov5K;pa(#=u3wgkuMajb*fXv@1J?C;A(<{Z{rp=9(oQwN$cMLYLPF8mM1Q&24jH-^y^SwSv<(^9XC|!M_TSqw z7pQv`vP#|c*<7S?8XE<;A~dl-K67IeQ*e;S_>Mx@?=hJmXTR^?&Wu}O1xq;8g-ans z;6{J-eUJyv2JMT#7f#zc{mtIlIkpvgJ~tjgg;ctHyUp|u{`^;H%*eak2QycZAqAw= zK*&RF3-M(jAa$Z&iku-EMkyFoF#Jx-+l(h{7%ePpYMBB)ZEks1tOXjlju8R^J)}E- z9YZB*^UD$N3V?>m^iq045G!kQc?#OpfT}Hud`S^Ew=!pOZW5Z-%604&8lcbyxt~}D zKK+Tg|3HBlwk{(~VZ5*7ymI*2BVhU$P^?1IRbQ)**#G%?lagCc29WE$AI&;lzteNy zW}Utw=SsN6#-AY0d=hrqY|OCXvV5GY`zVBNZ*7?}D{i2vR!p~LGd_nY8KjtdPT}aGlm*5%H%G`DX~>+?>&t0pX%mZr2U?>~Dqf#oFG=@5{NTmPk%{umv#TqTFzkbY&Um$R<+79;@JARFEmd3)kH!E9f8a+7@Zy_C@( zh61Ah%gRWp^CwJD-7E5GT4T<-6q!JeEPH!*WXkHA zg>! zf;-e^sFB;()F10T-CcSN^7|M;AQqo6{rg1v+F6w*fopZ#-8(*;ia zqDtV{A{@U%&G!!EbJ&CDUk9(Gw}#cGuMiyU@8g*5{4z3`WBjWnCBu?MGJPZmAn##e+_nx4Tvgi;`^Ew)&%xK+0YHlW5ZxJ25A z`HBP#iA1@@IwcbvHu@RMRb}|GF8z)m=IZ=UZh~L8J#eK;2vkd<-2VB*7B684&FR|S zdi5PKbbaB-_Iuj<=EBRp^@OK|gq*L2ugDEMCucj+vh?Nj5F<+_%p<{oLhGYrqK*C~ zb|!uIw+O+0vrs6hhhWF^I@8)Tf2-pop`C$mDDSv?GaLn}0D!P0Fzv5LItLcWd) ztTf(W3^)-&ol^}m&02kffFWfyM<6>F8JQg%1J|CDKZntJ;(gv2kTDtfB z*4W!&==~|iup%TvYLN=TIe>vFaZ2Y};aMGn48{YjBCCtXzw(W}-_T#GB@J?BEWbj_ z{Dnb0$c9gFt*dv|ea8-Fw7$2qzDZK9^>9~UI@N*PCFvha(o&b>RH`M4p_62tB$J1< zhVks7z#(f|+$_VI)sO6^oY*~uof6#wvMe2Z>EeItE`g?MXKwnwcD?r8XUx;kHkUd$ zISIaA*}XEx67vsW8obWXv=w^q^G{zs zQ~~D9Fz2BI#?9kg^$F>zX-)t*#k-L`zD+TcCq z{8Rk1snuuolBa|z^R`N7^^F=XjjtZw&}1_pq8stES9Z%@f_TJ;(I^ZSQHV^)Rq$Ew zep8sM*t5KQ{SXCk>p|QTKW?~2PVNsf9kZq3YTOZFFEcO z5Rq6BmeiBYj@Lflfk3Fj`P*2Z%-7pT!)@s7>VF@~TmEi)b3d+1{f)kyR_PLKd0`s$ zK|Zf1fe^OmR+np&iriv@k~rzY&f|7`VI53)Jd?;a&uvsuLUiYJoJe(Sjx8vhI zd@d(l(F~2DRw?Ez9nK`)A3G*x=haL3d9Dt*qh#6Y4%=!);VHuxT$1Zri4`t(*Tuoi zL+FGJ_#~5v_nAI1)KmUCrx+ALa|yKLGsw6?6EVv4E-PpAoD3TpQDq66dc++%Z#iLF zJ1vezKwO1XFn#<;7=bG2xzc}Y?jOncp?80?7H&|O!b%0rcO20QAEf4#5hl~dH#0%@ zLAq=StzP#PI=^7o9!Le#2sSoqF0|Mp6>e1R+^maI9b`z zL=Bpr@a*(j#Ok$*uklM*o$~7u@^q};1;I`>X*0@4y<=mLc*tXTTWCC%BFE;ki+2j# z_W4b7)k>>}!#Ch|r6Zi|E_2S8K$VL~0Gvj}WZ)Kkcp5uPTl)`~7i;eBo?~;r5w3Pz@l?g?+sqxX88TjQ zRe5E2LHseZJp5k1dMuB+vcZ)Ikapa{4uXU68QYZKa+V%uXN+DRy?vD;=vK_}B_3kd zC9dF@jG?-pD}6lp)NChiGHTTjK$#|W)_L#P>b<^EUsa8RZF7ZTdq6ld#nC#cSgzA| z?y?$=JDW7hr*NNE_5EQcC$HnqX7Z8aum|FF#mq(Bf2)TpnG_Yjtn)28t)fGoZ5lP2 z29H2lx?~57-%N-BK&doBCS_XneOq_V3Q@%7%{Lo=CQ!;{4;cd9DunN@+`n6Gxg)H% z`W{0)&JkS zv*P&*qi;pD&5*)9s1m9vxfi`U3U^Rb?qlg&jE`K#yFb1e!-pH zRsa|7Z>}CWE9U6pz zusXMKmnLX{|NI2*kRkoLfCt1F(hohi7g^1wFILTMFDuC%LUjc>K%KbMnjA8 zMm*0IW1!c0x!T6tf$+QbT?=E0soG6VXf0a@%g0Mf(Ud(DUV-3lzn)g~=#{MQeL zkKxmAXOW8gQQ=gZ&0SOT;|wR6ZuD^ujkh3ki`_=AZR=SiVn8c6H!p@P=Xupeya|dA zYpX*p(xAFG>u%S>4gWqjSB-PiQ=!DB}|KGu86|yW=G{<5Fw)A>68kKf+&;0K=?T4uuoJnn6AzuF~Z5gndhXnRjS?XP8CG zxH(ERB4`0_QJpp~SyeI_g6M@L*x<0r3F*%B-pyF&VJ&qOP8TG=1XY)OTjGDL)oXfP zuRqlU4xE+Kmv;lJugB_ks>_9}?CfH`hB-E>C8{KpWjljGa4aa?^;+I@$`wn+VAB## z>Iw~4wH^$>42gt=oqB4yycwR>uD{Hc?i_a;-djT!eBF}_*X3Mox#ID?yMERCwt`H- zGP!g0l3x}=lx5G4IeY7V`b-3L%MpZlx>z6cR;c!sVTHgJ8c&syaV`q64p({Y(XgI> zs?u-!^LjJ;$|YXZ+b}ALE-u}JROKDCNtthCX+#v13tKp1qK%lF>tDje`C%H_IdE*E zYfPzAs6b@SVslaXS1vtVQuwwjMfb?(m=ShtVN=DPC6D9qzzxD;PwAkIH>o4>V=m zDS{{#^iaI>{MzsMOKv|D*Wi2G6h;Y<+TN?0krim~H6dIXc~1+B!-?6IP7h}Y1CsB& zfDVFDSoL&(!eIbgk+bM~?~BDYp{y>E(b@&Km3>cJ?dsdO!itkPF4Mpb^4 zxxJ{W@s=0HAp5&D21W16c8EZTnF&F3k@B&eEO5wW^4TZ01ar6F?_eGTM28i=M?$={ z9prH=aL3EU-go;h$Jb|@+>O2p89z>1L|iB#wA?un$u{*L9Xn&*5sLUV*L*7lB8ViF zokUjAs0jE$EA=VwI59%U%?R)?j>Z${-7tLlZ?J>Csf@ZA)-0VmM3FG_taQ}ow!7M& zQ@hCF&V||8vG4uVPCl`4jVv#{$qx+7WFEa((F^;4CPG90ASM({Xnmd`1`Cg>RNNN} zr?oB2$1f@19bYs35GLQ_IS zH04F!nO={scv~*C{(E zr`Kz+>i+1}`O0;5U$vdcgTqnzwy|Vw1-+)Zj2^|PY~KeTYvW>yEtr4Of5b>J&KPh| zww&GJWNuN4S2Z%LET&8PME)ae5sNA{eI)QU)6B{8lLx(Otisr0y)Jr@ z?)sB7?_Z)D7E6IGbZ`l{T#+6jX$?JXeWZ2lD`5D5+6T0eiR5#?5N>}?(7bPvwaep$ zup7o^W6t(|VG1FN9IeXz%pAau8ca$R))X4P{m489d4@R!XR5uh2ifzyeAC-ux(AW% zy1nKW+l6z9mAWA=*Gcmrjr9;16JWcZQm9K$lMXQzNzXqM_@pao|9or3THx5&Qob5>Hd zGJuwR&*Zyqs+W_wbI4@)iPzBJDYI-nBrk6?PsDcGDBoY_D0jV?J~2YC%`p-HWO1Rf ztC~cMIxQtC#Kd#Zj{79vKEOj6Tzx*{ZS-l`7c=FE$#u00BF{GxpVhIIJ32Zdwli$} zBeINKIeDA?6=-F_n?l{y&zLxDo;JK={W@dlmE6ws%m?V*+&E<61ODT!;iE)P5PE|n(4T*u1%!4^?+fsmFM|_@{nEgngaMtb3XvodkbsdjT8OxqrOgf23 zBr%9eA;yH9V7~d;>|H;ah-lBWsFyCKRB9Y^K1|~%6+y(b1cXVQx_HktbTSc9&RphS zdsmB?oKJtXf%B{=e(RKg zaOGdWT8-&l4Ue%WV=fnl>F;ZXydPsPCoKd9{M$pr=PjfP$+k@`e8WRy_@sD}3->U8 zfC91_k>p2zB!*iZQzwH&TV0xB-Hr^L7!YJc-=bfUOBZ9yjWQW!P+^krPM`huii6%^ z9^ASM@`jSZe_{|P_`3<(1SORP<%$x38c%EoN9y)en)w_;K05$4q|EV( z)+=R6wd^~QWvy~wf;hBZtSkbAnkaPStOQ9w?UtAZ@%x9D#hhnn0H~GA2W!jrIi3f? z3^7ahZP>2bQ9Hk)_GQ=WARu)v;xk?V$Q~V+coCOb>R0vS*II3`!V>s_<#C>=YjV`- zw|v1eq?%Q}fPcE3SY>#eB$#? zdfj_0wuk7^qw@bA6D6V_WBu?Rm4QEOLO!uD|GRf8lA?-A#IE^@#p;$kDUU~b;3EbL zCzpJ?p2?hy{i(k)`IaXa)Q#;oGe%aWy24a;-~x_VMGg5w!^bb9vjPIzU(OorT6-sB zy@L#W)+k7My@EbT`+rJ!Y2DX|3tple`WhJ>F5i^7rfUNc&#>E6D=a$dYFQ* zH*<8k0#SO4>SYk_>e{u5RW`a)mJO$h54bkD9n$(<4mR9PQwt3L_dAypmVS$qxEN|+ z#7}@j^$#h|uDIn^lyC-5yqOQ?1DvLLOz#Luh0INAoY}jTGA3o3l-br-g*barr#6K* zG1hCpl7s`{iCSVeL1lW3&Gqhm-l;FiRj=a(fg&@EfJubrcE8~E$gNtCS+GkrE! zddoYht$)OL|LgapEEdskzRW%LRIPV1W1uGCmKKNK7P=k2w4@$93e2^Bq(eVigs*s+ z#*_+C(ovd2J|1x8+7NAUS`uD;R)*dr$bY`qfV_DgEc3b>vm)hp&PHhHuINVd^|;41 zXz~n>AKO{yZ2)mN#T5x$v9xnLzO}W7NeroBm>Q?td+Y5dqKX<}7S<;;E39e+{kDi( zsj##rxb4X2v-LiftR=;t-guR{)Y^>>82)POa+GG_XkN*K$2r=NMn zrmQ});ErxjVm`lzN=k5#3I5GGLKE~lwOwg+35P1IV6u~TL-gC9Z-$n#voEL4;<-9ML@Rs5sFEeTIo&tzNK@uHbL zZc#Od%&LDb6zy6&9Z#Ra^s2{Z)QAL;?;bJ)$*rK=zE|%pFqV6cyfE}NLR=y3(LTJTiN4PfcC|yApQ$dFZx^kN#t&<*-I^ZlEKOzKMUrlXtQ*9<3CPd zj79eSNx4E=ck{R0t$pV|(+hLe*aO&c6!X6EG@1CDq1wB3@|?S_5D!tgXsig8DaJs!ZF zLowUr#xT$?X2zj6IzZfa!&c?`l8FC>M_D{T1h~gTnm5KQ^-BRDEhYtW-4U1nlvgp^ zH`A`;8TECx;l-ivGA`=#FLX9*d%}=Af5mE*!YvS8|Afon7`jR|sNPE1Y4E*_?4t1D ztSup8`UG+}%&MWs)3)I$KvyIie`mn^qE6i1{H`tp&zq5jjSy4Ug(Sc|w2_sd>@Rbj zzZH#O5lNN$@^g#eU5_(aQFahfUeRw5vI?8BYWbQ(e`I? z$~eDdIS@6ls`W&-_1=1W3I5PwgKWF5to6Te!Q4%~KJ}@erp%arLMJLnZYO0c%S_E^ z?lLNk1xOfR&%@13oiH&;);b=p1a|?I^1Ywnx@#fxb`8u?zeUaXgg~?UV>HZhK5gN* z{bn$}Z)ceu_^FSNKUwN|B_#G^FK1d>R(=Olt;rLf5NAdYJG#n%WvnZ0S}!|#%^?V) zuK?%^O~x=Qx3}vt5vQ@98>#cz`;{|G$=k~iNo6EO;6Faoi+b%2N!~qyXc%Jh4z`Os zM+2&#Od(*!Rqa`i+c(Y)LCv}%WJ7s2(ae-d#LL#1?)_=IB!$v+Sw4i1pRe#4NWWYs z40sS{jW>C_5^f_HiTj>~db0!smRPFUPQ1~r;&_HrI@w8nj5u*Mi0rrEannPYHPq?Q z4VGqmxYuqCf~#H_m1E8%KZ>1ZoX)8*0=--2G@fA`)P0zraKI?tn_+x-1S(%;Wm7UI z?Mp(wTX%^!3HKCal!$!bNE07sh-=mD240cQ{i+XJPC-5|lsQ!<0U4dxE1+4kFG;1C zb29Wm`e)^D^`7WpGhOb)yyMMNJYxb*HN3w9oYIVSpuDGh%yJLG;E$CV=%bo6Hl(Em z8z=(qFOZkWSf7xWuOWw%ICT**YV=(=MPys5n0&&OT5DB?_Zk&7U#pnk{PODi3X1J{ zpgMxdRDqkLeR#bY)@^9yZ#wUQv^dsAVKMwZ=u$=}E*0)Izgqhzu-4N;zxAgf)!UK+ z%j29$0Oxb=a~m7h_9Ab^*(`nl)H)<5o!mHp28QG+moxG~LuwHJ>R;!ve;$l&v!wTSt&waaIi$L+c7 zYZ~xmKd5yVRGAUfSS1l5u?9Y2c0B2lte*Nl`M%r^Yj@ULo(|9^%gX&#P%Z^|Z5>e( z6E8upOHiIVch@?Ri!ez0&T08v*CnGy%U^?@BFSFOMo4+*$GzJx`(?e3k9XR{>LXPm zN}4`6>?f%*@Uq}1bGCi>4X7%$t!5`hSO3YB0^GREK9hj#MV|%lO5p}NX&lg@PN;=F z5-|t~8=zX|YbN?i6I4rup%)Bv)6#TgK_OOj74^ka3U_#`h&{@7R49UC4cfMkk}YjC zrK>&H!ogl-cF{E#1Ln0@@O#Y?V;f%FHX4&1;dz^O3eD^H0;<3Dvdg> zF7*H?xhk)~_~$gYt+Y8fPsTQ_SkZ2?#r6QPild%$z-{V}5Fl3R8~?zeEhdlmZJL<8 zjk{U9%o@Y8eD6=_=bdhq$?BSK!MMYv0zX)uv{tBv6bQt5dC=)J%F5$PBTjJG81MpM zhS-%Nne=#L;KFBaziE1p#%$L+zzynIWmmPH#p>Q6X8luf2DM-YzkG)npero^oYs8ywPPa&pS?g7}EWHfhrj!8h9xm;W=Hw(9@w zMba>M+2H7aGYKGg^Yb77FB4yH!}$Qr2C*}O79-9tUv;5ienIyG_2P1}rXv~_b#1wz zq(t99u^R(SN!5YYkdCo<83WT8-&3(KT|E>fX(btIg{LK@Ro##Xmy%d$Tr-teBVf;* zgi&?{(TY?l)!0|&H`jVRow=PpgUeYQBD6T+%(|h5ETNu`%3r=LT_u-WfCWa0?-{sn zG*oT52A2&05-+=99ySz!g0tpV^IDNF8?{#zrWvT^RS}}~B{p*2b{K$(2WyaN{7$c* z7%R#T{E?rgP~X})IEWbs^R;C-IIH7(^U4Zt>6Qf0)XUJYnm1|4Y(gUf4z6cw3EKdS zfh*#Ej{7tmMoydCV4_x3@3!_6tbE=Uf`XR;P-0;Q)axO0xIE|}Ak`c2ryDowv2BhF z7T?)SE&c&?m(B3=b%kIOAjp>P97s}Q`Gy#jEHZp-R&`0^H_f5RqjTw{^o>j{|N_$6y#e; z@t=`d95Kot^tq9p`&CIB6U|QKeSA#jXzE~+KeSq#j6}j}ThJ1%Y>7-aQ+i-IljuZO zH(8Xgj*HBWNHO;G)$87r)3YO^VkZBM4%ak1vPGRvBkZ{2tTiF>)yUDo4n>NvA)XTza`G?0zr=iALi|HF70?Fp=74X$b{x~yso(tKwbjv0s z)&-M(rrWmi1r0}#kLk6WEHWqkp1yL`N{_zRU4ckz!_gf=|CU^RhR7Zb0|W3dBcm0M zj>2DDxQM*3{6pusK%dl!GlU8&uClMyoYjD$YYlbDBA(^a2^%8uHkZKoz10lg@2ll1 zCfl|PhO;{BK`K_I3_vwZtid1W8a)c0A7kv%W4AO(vUPH~TC~b&`VVTGt2x40*zm9m zgwH6+is}$iU(7z-tTIGll6j-1NLt>Y>b=9VCJO&1*A5Z?**5>UAR?1lZMwBT+ix@5 zxzcI$(LvwC3k2am&&}!A%+uG-XT6GQrbpj!rqxemEL0p6+sQO%sgoSm#Scbl;9_SK zXcJUtswsqJf8B4)4Xp-o!@W1g!g`-okntr;W)CMsnIrV{k)bF0!6;v)ByMyYr6(@p z1IHkGfS=IY@$Zq;Gs)E(FNcd5lZ$ffdI7ect(bZ_Uv0kn-Eu_#Q0l+s$M!~vSxw8g zABC-{#-QcnCkqytbS5ACbI>7~?8|@HAsIj(X06m+%=+aMyy$AD#Y~gTSlfCCsq9Z5 zyCQswUh|CqfJLBj`QKBS0@gm2@Z7GwSluDLhaPaQ*4FZnX1#5e$v0cqoaj2s21YE; z7rNrWqO%Z5-sUPUz6c&S)Xnb8vXz~Sq_QI-(y#VLFn;ZFA+^+s@lkzE{N5I#-|%Ip zmaz}ODBkpuH5|VKL{sB!>Dr9`FSwvl?pGBcG@5h^SgqQ)Dg*7-c@wMCgoGQ@^bsdz zY2Q()fXCdlmpE%nQnq8qw`$T56Nif<9x%7Nu{WKd#bVXG+U+0rzdSLMwv7mI0jWgkCp@ zm(ung9AxYiaEkL?jmniYgFGc7U@wsE)KQBS*Mndgh`}$~##Y`8rPgdhYi}8_>9c_WTjM8h@?;H`GMvy@OO|H3y*d zmVTebaD+k zdr*t=%I&lfko_U_)<1PXsT5OoKT$N6JWQmO8Eu^1c3N|D_wD81zaty&q~}^uU0tvf z`|N{LDg8fx8}q)2F|Bp){vL?4+9cFL2!?5d|H}_xE|Op(NyaQ_rnS%aj&Xa+jyvv* z^cYf@kdUIDWx1MTBRKLiZ+ku`eJC>;yL^`kOrhGR9;bJD!w6Piofr%B(#970R zMm$4jA|FI2{~RlIDwBa>lpEutx}$sWM~xL0Q)LX_>DaI@6{E7-qo2(*;e0yt{?f7+ zQcVE1l%3|6p&aDWK;h~xun%PJ#eDN-wP>R`bztrR?>9!sL|6uA10B)gO&jidNNejS zmo^Rle?djJ`_L-Rt7VY)sWhzS({USdUANt1RT@tYD4wj7 z1dZz&BndViVfUR-JVnY-G5ktOtPl|&zCCmO49IsitJS6|Iz72! zsEKE5h88$sD=-&xuqrt8}C`lh)z1wPm0Z6Ted`0O2+E8S?U~DsEFN;vuhn4 zZ{T2`DjL&k1Omm~Kvh$rddmni8vPI$Qk`yqCW`dF(8@#`&lnlJrh21?O7x_!YuJ=) zMF?nLQ;!qXO7p)t0GmlHoKEn1Hdjd-6kfVv8- z2t2O1r*3zO<@ZrUX>oxb2Qfo^(!XTzc-p2jafdt{}P;~SwHod>4V{C!wCJC ztiUbEC^Z{Ca=YT%A7NYHX0)Ri7+UB@@9f4&N4<1WOAhPB_C zFxd{7s6GIog!2>v@!@_`wQ{zqu;Uw(WO<$>sx&!l#ZN$wh`GXHqvqJ$D;Sn#a^nTG z{>d+7^kza>d5cuS1VYH!rz^#kTZ&9E99eV(4L_8E1}#WK zi*mHkW$KLKlPm1{UWtt8euG!4hsaURw&7J@2HN#Y_nD3gPU_*%&nSFBdnO1yyK%OT zpEx@G(zc#A=x1vjKS>~_j*Lt+2uiEe(kRb%*q$eyZ3i%upQSul1R00rF@_blC=vu5 z7>ONiv?1#RVPzyK_Od%36FC9`79$viGCmv?1)Zm$pjnWLV7tNx|4} z!7wt@={Xvn_&bi=C)^H9!D$e!e2PPt1bfjV>0?A<=qWdl*Y{~{PoX7uRD$lN*09^{ z!fG(qi_q>&Xz}(E5tA8+dt>oB6q+%`Y~!f^jL3g19{6ZoBX#Y}UvjV~e=UquzFd~i z6JFqvfyroKc)YCaD@W0L<9J4cKL1rMM2jzm7uTLY<@1^M&Lx6*)CUvXV0@mRa5zIT z67hrtsp(i5*`DHhZbbO4X^+)yj zw?;2cH?WqmN0;|%Sb`{joOJrR&Wj6(cDlHu^dS-bX3m;gz<=7(eZ|I34l9b3C zPK(`_PsRS_r#Ofd*}J*jSfkGQJ4Ka|s#ym4`Kq`x5xCZ$EjMI_9f$lWmQGo`E76C%hOAQ}&Mt)Tt+f;U7f z9l&ha*kWR}b>Ptx6O9+luGSo6+{2j&Q9C@D9>Td@S9f<=Jz>PuO$y8&72gyhgXin4uPeGK~@$s6fHP(gTGVG$3s?2G^7bO z(*|PrS|z<34?N#ki5LZttXZZyFTV-LROMw8`gaf%7Q;-k)1=5GMvBw=<8$m{Z=8y z1koRz_2k&mctflR;LT#&<*>I!`_Km%wrCJZ0YhJ!h=PvZ!wSh{tvq~}N|^iMd8cX% ze~bZV^>WOKq~Lussk%?Ox;KpMB9--`20+r)`Bw6|S7vW{X6v@(6k6FT2A15o7q8N) z3eL({*_+t!O|w2T z-bX}P7O~Q)_%1r@%(vVpg_*ZcxUeDc0aw;!kLOFUq#x>=B_Rg&tsshA#PkBw49Hbu zFqokCm;j*x9{d@V3g-P?c4U=g;CrW@A1V-~<`8^DWk;ogPV{sB9HGz)k&+u{!{S8z zj3f`YK$f!c zUwxHl?vF%oYqigQ=GQ+aT3?4;4XO1A9(G%hl|GY-Rl0O2AH zMQxhl=N zs!G~$;Xv4CA1>*8pcO%*!DW1YTJs7@rKr)9>KERhS!oq~4Oc^Aba{P%=wFsCgib7l;OO+* z2YVQFeh|!woIK#!!QBkHB-WKvuNC8a-iE@IA(H%qm?$8R%pj5$%@%di;VX|M=%^L+ z8#T!H#BgbSI;`#QU`yuS>ge#T9h>X3x5O>U+E!P-Ro)2KE9V{0!m8_S>oWrB9nE-IiHOFXYT)FtxArLZb$++Yd@wyOsFTe3J8|IPG3$<+ zym|$FW&4P&Cx-+~2|F*Sc%-gdJ5-52__Se#O4-m#nLnyUCKh#>ljb3*xYQW854hTQ zh|CMt@A37CE!B=A=G4A>@BC;xLBy}7`njlU5dGJ1L4R5O1k07iHR3nT=;C|Sg1%!4 zao=m(k2*fb)fLwD1GCN3$J80OHQJk}u(r!Q-mTmTTY7Y#$iws#Ul;ndK% zTNXShp0{MHDCPdNHMjiJ4ti3j`3Cc!mn)OpRc|BXAw*+yn&b_`r1|L!PbL|k2>rXF ztrp89KevyVvGij7HW}xw%@$U+b|S)B^gUx86B21p!3}Zjp=FHR}u1 zzgnc%Q&ucC#_?f6=lFu5&c>G(35->omS(kZLD3;d%i!7`^!enEVkGl<6U)TVc%%IA zEug`2NEzs$ptoPpd{_kW1RQ{m3FT-yMM$qyP31bor z>v(tK+TRnG)=2WCnHWqm#~fLZYNaw6nQd$>W7nf9`@G}J$#GMC4;LG3t=fNmWnO+P zst5IMkfJv3bT|%zLyuLbnb{!s24id<2j84D42cG|0jaqZ$?<;qo7m`T%ipO;1A)aF~WhS%9U+{SWh@F9?!| zH~ChCs`uOxNi{+5^r>z;Mj(ep`GYH}ueU1V22~6!^>hxGOyyBm+9(iTrx63 zLY+&N1L_K?Mv7j-86121_mQpM!Y`c*XxKJ3e>H-Le@*$Ry}=ldu_nWe8#8UtA$5Z} z#Nhu?yOvJ~-s-_Nd|O%Z$Rh4qhDlXl`!P>2p{t_tJ&+**wzi=F;KodiMkCBGJNs)G zxMS#^?AcuvH*b_@W*w|q2?pwfc^6wRMl0WY@rF`1LB8dl%#aw|azi4$2 zwQYRSSnE5898tOcE7+}Jy}ky$u!X%Wvlx>$IrP2CXNnmWGBC0G$tUkubE8nrDa*1R zguQk@V`}L}3bBk&YjZxEI5>4L)FzieLN*jXViu&`I%b~*Pn@TU?Qz7Q`_9MdqoF3r z#NQ=CvYfo@uOZ6>mGqcjbb@inVS}|MM#6oHG8OUfXHLCv{E7@7*h63M{)EKNEBsJW z><*S{|8;ZPV$*(p`tTxWczoZ&!`c6Ms#t%mRnwfVY3;JgH#_0g-XYra$lwqK|Df)Y&E3?& zk?2VfD8$h*eZV((>MG3@Z~3Ydfkk3z5dlz5#3@yJ6$r!wVgX1aISGFGaKJ{#TAPjy zXa0I~w%rS9he3x8l~a31q%K&8kWAGe^xg{w9hb~6h>RZ`wTF208e4V<=bv3U#bQYtypn{$$^f-yVsz8ThLgv{e zefmme>?8c|+k;n$I-ai6sjb|CoO|Ap_d7vt1?s}sj80s@f@_6dBN8j}y$}GiG;?tQ z>(0za0>MD-X={wlfui%6%=yGPfGFx!_y%O6VEcq6m8w%R*wx1P5L)|acSPu2*>N;X zm6?=zs1fu2x_`#t?9l+P&Vd)JrzI3BiMVf>o{w5}KbT(RJw>;r07BNwQ$f83^N+|w z0co%ZP`vh>-~m2hUM;t-#?J^*rxus)*o8;zfH1QIxJYwj1Sd(=VK6_<$&51!g-2`< zk%)~SJaGo#L=JvUWUSNH)zDFgJQ=;_Ypp(SMl-61F(~_*ELb7@Ym#K}Tf=A^-8dLX zXP3YRBUcLpVw@j}@m)@=3Pz^0TI|8*DrDGFsM#79$+hvO$#PPuZy~xzH&_U~e)>_!6Q=*hRT^&N4)Ar|lK2nc}8+!W?yPoL-4~zu7 zEWcTuE%O*3TFERefq%dK*V=%1b6ByqZDX-xpP>hp&WBR!siq#a(2U}F8R#uOFd5$e zMp}^SgjiTde4Dic-xIb-b7m~>e-4xXy<#1sUIzMsXRjs-gdQ;{bgXcrIv3W%utbo@ z%K*VNNvPoZkMsCt@djhRw%W78BGYDwHm0k976Zn2)%a>3g2EjHe49cn8vahi#(&-scZ z#tJKvn*bz)QVXqF6$UM_(B16>)q8M5qP)XJ*LROR2`UgcNG#OxvXksfDiU@AFjw}L zudpzDqnkHZStJJWSSBrZx1N7}zC7sWp7xVhpZ2=CiRa;j-W(U%o$KxIROl{cFU_6W z0T7`V&)PLo#+gpW`P(3PC6Cqn_C$e6_~?fMVO;$|AFQ%qOzA-~Zd^7ou!cccp7H-A zo&^Pz{Izy|;gUj(7hOv8uuu6jZ0Ns54gyY$pgBBjd#N1s>SmWx?)FU32=!lKQhI~J z)hu`oPU4EvoXU?Bp;(@>zJ+#0Dda&|CZSTJ=oIzRE&QOG`K8LkE{d)YOHClpaQ2#@ zs#k)@1LAkJiDgnXG>i}Oym$|zP|!W+cG^Ks9%QNLJ&LZ{AoZFApV{`aeK+K=2}rMT z7KJ7Z0uLNFr~qQKqE4mi96(+@EqT)aX3+N4!zCm?Ka}g(jTKcR%y#A^bq3stdoW+q{S~0q^=!9p74Ui$>OJ8BW>Ff5~EMY(N4Xc0#FvmID7pEe8^5$?gK!@RO zWDr8xv2Zg=+F?u79R96QcT68Z^5;eVlWUCmW1thlJeIB*n<&Qrm&ZNGy@)^1iIgg9 zWxwFx6Dj_ggFu&Wo$LS9*kq^ekq}Y8yqF@S9kb%>%S%5lmGYS9!_lg zpDHvf?e^8v%PzewL`P2aV$}cWzVod~H_4GHkr*cG7`Sp|?gKasEmZEz$=IpN1V5mD z2~h4^;MK(Nwd^|MQHChq~+HKc-L#Ey`nU%2P5)MHsR)WN9H} z$-Ye`%g|($5fhRuV<%*Z6fu}&5QDNzwrmg4SR=-svTyU=nV$FazVqLmyPbQ^_ndow z_nvbv0mNwWF3O!hPZeu+)mwKBNxcR3`T?%l2bGDRK9#m`q#3*z;W-pI*Lg7Wai=_g zoApbBoBbh6Ukg^A@)P{ z97mr^1R)e&fNLFSWnjs=T0v08tH(JE)BS9Dp=S27@}7X88E~@m;pp)5D!eyc!Z<`9 z%<(MSL9SpeMiPOEV#POs1E`|-<~-mAQxcqmx?j=Cisv!$CbHrHj?zPGPS7}|%j=_??y_e7j^98I62F{YZcN0OhLB6&3`d}=}v8=DJ z{F-ed0FWXp)(Sr5{>8J6X6Z64 zO6bb$&&zfCEZy+k zR(>TA5+fC#dJUN%Fz~7Dr?1S|9q+uRTC5pZL1yj&00p4a0ZYy0BCD6}rZpUA0J#3< z&{0T1-?Mm~6*AzWx}^k)I^6DNKF*JGaNQi|E7awI*IBS;g-CiMK@-4`s)gc%`{=k= z)%3-_fjp!Ifq4?hMH))TEGVqZ^Efz)W5Y2UZH%mB{ z(i(#}s8DGG#|5_XAc0g%qF^e43Rp+FIzJpI!lt40pQj>dS~U22q`K$9z|;lT!je$L zW9BVM#}Fu@8rn1eg$oa|A3v9PnGde;k@1x9$aULyMNo*n?)#JHq#Xj9lP4y!GMxwpvUP$hWFUNrpfs_5`0qEyayxrUf!} zSbQ*l*+pPGGfK8!7>?q~M7?igOT*lz-f%B6!OT#Z_- z*M@)~fq|D6=#HVG>IRvSZ%a~T;P|2QC&g!LaiGGItOduN2XPAaFc4>cUG4XS*>zx& zG=Wu>vKe*qob>Of-Il%QyL_~K)$i7*rf(tBymkTDsbR2~aCG1O$VYU#!oSiwJ(N9t z8$<(O;*#{GfvK|U+D)APiaCRn0V133cJAtUUfSON;C+=Ww}ya06Gaf-bKSPw@YJEk z)+@(c!K{pXCv%CXqf?uc_;}mz`$BK<#MM3UZ+no*=fz3<%2Rl3O_LkqoZF?4&vviV ztFCepR^H69A*iYWAXt|SzN>f_R~(a%2f|>$$0ClP8FH;tdMt-uSzg}Zqwnl!_n>Gq zc+=A44N2FZ4?f&pwZ#&RRwNKGPe+12j4#^`_+@Bt^1&%Jcj4Sx7ikD`$7{MN!Qwn^ z;ojqY)t&N;oD0i;1;j?~Bff~s(40ZC8<=M|K*7O?3(t1>`Hmdj2{7COq-$ zU;d{tsQa!ZEa3KNe>T;t0o(3*!J@AZXOw?QzNk~|hUiS!oI!8pUX|(pEclB}7(dwf z;31!GhVil1F`mVfZY;8H1OJrwRJTiV{KJ!zCL36JI)(EyMUadD2J~NjuKUos*tP3>?l)TDG?_>to#Iype?@0#E}r`XHMX)wS-m7on*w`r9)kc& zje(D4KQHv~Gpi}3BzX}8VhdRZywcpIvV}x2Hc3(d+jw@hB3wX(^e&|!hWMkLDduXrw|7$TfaECTO)zGZ&16Dpp;Dorg)jUqX0pl|>!oBu6R-#}_C8c@cgza{* zm{qhu=7B%TxcXLtiCPebPK31vHoF8)K&v)PvPq=9t)CdQwQREJU0phuy_@{{P1>qd z(tTk9SZk`!{k#jN!~7p+YFkO)Hkfn#+a8*<7@(GQ!To8KffJ@mK8rly@Da6`jH8hL zF}n}M-}zRZ`_vM{W4_#0TBR<5RXT_v(>)th6O2#xq}% zrBY{_%dZ$(f3$q<6C0vhh^6XMv}LG3rpxC;f^b}Vgu5lj=lT^n5eZHUjBRd=+bIXC zxXQ{A9UXqy&u?_~@rJRw|JJ1MQv4uuiKWJ`V}LdcH2VK?t~_?ThgUhczhbc>)@fBk(uQZ zJ7WK|SD3~Z{)++Q=kUNfyfBk(VqyS(Q&<|qI9a{+#P&@!X3|Lum=0X^-AE#?mS|9h z)E?-Q*{cF=GneNk%-;SAhpi^sNZDPR*oHXB!ty7dnOwGT;60KX*4bWn%`Cad!})vW z_O7i1y-`JoJ^SUIKfq7!a&!0=dN%raf`Y>NfQ}vux(&6IqOtRRSaZ4e__p|X3sUa3 zTKZnOQR?l%vgayoD;MT}`z>{+7dS5QB1X7sJWk5>_nJ2ZK&IIBmOdgOi!m_Bh&n&z?ql zwsFtpdzEA(vuaJuo*R;n@_^+85n$T%%l10&HtjmyYl%HekzF6Q$we?oI}YTA6JSyY z?RCx_e!!z5MPL1DHdL@fqxg9_$Bi$%e0DM}PsGB!REo2BRANdZ(*<$7i4u>PPxWH_ z{g-e0Ej3_VZ1zHVXR$D$yUI$0lDO`^Xvs*cjnSBNS!I=&@-?x%Ct`VCI7v=^NNC5W zy%~o%`7%VpYKcyBj6Nq)(XmEV{Q4oBB=)gRXWz((kOh>J;C51jbO>WuesAe6c;Mjr zXehzH#G;qn3$AQ%7;tsGd6i)(LpOqgb&}{tK_VKnX-J%W%nh75q|{7 z6+CUvQvX&h#oSD+&Uttq%GWOAkS7vgjMAesWhGl5`;+_2r`m8LxPw9BO9$K`Uj7lT zc3nW*Wp5E&{)$!tjv6c;_VoE~Rnz1BkdQc_oV-I+!}`N6m6$Iz$8yyd1s=5Q`?ua5 zPCh$<`=G6+nP0j=;sbY?nVS{rn`-mSt=eR>9W|G~sTbQ;toj(7II&xi@K|yf;%c4M zY#Z-UTs}Uj_EUFi=vz#Wc2b74t6s<5dUUp;oYYz-5ge zj^ps%QR(&sV$8F60y$z_Fc)AFs+Nh`$@v8Ay*iiF?;9#AdtxQTQ+ zgNpprV8HBHsC-oBeC}{ai+TZ4XrKF;oF=J$yv#ob>Xiet6Fo+2wjYVLJrSv?0Tr(q zj`t+Is&Kr!2OTUvZRmC8Xul9Idf>5a)^me{i@XI?#ak};c`?OXck%O*NtJ4;lFrsl zCB1WU6^qRJ2QFLwSzrj)1wcazy1y^Pl(%QK&;N8h?|mTr!h5WD)y8URtfYkR>Q^hD zjXBE~u^-FngPzow-AnZc=N2<(j#67bRY+wv8yy_wJv72~Mt+BAO-`=LqWPDZ9MPe zd5wPAys=5GU%v0_^h#}B$|1F`NLxI{50Cz9XcBO${idh~@E;ssOe#KKz?0z@X5d~< zUU^nf=(+g~f5j%{!&>1QZHrg6$A#qK^lN?5*HERxOJ`f2yqpl_H={C7vtHKvsP7+V z`1u6&@Ncx>^z2Ugz-d}B<_psr>G|tM+gAWg%}F2_q%Q*mXcD8GwU-Z9=d4s_X zE?^{Z$-FjaI2(r#{?bF%SEADFixy(PRCDOK>rdp8^Yogg>jry&3qp6V2MI;0E|b`d4#TN!3{8n z4)=OLO7-_^r_VEgv}NZzQX5WJSxs(`Xj?Smaktc7bbC1mFLfeP{j2BIIHV}#J-__& z_Jl+!2AkyXwh_1|^2!Y7WP`;=-Hm=RjRTg9hT_jtqn6^k5it33Wo8%GX} zFV1Bjwtenz)sPUU1#~s&VivR{5@a_vnNo~Ar{aBTCLS-|oP;->6SrTD^O{i2WzJP( zrW$r{Q>iWUGn8y7!eegp36Z}^N8C@TO;kmC7|OYhCo51|{D&%AT%Ii3N!}DD@}g+E zCds|Zg;CtQjg9vNW;AaW6kuU@4xY$`!qb-R#-7cRE|lOkW5$}6@V|>)Y^PWI{N}vO zYGC;VTh|HiR7hU#P{ciUPpu242wCcCK+7xf4)wRi|}k$^6CPvb80FVfP|=9=-KZnP&DLnUruX>DSZWXdO@ zEHw;zRGXSO(h=YR6FRAH!~qee7V%McE|zhGO9J-DcLCr`+i*e%2JKIwo9sf{Q!9Ux z&LDZGz;6(~!_LiwcfSm)mkCKh2$HfD4Ak25X)oc_i&sXx!ZP|sa<>k91llV!w}_q_c|e`9m1g<6Q10{Q)r9?qc^J z+D@P1Q`&DW3PDl-$gw+Mbb==`5(ZvphQTuYjE#-GWI61dy3exn%C6KGbtLumt$htW zV8S;uWH#Ca=^8n!$k*iLxv*K*9{ArusnyUdNup}^uY)&>pa?~Zy-S0F>+Azk)5Xl4 zBU~E0OsBpVne2oJuZ8JF=Tj8*(Z3sVT~ofLy;}cMKrdnXyDqQjPADTu0b}(XyV!)N z{?eTXE`iZ~U-YuXjh0waDW_4Z3IIjBp6%q$wC}EshqN1i)6$zC-GnvbyERnE~a;j&Xi(fyItLa6d2`2YE7J_rhK z%-|Mz_GK@@g7F;!7k;REJ=i9L^da-NStG2k7SP=Gmeo_R*38ovSlCPM3fL6hm4ewS$3jqGO|Zm zm65&jeNOuPzTba-Uj4%>=Xt-M=f1D&y080w#Odp4&_G$B5D0`u6QzcRKu8e~2r=Us za`2OLH+w1}5H5(OnzE69=FiFHB%a-1-aWpahjPXI0>yPj#llQO+(?7&sxLUZ%5U*f z8f%h zwSxUB>gtN#6~E)J`2BFcS{NtBpVaY6j$2GzESnCiZ_M$inFr}Bw=a*M-p`t5VBM8A zKrr^NG^emXE>5jFJkGQB!2QC4QIY*%zxzR{qTyiA;ndpbuNP!s83qR3ml0ttXTDkQ zs}Mo3nlC*A?1iwm^~$eW>=IKV`LmBJMfBYH-yeML^bZK0JPZbJujs!S!`?~>so7e! z|GD~$$m8VsO_|WkTbr4_^9MTJ<{~H4YJa~{uCMOoyj~7w|2g(6Lp4hWwjTw1)9~BN z3LceuOL?RE1o6u7A)acncQ#{sFTg@($b#N`zg^T+S&>dr2eUG0AH_t$Y>`zqT=AaemOGZDQlY?y1{Q)WSktocR5 zjyIf__vlWR>By&;o28OwCL2TddN=0gY;)RIzbrIgfvNp6+U__BItMmgJ<)4pu5AR; zRPGAv%&X!};6i?}ivI~r7zfM;mG$x8z1xGZRme9~5; zcql)*X!+pWb@uzze9s>QuU=YmZ)Dh6){7+U zB+)iaV$P!zV;nm^cg#n#3%T3jnp%UwEstKb1z7m$NN8()->E`?9l{|t8y+mb{ggYc zoSyLG+MS_1I^l|BoJNR%8inifdMiI>CTc%j7Pk2x6&-N>QCTi}Bm!{Dwx@?}YoS%O4k^d=| zkGZtg-~T?SdpVU(yXa~OOTzMT?~A8H_i{s+(KVLA-|eT<5=B}mxhB#g&6rH=wO-!K z%~Vw;{F21vH#8@!EV*Q{H-ZHO=lP!Oj5sWAYM`H4FY@caY>Y9inRWZlXK;3eufdYS zwu?`?4-^Wgbvcwa*)V4An+47^$cCT|Z9`5pNCLNSLhK z*fV)uM%bj(eQKOS46${FMy@uerQ3lEVZ}X_4OM)@E}uMS>*v=w2bI$_^IOET)ha%Z z!8435FuX72H>`1c{5OMk5ZOViUq=Q$@fZyWWru8iD_c7!Y1|f)y~*#=`Eld+DzxP^ z=3=gnBfY%mFAt~PppUO*MeAkBQZ9Z>+VGfHxcftR%ZFN^n%rqy@Qc7S-KNo@*X+@i zqlL!(8zK)|sXnnvyUz*#>Gb>PZ}Pgk#8vLF%Zxdis8z%|UDCzPHRff>sR1S31CsGFsL^!M|jg%N7+x1^`)}VA+=m(a(iM&bLr1g zNxmiUHtEKVZB#TYM2P)lR`Iym)I#>igAj0RY0ELL9H-}7Sn`0I;kr+d7dWHv1y_!G z|DJM>*DKSZ3MDM6nEl#XR1|ER5m#~wGYY@Gml+Ai_1-4^&$yh7V9MVIIOu@%)qJ|h zK({vjDR(&G&*5FNllBmf?8{HAO-&pZMdMf^G7BPM+i8g(J!}WeWsgd`FB0O#=kBI8 z<6lhf-!f3xpQw04)P(kBfLMQJ^4A<`#WYH6mCAKpDwH-@QT{vi@0o7JuD z)nfPM*a7th{!W>DD?AV`@h8pip1gUu{}3nqs`ra~1_i`zGbjCy87&Ev5cvEJ-zk;d zenXy(pJy4DdtM=U)c7vxkvQF9*CM2g#GkzBj;{B@g2BYsx){#-ljpmKM-yy>WJkC+ z(9Yj+-wnzX8I!-9sW>t`;5on09p?_P%O<^<%Gs3nU#K`loY#N+S%ZQo!tJ-?P3dQv zFNq-0_OnMJ9J@p=M2;?O=_K?NrQ|b!V(LZdVCS0=&51Jd_>Ks94{Sc*E-c zg|d-G$to=FUewa+lqJuCuFv09Za2gTeP)lbKTF8`{;hR$IXlhYEhL>)20!~g8;I+g z`ks&o{_sXXs=IH$H2M(DGaG4d%MnJLQ|6{hrhm0Y@pgKR0?{UddfSZo;GmhzaAWB_ zwX)%4^po0%M!v66WP;zzYc`&QQiEiCb<U=hvLo_dMB{0j%RygS0-f(0Ra9LM~L)O7~y!&H*# zmvVF*$%&3H^X(J97LqtdcT~^_of^>)L8FJ+8k87)~n!K-P%gaPZ0#+n~j2B@d zU6uXV@O>QUFEI`)i4n=Jvwvb$p~ec)Z#T$L81fe~VS-%6EIgVquKRT7XjF6tA8F

((%ZrwfGx>S zIIj<>cl}+;9+(qGtTb5H|Iw9W*N$w%oYAbtMvYC$-t)p$f%Zq^!9Obl91}?llS@ky z^LO7*4G@_rbr54oxkyx)u(vg(@qmGlD@0^rk75WI6uPc4{rvOFgHrRe4rZpQNEMk^ zIIg=*r)%mODwSc=BLX}&tV&D_#K$QHk(hxh-nTarz}lQHf$e2>7g&p;T}m*wJz8U< zycjb0uHRl9Wv7h z%A=5G=^O|-=i{%V3y-vT>ZRzKXpnZADqUiaWNX~}eM>!E$mlBKQA^~uAXgz=BSkeK z9xpf~8q;VyJXE1=C3t#@6Dl*M;ki=nW~;v8E|xSVri@i8e!Ry*l5*%_LjK{35PQNV zZ+;m-rg6Ck=S>*NK(^9eNwiiXFt%YHGH2;tibffl1Caxft-cRgmBXlyt9e!m7fE z&+y_s=8!;8{Z_#c()s$EH-SlOtG{Lkl0qJ8uUXPAy|F6?%0x!*HM@qd4H3lJocFb5 zqv)3C*9B#t*wbjuNP}Xgr0zQw$*!|uK1wAG^FtvuFWRxCLf_aZSRhx@uOXK&b1^=P zZvUz-xI&(p6%*c*yOfuw$`*Nc+k=>bktz8R1jdMaf4-yk%RU)Q$phZjw%9YDEuZ21 zOxnPG`DrDUkBI@PaEewycA;SBi>mu)G@_Y`se^-X2%En2gFexGizPW~0ujFnFvGMH#uTd2rz)4jGBAWJElE#<_CS+_)%fq}FXsu4R6bZ)y!} z);uV9V(b416(m(B%I!#NRj)ICcNl*k*LbixP3t$nFk~t;u$SI9bGbh7!n;5>M`=ar z7{Chb8<;7Xmd5R_vPz}I>wnpIzF*3z9DT1bO2YQqc*+kSUCtFqGkZ1O}o;o@$(M0+DI4>lDj2)Bo%nWq8T8$XN6xKsRKsiU@r8Btm=BJo*)`?;~f#qX)tqkKS`o?+btk;#(A*K5sfvdt9fqPav)9o88 zx@!%$T**#6S2t^f?Q<;mL%0^%jR~Tdc~hQLkhYVD_!Q3%-jc!U-F`DW=<|BW2%b|K zFYT&xHCAt_!j1}arFAzCNC@NgJ(~YY# zj2#hvE-asTe^wP^Nel%UkB;Mc8?ks01#5I!ojt$vhbX#Yt$y{|-2Ee)v160*&n3#{ z@>d7pWHI*9xgd3{1vIVzZFHI{Syf>;)64KI9Tj6^5TSAbzejhY2-4<<+{Iah22JOy zcYFe-CB~1+*q?q?_w!h2zReFgobj9V)YsxE^9Z6T%HJnvjBr_YbX%4wD92i~QZ9;o z!;;}26B!gjQfDteroOe?g3JBM^qXB36MDGid6XG!npa+2GV^Qe&PH_qL~;xEficXc zCg7O7VQ-EM5(X5~k1TCf&J<&qT9}|VBK5dYji7umxT*`Vl0>1)`%|2QF&V1;ouxWW zuG@QW3aQo>lR%N`Rio-_!t z_cRMacNO~k2H-r4Twjz7n`S#`Jtjg)G@iOmA2NUcJj=KBJ>IGX2-JIW?250R6;%5i z(RGK?+kHRU;(NK;Rn!K!Z4y}$c* zBRHTCS88{moCkiRu%+X2OEjw%#H|HKG>SYT=C2$S*%}`;Hu`XmQn2Ke%E%%-V=>Wf z8B6ZGT)?^LvDx0dK||JOjJi%f{V-XJC-8Mn!Fa$Hz2?Q$%3fxgH|{RWOAf;V$Q4%( z2q-VGBK(GRC2aPLWZh5`LLt~Mu|b2ln@_23@;?6dt&!3U_diu=1K4ye!|~|2umnx# zPlGM|LmmFf5oaUgs3HXFQi|^G z$xJurT%-FF1B=iXFXy|wP=sPUN^)8?8PdXe_9jn!%YNOjex3b+PvMrb zoFyp_SDJoVDO=1dO$0#4YM%}bmt`z1$(at^ep$d_3|jGdV7B=A2&31^{5vNx9Z&Oj z+4VEcuEvpN4@Y+0B!6;paL+NV6+3t4uOfQDX)F%UJ)UNm?dY>Dp|MdL{HKUgUW+3* zxy-$^+XrZz$pDt+fV7Ejh^rK*U&K!Q5?G7H{qS6ImuB+|RpM)8O|ku3F< zjZnLGl^Tw3Ejr^D^1((j(n8%J+n|4Rz*8hc#glgI+Ds+p%%|{+S5`eQQG|sZPl(2T zw`=#NQQ?2|A-yt1R|vj+fivvtb%IAD3raAJmB7$}P0u^`c-vA1IQ#{hC2+;g}hsRfcHXqGR2F2~WKVNy7c>ejJM*KH z*Mq5`>%1suuks^d+r_LMPi@^k z`Kh?R5hZ+b&SyTHRRaX+K%FP(jKQtm65>5^4g~-rab0{%| zK|h2Zm|U-|Kh`=_|W>S4`Oe}UwI`c6xg^(MRv3Hz%aTlp}Dh{+oML2ZH+_{(8ckeEDoQLjB zS)7dC$mm{Zb&ZAv18ec)d8_x3Cf9`ffK6{J{tJHE#0 z8#4~wW&D2kQfU~juv_)|+)Jy5l}aBjO1we{(I+~^S=!fvP$MC#_%>K61?rvHw{ow( z0UOnhvpmMF3&*ZMZxm-)$l?#62L8=zgYPK|^YU^3w~U}m%6eRy_%`$&2}a@ zk=Lg#ECpXcZ}B}$r>waA5Xdc3YE>J+S+LWy*FAtDj>sLDFl|b}Eoy2tr1SLJm!a+q zv$;?ZgnO7}m_)>A>VG28CtVSCk?S*Y3saL+jtfa#y^NjV4!MmAaZ#$+svM#fZ6sq- zSevKn_5N;b04oJcmCqMx&%G)i)N!?skGB!ZbMM+cpG@f#Lex?S z5ecsLd03Q}%lb%)E7ci`;njQdYId_XdspGMbxm5L8#8(<+88!_=D?d#g^Pm%?2v=V z=?;nMEA>l>h^Mw>9qt~4cuzCp+KI}zJm%!9G2Bj{Yg`}0b*l4J<>>ofFX>}2BULt6 zr3Rcx-t7m=`J-jn0tz82Ps4~&pJXz%W<9jq9|2+B#61dD{D6jLTbZ?czkI$E9Yx&y z*2f1BwIhM3hkNgh@^AW*6lgWC#hUJ((0@Pf|SkFk9v)8Jiq7%7k6j>Qm^0U-{i!q_2b`KK#zVs_6fa z;@$l>_N^tc9$YXA-(}IrIVJNBHn~*@MG|G36M+_sgfkySpM$KE*rY@!#Zc(p;2Yo+e*}O!#$iATl?dkw8WeR-K~~4$%N`>y}mIF^fzQSzC3CN zRXVEp&I?fNjJ~|;1&W>ap&!!k`7u9RTKa~Nt5S3q5_9)W43v^Vh#Iz*vwhJCoOns_ z3}CS@h%pCEI_f4^tvsy6+-T5ft=xE`8RGaFM^6RqIveec*pFdRomSx?ia*Fn)rqvr z%jy<)9=(LJth$;~C==7FP}Iyua?=(e328kp#nV4A02j2rMAcrz77e@YvJ9ET z{D5zL5#sl=-G6-QK~SjAtlA`i##cgb{DpX5>SaaR53esJDE_>HFZFUZynqJgvp>s? z+RMPl3poDR)LvA5zkomJMxxePU?k_0|BE73GFa0rcyRB!4p-3QFY*Y#$1D>&H zCp!yS+5HFQ53d)}2(jytJ^3Yc)AKo`4*E#@;U#=ct>+WCI>js88IAcx{?6Zh*~LX2 zeLj081|Fuoy6663W^@Ca@MDbs`*%N%Lw36A);1p(LAM|J%D8jSSNYh599;lrh3uy zW~WO(CZG86@3H=na=UUk70k^Taa{YyA&~TYp!@N~-%+g|-#X7X5?WpG{liAG?G2Ob z?FDk1+(lN0lcjo|g1~3^O6ZQdJ-j1!i||dxhNz;n^wvYVK`-G^*&bYhC)26Pj=xa% zfY`%A-iyktpa^3sI9!HNIkchfxgjJ|tmmz*QQ{d@F#no9xZs6;#YWt1w+s!P6oaB? z2vZZFND`8eG#0X$OER^jGoxYldTQG3yT527M9efrJz2&XKz)?SRcr`KB@90y9upY< zDh*v?N(3awVHlfb1%cqteo7<}zkNVyhY{we@_9@e`Q2@~$(88W9nlW;HY%1mOr%ar z{ZnaIR*O_~u%uQ!24~~3pzKIwqn!CH!bmcl;du6SWgZD+s!VDEfE6zSUtlG(0tlr7 z4qUSq2Jq5wQrkMH8B;?AA`*Kg{sDK=X%(K*M2yj@B#0+d!Dv&#g{vZiz(P419&94E zzM~VH4B-#+=i!=6eK9!?4DNoAKnJubnNX@%TI0pPUDXA zn_ml?;cQ)=Y!fwp=X>RYnIP}O)2~B!;hLfd^Kzt|{__r3A@*(y*@<Z!B(5nKXPSU$3-dmG+r!y}b91wgiH&u-|7v1GZzh8X2u8Io9WE~?N=Fh zLKAlLeVnD59KN8Wk$xZhz?Eb6O06&3S2DjPH~MVX?zarmq%H#eJ5N3A9Lv@h`{<*> zPlNm1_qn$CH$+OjSsb!>eHa;Nh5h_>{{0I~0*QF{STLeYUFp}{eEBZWAU+q(Xg}DV#pZ?cBah5wS4WdJuJ1%NBn_odLXl}+W;YMtt#ujw z6-TuJ$Jb_rBvOmW)Du;cAMa3HqQtbs%V9YFLFMC3#a-_=%g?Unh{a-Y4$n$mik%8< z=bLokI*7Qo(|F*qqx63EuK!}8V~x`S#ogtlj<;}Q!PxH-c+AkqLBF05yJ~mFQd?vs zp{NnYV@-NnK9_9!u-*B?yj4AYX46QujUTfP8bX$gZRpGK#Ut+2!8&lZ0EsN2OL zUQo9G;w5BF`NB9IZR4zBSpeIzn%4|T&&!G7XwcL0*qw^@JNYX90|I$hM^gNDvTtBk z36(f90B0GKiu?vio+qPMysV%+6Ufi2DNdU+XVZ>93! zmC)js-(Ud9ouGV#eUl#kWexaT32$4fIAXy?j~{MqC%DG{A3YMiI`HmEefHww0zr=~ z{y7#}TYNb(LUJWv=(9&;DCEbeIoI0X*1cMUfytj=jiEw~_vr#$IScWuI>1guls~Yo z{c=LYNEY`r{Md^!gRVNmTzK);iAjF2GPh#@5G@vGVBdT9@B z4GoG^SkKta5iJaOe1$j9nQsAwe!B>NI)AY%RsBT(>2~y;bN8m^><7cr-g?+qEhwR? zyiG+zKXGTg5c8l_42dySCOq7rn%QCAw12myY}_!G+l@Iq5|&WH(VkQ?1FA^~#CL<} z+Xp%P(=pKGaMx~sUSOlE&Ba?B`-wlf{2>jD!g+b=<69!LmC;p$Y-t1OasX7^9B8$B z#|QxG=RV#Mm{E*>AfSQ7*qNymvi-!k5Q=P1gW-^6X-kr@QWZ=>jD;m58N}V17jni% zxu=WMZ4OI25{dJivF}WyWtB=Sb`$vYo~@mtCl{iC@demuN7=!=nwCUjW!x*_y4-P< z@hIWm)lnh#2#g2H=KC=Bsa$C}a4`e=Kk_uqsDyJMEmX)I=>6&NbP<8oYf1Qi@J8bU zaCWz4e{N$>v}QmFBeJ8057QdTqJU4PT!Lb?ZR>O9>|N_i^5zeB>h-4rt*MdM5`m}( zHJO3mDWI53kio)O(Ld7!Km4``kAg{7kk6i3Ymo#d#lpv1kTApoJWt%MIOe)`3=s8B zQv){IOv84&{+nKGmkcON9w_st@8L{8yv)qYKb$U;`Zzw&-%T0~+o^pr^TAMq<01y$ zwlM5F<1G5AjUS3zJ*}zVI#MAZO`3N|=#ajfflsyV0f_3BaJ)-`cjryU-_1@-Txe>^ zx?U!57p461JsSlC|6;zb;_4n>f7^{AaTy0rH>poo8H3v2D_j78u49Vw{LvfYUZjfo z7@nwH(#CVc)EGwSv1bF|6#e&}d*m=B8F|IIcN(l*1LQV&b)TYV+zo zzBb{;Fd}F%Mup&a9?II780bI#S0?p~=0G0MA^C^+sc&frGDYxcnp#+Hn9J)I)>Uwz zqusSNUJ9{aG5|k$@CsJ|_&rm4Be61EAeEg!5K-_p2H7asi2Jn0Uk(QbD_jh&ZVEP% z@fu^45I=yLj(^mIb5fy^$F0jC`W*+w6KyTu2;y zg%dRM%P|kQaV8a~0b{g;&gkos{UgEg?YUDOS4U6p{OBC|$&LN-sr#{7l@GM?9vF$m zQDw`HY}LH21;RL|TG3BTK@qKiZ4x;J@$w(s#BDz}fI{QSae z$jcu8+{@Iwh!!2qz8Wxjr|)vG{{_D_SO33L2chZrssBzmJe+esF<^elRP+D(R7o2; z`Mp-byYBVb*_Kvx-=0<>TD^`&U>TCFyCDSYlNmVgNq+9b&QV8#a7N%UN+8B*b z(fqlv8C+lH`n3Z;SSm;bh~{W(_}-dmp(C;A1@6hiHs#xlZ3M{J$$f5R0buEd`|^@~ zRKeRD;WDCh9cVm1GEv_*AI`yiogy-M(>VrQ!tTx#z`e0n= zwMbRoC~j_i1%Y(p3ZUxduMV%^Sp~o)=#+>_7n0fK~#+7RX%0%&{0KX{Be)ijn z=S0J9*>25S!&L#iVTY$v1@00&7OP?|PqqDdw^d;% z9Ly5P*#uV+o3w|gC+2!u^XmRH8igJY-gzEC10knDN(nb6L`B_SdL{)1OFE!)6yL|Z zmnEwFIGW4pIt#xaMm4BlV0K-do{%gGhpH+c2!()JpyToqVh&DbTW(P)#@!kXGjVgB z`>R&@UiGGth$AuoplqEOYF&yY4mg{naG+_3DtmlOt?k9BFUk6mq+H~3lS`{hmE{MCi+7dKLfV|`JNqfi|%}L#8@|pNBYW{18yH zsP>`$GSE+>ifP!3f;mfvh)BZK=goD1$teKl-8zvfhGMR}6_^LSjHhCo$(4vq=Wt0!luU@T)Cq-eVyYVzx8Azul6&A)$66)3h=EKYck4SlmdB)1SVSK@a$ zVgF%%`@*mkkZT>~55ee`l7JD9X1L(;=^Bsz&x8}pGj}B->hoyFXBZ z0MzrQe&FkUelL_36c5fCNG-w6Q~T5K1sJ`c=0JaQ59(t=pK6t3I~H<>mAdH3AP&)6 zoCv%r)(4Ef6j%F@in-&?QzH)sn9z=rnG;`uaR7v{$RoJ=Z2^^2kiVOy&R_@m;`$3= zA@7*{AI3`pjHg1*MSI$z`ej8b{v3szy92Ux;pI%2fXGL;%r<1K_fU^#e8^ z+;ZK9%&?+kZxZ(z1IqaU?Qbk|n;+Eb39j!Q>o>r7q2OMW9lKN)1ADt;#sNctz6Xg1 zJzA;V-gUNPME2C2G(s^9o9lR0(q5zi3sE=>;Jw+JPv>V;dO_sWVL_j{lBVkw-B%YH z^DOE zH?L})OE^_K@eLrUeBkPp=G*4-EX9bh1?*hQ%bwZV?}NH;TyMe0>U@1bQ3O%Ngiy1h zbp{R$Kou#_)jPtF?_L~ZztU%$sx%ehsQ+(!5sh2gjeE}oJ7e4D!9T>4q(7}Y2o=mT zrvuuqSMkfTmi`Ndrt(#Df6b7@`;*c^jyJE$uJS{<#^6!j4n*i$@%-Va{&-7^T%wTh?C9^a$#F7F3yY;9 ziZSZ%AjSjOK4YG!C>;J?aIUfnMvp{%FplTB!aee5D-ADkh?+omk`w>K;Mly!Ylqb) z26(Rd=Lp)(uQWpCa56~QV_TFc1iWs%vxXDXKhOHb&G-Hrm2TJjB)i|`C4b7d&?~h0 zG}fA286&=+Hz>4dHuMu4FOX(2dSF`{Lt&R3!%JRKZc z3M%c=WEOOs){QrRJD`22kRSjcI%zrK=Q>YNJ{97ZGIi`_1o?94_u#l;Wu7Wy*#P)UCft5 zvAJiS50Gt1Gr3r2!6(_f<+Qh`cVhAmy5a(u`&<< zY@CNpU3I7!m{SB?J-ekYjCTb1pejyz45e7ql7~y>u_)-bF#kJ+z7eJ*uiCjubJc{& zNqHAuld>`o@{GIW)s>lk0!U3cqs4XotcXj?qc@VLO5WaMP3GCYRamz9t?azs7tlnD z{j}QV9e>J0DWW13iE#C`BNeEbMYC(0V&7c}N_ZPs{8}}D&y}E$IYaxwc zMeEpq>muP>OY#gG@Z5~pv7?UGx$zK1Mt$D4RM8gD|TGjWv*1f4}jE{V2B}X z8n=rn5^k0_oNjRkm0S)anhGhk>S}9a!%>%C8AT61ywaS82S3VK83(YA@R>z`>%bF( z(Qwj|Y)}1EewA2I^{_qFoc}lTr;GrYWr~{prlVQ9vGEt3L23ND zg#na}9j)V4OaYLP=N?y~h8P~`l5dAmkKS7usX||~(M*GJTK`Rj2j*7;j2OuPA{P9M z0(x^LqAgDJnaOn;B!nwP&yO0=L%$>*^?~~56YU0g8&7or#3LdOPx~#|&6?p--Dfb3 zVAHLc<6z^WTWBPNPv!@`7VdupLw{F^D3TS>*IWtw7oaiBfGBuV$;WDKRLJ3PU3Ss1 zy0gnzm2!5!3at(tGXa@`Y)aVgMaG%x%#RtcT>TdiDs-UhipOdnmOjzj**daR#n{%u zOi`krHW6XSGsrYF_H!jF687x7(jR{xI8ia;+Qo-l9aUr_i34i%iAvpX+y9;L1x+O) z2-?#x2P`Tm_x>KuvwZGU9pW>5_@`Ut3U&ndAOLd!_x033Ix5*c%9e#ZE4kKAq_diD!^S+E6)?^JQ+v52x zt+2$524#pYJnFUcX!qjr^fVvdKRKB%WZN;zNDNqFz+ws$1l2vl)LxL4%C$G^L(T)Z zdc{ZgU7FT2Zr6w;!epsqKpEjbOMh`>Dgff7=ZB+`zncl zdfi@MTz8ZXYKdZqx(|au2BVG2xY7nKQT^uX{f+|he`Qw16iyC|MRD&o-2tV4p z_{iX#zJ2AqHZQV(-id_!Nmx)L{Xw8^0E%HOpYrb6;V}aUeM>k$-`MIRSc2-mCC=$X z!roUfIHERW8sqO)j=|7A=8EPcEND|F$+MdXh(DZ6j66r6bhmS=smqO*x1i5B8s^yG zK@KciI8=c8Y^jV$$~7$l8~&j;Z0Yr&;_#M<7d#_I6l`d5f*;BA(` zBR4Q66O*iTW>n9OJHzk8*pp6%`p$y4tqC0kV&mVOZeLG=fQClyyfnk8Zc9~w{`y~wZ@czaqz*e5Dv@-;T^3x19ZA9{0T z^o3F%>EUzo=dk3Nzb&(`8&nn*$mZ7PJo`@2o4MzP?{u5cu`rJNT94bFb}c1J)Y75)nWNHZYh3n>P@eQMb2MW<=F~X#qg!d%N0d6+O+l-s6fZdJ) zyN5M|y6~aiQ)i8Ll>w&tv_dA7-+~>hhVC+*KIB^zDXa-h8Go$T6%_1J9RY)&qXOS- zzE+(_+YKx~SAnW0ms#-#oG&v-*D$yz=$Nl0#{{YqfArT@hwq-KJ0qY+uVSTIS8b(K zX!NY$?^_H42@EUYfXv9SEE@Fn{o7Y{UckRp$jk{OB4cEIrnxmA%blWkd-2nJgDU3f z>stYI;_`fNxehdG1G!>xq&%6|Qd8?&pcN7um>iA632tkxaBmuD8O1dz3 z&qXmH_UFWdkrhw0mO3{c0QO}G)LAa{!6SH^TGY9Fb%oJpAcRKbQ{`l+#mu3 z=5piB^cmo%zIt84L5*}|rbZx&Z0m@PA2B336{PRfT#t#3{fO`)B7>mXCY4k%B{6jG z!96nK0d15)iOHkR%XN(!b{y)>{1`OJcI+J*WtcW7DB|N7@#i!Ej#=72bZ z+_I3b33yCyPq=jR46!Z3oh4!Y;cbdShExyS<)1X1A@H_L!#2eW&KeEF zpG(M?(2>FYI^9NQ*BmaBw2D07eEMl97e-7DlhB)NIb)U<)OtpdP#-y1;7On}B6#`@ ziO8vAR#z}`3=S121+e^th<>5T`};7@)+HpqW9>XvFQ0yJyW?$uzcIlyeykfCnaGEj z`!f}>@q7YujUCP0qtKJF59r>;Ej`BpT!;k6D)%@%U1@hH7XXVgxb0v-$^US@)#MU4 z?km%N7%{l1V86+dIZ+7G0KyKgl^9b%k#{Ru#Fiys>Tznt8itH*;gj|3Ee3($(o0jiG?p0* z;`}YeU$BLqRe{oWv1OGOn~bg~r{sieeD!yxzRDb=^E#lkuTzL)a7@9kQI{o`lKbfN zwuVG2{>{;x@b&ND-t_qpcD=g|i;Kk>(m9sFRM)evMBVP}WY6C9_d7p+mF}v-b3GnU z+ie*M-H3cA!fe@iJ7xbc9C4EFOTjGULafB z{Wk|MUq1{+Tfjwxk{44agh|zf#fi|@ZWI45BHWW(x!l!j@n|l#FuozlsSGM1pNZkZ z6_mf)`OMw<+nq`zc=gS2fIB>P`Pb|VPTgO>?%(b0O$iK`dRrz4=5YRmaxnD2dR7O; z$b!(w;hV)*$jeV_-XW5YJ4&E?#*Z{_qahi(I|MGsg3Db%wBygN{y4WGqlfUW+4pF5 zRg9%Cv?H!N3z|kvw^aEF!%fZA#Sh;lKOhm;h%ez#OS$+8L)Vxw{o~jzYpQX3!EZIB z+U!#2S*`C&l~2zy7>MM9G=$v0bMY|&J$KpBcubSS9~-;>6ezb$jh0}ZN`|&*50>zm z&Y2|~X@#os>f$^++$-k+=;OXh4uKM53abM6(r1^o|L2j)Th+f(Q$rem#?ya6Mim2k zhcofQmLAhjNW@h~WOE2M4mr>odJNB!H-fu7C3JplNh`!NxA)h^I{yh4z;#Bi~ z4zy1M2p8r&LyhT6NZ2CYTj%?hY$6`GZO^P2a6hweVJJ{9%>uV)qooar$ofK2aG&`O zEV#6QPx*9F6(~qbGp~{8EK_-oUs&6hq~DUmUaLv{tH_#?L{3E@S+%fO73|y zWOb$gObo1V2#BPEENzAz7t*`!U{lp>u=<5!k(aoisfz=%?l=Ypu@=tSQh~OLw3{HKOJs?Az8%|;cY9DT>@*OFs` z_cm}7V;#-^C2_6;2)qfb%H?0Jma<F^-x6T3GKnEjqcywfG;G`0|-l~}F zTS;yx12LjoaX=O;3FhT<;~ibES~IHe5ndYh*9Na}&L@FFu$Xtjz%i!b{M)Jl<+3Xj zxsdEM(OA#0k5$Qh8e>!zc4j9LlV^lz71v-#OH{Fw*4sQdDjSN3MaYy3zA#F({()d% zpmALwAzVrMGQQUODeFOBUPx!3=E99kiQ0Joomj6wJR=(vj?!*J@2t>Ubz zP+h}ETD%z?NvzjK2-f618YFk^Y%6FV_=vcmh_&eso>=CcUQo<`*418cZH*DB_h`SqAWcf0XIr>cZeT8~g7t zwmH7-f!qhThQmWv|5uT4KVu>!g~yB(*!CDA_46RW!rn#uJjHVVz0D(xM=-@B9%K4x zky`nzXf+?2LKG`~ZREJuxf}z~0YBeq)1}T8x@OsMc4cw(OiHmvoMVw$8lfU~Bp1z* zdGNlXf0qRfN^M_lCfofIAP*;l8j$#>+Aqt1W0U5pu88kT1v}qo46NhiUrPMsHz>=2 z06o31anViYP$u+*{pd`m$6S3$hCDwWY{>>8n{hU%0;3C6XBoO#$YJuQp{FOyib4VR z$Arn-kP#hwZWGJTL|^HC&4v3jn zVYus`7b+h`0t5XtUBu#G9E*OFSe)ZES$ymf%RrvdOsjYV6e(K*cb&LQa2_tG7sup( zT0M$m0+H#+%b*UF10pqdcaemfn}wDHLv$MHENUnQ>4#PSn=yNhr3PZZmSSLVmpx!k zm{d=-4+YmQVu{!PZ2`uF?tG{U3$Xyl$L(%e3wMBm*E^>|0%p2C+{?($agUH;X-kvymL z64?0~Bl_U_&*J>sXjlSp<=20T-}$;C%5CFrXz&FpA-OueVpB|bbg%!2$wo;O4;m#9 zf0&ipy&oK2aSNCj@V#*|_`@*uSnl7f3dsR>BiKZKyo|}%hpdyuljz{pyzmihL*PD? z!XZ(4se}VuZG$AQpX_GC$r#jW{?bxw7&jy$5_aeXjblrN6_WObS*=mb9+LXB)RRMOCQk0wux z48wEX7zNksQY|u7`tZk^dw^W+@@&-vDc%AFFL}=HNV8noc&IlRB?inkzAY%zClzjZ zv)H}q7)CEOWuz+!WTLV4%5}rK4ws zf@{-vE~7xU4n2y3N&oqsbV!R_aYk(iat4Sq01E#Uo__I5&F}3mg(>0DFfh(RVr)2p zp`6|wxqzlOAO#s~wxO;jq0Ouxsr2>zupjDwn7ZzGs-wSuZLXb*YjagxBV=Z;%WWAq zA(WY!nU(DAnzs<5xNc=cl#!9W%E+dWtd#5#vYvDG`#sO|kALcQ&iS768Sl^g^FHU6 zZ+I}q_o;ec-&$1@A((!;K-x4M1H)Np6%~8*iK&Z>@v}x;+RfD@BCG(*Pv0NhAL7dR zSec*C@<$oE%hf4jBb7)znDjYnBDp6WO@czF_PPYU5eOrDidIJx3cptzwkffhtLO+VkL0gf)vO9c5iha- zIDj(`yeAT`St@kGn!{`B*MxG~(^+&&56fN=Vg7XiR1huN9Bn8g$c1UDn379QAo+R4 zP7BK)G61vjI>sRc!3p-q z$EZ61CuHV&-0>p0@vSGqRLqzzzh~<6XF^v`T$kD|y80FCUf`HYL42p@%hANTgzWM- zrjt1wn||g}z2HKt;Qqr};UF*Yu|CoL01JewG!8#~9%f<=xQOGU(~l9S6V|axNwK-n z%fD!prAegG0ZdV81RwNUS1Aex;h&b!mL`DhLllx-&Jm!fje-50aNn+smdPV{)CP1a zF`Vv|ak64J(w83jJ~%b@JkC{#YQzd$!J&m4B%m8XFX>(pM;pK3N-Bh#p>>-UiCw^0 z3ZMuv4(EONpLmnS$8y|610+ZfZcPkqSzsry&Bn=6&aOLfUG&U2z@UgMg~}}A&3(sc z$y~U=0|zoMC%!*}AD>yi%WsQ;B8x_f9u5qg!Dt7!#*|7D6#B&p25$lz7gNGZc<0^$ zTD2lTrYA*{nyM&!JtzTK%XN@3w6)(wk+jDGQ}22a6zgBRC`)LKgq^58^yB4P%vsz& z+Ty;sW5inQZ;3}Qm5E(VKgYK@{)|-fNzr9XK%*0k0J55_#cyy-XlHR?8|tD zE(Jn!F@EZLsGYC;I8VOAOPu%a_S8_!NY%tEvENm~aRf9DcJ2!5?dswuz89}dZ@!)@ zJb3WzZ#_gyh7wk}KS>3cBPuRZ+1kBy#UaixXrfS4OB3(R~KDTSie+ceQG@^1n51NhFMHM9BN!GO?DPdgh@*e zxyHe2Gwlid2wiEq$NyQf0{FtHvsciBM|G>kE{b>@`Z)NeAWGB6574%xg4RtEH5W1P z14;qHTc$I;mJdtNdG*I;y|!r7w01CW`#qzk-&Bo|{lnkaExEqj@IMsp|A4m6LfBbW zy=XkojJr(-%;rN>Sc^bbB5brA{{n{qN_xACC|paeMm;&X68@#jDo#G0P3D zCc+>+0}V;qP>5`@!0nV&JkSgN74&zQ7UDoE{_Od(g~H))cQzWw!(IxsNCqarw1-*o z!u*+D(_{A$2xmI7s0eQn;x1VbAP`TVi76annW`mN2g`}WkFNLlr55Jo>n19k*Zng$ z+4DF7#$yCW!ca~V*O;cRX`P8+B6k`)xTZD#kym?I_H^kHVJ+5eiFac^Dr^rpneV<4 z!oYadoaHg^ANZed3AQ?$P0Mz{HtA30GJMcp5H&E6zoeM(QK(GPCjp0#urqAyxwg6% z>8k_nMH?l+l!3F?qQ>Zd)_z&(=11Teta3g01(;nFF{xbHndo!BlVEOYGi1RZKj08} z1q3FQSLLg_-TIH=8%*aJr7+%IpT3GaI#&r}D(3bKLxDwS3q2iy1Ewf|oGeO`(x<;OUDeG8hz&|?bZ25qdDxym=gm$`}8z=!sy6_0TImP^ zxYQQ-h}@RDsKq(!I9JyNLDVnjcq|T)r-{BBmisxVGo?sTustYIhq!9Cvr#yF>lMNF zo*r*49Aax}3>Ubx#j564n_0?EJhWayN+ zW)TYN>BIE{-Ias05u{0oBx!6z8#)jQDn`g4VClDO0_YieRLK{PjY|RqQ9nlB2nOvT zAvK?K^rb(Q62Ny~(~7j-gCk=LT(u3=FD{h68PV1rhEqb>oplMo+rXhgyl^dw!LR~u zBt+d}%6H8I+bbhT!5I%rs|tW5z;b+lEbrsd%qz*WJzu79c}CXRWp<3&R>WXo1Csa> zJss@A$PyZNa|HY^BiID4Wu#SlO&1#x^q9H`QC0cFa@`NhVQ7^U>4ht}oT!bx0^*wv zR!=kmhQ$-(ToKqS&lZd*25rL>&c71CCrH6u$wEfKZ0HWWpxjs++d@6ijnia|g|Bfn zXTYKuFF;v?Yg}-6@8ZsT_RMc$7#5!=SPVG@mbI~A4Z?4Wpw}gMO&5NkahG2* z(d=lf(jp4F;WsF!SVU^!NGRw7H{~xG2lG-ip$9Gllg=&tf=3$$92Vp#SPvvOlAhE} ziyt(Y;WT?GAJkGYR~pF`O9Ak|1EGX676@S=O;~PM5e!6K0lsNL=$F2=O(iI)6->=R zuW`#$zu>10!CyDCkDi(t19=y5~#{#h;KPb|H4#_|=l*3bF6~l?4 zT3*t?Kk|J!ofJoms-o-fo*iZ`r$W}S9)^r|D;l1z~tH~AeYtuj_=SZ^o5 z@a_n;WE;76z$;Pzypo5LyX~i-#LRY>{_v5-2qKDxJ`{3`?q*>9%fBQVp=USz)e+7~ zP8nUqBpMML`!yk~MJrOf=hFXL{>{!5Hy32WWkYIGt3Uf&IMPrhP1F-adpH5+x+AO{ zFx-M3xMWg#M>Gl6a1ZRa}N#mjt&9T*#jQ3s7?iO zOl4w6TLFybE`jq%q!o zAVf(1?YauDRV#bDO-KtE{#$?Z>17h46>QP9+7XSGgbv0#j3!X4YqxcwVvKd5kean0 zb&eNM9sNvcS}8sx;r6MCu+S~7s7qhRK(Kf}l0Qgmql4}1s{iYgt-2m}Td1T$8bcj! zQ#jsgG=lrJ0q#N+6Z`U_#^O$=kbE?@}5lfQT$8OUKEee|q3Nw8N!$qS2yMqih}cUN4k z8B$CtE)UFwU|VsU8+FttPeUk=_CzJaE2$>z8M8w-|GKbFy9;69(Ttl%B|_TTzC@#a zz(&pKf?3;xG3V^6lw)5La3B(#65SQ!-{P^1c&XVkS9@F)9(twac z&RlrUer&7m90pc`fB)Hy0P)Ie0UD)CKVuCBKBCJdedrzw9=Ny>J;SVBFFS)z8On@+ zi39vOmr)xo?QnmM{YhWzD~>7zs`9alm@gtKi(d1Q54FvX8sM-XxxXpBr~xplLW6-gQ#GJ*!cMpD;B0=f2b@FqjED{Dlf&>-vMfkQh4O#= zEGZE-Vdgw$%m~>>TSp((++<~)yy|XqE~vWK71c$#-OeXC@K}W{J&r%9dWA+zkX!x{^ zBK}_}i4DW+Rw6K_0{Ab06P{hF%3s8!P5`pdfS&r1ffPnTO3zf06Ezuo;<|eIMR*oO&UflIQG7+@gn~GJ}<0cG*2Qcax*~ zFDhU1pM8E}f7Y2->l45|3;zJYyeAz@B?;HkfCcpRZCnezXUkw5y8NwgvEzTUl1Y%N z4t8_7BQBZj2qMx+)BWjh2^KsLlc{U%;P~>zC=DNQa3cng>2SNi5d@>I-!w4La&&YH z3=@YBwJWN*Q4ky3^#v|Wt$u_Pb9X16$hk!e%hOtxzm#man^+nF>wGWK}}q7wUmLu z9TglxU@zbz#z@&0rX(!{&{Zs{AS#o+t}$>9;88g~q`h=}0!+>b%R;tfcI+z+^1NGJ zr&bK(3_$FznYtw7@i1pO>dT`7v6ac&=Me6;AUbc#Q9?x!Zem*3I`WeB#_HW)pqXi6 zm?yq&-Xn~UV&FHh`gy`RmzvRrDj1mCPJz#M!3z^X)a>VD&M&`aAMmWivZN0VslZUp z#EF)78)=@~k0-%=7Y!jbXzL6SJ1L|6OE=X(*w*+z#4Tr?n|nJ_`*k5&pxdikFe>F! z3wKFFef?voi6QVkx3gn@Q@ZFPra{hx!eDin*Fej;uRO@()srKJXAi(@jpK>|!7&3$XejMRyV#(lK&@Dm*kB%lkDu)r;$hL^~D`#r@QF#AbG3<4$1 zM2wxPjg4oQ7y&x~@Q${=HrCA3<_1S+CXPisnI)=JVya6Qq_)pvF>39D<5K2Z!rOCi zhIx=iwzQAnk^Ja|=TC$JnRaA|Q-iI~#V#enXd9Rl;7)tJIqWk7Xu<-HRD1eOfWk;GB4nrzE2g%XRgtfvjxEcEMB$Z|JUIR1SEhc%!r2GlW%N zX*P1avCzf+`|_}~ET8#W|FwAgvqVrTHYADj8K}C9Kol{OQQW+Xf=a`~ ze!V%GT4B9pCWk@eBh9(0&Cej)MqD!l^GbEG35K2Vf;vzO%LYRj(%$~1=f>y=ARhqF4u%&P~*c}VJmp|bpBWSn<$LK)ucg}*+`T0Wx;*Cvi zZdRl=-QXwg1YBmcU=*t$*msD+dCV{X?f1Y%@3)UEQBs6bt*@h!)AIJe_v_h^0E2CQ z@DW}+&Ry|rc`J(9ds`KO`O`!r{HD=(_sy-}k&Ix9Z?^FBL=TCPGDvaNOMvMq&E%iI z8B>NM*J%m0v>~Xk)@_vc_U7DBsbXIrSg9z{NC@>qpq#S(Z%ws5nOzj=i2FW$l+3gy z=DW@5hl2V{`4S5Jcu~ima)>DFJ^q8YK5FvJHDJU3dExDBHlPinE97ah&%)vPF{Yj^ zfA{CVUb2XbuM$Lk5Ykb&UZb!v`vWPg!>zurFdzGY-dNqQ zy$mP|;03iKTu4$TW+~qmGC@?*Q^BZ9XFio!IcYi(gk@wDr~~(I9O#;yh5ziW7=BJ4H8tiMD&mU$K-|zG zq+M#_i)Q91dN2(Dk~e{x0@gBP&kc@Tx|X=88iHl+1jw5yh{ZHTRPbCH92x>(>zOLq24+ZoUT>V`B^G;lc&TULEMIbPlA48Yc2cef%@p(8|%HY!y8d z{Qy=u+jjWf@X&vc8nW0Cr#be-Z64(B9(%T89jtxzd`5pRr+G>nKeE{66$OwiXc{ia;sBOFMogFLOv1^L?xp0_(CXj%HAw(DFpEXHzT5r zCLYfgub^K#1M59sdTd5!GE2rE<#W)0N(%qIIFOGxE;rG+*By>=VeZ&w)M*oEb2i)j<_sGT7G}b3j8pNz|JYLSZ_mdy@bfK?$^825Mux{v|cn(YuL8R@*?q>BAuaMY| z4i-#U=+i<~_HH2}FT9JEoFIL8|C;tZYH;hb+DYO}o`59AK(qpZA!m)kwUmI;1Az8X zw6%qj>&c!WRZo5aOo-vUUrU_HY~+h)XlwF=T)vPO=Wv>`RqwOH3#k5+&<#(AqlZ`# za*eGCj`SdR<818hIrr9InQ|)GyYQk!?;Oe%vCl=m_=X-R62IhYas%Myw-OWEZ*;YD zIzbITe|wNDh9M|lf}64ltx+=9_J2H91mDd?DU4APY?f=f16? z$-?}VtDC!^>LLHj@R|u=`1wn0nwaTQTl70BJ@p4imFb7Ilbagzu0*cu+u6&iC-QWy z6AWG7{ao<{CLS3fpsx$PzXpk{pnUHb@SqM6g%?)f?D?KQ z;RI5T+5T*Gmd

=nOTijE!73mtXYwyI~?F3OA@AhY2Qq=|N~ux0Rv?mc%dZ+}meD zv4lHTERUVX|FI^5g7Y6?3+@HZYzeU83z`UfCCpiJ%XYK?b(6939T*ZZBWYu9j@sSv zCNNQC*fN{wK*_bKxeBA7=VJ&8FH66ZC5&Y2l2jbGuaz!3WEXV#&A|GCHyfLdd*ndz z0LkbTTg|#UkR*PoHZvOdB?TY3hR8#{A*Q^-;L?{s<8zuKAEg>h%VU1g0qf2I*~0GD zH&*b+O$5Ww-;yBAx;7_MngnBh;fk|a`pWelKI!1%XkYikP*QLBywDki-St-k5`U#K z8t8Km*L!^LeFVI&^cmtVGymIVWL|?i1OhhM`~%LWSw1{yNoQc91YPd?kY@mW_M}Qj zFsck^Lp)U!Hm_OZ+PP|vs*sT0&g!{#iMdFX*&G!05zG6AMRYHk=)dCkwU*uX4c=*> z-}Z^~X*0AFE%f@nI;aQ@4*owUs2fIr>GThOm-jmsKy+Wka*YS| zdb_RI)yhpUiFOcSUs{skS=(WgQ7_t>E}{DF)g)Q<8)qU|s{ei?YwMLn4gznRn$qF<&w_*LvWk=_bc zyZUdnb)*!4!QKnJXj9%h7{fHu3kt$e01h_bgWl)qZ}rjFEdwJU$iit)+l3f?`)?|F+2ghsHy>izc$T>nq0$ z&3Hl*SQbnHxSIL+7B~B1J`Ha$u!_#(G`F~}F^@PsTO%n0P_qnk0J!m;u{D-%q~0CO z>g@<8@~}ROd{QKh&v7l*peF$kGf3MiTf!IL1oQlA)o1-sVv)V4(9am^iRW}WzGg^3 zQ*|;8yxq4&Up2YmD0stlYSY?J_8&43KiP@vQa!cRB2Hn54s?mm)3yeHI1uis1*2%e z?u_T?HY*GSjP_p>gm*;0{_ZtBUpfLyE;0wi(@z2T=T54S789| z!W;F%yBky)-ERB+$&G{QH&m}V67AmObZ_iL|LqMRaU#FBhP&I1(eP;ixwP^(KqDDa ztY1~(16jY}x6=B8(Lrh83k9j%(gk;EJsG|Fcd<=WYCZ0|kd*1oa`}eTM$1?F`vnf& zF~V6)+W8A(>e>sZsNnI+KYJWzL56M$fm_lPS*037mERI!Po1pJE`LH>Cq?p?y2&4M z_W~yA0W5(f=Z3;#Qiz-#1s^@PNZo?q*`0;zRd1Wnm#1aymxGLGY5+TADGaGjC%ADt z43uZNeFgHE)TdWL3E{2_ZK}kP2G^X!&2}|w?SmLw?RV(dtPJgl>wEm;v%20{XSaP2 zcG9Od1@<+osGf~#{R;;C{|v@27cd+J(q^nkXpB8+0<3f(9F4nnzT6=Y5mM(JuYO6V zj1h!SD_;NC&e`Ke9iH~{3A+CIQ28+BFLLqY8=nIf5?dn08aZI108;Xk3|VtM26MjLwd~nZUAQ z=+>?K;)bf?hlPk@WNd9bk->P%$p8cK%11{Kho7Y3dl8NuGzIkvV2!=iFx0gq0){6( z@|;L$T09F|N8F#cRe>2t`I6x^Z=`&y1MTkoT`J8)lwdwXt`DWcMPkhoPRGoG{u>jt zIs^c9{fS9#NPV0!@@O?4mLJ4~`I4jyws4hYO{~RlX1G+G4;)a-agT4iI3MI|!$Pa% z%`TgQ*&vWNouPO+D`M(+`H~FKwHi4B|E(z}YC|;FXLNKr&`WZMs+R2sI~D|V(P{!r z-5e41^J$kmz3}$i+Bk{!&r*5{=wIoKkh|4^pnLY#MHU6J8cpw?bjH4y{LVb5zTtfN z-%)|;u@r6nm-Thz`MkEZJbgLQZ^^h86*C^9PuC&ZyO+-2nN+4|k6q;LRG5Je9&(VY z?g=DB2#LDwLww)7EUOCib`E`MU3543+}#3xXZnAm-}*N?D9s=qLJE_A&|$fZ>)ott zi!%FYsWW}9M;=x{Lqpj+EYebd5OQi(+JL`9fh?~fP6x)i>-I$vZ+@HuBJK=5EZ5Z0F#2kQ+9ZyMnYp%+BvwA)0Vp@oW zlF1FoP7KuTfdB1(nqbNWuK&EVP#)8kMxE~NZZjThqC67;2F{9ukp&Ih4nweUx7%1j z)Gz3vpXjGO6uy*@BhH6qmZ)3MQagqMf~ned%-;0?^o#St3n)(Mv%-@99Tkofc-{Gk z`d-OGh-LcHFLWM9Xp!H+qkArAF+FuGDskt>C-RPisQdqShh`*cX zNCT;>4um&1Q~?_RoBwSe2KM-0(7G}4&uj%tdPt5X6S`7L4!CdvZI8^%1t~~vR@>iQ zH3i-1cy+YPvqYFsGH)l2innLF!SgsqV!D9Z9VppBj-k)Ix{?xg9e>3<8eq%xeB0{~W^ zb+C_hlWpyt-H-nyKJE5Dnf-EG8u>ThFfxr_FzV{%EeC#~Gm;0o*5vm?s=8hOFT625 z>8oD(tAKu7;F)EAnt=^ENl$%p2oNrp&j?15-2@#cP)kZTB$l1g4v_(iXjy4fieJC2 zQ0daGTSJod!d&$&m0m@VEJc$>mUiMlGfbj9U2O~w|G+I7_5&?k-TR}#41j8{gVEB{ zcvB9-@1K6Qyppf^?LrFLnG>ecLS*t~pG-fBmd_f5ygIVTyZbk68^;KF;|5E(|)V3uGl)grLBEuC{3MY9s$~|T8cT=gxsnkc}zwyMclfu@$^HU zhzPQ~$pUG2YhEEJj6kmAht{OAy3IV)SmFEJSZJJGCW-OCAqa-`zSm9FzsG-_ zgp_>1@nDD9=c#oDF=6lySAt7^PbVe-%3w~^hPqCBPTtChQR4y@oNoe(cs9?Q1b;Km z*4GtV530F@#6+vzt)1@?X(@^CW~t>wiG?+j z+N_qZn=|tU&8~d&KBxI@c;_@DFUE3pGd=eFnLkv;*NQf5Ift_`$(CH5b)DvcQ&9@M ze9JVubKB3FKuu1X!3p+zJ$7&e#`V?)m_)TE1(nkolG7&tk1;;bvPDfQ3W%Mno=2~FD*v}B`FgkK9aZ-oLuI~~Hr z5UtFGd}~gl9Ze-QAy4w$*~a{;&p}a9Crxub9};5wx}0c^1MJX66O70CC_kgGn;Qd7 z0?VK8X$_o#6vaTTH<`9=B|KBk8&aKmNOJ!Feocz;537WpVOAuj)>M|*? z>lG%^-_>U8h6dGX=GQ%I+`Yy;32D)eUSMK}pa0h+)l8y2&BMm|IGcs#I@V-?L>+_* zEAnC-Ii5@l%toE1y2tOUY%~mv$zG=4fFR71{e>^_BE~;fCWO)pLEOzN;W-02vW%|Nb2^I_5s+Pl-5KQi-mR#K4Y^#fCiq zcqxsC5qot;kmsof`m#)^X;m@UL4}QH<&pP)s7!#F9SNp2LGiejxz{5wd{&{NHj76e z|8*9#FB%}WPYs()v?K}fzbp_;9LerJ&_ z+-{)Z)=VtsRFW8BO`rjA9aMA^fVR8V*n;+a?&kP&cXy#BQa_wyQ>$w^Fi_)GbH>H- zM+SySy$p3N&lVdUGRe+xrYFCZ6f0#grkyF^%&yivRt^2D88t-ZWCj=M`UNtA@yNe+ zxn?Q#KT8nAX-@cYn~TcNeC`m{ff51axh?lCGeQ@fGmwcnl~rAqAKg-lCXwM2Q59Wl zeGmIM?RGP}Ypa_$olHJp7fjryH7{niJ=>rGT)gLen3i(%a0Dj}>(II_9KlAIWU_e0 zI9TD4d;U_|OODgHHkSoTwPe`CSAY03uLz`F@!J>qDEgmZWReKeKq0x1XEn4%o)+%a zyPXo{wx5p9t=vRV^qUs!y{>08^ju7RoZd+jZy7Dc7M;;E%8Hbmn?Rp`tQ=jTYedWX z>pR@YlHi!~Ib-;w8|`Yevald-u(td4+E{h;)#(p%iqilxi**KtN~D5cc}bv^~fbXU>#I zBT!<60w0v0SpK?EFz~NSHYeC#mHvso2exLJpNJ+gVq{&IYx6aqi;U__d31Y}|GGx1 z75V+J!Cw(FVL1lPmssb|M_XSc7QYFi|8T{*voxdSEg;p9hU9O~?+h9Y^eR}-ND=Iw0KaaaePtn!9%}ht6D*~Nsjr}Cwm!zT%hd&@ z&7T|mWYG$ipL)2aAOA!Ubv$lZ{{62JSvVvk=r{{U+7*R$&^+jOK!;}5xy#QImy1!E zR6HG0@3c@+DP@2)t)dP6du%NgdVt3WmGq3rDi2{{eiwpFVFO}!l3;bIr7G=;3xZ0EQK!5B{1@1wXQ;<{^f2+tQ2S^KmSce zVZe>FDZdVAv$_ENJxPRCsM_Rx9DZ2@+GI>n;Qu4&7^|+BC@!7I$3Yt_Ff^ioTYO^8 z4KFx|WaQQQI`JtA+ujs92YkhUlj;)lDHZRJIE4`pKn2+{{XE?sfHXu;?1vJe93x*= ziWHzS!cE8t%)61PYp+|sfq!g|v%APHv`wKdxz-tXki2G`E!_W;hA#?7`dy0fp@Wlv zoW3m%W!2*&IL&wjf* z6UhU*uO6Pq7;$EBFb8HZAKaH8bh?MUbtw6kK_JcNdUjdG66mpDzb*XH$VzW9Afet3 zd7UH_VgS@xpr76T?%y(4{_8Pil|S~;hTvIFVZF1D#|O{s83yqFFr~Ivk4!PT%_6j! zr7)8(gIR|Uej6#$$kL-`&BA?GzwXR+3Vb%ab3xA&+uTe79IOdCk#6ucOr-XK zG7^%}&zW_@niEkSYH;g65FD*f4z=G%hV$Z|Yr8H4C^^)op!mJ%>dfSro{uk$4+JyG4ZI0dMN50w4P zV)(73?$fTpe?z=9@RE9_k&)277ta9B0-v?%Oh5RVO@t_Dc@0!VNtrhW&;<~f$k6WzPPzRt#i zZ>1bUV#b7i2RxwsB3};_cDr$acAkcG7Voo#YDDtak3*xMi zI?U?Yc8wgSNum`_TRk7iSgnoiF&Rve=&D>p(<8YFx8Ne7OVT3I|GEJwI3J4w;hY=R zyW7c{FUmDTAsXH@(;P-bjU29e8#s}#E_UImD60Dx2eN>NGY4h9*P~w8|n$ zp|cd7kJ5)eq75(U&AUy+v811hD_7QgjI-BgqHWRgC!4%KERW!S9lW(0My6M~H)KSO zy5h*SWo<=`gmoqdbW=%{UWJ&JlQONII6lwo?l)3P7T*D#D$q9m1*lXQ=rWsHHuj=5 zTtWDNK!UtE%L&m4Uakwi}}bPm?Ii;2FkocvGIlCP1TJ)e8~+p?O1~f?c*RlRs1misgt7)e&zuy z1S|ky2urzEv-KOo%)Bx>6h>Ocjto@gC?B_%mw2qK^MCmnE_l%h2&2?x&NwMxV&iv# z77-HS@?>TriA5dob`WshLx8}NBIsdZnQsVEyNiok)vrPxFddytS*7V3C;^o4P6c3}@~M3YthsDwcNEmIb+lWpU*{Yt$s6 z@jR|}7d*9M?|;63e+2fzbGF}-XKn+}FxK^v&$z&2^CRC2GoLfm$>Khx|7pZh=Y`m1 zhvYwzlCGp8BO}|NIN0sA3cM#4axnT=@dtbM!+O4&Cx5<6_y6I3ec&l1-TiZj1?67H z6+biD(H9^8I;-8edBr(_D#rTSS0zp_lk9%lDj#otJ=nz#P08p8CV33gmFKwX(5U(|bV^5;fKcu!uZ--o025)`EA z_#wOBhc&aG@Z%efC#BV*e2uga>cA}tv%s{HnJ1J2@iSljUbnELTNkVOSPE6D=A7)_ z{?l%ng^CJ`e7^!+V*4GL9Pr~*lG+}Ni=LkR63=A>1EPzzqcoPC*90axjJkRxM`1Ai z-MPpwISM5Hzu|)cF%G1Fu_7l8t77OEQ`Uo7WqZ__k;zU4Zt51=>ywiB@|k~f<)3OM zK3DmzS=|uGBYom!pWwfV^ND)FNMd8*N+fs-0{mw@5d8OVFP)^6vLZz~XmUkCVZx*3 z{71A@btZpcCUew~5R~UJLFIVoxUp|Oq)%anr&1GD5|*W>x}R?}bD6)F*W8(cwy)$T zQATpJCL9pbv~Xc(D?+Z@8ToV|ndick0RSHAAvtUW9`q6F{~DIzOLL3NMr`h{Ejp|t z+QF@(dO}tG{*L>T&Ca;ZHU{@1?@cO$AU#x#0f~YiFml$;bTbh!#~VkL>(WGwp&TC8 zLJ1Prd6#aY-1a~U$ZbKxzmKerMF@JUGo|(@GFd0ufpmo{_m+RQa1)DCed)kswPkKY zk!^iV3&rVyq23#jxCy1WrYj*ZkO8Y9T&hv06X^ng0ZPk*ziM6 zbl#wqb#J*YW8n}kn-UGac|ySZp&nuqtuwXYPs5;j%d5*HyGX7Rc|K|9z!N_Z~| z%F5=FgmNnT&K>{tpS*UHnpgTOgjeIrl<}G&A!ej5!zezPU0fv`1{qy*Lf zzv@e{$57b-ZDi=%&Q!DPV2eW3neddhNqNaEm4=Gtt!~b?gS>Fvr))zqWaZ+=Y66H& zQc5hP6efkmPCuALXIgzli4-o4QOLS*tl|WEH63w`eL<1?$1({jN2OR6ws)VYf)tnH z&;nDF;r_qew35Zyk#1rVb4Oba-QP|Q&DR!zA!?)@sTN82I)t2h>W) zG&Y>y>R%`VI+)X_EE7ju18}~70cw9D4bi@pta1y8 zDtk7VDr{{_L2t%Zj2xoEgA83NMnV_$=p+(tH%0&GrwV)uUebr;E*D{2Gp{E&*r;%b zhUT~m(6RN_-Iq5!(9_nQ_osu2gVu_kRl-V)-2LG{>B(j|o0D%&+J6!2`(7uG7ubcw zezYB-XD}TAcXv@aHBXVbMfp<>w%E7cN7@U$TyGN;!hZWR>VC+1vbU_iRh_Kj_qNc5 z@a=`#Hey?aO4RM7j78L@f#%+xjxw0Pudf_Z&wAk$?}vrq!40P_XtIlTWT6 zuf!ZL!AV1kD`w9WcHT6@NlA&7vnKEh6|y3)P}!RWs9^jTA{ikmpWjSy zKCAirwa*g|phm`Feh!P$75%^CU%z!s9{Pxt8a>z792V=qcChx9|1_?Ec+HTiPZ-|@ zbt)MJ4yf!a3`@{B^m)(Kzy+rT?Ghs-(UEUX|18afec(m*q%h9r5Ef$`+>Z5k%eFtd z>`!#w84t42t(-&0DTbBfWwXy*2pzr04j4KBVZkjEM`^IdS<4?K=93ZPi7f1C9IxXw z5;&0D*VkUJUv?OLe}C5vT>0pKh->-XDt&dXEic4}F04@^#HMq(4aTsd6zX{PQ3w}^ z-ddtI6c7tqp4RKrOu;k1B@Ti`jk~V$X$5RO?Y&*mnid^DnLK6gV_18eT>VQZPOmst z=p9d;oEI-86#oYo`8C3!U&CiBI8Bi%!h}Fr5PnP#x+M&7C;ZZLnEg(~tKGx+` zN${7@o3fkkV~O6Yy3!+Qzwv!Qtnp^aj@ttSNe1FUJ(wRijMU0ITp0v9N*{uxkY;~U z;z&b&#Dly3=Tn|u#Rbi{4aD()21pbLD+Q0sNyll}Lgn=+3!gl$iZ`;&SUTeKGd7d7 z^QR)CsMLDXP9g*@ROSw%rDSAcsrbe-X^4GTD|tQBjs%$fa3X$$4Jhe?EE`>t1t{ue zmAB^JgovJO19S6C2xfn(mf1|EV>|Y>FlI1eC2Yzr2Ae? zaec0PbPl}iKx%dGVc`?7XK-*1H=MHHd+l(J>M~3yMpt;>X`eEstCsVPb{YkGclC$% zgFB$T)G9r8yiIB|_k`bSH;yL}+-Z8{a`QFBm(uksJ==%(;)FBR(eYkIC7*KpYU^qt z{OrPbeSNt@79)YP;Wz?3A!qpwl$++9_HR3-~lRw!cL2VIDI3T*IX zRK!j7_&mgFeUy25f6akExPIW#;tx;4JmpRs)=Wz-EXRr@cj*^@`kiSujGohb$sRE~ zsmX<6M78N{MS6%qdWYoRCVW{?|f9%3q1rAYaZR%HSX;^(>C0;6rUoi>pA%UGYm2JfoQhxM|cXu@h4{ zf+edtFj8YK92F_IuWpty@MZ=dqxnmH6x_$@xf!?XMJUY8BOYa#t!m7-_e_47I%Y~H)KgG6bfvtCj# zCJf&V2hu4Zqh-^sL@g>Cv{Xdg-o&y(l2OI_Ge`P z!L}_LXlV^(6UbJKj=htyU*eG5U;Q9N9hDq#b}muVpMnqb=tqz1uoIf~dAJmCmG*%fJQK289q@r&^T_0jQkrrsnQsiZ}UpKIyL;r_4Z@U_`ACPRQgxubF6 zSp%Pdcitp)72SHxHd)oWf@`4xQE5?+d;duYBt!G|Y3G1sT>-O155}=UCa}}7&-;SI z{??>EqYm~j*0+s@RuFZ+R#y4`t|$I^%*j1Vt$*Jk+ZQ*XdBt;tq6V;<#8|6fRDvcM zSHgt_XaPa{ivcvQk08}ppV~OpjccLX=l^!u*X}}8&Ybqsfw&P^dGGaT=w`i6Rg`J5 z*fJ$;uD=Vl!HF|1t;y|_8-V|LKn5=20yxH#14Q~)a6o#@JtZCfBzd`YbIR2sc-J+- z!S^_?AB&zDWl<%4%gDHPDO6u|Pl0WuZm(`qson@Ie-B?PDrx-=b01e7zJ_HW)m$Nql(8$WgqTqi{Dt= zc$s*Q7HI^Rc)t`ri46Px01&N&7wngM~%cF<9&;!M5-Q=9v9f98`}Y0K7$t;LO3)BDr8`nnUG z$O|Dy=KIg9MfG6L3(iV;E+3 zLl&QZXZfs3r2#7|D~oO1uXCR@asLp7o3U2jZ@WxQx*oxI^8OqjqoJrwoj7^uN*Y_# zl~xK!X)S-}Y3{9=U{@cRdS62dL4m7E`|;p!GZn){%yzC@8x17oO+CG!B3-_F?$Xg{ zJAZD^ykOKBgR+n{nbpY;@hf(u!O!^~x8?((w6!?R1My!=w&PDktN4f_O%%dejL42N~OSd3({a(nrnp zugCFXnENrR`wh6LO#z~gQT1$O`^oVxPGvtT8qxmkql)RB+kg*(gdYAW`n`xj(>|5# z@DkM|MEy;&DzO8vcr$Y~rZ%ctzG{M@;@p`ZA@?**W!)f#eq(_-7u5dvhA|EffaRzBs%G$ugE5f+dYc-TA9< za-WhO;q_Ptq27Lw&^P|Dw58F({58+?1-o1iaOvr-x00UeQXFhxrq$ocK=NP7ZDLKN|9MZI32Q$4%QuCc69SKb+$W>E~&f!RbfoM)SrkWyxChpeximrX4v{((gT1N!_MvDW)W`yhD7; ztz`KRr3Taz8q}%r{QS7$X>Y`P+jwR-iLk4Z)!&*5Pr7lj=i7o;N9wAuDN_$@Jp~Ebl1l=dOivPBS`@I zz~`T1z}=p`fzQEMzT<77ShD_C`1Q*d84|D0Z6zxw3pph7&zt0OP-<%s&CKgJWpLn( zYj&1WV#4SolJlrpRk?D_I`GHOAq5%L#L(p!Vd{Q59`M^ZZTc4)BA$mFs-DR-8ki#| z@&D5#xHlN5Z{uY}esl#Mktb~9e5R4}0pw(6Wo_=y;l+dliJwA$V>UALKYwr6O12S( zfykMH;&>!HYk!YNt?p1Ycw^%rmB%c^t#n>S)Jw zl&31Js%C8CxBmFP`<(gO2_hs&^>Rl%_}4Y%V?@&Gm*k3clyXj+uVR$n8_TB6DWAh9 zZw^)EW}m))Uz@@R%g2$_`|nBBZ}-oQD=AQFFjgNXlM{Gr1E$BUeR+9QNPTU1Q^%Q>@T89)FLSE~!fkDBV})kXXTAQ1rf-a{ z^LxUL+PJZ8Hnwd$jcwbuZL6^w8z)B7w6SfQ_x=6vz31y$XRWjM%$|8>=9w8C0aNAR zI=o1U63>V63Y68g;kA34r+@XEBGlN!*AWTZl~nnmz{UjccU%FUfNv`FAyHU_0|5_b zSXVdODO`TLEdJiddTUXm$lsuxJbf_>czjWj;%B$)oq=v*gP?NG*5pCPS4Zaun2%!@ zgJCHH!3~}E$WsqzRj|0PpIdA=N?vB^?ZHt0@ek>7ZY!79qIE0 zTycFo9nTv191(8#zkPy(9sSR?S9%9JQx;d~SxNg$e0 z@ZIV^8^ycGD1<6L6)(3{5OCt*WatXl*Zl@Apw%90$`P`>4cqOz2TQ-H2h8Cx^n2B} z$AJL@9gaHiy`lHMtXU+ft9Nq-zyhx()E+w%7auhKE_u~u@WBs71%2K2c_C>0?(Vnh zIU!w|{B$uJ5M1&~)IZ?&dc9L?=1s;STz&<0+?c9BT0T3oPij7m-mp(#Frd*t0Pd; z)9P~p<;Pk5>FfQ|PS#3c8HrGj$!Q0isG}qsHc6FHp(6>PZM%N~Z7cX738jh$sFF$r z!C2pBMUbIkw({!6=TH21E!45#KIQK zi--3#gVdK$@P2~@faA#G$WcYU=%j6w*tpo8;YP`;xn~y`2k_bQk?YDK#hr;4#J5Yq zS4xKZ?|b!R#i54Tl)ZOHRM-1d`U7h(h_+?8IVnsi1cOvWzWB{UXip!@oL2#T&w6Vc zz0ktQOv{47fU;=6ZI~1c9wzWd80hh*1mr3vH&g^b5z*@p_I>Pc9%?d$u4h-(|zwLUuSXO^!J3bVuuIBxAnv}LMqC|#vE7ijW5=t&LGg>VLJ?(2o$o* z`kyuaSS0ERPg^3$EQggwZ*+Z3d9q-9M+p*vv1N1fIMe{j$oq+L=ojyPxti!aUC7p zw)VEftsPMTPuoZht*zmLZy}7kX&DA1Y1Nw78^=gjryiRF1CY@FnYaHUHed~g9sTAM zsBHTD`;>y>(A$|sqyHht$8|=Zkb>6sKd(gB*ZeaB^#0zYQXJ9!c~XK z><$_dU$lQ&{kG6`{}CHu_EJPncF?(TpQZGp*E+JPxtrD;)_0q_tJP1Svd5&}&(9e)`88Sl-N6Yr{JfQfsG#k& zPn+cg3nT%E>EBnkF_*gsJ$Y&0I*qn`EH?Tr;`!s|q^<>53Iwj0D4``B?VoWs^7=9p z(7+Ps)Vg^CP!gsINB;AVgg}qCp!YNWRLGxSHbf4u67Cm^oJw=(X?E??y zc>dz{HiQ&le9ChM%!mOJq?azTxnp!$tPQ^!!#;Npi45scM=Z%hmy`UTD2_jLBXPz= zcRM=Znqs$ugkzBs4v2Dq_G*jWZx^8GfXgavjB7E7V(RTri_4zfJ-*AKnakU5vy+Rn znFk1ZZz>^FWGPs3ahXzT8I3aX$J`v>XtdYlBbga0Nhbz{i;EQZMibs=v2?$50#Ncl zieyyzsw61kKrt$BZTi;7bt?y-iv$mIck@$Q@CL1J1ON2Qn^rFi_d~zl+4@isO0XoU z(Au2$$th2Xn~gn%?r_Ux@9aA>VN%qJMxODwq%yrb4vob>$v<~pAI&;PC;IOA%eYou z(q{c`6{8bCqA2}DXGn7KGo72)ws4AGp>Aj-P)&mJoSaW7cT9*lArkz<1BhMBZUi)M zF9h+&c{laQh%%=ElP)`g2H3^$!y;LBdxD>Bcvw`3^ z-fk5pi*mP8`ej7YvZ}VEZ0<98qt}mD+D2OGZ`u|iD_YnmWt=bRbex7x!6uz+?WE1g=XnHBVgRr;ZpQpg*b9R$hb*LnQ{y|x)L<%a_m=a5aC9NHS(w|@&XU6L$5o85C)gsO;$*K;yYYWEKibI(rGsfv=|w2Cuzb#cyq~$jV(rMC~&<*Q+I7!kv$k z`@bj52=bC}L3quPl0)RuqyT@_gmYb&z7=hH8ME?i%0%_2F?!IIB7q8wb+HpV6C1aW z&ve~3xa}g1PYuTpc_~h=1}CbnRnBSpU>YcD(AFL`_vlC>PvVe`^i~UbBEQKbDu!E& zn`QQh$tBOQ=<8;Xh|v*Gr^ZJM2M33QA4?R+_iPGc;;jXhL`?Xy*!KH#Fn9@l^i2N& zfnA7Ra#|CfHXZx5^EJ2T-L|4K_dvz6kh`*m-~IkHYNU``8yFCiWp(yuo6SN>HQ*4^ zjSuZQ`%qx+-*(Szv{t`0)pCzp6nJHppKxWoM0o95b3*RY{7Dbl_2TR9hzrSCks7Bl zQc~5EA7i^t9aN1TS>bt+44)texk43MCA(4%#R&RF=%Mi z%_3B}JTQ6)p~B0zJqhCvr#fTLd03%B(=Uget4>*{9CS(Trr$qw@y-UaDY?4MBvdUs z!;yo5Opnv`1O@#ht-zx0rj(yu@<5W&iA{>Bs?~%2>df}8!*?qKaBy(CNnaYWn@UCD z4XTN4LXnh=7*t4FESzR1-u)4o(h4a0pl;tj49Fv1ZbyB%0mIh|F{0yoPi?z~>Zbip zM$O)7?hg*dQA@j!o>$t93u8c4aY+)P#(Z9m*6;Y0kTH$& zr}*O1Ij}BeWR$3zTEmKt#ip)mCe`_Ha66N2Jrvr%6(l-*T*s9|9~y8G7lz7|_WQCFqJk?O z_kY@Ndq2uQKnIf=l0Zm1JvL+RiGeQ%q!F}`$jR@PHEZHvD`t#GH5AROpix=lg1Mf+ zvXum-55B0VV8mc$FiJ%)j~zI#on4swz4CC_t!YtGi#g!-aK`x?pw;@cGUdy&=Hd?B zr)w}dvGET$TIXg<<&IR5W4$`0@)N;}TUJ~3JD=gO(_#)SjJSzSGYR&3=AMf3?{Pf* z={o1`&p_ktBrI+1O;`Aufw6GnO&Ee^@@rvX{)g&p&U}7`NJC3yUZPPd{{}0E*viBo z{Z%P9t^@e!OjsJhWZ{%#)0*rCBbMZBL+5}k>$Iy(K8Ww(&;IULPKe$d-W zmf?l%+)EKNoygef}KzCp%77svVjqrj7mF3#D3%jT1b1Z#@yilXwt-e=EE)S*xija>f8n>?W!5(=}3 z6uI#a*CFEuy$E=}yqap8o&IowZpRbH#*I+q;Ph;7!lNYx&mZgYteo{%Pw~*p^Sx2> zadx^yCuNDIBw>Xu<@p5xPgV;Qc+aOpn};p36$b%5-(fAKiEU_O$~|v~oi?81Be<@% z{CjT)U1DS7cDO#AWND7I+VT}YdkjEM1Rp1KpLv<)m?bn|Rl834{%1}Kxjdk`c`6cv zRWahMs|E`NDek>J&FUd=tV-Qg>x*0dCvZQ{|!3s^h;Xp`T}`qScvaP zrxe#XkzSq0FM}zhKK-uil!Xy3Ru>AGS>c0Z^fJh;!9I^yFwfcs%zdc-G&)U78@v5& zp1fPPe+Y7=bESr=qTgo;mx4~cV#}KUiiwh&pdiTqsicyc{6<1i{r|ZDH-lMoQkm6y z{-q*(xMZg36&kVeao0lyADI>To=A`9D?^OFI~LC`9=%~^I+iLWy}kLfA48i(m7VFX zn`2EY^7?0&JJT~RXEvJ?yQ`1$+-sBLb+TZ#KOOeT9t9-C^ z_-k{PHXBp0h@L2c0fI?qcs#=uk_8kS_-4fX5^m%YqUwm@t-k~h(@kzuZb!Y0NB#5H z+!8PIeAB8S*V`w^%)_7Wx&)&sTX0aQB7NfR^}loK`ICPtT*VZ; zX@BFpBChZLz)d&1e)#8t&+n5wz1o^?XW{3=d%C)Me0)lla<3X`ZEd}@G&gXxgbl3h zIpe!mgn)p!u#t1ZE`Ww79u(5gfy#0FU1*Rt83FI{(QCddMpT9d-0FFCT0~W$%=LL)Ah50K95fv zl3+vJ`Lvs_?dP`<%0FB}GMQY)w8=mLqPfvePgx}tp^v};6ctHed>$|A55MdWw$k(71XnJdr1eN8V$aX^ zGhO2A-|k-d8XrjrfApnTAoWJ{Zu?7QAY&xAeAgH7h_!g=O@ZcVy(S8{ZpQC&kB_p= z{w{xRY8P{v|3uSwH)AoefG4kbl~FIC_!r?;XwxVh%NcdwFF1YdDSpBec^DaS3v7j(d)f zVzT^Z9}jLsq0dGU~&MyaM`D)`8JY|QTf9^OGK#$)p%BjT09wS}&00RC(~2Kbvd*2m^K8@^xyHkK(yaW< zNEq{IDtJFb@xeaI->cvB4#Jx49S{;IE8;;f>!?d|J6*x)+=>a?{`*v;$Ihpi)aZ;* zF_JY_9+RMGI{$W|`59{9zsQQe(wbm5eToAJ_+_8f_qgS7xyv4220$kzzp_S;>n7hO z`(9BM?L7k}+s;e)mqU@6xR@u9W_!jTXS-*@HfAVdaO)|8<~3v~jhMLjhM$H#wKqEG;{dD@7FSe6sweW#dw+dIOBe+<*`>75CVasB_i2Bh;^5LB2X8j-U~6lA_FyrR zP)Uiw6{|;&A&6yc?=fs3Y>+{TdMPioxx%&Z)3M1a4Q$C#apYvyQz-porI07!1D$a6 zux0CmZGqy|`JGdtp~wD2mOEz>lZ*z8QY8gJk={>Y$gAB<-CtVK_h&>7Qm;z)ru!L6 zRo^lMOs2p_Le|etYE#=`Av1AGSrifCFfkZMU5}Al!N=dKZwo&8`?injA6u&dGjZF= z3tkjq%nt0b#}CRh(C+8otCf`to2w`5l~DjMqvLt=yF~4<%hUJ#`Eq@`MEiA$J+TkZ zqH*(MY7@Q7^XzS1v3AMbra4*6jh$I;Cf==xw5={gQ>cG^xMGkuy6tl);AI|T)gD>c z2?<$DrAFXFog2K+fD1vXvGhp04M~PvoD1Fj@SxW9-jy{;0fX0%UR~uV!sp7J(rHyg zQ4`w6!@4~8Nkd;@sytN{lhmvT*ZAi>d*saWJgK=ToG?qip~tC&tNh`9TSB^<&RnUf z#pzd(@bS290p}Su9H*Q;DEj*E$0Gk(;t~tR8Dxyp)e3v)Vp1R;WM|f6kjsE;jtcol zy{F0gV}U|hCjvQGpBFUZ$)BgmyWH-EHl!a<;&Yt>0q!BVoy@ieq3n0!F=<-m*^!bk zj4p$`fMEQ*Vru_!9ecQS(44NSkq*nLsjCT}qt*QPnpU^Ws)(0va-@g;pYwi66ojx- z0aX;h2vuHz=1zHfa<|e=+`)^LxZ9% z;OWkyjkW%dRoqV@PuhTPipyqLm6TXB)mSa7)I;U6<6(Tn z@1}`)av^2Nb>VFH#-Y_y4k9PG_A7!^3NsA7xUA@dZhE?-X8pgEen?kvez|XHiLLyX z*NY1i?Gq`avgQTB%?!#*M`wIHZfC_bf=2u-tyDl=T<+Ns>hF5B^}vx1hpQ z)WvZm$}s9n{PeyN>Tew2tF6Ltq16op5#UYKG(YD=K;X3+ER{Rn3`S)|r~5-(dJ1?8 z`(Fa=#v)|#Mac(kNnz;ECgH$q;9IxLO*w;4;kYS)i0*j8R zzsPt|mpSTUjk+sQf40zur8GNT{}!c$EdjPBWoF(bEP_CjG_K^?MY|X`zIwm;5a-$E zM4UqFFlI~6x%S425@OM0G?WvWmu=H8wiP(+mICc$nkFdES6upNJR*gZ)=Z$1cV@1E@`eqq@&;B!fDL9$b&g{9b@9`6OapD4R{Ux@xmir&~t5Q1J3Ty3S zoSSdVj0LQvh@OeKi%*h%=u%F*G_&V09y`0FAooe0)QIu&$vD-;a($; zMRcJtTFevHi^m_fd!Bz~mPNISQbmhFbz-~A6=g#erIj90FO?W!E)AbDtE`fK+SIA* zpQI6Kgh@9mIwlElHQ@27qfztM@LO|hVEvG5tFy99;UH8}caGcX&}T0G-DhXgL0GO$ z3L9G3=}n8OHd}!@j1a(UoDQ3*%MnvS@8gp{UV1mSqH6V3g-+4pcPSJe!mLnq zvZWfi$jn-V<0PY@a~-=$&NJfE(9!WCuSnrBkAz!lrzgzxeWVmx*q{bsx}z}ks#}q1 zv;W^}BBMe+Bt>ciLh67|&`*W5z6HmDf8|gk4Jm^z6?Fyl4pmG()|RP>_J+8W=G38i z6UeaQKoKu9JSY`aei1CFOqXwV$O(ASBstT}90D?2%3&!^K;n1rkJVlKr-0S7i-|?W zMhGb!g1o5AaSTS5ph0{DGDO+U&bagMQgYi+WSPQa+;DqjW>Gc{4i*l!!5Mj-<2-y4 zd17h^4e&h9t|&3mP!Uyw{GihI7AR+9drUf-8okS%;bqO`MX9V(Y(j!E2g^cZ>1zvv zml&@Sif)1y&)R(&q6hjf@T1-OK?t>BX5Cq&$*zGS5mAmlxN0yMp^+su8!W z>>p}Tr(R2SA-f%uG7jAH9(gg08@e|y@J?M~pt~3Jpr0@>TC3>fV#LG?Tx3?Zs|Stu zT}~?88$5oPHnvb?m?q@x0Ou~VJnB0}io&?pVkQW1lquyddtRtU@In1b2!>!&SAYD}kmHFuEn71q%39CIaso1N(o0&@V z!ITunE7wwf(s4~OApkg&iHrr`MG7&WF@PcU6x@ZCY3+IG}JVvG^JRPF@RJDV^C;&TNF*)cs}#RX2Tce{Qcpu zc?5WPk*|N)62k{f8A8$tsnB7`!bG-{r+;LUpowaFa^q#m1KS1YM@h{r=88$~JfS9A znWm`YZyduQ^lrZdR+d=d+S7(;v#R@)F>wJ!dwJy-L_KdrL835@?XcD0%2X7;R;h69 zg-4{aH$%8%Di?YEpI=VgF~07B0%QrXp4E^@4KB69k#r)V+mVg$ zi_sz(YK)0k`NxMC52k88SwQ|jwOV)*D0c-ExZ|bPxWf(*F(E5@ae!^E1_mOOc>hVU ziZn{XXbAW{D(s%v{u-=wBl69;QJ@Yjjkyig4@xSHLVFG7eG^zcfeQ_|FgAFo|G_L^ zNtsk6STiRmBo5Ci`k%|g+Nvo6jCi%9$?9_|WM4x`oefCIKa+OwJG?UV-sqySyK*Bj1;9chPgVK( z)(U?kv=7~M%k0LtKPf+ZK%ItC#$v*dRCM5}yLfL5CncB7R#7@5&gn3fH^>!?ybMruMdMxhYxhWKf zM`8p9-Ti;L*(%%+nD_ZqDzEhSH#Ozwox-l*2YmFI9kt+u<>iB!j0{c1XJ&(5AD!=> zCUjq+f_DfjP^D2~Bsv^s>kJKhq#(E(JptpBd*8+7cGqRQ*3kRp)q{~N5^L)8z{cQ( z=fZ5kJBN{qRz_boDT&k8Sau|X5*ZyB=#wBMwwCiZy9?XMX;E8!u#kdqyEl&axN{Cv z$S=)M!^ECv$)}*s7CzCr^z0fVLLO{?lo@`Ev=L@t@B9$t-`hkk)H?(T@_7cgq-Rk# z5TW^HwTkkT@#R(@O%87_<6HTmm|FS?6M;>y)Fk%-(#axAT3sliHI6Ji`8 zSpVh_As1WUevm%>8A}UPDotbEea}=TGfubNRgw-;Q?;f>*PezfE3#^$k1kJzT{q#T zpqA)%{cX;+wZN27ij7x5{jC8~y3rH3I5r>{>h?rj2tsncKk}Fqs2|V9Ely(6?6R+k zEJg0Iirui`LTaly62G`AS&VL5jVJiwtULuG{;CrBD{e8JdZQ1EIx<>Exq|e6FFssI z42m9Wn>L#iHvH??da zfoq*lP$chlSRYVvf{6;&%(^lqEH|HY+~&|>ahh}Ns-VLPh}bIZl#<KGF#V4DD9+GDvefNk(Ml)E%#LMYm=IKhCXT+ThAtbmK(#G0B zN<#!-Vb)p`Nt=(XGAvL{W@=bB6I0p^b80>>k1>uLl?Gi~RiQaCEd)fmq@<0`^}~_Y z^X6%A?A5}nvU5-*j27%#5Uhgx;}%WAK$LQB12H*8OG^tIMKZR?C@Q854E{bzsw8cS z#Jn3@<#P*csE|}51*GTVJ-lpJUCbek?&9@o+zD>$og<>%#=y3%=)#}71T$q?ii6mf zOq+jc1^g(^4~u2p%NFml*H;s(?F8+m$~Ij1k+KAtbD*F=E)WpS;x@5*7lwfDoB0wnXdjM|P0?)TfM&l?_{61odBx~jkms!N4$4Kug0Oyy7H5^b^1318`1 zD%$AD|7@h8zFJz4b?kO+J*=r%|M#MafBnuVjmZ2dqFhdh{HB-%NF^!m@0UWX+F?{s z@#Q4!aeu6#nn^3{pCFA07Mh;M0Ler~p*AK?{XmGA_QK5n)H>Jz?Jyde zPr!-`C&nJA9LXe3o6X%4e0SB67q8i>@GQ-pDt?6bk5M0D`W+{p8}nxK%MMRxKFJG( zq%`~nT_hXygP_$6tE=!QDz{M4N5r8d5H#`Qj|!){?q|x14DYCZQK$RVeQFwItI)TZ zicD$()|DGpp{$(8Ww|IZ-}JJqY2?V1Mp}y$Y~5|cXs|B53!!8 zpsNUM&B*+RtT_GlA)k9U+sZG7MbP0b>*|HshcB{H6I8m>p?;AgpE^fIokfeQPf^m! zP<;9C?g|5~V~ZB#^*qs79X;6BJ0Rh-ZjZQ;ilE}J98;lT?i?dc?Y_ss_I)`j<)t`I zQvvP7#S|$asLub|sp;8O!~DT`%g&HKOg~7R)v~nkPu9TiyQVBpL=6-?VtNI9YzHY7 zoT-y=APQ`f`iEC_%m|ZAv>1;km$lOz)R(HNbb&c?77k^8fHW0)i-I0rN5-BNARnys zlPzt8F}@0phE}8y-7@~X!mpjdn_h!*Od~z3AZ*pQqk|ek7=YU3y!6(W&E>ek$q4sq*$DS_2iiL)OT&=GM7tGZM&E-Hn%{yk*+w2RYNp395}?&qP;39b z=%Nf?>JUgIYgAoUVLTPF9efZ(H=y6`k$s}Z@@}Wn%$IJUl={F)Qz_b*e9ue^8aFk9 zt$%e#hKUZ;&XQLNET{t#A6Zb&I}1%((#qL4%%3o{d!kz;>tqrJ%v7TnsVdLr zz0WzCaklpx{?$uGr%0M(LXR&}_Px}KRL?-^uc=FHc!s0I0Xk~)cdZ$<(}h(=YB0XT zg|UMD;;@qI0RIXkQbRWuHa-#g;?7J#^}@b@z?Bu;DPMavJr-%66q1zjji{mSUEs72 zg>DAJ)dmSHbPg7K>J;Pc$pdYhgG{bF%%7yd;wUs&@hiTJaXIhhQOd8Zk%?mJv+p4H z>$YC??)3+AeT65R&6ncL7@<--u?29^kQeO1>wf(_1H(2*^?eWMD~`V+Ql#PO>8C#m zeF_sUf&`4WVWLiGD${<}nIERt4iBPqzP_gWECF~H{U5eyi{`GK+>V`%5c{w)q7#$b zr^PqxFzK9wPyJXg9DDD_I&wrUz7(YUlsF`?-&Y=8hkC6%=p-B$OzG0hY~10<{uyB} zt>!!1)a8G%JzUIA0mfe5bkQ-7`PeWMqV1%yr6mjvd8=8*{uAR@8j9@lqEnvi^63|{ zvfSGWr3&M^0tk~Na<5oPfc=c@Y|hO8YD0A{-Z6OSD} zb98iLQF=)U!R_RuT~&H@vdHT6aD*T|r@I+>$`z{+&)AR_mZhk2=YN2({6xIvarX1| z&%sS6S~cRTc&Qx|yP64x)b?iIC`}}sI#C#{i*{2nAd9woT?8@l{%j%kkt=tO;vdx& zp$AOH5G3%ARQ&x98J$l7S2~)-QvprIBK!;>tj7?#f31_w(M^XLKM&1u~BEPlCoZ*SNCZ3??9$=$IMg5^FnGG;3Loo1BDz)X)8pzR*gXZvW@0 zJb_a6q3{>;kAaketpM+rLr1*~&iVp_n^xNR!m*`c_7tga5-cgDO*pQ4WOHjmKma6^ zsOoQl7{o|~VA89RUR<*sZk4U3u0E%wBT1?+&xV=v0xKDbO`?+OagnJ{SFD1IDlOo2 zL?iHi*9;`mcQrHoKiRCBEo>Z`GVOh+Me zS6=C{W{I}ZH1$nx%jLn;G}RkFd;QqRPt!5vlU_~J@h%@erQi$QFt9+n^ulc7W>c8j zBofV$9}_c+x+oa`)YXBXd{M>#mo5LTTmr-~!kTe`J~5W$u@^zk>rK*}Mbe~y`e`ch zl&JGNm{gO{!KlN^himk>&24fze*EFx_}n5PTz@A9v*2NLDr8^l6gK8Joj@q&4;*gO=S?XIV$O;5S`?@%#)E}fnM>j@mH?-8gToYigA2c#&F zG{gU|%;7lOMy?kbTvJE^&a16<`bR|>d@B26F0tk|192twYbtVNWMJTOl;v0V5p$N5 z&kYqgBZcXS)rs%bt3Rcs%|7}K#%|vjy+tj>jg)DLYm8&2|9J@i)>xDpV|re(2^e)5 z^`DTEM!6ozCXcf81wFK&)^8xURWuy^FkMz=YD)ybD}9uYyvqNg@gKyAXw@k1gGPIn zL<@Bu(_L$E!>vuPz|po31!mj&_*7N?s!@4fUnyd`;SUkvQE%u!mQ0fiXu_Ayz1HpY zmLOv2m_deSa$B57g&{-Ih^i9AqDKm@3JhF`ZW$l`?9lxh&LnPjPz9guqA*+(14S{H5}l&nv>rAdG_Wo78;CS*{VA`x#**@?Y- zi660j-}zn7a7I1osPWrUo3I@U&As~EZPKOor~-H1cBQ|2Uu5Ed^AL4 za~j@pN3o;Lt4PW3ZywJhF#+R}^|~~&&reUPM1{BJn&NZlCZEosMQ;9fft`5rK(Q?B zVMM;$&J6^9Qe_zBTP1{$8ByTi4-dHoslY^VrAe z(!Wj=(ZvqtzoUx@?~#`UJX8I{mQMU6P~%$cmmAl_f-avVtsM1arkSy&lw4lBq?^1S zw1ORu_@jFM0)5EA-{nuAmV!pTOjq@@QQZIoyt=;lw1UTYI{`|GwV3Fmf(u!jjyw0g z+4AwS9epR?g&mov`DP#h%Fy=%TSYT$$gXXk7JS6fbTK%!0no%>D#DUe`KY7VF z%NhS38D-nqe(qu4kuWQ88xyM-e~T6HYG!@1aGOBn6HJiPiV7QnlZ(9{#|mig-f5{s z`N^B5N>gQJ-s7d<@W*slq+~Hde1h}So3y@wS7_cj-t+WhK(a~3%vF8w%@;7aN|G`| zJrnp#-Yb~ZMTb%z%uy#j`)`l8C#$2+U1$+F`av9rEg`39Xm>IHg*u~?*Xv_i^XV^{;=JxD zl8_)^kKab-i4MzBB%gMWdYN~7y6tM>YcjjAzJ&jkiu|2?s-$~Q=`{*Rgb5|i0+~Mk zgE5yoC%0Wke6lAL|0H`Z+Le4|qReua&nBqFiU^C6LbC74VY$(dZo5GcSxQaw^_=j~ zN}T6`Q8L<%3XJ1(YDPN)O%w-ae23Vi78!j`7e`IKUCVNQRp~T9xJ_t%Iw6_2CfTSTOxS!^0diSSv!C|;t?{|Ld!^^>4eS%i>4^|ZXFd{Y2 zZ04-Laeq{IrCIKCqDrt|l_dQEN}{t!=db=;dVqeiAbNEpT=f?;$&zMx*ywlCYvrup zjar9x)Xj+T;~ZPYY-yw=Tx$qf$o?9N%-3rp2vk0u8y~+8RXSy(Nk7!CPSmx=b-N#< zqb;+684c}~APJ20JwI<6nTXOYe(myF=b9=6+WHy`JRCL@W#tJR^!k8$GQ@8c)!Cw2 zA7Ppmylk(XBGJt7@nt%!2L24U>Dsg9Uj*_gxqV)7x#s~N4|Z!a6$Sq39=7Z9BNI;L zx2P#uY)JMSU4CQwDhc%8n zt(@d|jxO+@>9$3|bJjEGOEW&}jt(ii|8giTX-uQ*(F2iYH9Cequ74_gj7$1wwVIOU zLH6W!`X@!nMc396@cnuhXl-$Ky!(SgKRWW;_3NmlrPN=DSn@K{^CsDmfWEk544Yk*t1&jk08=4ktcQPKi2o{q0Dyva-W*z<@~)`D$b$)$*w!peBW8XI^2jQ!p44(9 zFkvV$u*8Bi2h06=Mc>q-apsTvw$EUqd>^zj^z76#oxZfs8=FsFqV-Sv-j@;C?sY#z z&H_U4hAzAR$Ww0voPA?Di;RX{-^%T;bQA?9B?*0F-|^h9M$($Q-QFS8x2cIbKT+~~ zFG=*fT(brJj%{*#yf6Y2?Hw&w1wO`K1M(lwc=}fXbzB=?1XliJSEam->=K##>7fPO zh16e7a|TRFSwqOnay9F}#-0+FO;8xi@pRx7@p7XqYaDLFu7VyczMdFQ`d3j(a` zh>A;}%uD=$utmn#5JyHq>W!r}1$nL+gZJ}*Lug6;qUOFF%i`#OJG#DcfbVpClK>Ac|i%Y(b^{xLMt_5I>U{6JJ%PX9c6Ty5>?bJ?iim?`Bn zk>DdIevfClRzowTKIl;3-s-{Cb~^-`a5tyEZwe1<*759*c5ADVyKvT}+GL`TkU zg*h1;0@3?R03=^%)A?=oOkB)^y6+I*JyuyaSz1fqdYU+4#^rvG zzfKmyra@I1r4A^$AKIgb?e4)C7-KHa6u>9@Ux85WfaO1?p+omG8DQ)-x_rFAR~64z z6m8@o9rU~U6&Z644UK<2W%mZWz>L=Ali6mnsZ+rotJd<$uWuPUP#Flmh)VoH1G#mE zzj8Z2BNz>tiuzUe)s#1PG{#-qX5$U{@pvQcgePX&w`vQK3{*;yms<$~Fbn+7SRg`f3C;?}~W8y*I0O zD8y*sa}L5e?Emdbxb73^NIi__P_Q?)N;UoiGyZg^onZ*g#P>dph>4GTq|1Fxv8l>j z`_Pw%y^;3Yxi47Q4wc2`P8@tiqaO6AOQT-IK%?@<&Hm+{VIF zq5Qu}>c2JAFqtCfu!>$kDKwH`_6GATXp$J)Vu0Au5R}Q7Y;5ZrY^U><4faL4@dw#| zF=Q(cPEy?MZ$=cnb`udOlPEN0jZ+0=)#nQi7HRg*B`h`mK3SeC>LshG)*&g>!ViTsTYGq;uz~4D)_bzom8X zue34><%r5>2t&Q5s0UNBjF(OT3A#uyPbK|@I`pn9k&bI!`C3KRNU?~q1hBrV97A3B z7qJ!MGNv0UYUw{OoLVPWUfLt9R=FU7K!nzwQ*_8~09LagKh4U1v-9i$wvpnQacbMv9~9JG$==z`J9U}VK1-={7S3r|Eq%#x6wb}Cs_Kmdobp=yIZu23=qunCpgGS9`Im*- z!P#hj&snW4iVQPZL=psE-;r~#lBSGrEveoJExM&1lE}{JEg_)5i?@cp1%Xm{Pc53tEPC=Cx&rpU7j1_L~>kWw^dyx(9 zV~fKL_p9nxy3W*`|7{$t#8tP=Dlls1$tlsQUo=G2QF)QP1cB<=N_S@%#_pboJ zb>zzcA|URZuKrAc$dIAeaKXXykyh=t!*+&v6O(KbQx1?C-rwbwOl#~;ecMx>Ri}z3 z))?LJX=EAUMvB2;acKGCJTG?T2hk4tpGLgD1^nF!vdz2Y+EzGVsK3wZ^^Hoyu3`8H!g^8hr?BG z9#VVwXSs3Z=;cN`Q%!Wt`bHUXXJ=nTLG%TTNp8Zd$og>G47;p}pH<(*aO$A|5w=sP z(b9mm+AaHzQiu~%EfCJ{i_tU!!g7|Cdd7YQLf?~Tva6r~nK~=l^7F>eH|)GFS{w0B zQb*m&-Hs7$Z0%vVcx|>#M{n!K@&gbjw?`dW~LAFFXUUd4p=eK{vUC01ySqVd7%4?t893^Arboanu;i;s$>$w zma985t7XV?70quk0G-}PUR!x5+cwHhkv3JCC7q=-6^DcxBI71U(SsE@ra1orG3{^+cU7jibG?*8q4$% zI5iPw`%abHQ820fY@^SPoXgAi-WKIE6%czh_alhOa~2JGFnsD2nbmk$o~JCK3eYh$ zU{R4QA;-MVqc%aX_Cein{~_K&+NmDSZ0Ma(b5CR6Z7Om>fcv~&wA7q$s8!1qzN8nE zgu1~=tyCDzMp?oa`Hs^`k3_Nm)WoAq4G8fDo9`dntQ_2*FJ%~q zzc_Q>|0Y_-fLec_iBtbdP|lx2HDt*oJHrw-SN5LMWV?Z#^Ogx0q$40^e2|(6L&4f} z5Y~^I{Cp7AmuuH~i^C@SnN{X1Aweyx2p z{Jf*=J3U1L`VGE*{I4#^%gaNF(U>EA54cSqg)d#q$h=Fcf5y0xeG`27-NE?g-z6FA zmx6Ea9@{5?Z17=+0~zX2^XHGMWp_Vg1ilq%3AP?z<4eLTQPJ~Vnw_m5j2{BoVh|`H zPo`sU3plQk_WtR!vsnBOAgy&l3zlWUNxek8q#!Y&5=>F{RDEB|%~4}DO|>SsereHl z@tq?OID>OB6YSHv;*pxQ!cd7$g%=m%D>OR-oLn96znYOSxs+GXpMFbmyV!QJ1C8?X z0Mf(lzL%fh5DxPG0n(phCI z^^Q(H`wd84&&-`|Z8;>`cCP!f;cX?Y-_cmKwA`KrUHr8rV&)IFAc0YjVV@MY-xF9& zCwrSTqQ13V4;!TwziJlzN%;M2 zc$aGpgM6DSH}gfCzmJC64d&mkXV`)cXXK~*^54>Y?G|*r1y2t&YP3J8QJOAjkWdKOYhARB$p`ejLgh zX7?Y%7dCspp(RVe4h^3br+6}jzH-RO=YpQ^n(T?D>^!_uGblCXO@Y(;zOpv*pXwXF zoGza{Q2Lnme3{|Kt_**_iJ)~C{*d}cA1HJx84GWUYzGBe7l{&LaeONQ=lsiUwL^8T zuZ%}O@}!QjTN-KlMwH&{eHMUP^>MsWaU<6i*$ui$6G!6{5K^@A1<7usFTY zm2+Q?VsK*2vpr!Tya3I(saPNJVNCP5=q4;XL)qiv$z&#Hz*m{x91B8q70OyaBmcZ% z&3g}|XNrq0+@AQ>`1}eRZ_(-kCnEf$`iD2&na-3b4b5taS6Qm`sSQ!4$?_L#aEgfu zhzeb@LlC)+j81~>(i=T9!{orAnR)K>zt>N_=YgNLd5YBD=^~+J@ejREbFHdtPYH}F zCl%HGmcc})p>{2 zK(YDb7b)4#25V9?-oPCq5E*fG{+(sO3tMBZ0wEw&FW_Ip>gW>Lnq%{0TV%))(YZ0lq6*=RS%%eIAX z<;NdqZ#wRZ4Y#l((4B9dQCly+h8HwZej^K3ZcpnQsodP|{#NKw8hWq;m5*rLH*Vaw z%FSU+7l4 zfNMIsL%mR1cWYy0-0+5AwTtjkm6Fn=p_)2HTh-2qpYKq%)^$y*=eGWH-+2|6?{IlcnLDHrtf9daM=zIv_yi& zrS!Y^2Cp89Jj!o;RiNCxy@iI{x=lRuoshOj@U?Vx4QXczIHl&*AbM;~ z@%p-NKP9$Tj<`9T9+7nncX%F;2)wu${(+jJJG*=hGh^ub7@fY^6=d4_bz4BV)tPi+ zeI1rtbt(6%}eR@`u zW?ZGB;p)&8^R{k1zG^c0mgVc7(&4d->U&mfapxd>L+^e0t!BlbO_440&&GRTh;J{X zK_k(9tGfkfr7Z-*cBi`RGxwP{P;+>8LQ|MH>uO7DJ*#oMY1@*eN9hhvhjC5ufwsu* zXIMZZVVA2NN1r2M?=Q;CXs%?Xa~w^0^c%l4ZJSCkk`Z;>R+e;}CcL;DILq@W?-%@q zFpKc!`(LZ865Mb>PxJ}z6Jw;?vLVd|&5G){5c#6yMGQ)kfF9L1@n??X-QHL)hoTx_ zQorYo7+~t)pLlAa?#hfi-l;`-4K|xrr!&Fl&5+7JcS2dI9u?djy0;Is%rl?)J+5Y5Ajb&x3@Bu5BxSlM`oqj$XstO0KT+uLWj@|75<6d`VC%Oidb}q z`!3>Wl;YWbjpCVN)-#IDqWp2c{i)6=-HYa_eDve3OS+(QcuWRgPo>|ZORMK`i28t| zTpIZ)l#vL@mEr3I-udGx*#xEwvCz}tfcxf5Pdcw>_{`2b&6BmibvJ(9XLsU`t~Qod zz{SbP@a-@0+%k4$7iTpwPS?Ev&CfY9PvURFAO8+Nv_3!cr$3xx1^Il(Zh0HvpK!&o z?t5_3m}IbljV{u{8@E=_X5mc}up^R%d53?+N^C4Ee;_(K<0CCezH^ z`$yx}>6UCcyiWPQ-^3dGtfu#!InQNBu{m|B(x41cpMkqJm+txeF8bFSwpXM+!eb$UxoT@D4if z-^=lf^0fX)KMHu!l)WVPO=m}gZR7H7PCHkO(d5USF0SpK&+Hr9Oh;XL_+0!=YY=66 zHvvlOaP>qbw5;gr_Hm$)3j3zs4Os<{|2bKEVMU~}aKGGxNKS0G9V9IbT9hi-@$q)` zgeb7!MYx=ehpfnJqFmOHpvft?nC-yChf$ha@&B$nq-s#P(O#22;pZsgOp$i}at(t> zWiH*jdD}kW$<$LmgC%QIe4d!Gb;gQ^PHOCHl8T;m;{3I^8H>%FpEyf!5Dqb>x;AqY z*weoXcV}-Dq%cYbA(REUQnUS%OIYv}fxBtw{mX@e^YtJtntVt{)>`YAXsA{IJ7SE} z7w_mB-$%5?0(Fg=v=w>gElO;GJ7~;#?@$O7i?xDjb@Teu!aoyjyy>lY;tc*lHD}^! zmLc5p6+_uL#=m#eS+@)?f3dT+5?mZE$euTK--vdWu?L%KMfPD6rwVqOIj1MvZ6Si( z*l3R{3$#8}Dmg|J&_zF$*J3L~=3O8YC#P=MTL;}Mwpsx8=tBiAAr z5N2g}=Knxbw5NDgLI)`+iIuvN7g1IPK}}(l?=8(fWpOKwk!QH=|ARe; z@$9#5bx*+j0iT~sWEwcR^3}oRZwW1(u5iGj+3eL6|JZ0r(p0bp-a5zY`1#zAIy{AfEK>jpnwakK?5u!Aj$5qi_1V@+!(b`R|5b1-8j0T@mJIG z%Q^y!=#0(x1NZ&Tl1%TqXxWFdaj!A+g4G&@o2 z(+LF(e~Nt&&MVlZ;;e3h*W5LKeT{8OTsDOjv0hG|$JY3LW+tORsVt8z-ZLdAbTFth zhuElNB}UPT*~8%dYN>!wIaa;K;SC}yDu52(Miqec)Jj9fY~lg$kQ$YzWpjwHYJp@;^hjJCf$ig5=9$hc93B|~ z6aHgBA#-OE8$H0-D20k>5ykKBdi`R!sbT1EgKHM;EvZcDv+2Coi=Vx7`1=~fw0lx6 zF2n|`F%J1wQhQapoa8N-a&@II0RRP>6#hd2O}d1C3s7!fztWCcw)CRf_3TZ+xKiRb zsH?gwddG2}Fk(ME&+GEtD3=$)7}fYgwTrA@Le13ySt(yC3DQUH)PF34&c1WSYEvKqn4|h`jLb zv9UUH2l3?PJNn7`#^9kS6_#mop-j8hpJ$zL^yAgP&r8RZvaU8;NCEz2tuJUN`VPlY zNp&DJ8l7CUn0i(@mlL8Zf8c$PkN!)UXtX|Wn*;dZC*xLo9_8YM?A+>96Q^x~2rj)R z{El^JCD!3toH&wYVYVo{A?gh5Al#}4Ch|HLdJ*G38tp5$WSS0f@*I}jHfQ^|hRSQ# zhe3tm?Q^;QAHW>R?LMOJ_6FT9mNgg*Y zd=dzo>g-%R#M(ksIE%@8rt6{7e7p~a|g=XBcwgfv?x*yZXhsGAvopTzxWfnL;`;Uhj0SsWJa*@1PH|<5tGJj zHoZLN@}Su3nw3lL9ubH+CUFWSkHFh#co{@fUTg&HhI!U0UK-C0GD0gNVYiqSiQDGW zKYqTp1IxU@LE5KbyKs@o^45Y;Ctj51-K%^oDCfB145&RcN43zJVHU_z38(pzRxsgO zN3M4_n;cgg?1l>eqbb4U_9W(vtuAk=A_uP+v9?A&H>)eUC2U1vj zxG#lTeKU03bkLV@l%x%#R33ZrgLh%WjyxLArabymg=BB0X<>7QZ&j>#@}Jz zF3RMAB)b^d__>DCF{yPKsxlXQQ3bHDWp;j9Kv5&gI&e)MeEqGCS(I|6Fy0hYQRvAH zFtpeo{<#+-O+fyV=iM=h@#n#JIxg~aGNlbHILUv9n<2qW;9DAVEwNHB%Wy|agne9u zT{7k`f3f>2_%^ey$7tWei`+o2Hc5Foy=`gQb9nu#TthZJZ#-J0$|&&a!w)=zjc?o&|eSAF6=&fSI*xaHCZ` zYW=hDsW;hl?KKKUKx!sh4+}v}dUM0roxQqjUg4qh`0wbCHY7$HF=w$w5}R@NesN_aQMp?rHRhyNz}Pw`sfr^Y3{R%$%%(uHrvR ze@Jx?9KK>j`E(>K<=*6cYCX1Yu{{w=c3V)NUG;+!38tk5jvm=(F zztw|r;>P5pHhMAk|E|2f*)MmKULsLYv*s#V;1Y4!7SP-!wbNAsy>Ff#P_TA|0pVy| zLWlK5@y6cbMVhT>ECMk88O!BssHk#%vbFZ$V)bQ6x_E#3P` z_!kU;?O!&^0arB0zc9Q^V-~1XMeV93B(pO@J2^VgI8EovtTK|ok3v=J;- zOzqDSdu!gejb_79XUJ)qqUzB zN}ZgV+8xG;-~6>Sd~@dCyVA}jTR%01&z~-Yx~;>jj`CC~`mUyKY-9R5;d|a%L_8iY zz07`9w!Y3Y`u9`SJ54P{B z0xB%h7SvB1N?Tc>&R+>zA8cby9s8WWh^vorRHmFtf=Qf7nf&QH9Ak}SWZh#sf=*_g z`LMY1NDFXfq1@PbY%MXkJ%Y$~ER1FB->N_W zxe&f&$`1H3=H^O2$wt2CqS{~h$!|OfqMtJ*eg=+C77`xM0r3ifam&Cp zUQGCiFGf8&{PzT$OvN0nPQsJNw9lB!EHXS!_Pe?^IddprLTxW~mDaPlWpx*tae*(X z5lKun)zwQ!stH_8P8a5tiaA^Fii?Wu?qJ-n=MISJ>bym4W^wx4F5z+ zO6ZreIkJLOhP*z1mf+y;hOu<{+AAnra}y<@Q(N((T?1P_dZywNdlBBUrZ zzsh|i+j`{o)fNX+imC`gY;xYgiMs(MihQKRxqfOhgHK>xySxva?m4WE~`~vbInLOElhQ!gznI69O)u?@!$l^ z8W}`**dB7@C0oxv$1{z|9px5LOC0jD%5va*cuI2m%FWh%FjhjYb%+llZo*CRTl$J| zxw*C#`#S#AnYJi0|E9Jna%-O|R_Qmh$d>#pgS(|}8G|jn=U=-cLv?I9(kghmK z;Lw{ciONsHh|+!jV>D$*JMnJ@3f1)|2i}!e6rs=?A(hZu2O#YksDGF4(B{?$nt482 z>}VOFm2y3K$JsK;(zSHynfxH20xs*WJZOGEqjE+5@Xw03$p7f12vKx7AWTXuR4@i= zDh*;kb0T)}D#BQ0^ZYX3;N<$2=GtbSoIKO$y=o`Bk&6rV2nVZtX)SxC48Zhk@+i~Y z^$aXXx}qpGdiu)t$gGUE%Uy51iGQ&(4is8#HZS*tHd?XoESu>rOm3BQbW!W@Hu2#o z4R&fb`(LD74~W_N$uu$ zPhSvj4fwh-TS(f`Ivr9%o2m+?C-(-ayM4q^*Ssvq0bGLhe-qKc8e&i6uxhvzd8M%< ztX{X|ti)&*zna>b!gmqhNX8Ug(y4|y^_LUCbL+OpoOmP$hw0M%L?Ah4(&_ceY{8ZL zo`>j&h5Mp$!y`2!DruJVFMO4>BOX>5=KVqm9}VrT{i=WNNA?e;jd!rD(-8XsX*oF) zU9Mm&3>TBzijOOiu_GgdDW_nY&$K;l@!`UY6#^Yo@1 zs(kzl5Ab@ho?%)`>^}5lh@S_^n-ti6APOf5u*?e0J}SLb2*L0=%L{TT#sZO_G({3# z(Sc#i!Q!%Ul2D|$o}zg&y3jBA@EPSI9+7`W=nfJt_n7&7m&@vEVO`@)foRSO8zMOO@YNpa4Tp~btqdN~TGK$3f(EgDt?LArErAs637s&}X zSG&OUtdQfe9otY?FrhSWQaz1;_Zm}ROm;|hTaQ-fb4VSPh|8jC8*f2F#)Jf z{0fl7PBuG%jzKMm6a!ull!RfL+_1`&0kF>3c1=_iYY=5?`jvP!b4iDA=Yp=A0aLIEe|0gn*)aB z5z6pCo*q=FA<4$<=DZ8RL3WD^g(MY6-DvQU;eBm{Kk+6-{cSwmD?-TJabP0?95xrJ z&fI@^GvT)%w2y2qT|Jg?nzhY^oNpy+OdEgxxN8?faqW=~9K%5RBu*y}H*u5mXKt~c zy|vBm+W~$_#m!Suo%v1po9PwL3OZ)53SA*7LHiv4w4t8}W(Yjd;>LpFw$|?^I9OrU zS*lph&Y-4T6$hKm_Qe@J17GzcI|mr?WDV(mOgO+Bw;w3W&1V^Z=Hrxg=STU{I%WT1 zLxCFMPA}1R?E{jxNpv8u`G%KJ+5r(UaT??RpXPSM?ja0dL(8b|ILZV$vAM#u>6QkM z+xR(M*5Q2#7kcG{xr^4EK}$kQmCmt+Al+sD>b7B69G%OErA`wklSFv-vZXZ6{^a2~ zzZBfM5SVnGtiZ2YvW;a3+KuXm3K7y-DV*_M>(cpfZ1ocv1s~8DiA_eM&jwdmg;2N# z%Re_YJyRgZ*DM5sWI`IPLQcZd@PZwTnnCq;n75!{d?S9mM5`b>M1SMd4eMp}P81ez z7AIEJc$g{_?13sIFw+_I4XCSr5l<9m(z8}CL;33J-y*#7ov)g*GND@XL$WdS2{TO- zS7^q!U3?pGdp9o3vEuuifpi_58Pl6(S{z~)6%**Dt7n}Eu z1xK1~D#(#1UdHs{+s6E8O}5c`R3F#epp3|-8|0eRH$B#ETqiq|bbz;Tilc(U6@>jT zZ3*PH>|~ZItieFh%_#wnJMT1?tyU{NFaSRoFZ)lfuB&y6^!KF7zu|fmp2{t6p%8Q? zA_icDDb(lG+>FkGy^nIi&Ki@@DDT|olb_bWw$9Yn+LSt}7LS-f{NJ5&T<`&*9txX6 zKrz(GM2nzc4tC<=6f8-+-l;(8Xq!fU!gdsCdW!(hObjx90RuT@*yY}6-oF>rEHxWeIhf{wfMyk8rE*X&n_Et|v#mYo?$4o3d)HwHj4Zp%kTQV>-)w7PGGqs z4N^CWY+17W3bbl~m|?j;hFXjMZ|B!jy75VRyfcQt&Ksz0gjkNhv36toN2nHxA6^8g z{a_<4cFb(V?W5O`c`&+1ftw4sKd*Ez(%)?Q!L=Gjkskg~*h@l)%81f#`2! ze+YpR1;YIMID#HFQ-Z{>15d5OFgxBqh&*AGHSFv-E099Fn&V2$wA3!@>^-l)$Q~vN z0VbZ<%t(VNpkxFP3n9^a4P1i5y5Y6^=97mvLOh9mg=y3WxMx0fFV&l zTs}q*%2DN}_NE$!(Xhcrwg-CQivsngTX;kZZKw$LpqNXNXO{4|qd1Lh(aR(WA^55d+8sNV6;_+#*p4y*Xm$n4!aqrfC)6DndoW?7-Ft@{>c zqg6h2l0Fi=HuF)616=6pPKcn?xdwsl%GJ5j1xwSCHfEH@rx{&%B3#2X4y_L(AqMq) z-(>=nFT<7LP_wr&b9Jvn{a&Ke%OFCl5ywDAm*1x1H1;*`URaJUYGL?UlcgK@(Iup`qOz@;C57eNP*!r+wvCl`oN~!o?dd^uD zsASnlhqr^thNHH~B33NIFj`RQdF`33<(6_%hZZ%dK$b=?|Q4U1QJJJ&1 zcG;YrGeKrsI44xHd8DMzv>hFO%&56bZclD)NB3*UkLF_jiE#cxHxUy)!No(4h(Cny zm&h8t1=N)We*xq*DCv!&gbADnH`Vt7VjTlx5`}f4jnFAb*&UYE~+`C7o z>z^?E<8G3P$t-%<92FRff}~iHD+VUcWz7O0DH@2ViLP+_1?G5X z{G@r``g~R&IPWTiQC_;4#g+29gzxmbs|qLbe|c zXZD}Hd|K04kbMJj;g$pVqiq|)f|zob`- zMKOhXRl=zAmNA>J5he(~C!dR@2nE!<*0Y9?U|i&3>~Y}P)5#EtolMnm!W=hbzG(9T z3ttLp%Ok{LyX1(^6}CKdGkJcB>RKRS}hsFG4wn30I zrGpDz?GExqLT}!UF<;cuUL0P6&kR?bE-wuy7PEW0tJJd-~EKFrCD` zjGZOukiXG?r#pfsTkFE*QGFxOM|g+46rU&3dZCJpA07vWT~!qaS(2@ZShNyRFqFfp z(jU0FcV(QS(_q<83XbU^2-t-XOzZhRYr+P&LqbJ~0uoh%!jxSX9x<3o#?+bzljqzr zgM9o{vWzAxD}y646O0ZfSu$<#7t6=ZKtsxY5eqN?ko{hgLh@#{(W6EHUE*H0BM2uu zTg(jOE2Ps>3di*@zdAfG)62`dEzUo`{ywMrTofeXMw7i4EroY5wq)njVHoutHUS6Y z``q08O{=_h`Tf_Y(U~uIcP-xA;0A|vt3BwN@9t{zJbiX-+_bbbD>wH@N{B*|u%{Ro447U5VI`Lr^m}eD&Ubnc`Tprs!2|yvLmln42PysY{+DYh-t5~1zvp$} zCfy7zo{y>eA}1kutAQ56AkhM;XL*B`>9w4z34wb`>KGElKZuoW?WU){X^u82-v5eQ z71YqsXma0o=FKNir1IE2`-rQ;A-d7~C$!@ca@nOomM|JIvK>=WfRO4+g}?wlaOg%9WWK*pBnDfb%ujTUHt z7X*Z+1}HUV-i|P1{c2AAZ&|LigceV8yr$8)y(AR^BxuepGLN-5CAaYkvP-~m##nYy zI*WMcg>IFM1JNbi|5&-eFbuZ+*8=0CGe)S%*!yPcie?Rxp8Q{``96X~{Zs*x*>q6! z)ns`G|4+Uw;euEKOpTx^3@A#VqY5$>TEd-shp}^|cI(k67b?1}^fFPOVGv z?#f`}>3kdAVQt~Ysd=(K7ruIM9LUg1t@)a(z<_C8vvZPr^2jVyXU-=u$b<=CUk=0stIx_*-I1xL`ti|fF|B+xi^m6xVgP-{l0gz8}=vjMP7CB zlL#uB)`UXS`&#S4PS~dJ6@hEs#4jbx+|X0ld!wo@Zhx&k={wi}kTNlwuC4d-`JrE2 zd*1RJ)htA*CJ5D?P0S4{gyhV0&&OQf+Db?bOa_J|GnME3w>EZM|3v^E2l62*80Y4g zk(Hl6FE&?9C~J4PPW0e!g89O(K{1$?9EFZf9E=ngJ{${#^tnV7lD%5vbY&QXEEiHh zRS?BrF7`bx&aj~>IYpF`2*nf;m_~xHC@vOONm_a9F({%<2!206^wqXjiJ7qg#kmns z-%;H|nSOJDh*)YapeneRNR%uQf~2FQ0PbjYI~GVwk-NKirQ+GQ_zZ!%_Me{$Jbl1Z zpUcM!2Yt8wy7(U!qq8i^En8F`66li~rniTlAyc~jQlxaXZ@5p|%N*K>~rrr~7u zLmPChbUG1KfQKHpX6Y6YLPsOvIw|*|ZxfDs1Q(~rKqhWt7gs@A`_((F_mS{aSH=um z5(x-$3P|}*M=$XXLtT>KfHzW&C!#pvIx^7ZLa(L9t+XIC6om{Rt(PT7erR{7G7@d# z@ku*;dSoG>H^d~RLB>jFus{DpR%skHwP2jz581i(FRQ}rWWEAytEH+~`^fxtmZ71c zwSlnUI0Tyfg&&^^h9^R#%gsw@Ax}E;%CxE4#s+#CS`_bdR@E^f5XgV1PacGm%1;p$ z0qDK!|Mjtq4etQ_3Z0Cene9N>`}lzfgY1r75xe7ds~t?2%~uAat~qFQFhFi%{^=!A zLP9Db*eo02@_hI`ynR^Tm9YAAO=~x98XYc{ z8K=?N^i+L*5O)GSY-F$-&Iyrq{iEl zTi-1P$6XMg`w6M2BG`XTQzA5U@Ki@fdk5%2wd2nOaOFc#7rWUnFRz+3r&ZZDdTYb1 zIacVufl5awDJn_1MDb<@4-&OZ>#uZ64uSMYfPw~vqCQFIFLRpaB^ zgm5u2_b~yoGrpUP1sX-@(_^ET8H?O=zBF+ag-VD@ewH>~ZH@%ex6zp{+-e%y5&=Pu zd-gM=xu>}|*5ZgFHDnSJ5<1y{Orq+%rKO^xaz9zQTRon`#@9*jq@RlP6zu~j>2LSC z5{Of@FXdMlnV{hBSseZ_yp}7xwgeYOkqt@y+2vqt93g;tURz4yxE39xSu^F%d$(e) z)urS9Bg<^LfWwD0@d6TA%{HmD1`{0K;XJ5UZbDR;TVbU5I*ZD@Vbq0z6)us1*RkV3 zp$OVhkgn`A^kr>TVlEHOPh_c z?+a!XJMe0Qmk}Leo87wV^Bq6+{`SFj3~&DhCPFe-r0*IU-Z5p#>z6hQ z0fu_+CFDh9$TS(IZ5R66OZid<@CTbR*aMvvT9r|1YQE3gy85tBiJR%Rvg7zz|GF(XxBT$L^AmH5(T`G-;JqYBG{cK?u+K#r0 zXJzGxpw7#P-^K8HxwuLK8yZq3g=p^>@6Y#W#NsX7ArwDEp?V}S82X%o*MSz6u9 z0YqbD>fiu12nPl*nO`aMr3+M6w5KXa*jj-NFuV?y0q|bq3Ec!{XVjiQ!%^s7-ck@q zH9o+{;@L^Bd^||AI6*EC(6KG<|CA9R<)J7ruRqGgr;vO#!kle?;wSR}Pnm@#8?a^! zfL#riE~N*uc;HkK9D+Y7*>pI2xfG zCtX{=LI<{BfPEzpz5_s0%-TwC@Ni*oZHYX^iixvIzO%^kDj-&y0bEc~NjuKIv#W#U z9o5e3DlyR@Y1988Fw+$Q$CY0}T4IU1#5Fl3WpOLf@hXtT8!-DySFFvxfQTxj=ME~p z+9xOSmq)T#{)eISE1)HkqG=F0r8Irq_G!1}zfM5@02-8yYoe6>S4s4%n+TXJ)5^6T zoo3O)2g8%OhF39UQ&JP9m-m7Z4U_Rl-FL;#dS&6+?C>|^s;ma$=8T$tyD zMja7}Yb9;bxFIuX2g}BqQ0WfUh>$@fOMo&NDaN)8ljlOckSQ%CWrt+*&sxg7rLgr4 z{+9R{alcn)P^MK?VOHARG(kb3gD`-X#Rj>?Rv8^1{lkOiQd2`L!160rEMMLgnU1ap zj2-{IL;2a0qcqnwZA!WpIdn%ov=i|A{(~R_fWq(d7h}6wjO<_JqH>p~6onUENkexNOeKz>TFn_B37m&(1w` zfO~i(^S-6d-_jsR+UGwsi~(qfS*!V~@rT7(nGKrD02pO+k7V3ROMbV4$;3a~8z=AR3x`5Ug zvtFPlW|vuS<*FV`E8$sM5C3Mmn=FmS?+K26QVm(!PD^swUdR4$B?5S722fMpVX1V~sTkm4FWA1fnbYH6G4y#7pe8FuQ}19z!f4FRxP0IYz6 zEO9Ll?Dw){^PgRm0rLz$%p4CVIPsgB%fnVLBnBKgat0>0ty0%-pM0Y(BO35oj?Mb^GL1$|Ap1-PdF z3`ME1$n^Z7D11|VzFYhy)uHvWoHR2ol;i#X2pdVqv)B$D%rEwsvKFlD+)P^Q-AbyeKOX=b4Z!a^!)&~1$0QxafYFfkWL9K1J1wnzLf>xAw1wMqcw z+OIZ6=rTB-|9vZxfCC9EjKhl^9uD_pBySlj^)FAs?L#D04GQ}5lkQce$j+o9*6N7@ z8e9S<2nW)Wt*@J?0dR<o_GNtU@sg4O##|E!+8{BKC zOJl05zp{$KoDH)n=xl1&3my+Rq1BawfcLEpE&>RrHa`B*u6G3&<7>S}RW-;kK)YRe zrx<`PB*5Q^3#J90w&RD#Q}SCduL0_+*G$ukEno(~7nS-62!U0&7#K55;v4+;oFG_a ztA>=~Rb4;e;YJ{61jNQ%C3Mi>8q8qL$=?G3GZ>we%j0UHB(C3fCxNtd4R;;ZZXba3 zEI?E#b{dKNT{RgBh?kXS5PawUXp>z-3>^b`x&>6%2&x+dPg4uH7W;^R{xVw!$S2Ki z4Tp@>z!}sAi%j0M0PTeB{ta6~&sf`692zR^R@^5pp`)>U>~uGb+kUZna&;OhVWxD1 zr!})gUsW_KCo9bekG~3pc7PmDj^m-fQWCG@zJS^Jz6)_Ai#{JC&UH`2NZH}k{5_7| z7pd)t)tB3Ozs0Q@zzte`<%#zESTPAcMli!lAhpvj+KK0~Ib1|&K*So5qJgmSywYx6 zMVbP#TD#tvJDDLySNBeD25m>p5z79mSOUcXPPpU**nNtA>SK=)8X7Vk00C>WEw$EU9bM5L?kAbUy?!QmMP^4S3ZqDur0}c#x?O6jx{l7Y zKYB)tY1kH6Sq!Qtwpj4y`WglB3(&ZYNeJYLB+M}C0MUEG)RQ=z^-|B$L_7S>GDBl{ z?9>Q|@x6Kr-fB5hV`=nkVIQ|8i0NValgQbqs-lKZ1psHW7yu_qglm16h>LEv)Doc{ zNAB`QFl_jm)mPBkc#zv&vYnoPAl}B5uZ7Egrr>psUWr8vDoc_+f)Sq=zQ3C1g9|JB z>g|g%zzz8}zzYnr9Q?Y&!$81~Q$QqWSyXIv`gh7I^xXRqbbGpkx+c`|;=JM7y0scD z>DGe3cxAc4SZ;kI){+siYe})fG#Q|C9|64BJ{^E@Hfv83y_tAYezkTzLTd@S9@IVG zPA9IUokiVBILEKY%0OT0?Ce0&##Du*8$aIik%3tt-Vz(ZKXr{69RmXmfcmR|$(Jy* zK~}T$bBuFFYxpp@AoIBsv@9O20fz>UGiI~Pzy4HpY37C!rX6LB9U~q5MI1wH5k-e zbzSv7^SyJX4vdgG!gU<|oHT+weYrrfmbKc_my7MQkm24yRJ)frZaH8=tYaA4VAG}F zgp~MvC0yXA_3XDD(|$d`NT&G8kfZF1fW9gLMQ+qDGZ!FJz~Sn`~Lo3YeqP(0W~=fY3o9Nl_rA6xPT*e%Rj? z>Wh0HGJ8$|QRxC|9%WP8?tNEBNKEyNk@bu}@!VP~yQ9Xf=OM)R78GbYk+L?{_(Kmu z<5MB!t1tIK_30n;%H|D@|7~$@?j^M&;o?pnWrG2PAa`7KYnIlNPw4@s_~|0ktKGY) z`g6YbYFE5&(y~_6WMo@+)bNp}n@&+fDR*mz;2)s8;9F}msV`&@5picms)OKqnWe6B=z z8|6%$b$f}*>UYg;8I_B(n-mbAEr6&7v&=2i=t6^)zWWh?kVrHaId^@Yz4L4x{~9;! z2v?6t{G`-0S)#zuxO`>rwrXkvVuFyc2zPLiT>C}FiErgU{PodGj*gp_jyw_}35j5> z&yGd{SCqu`N9SK2^fycLu`&0FK1P43fE_ehSCzr~py_t8!IuN2~OXT4Q>}*NM+= z%Q|2lUtR90kM`^KFaOUjB!G$)fmf{}peU-Y0Cur}V6ke}dyl1;WoPn&N-8$DTn|HI z+q3z5KZMS!e05T8-c*p$CqArRlMojd_wGb8sEBR+1oU0M{GM-BKR?fWnQ8a;&T?R0 z2Z53R_4Z^pU>SSjz(qcJumyK7zkE0YG{R!EVawt6juQn|MNbOW`#ZY0lwIhA%3J`+ z0D(t(X_ZA9s4nKQdHVraT<@{^={FZx4Xu?vY^V&XVl*<^`9WbZ@!RWT1!sVBI)ai? zK$|XpI0KZ}3XCBjFj*fBRlQ=*-*dZb9xu%gefweIPGIQ{1Z!Wqot_KQ=XL9$GqApN zSz>xus!tMB^*eim;ur|t_?tt$5pWsmjkB+xLG7yoT6O{!ui*Z-;6$rkwlc<`cBk8+ z+wb?Bmal!=56W3UaH%Da=Xeh&)FuY4f9iY{;)rOtdOzUixmC+Ry>r3FdoYz>K&dD1 zG;pz?i%V60UERLx%N3N2HdPryEr~L5FrMl+eSLS?uZm|Y)vGJgl$4lCwr+`VNxAYh z3lf4odw>m}>7d5ss`x|3moL}++UdV?7O({YOo;PRdlDs+L$8+>L)3bl^t&pO^&8}h uiHWI_$w%H+KKf?E{*0gLu6&>5&;N{UwSpphXR&lK0D-5gpUXO@geCyO3xtXQ literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..9a36642b2d5451830d70974a84715c7f2d16f9f1 GIT binary patch literal 29125 zcmeFY_qG9Cwa;&)1 z;xuOXT2;GTQ{RM9J2q2MMB#Pa(SpaT(R#8t{P!GagLr5PpU~MAi!5Pe4 zlgGi>p>(q`uWzPMtKH2vT6sRq*E*#AujYySTe{(mX`e`OjM?Gi{t|3*qqiY@jkO<&W6 zQ`fT0f>$M0yF>)l&+LsTYI%eidwzJ-Sm`=_(0Yg?BqBPHc77833B9qMoB5ki*Ap8}=rs8gX^dh|nMDZ4bn4C{ML+t2 z1I-K8=%C{CelJUQo6oXxW>!cwt>?1DErVFR|Bxy+=3Kp2Sa{>n)mw8uQpvv)6F`^p zZ4&5z_t=++&*`m*S!dXX{tWBYJoDWdmoZebqcp@8NAB-V6{cz4BX;U;&`LkNFZbbF zkBlrCJAvy~|8T={r+gbvuE1cxjaLBXav!MegTh}VaY994h|q`T(sHLFl%gz8bn1B$ z-=hpgf<>SW@9HsqOpH-lap;_ZxlT=#0^${^8n<4ko?=&eh)s8UiVkM5jio z%PGk6^btq=WUPwJ=AG@=Vs0hGmNG7y9a)u{Ws;s@iy=PBdRHeZ3w#9r#k2YT`Hy6O z?PO6g+u;r3fmm#bL>ywrBibzE#E9*#D*wZ}5fwQty!VKyP0_R+-ODm|%iSTik2z*m zR#yGXtZ?EKRaaCo$M-%6`K(>kI!KgHE*U(|44zO!e+C$foOnED2{k#HUPnt-fn-ut z{&*uzP5iRt>mBl@prk%JIJb60*Z~nyYurQ>zM=U(wzt^gg_*U`ulLP8Ke-+0tqdqH zeAS*N@m@}=Y!|5c1fU5;QoRJOeE(ELWgdesa$=Mgb^F65YmslBgQC??bc6ANp*21Mvajl8g2WF_q!eq0d+o{**7_sG?%T3V3zLin^a+{k zl~ATj6q67ycWVl=0v9^H$K`(O&zhg>uf`u!|{3e$;0{`tO2^xqv4z& zjY6~-Yje4cKmmaqR-@%B0kOJ;gjFNopo*vldfgIlleg{?svxQPWBL{D2{kw~|A}u5 z^PVbT>U2)<+KBqjIIS9)m6FnL*drN+;OMXZ0jx$PrHhUi3CQM1RsE~od(mpta zU6N;GkJ)Gq`_K04!=6@@xV!^!9osS7zaCc}K3%S>OA+exePC863*Nn#PczE#iam^dwUK<bG2Opvx&OcUtuENz)uGF}M>mAtFPoXy5r$pnNrx~2rQ%f(dsN$qiL96|72AVE}ypP-OAvBH-4$D@0>*feJ1#y<04j>?=~H6>SCI5 z+g0a6AX8N8B_b3z<-0&st^`4FG zKJCcle4t-GV-i*vk`Z)>6(JXdO{BZrpD7g?PWk^hxXg#7%;dbC3$d>vv{<=G0ox*f zRuD67Fu##sUeYm?g4h+g%QKfUswf!W48@>*a_Hnc8Xb;`QW|+t14uA```X#$`tsOw z47E+W|Hm%3qh@G=0HpNDJ-1m;iDWI~o}j%ledsAmsO@b3RpM+PGJ zt53up8m=i-R#s{1$8fEF2LcTjvvi%NjX~@?fH9+!$a;Fs`yQ-o3>u41a_-aT>QK(4y_cMIKGq9G{lz)M(Yr+sjr&H~drdtMcr zT7uTtktp`0BnF^BPI-#GGYP4RN8ZmRN&K<)aw-muq5zV#h=m>j5NxB6L%H_@@P$cR)mg@ zQ4gwm6K6L=b(OBjPZd5>uD#|1%QNZ-j8*I$3T#y-jADxt$dMT{$6=)@x?rDgpFn-QELOOTu`amtQo+}v+&i@HuJ z#yF1eR{{f^t_Q#}RIF#qt(VHrq)M{I|Jn;bhah$eXhTf$8mr7pmUDl>i*IyDUFl$< z$I#=$e3w_%PgV%^oc}S{a_&1PHZf*Zvc1)CeV6>&J#O*|y^2<95datGxuX))mP|E_ zhoa+o4OenahLp)fU;D6!CELyXxnHI-T|zzmk7j|fwPrF$4_vZKwESdR^rE-iAGf6a z;%YzJx_D&go}Wu3)8XIHXM89aFb#{p}N?3M}WaN^VbGrK9Je?qHGJQz)&Kc^2)qNOJAxey9X>5?$@i#hp%A+Og#P0gFvy@n*fdNOL7tmcIWoc6G+b zWc?aIa1jqWWQ)Cr7k!H~zQ7FCB8^zTM&j6&;oX$KV0-jz(jtDdL37?F$k0z!$4`wc zVR7zLJp@iS(#K(m2~ASZ&n{Mf)AKeC^i~qYfGJ%G*@T%?X#P@9)*`0dctQCr9*e!{ zjb z*`jC!pf94kcPemnbHC)mkxSsY%~w0<|5DLA%gfpD6E*YtB#sgfB_~qTeQBUrWou?b zllG8`J!;V)%cE0n()VM9b{Kb0KetvjaU*Mw(OPN7jQs%KLAAmc>6S`4hbTE1LuL1^ zDTJ(5N1KZCz;_giUBsj`EXrFr_XV8A==dYQXunO1rlA4wfV}AMu{Il`%~^$M7{G7y zo-l@B!fKOREH!L6uu3sk4sG)7K}r$2lJp;I`Yd-dRHcqH)GttXrht$g&2KicxkHTh zilmh2=;(`2z3sr<+_2o?(Iwo6X%cF2Pr}UR+=B`&SAnkRN{uHMlUdDw$ZaKp2*sD_ z)^dh_^yNnW1kquN-m4l{%s}fO&G0L)-R3MLxWtm`7CJEIq_@5gvJ5G47v1V*cQGg+ zbJ4|;(U$J^?`>iy+{Q(z<9?h=LVZ|Dv_i6&6PcC zZHFYez-xyN?RA{^P@sMKbXDf=BD=7cf;49%V=R3w{vo@2hw$K(W27C@$ALM+W>7PzID4Av(~Ix zHiT~H04zcS9IG^lU}lB?pXDchWOsg%CLr%))mfDb_*^o8p1Y21mRp!FS5)pju!zB{JeW!wR;ut=AWbUlFIV&}v)8Jy(Mj_LhN;V^X*N zSU_YIZ|aSN6m9Af=Da84ka;451HW5rKSjNLc@?NeI4(oElkxD7jG1vL)b{)WIYsHs z(r1Z&8D%x_#xBZQo-lZDpY3R!Z>X|LQ&>`Nq6+ucC?u&!s)E;wp01q>XYf;!nQ{T} zUyO6~5fK74z1zUREutrP;L~#~6Qbm&R1tSQ{#i47FNZ8UQAw-CndvB{>neyGLq*g? zmcpb@VIh&+16@uxYnt_4(+lU3oU`ftp*dgPRUaiBTc$kz>r6B3(L%nv+M_ja7QD{^ z8fr!s$+Tf3;Y2g5<|A_eS`7wN)(PvJRyF1)q8aHnz+f${RZ5Xw*nTVLp`Rx+Q|%|%K`KA>EGXP0{yFOR;`JAY$uiGI7|L`vsB|d0H8-29d4{+;thYx;S}YvLGOGR`-1+H zxCv|tg{{;>m1be=cGsRW5sxIQm-STNzA$J#7jRtOG~pnaGY+;+2ecX`bv<@zLuWm) zuvld7B&&CD21=$xg=eN?-gSTA5S$T|iuY1-VkAXXOGwu{>r)fFn~7M=FXdY zp_nK(W@O^+X6A^X{mh}dUP$}lCPZfCgU+aSGYduZp!t-}Gc^a%5(CaWUZ6h<{)ejQ z3G#EH+HafcoxN41oEIl`K}PJlETo#*!9T0C06Sc2mvhGQ&9@{?>>umBM)xI9$Dad~ zAwo14&Lv@vd^n8!h7W6dkiD|mLtH%ksrhd1D(~|#6VdD621@BMuaHs0QNNVh@LV%# zWT!G>J($pBg5S-ooC&)`G?u8dl9K$5NKz)$5dpA@W^+)wiBc9F+x+N3F*TNgt@;lg zyC2;AT#gsJu+6sN>`{m>bV1VQLgXSqe2cM{0Faw#fj%5nbH`U%5s#4c1e&QKhw~6& z>Bj>Bn~KF(Xpw>Wb#RUbefb+h29my=U+gKFD-OW&fqyGiT&A>9|FIaCAQu zHCq9J=!KdtZ{1;~2PdR|7vlZNA|;pBeSu$Od(O3&PHej87a_y;Hez8TQya4D`zN|@ z$XH0@g|7dtqu#MnL%5M;-EVg|5IPI0)Q@bO#f|DOgpFY2z%YV#h*8qCU92CrjbQF% zfmQ43>jvS5Q_3Oqb3Y-MUt|c%7yEEqbLCS@NH6@#`E}M8RV)~$nT})2I1^Q6i!l6X z9=wwbod>Gk?gl}Tgyx^=*Jv~qWcRu*Jx9PRqM0?#;LIJ6K^vc_zs+X=Pw(Quv-cE5R9 zo_JrreR>;A-eqYd=tVrT_-T(d-JEK!8jY_-xZs7ntch&#RM8I~+;2HzaD%Zab#@V9 zr0F;>kwXJmt7@mnJj0~xN5czRw+jL{{oB=-Bpypv__XSETGP%}8 z9~Jjtl%2CB)p2GVeA+5iIycVghJh0lc$I{4w-_KbkRk#5#I9sF#3Lo*6;{)E6|^Q2 zlFcnRGd-b8hLFKI-zkiaR`ikXA(D8GLKET(*$NQ9n@aY*yULMOLaAj`X@PBU1m1@Z zi?rA#gj&#sLe6gn`QX0+>$~aDH5UvU%kY5Pqj1{20>cxgGt|IC^D1i#m+aHd8)_-v z?Pq%iS{IVz(RUn|hJo9gv={KQ`MX<~pPpv zYt7#v^S8e+K^>3J$7-w0&kwW?Ha{O}sB_jTLRo|I`&ivIO z&E#u&?OI_^8}!OSdqIUZSmBg=$ZdFm=y4JZe-+eX?d$kbznh(k zh~S>#B&mV*`vvkWcJM_sI3&7ZI&&0*9!k@Z2wsEH524?j)pXrq0L%LcPz0x;Y_t)9 zj|I%Pa2eX&($lV?G_HrwZ;}xE1`VGCe&PzU`()5C>1ey|++F&G?P73Pa&UAE;`_Mc zcssYf#^7`I=Oq+@60O``kxC6|h-dN1!Es=zD>Sw4M{zJHFwuX;%E=5!@G|5xSJ0n^ z@p)G9%RMC|etQe<72e>_y%w~trh&<{9p@;6M)`l=n7sBtm}y(uA`atlm=KMY8@h9( zh4~>=>DqaLTgnM4B;51c_~VYBd}8_a*Zhf>HTTg=$~|()ix)S^N#~s;;Pbt^X-50L zPzlSxtuFaHD$t|S_{TlJ-OlEWpy5N1JcQakTYY@jZ|5c;D;Km2HVMp5%bcug3qn{x zY=C4Bg!cZ8tEqT@gKOuwvRD3jFOg*MDMr~3)*l(V-=6o2gMv5QRZS(qAn_;CNfDQ2 zAE4R_>$kfE9D@Z57^gO_J4iI1 zDVlX0R=`p2FJCk1<;oqvB=;!$4D{`*?9rEC8A(aEb5K^U&v)j`9)2vc|~=;i#w zHHIAAHPIb#LzUa%ku)PBe&~LK6#Hv2)RZ*ad{FVY-ZR&bTdywY-sQ1< zq+0jGs{-1y(RP}>fpZMs$2)RCiAS*;+TA)a+Ks6r#_qe$8u#FPY^0#OSBb(~I0O>C zs~E1k6PKk+r!S~h`kPIIGNc0c!1hB#==}jCSYD!_SK+KSEFg| z+{MQ6>Gm9|yzjv-?d7uC15ZP`(~GqpXjYB(?W|f*3RlohL&wE(-sZfVFvM+==Og9D z_`v(eKdq-{L#5aM{9SbtbFrT1c67h4hP zK>*Ic>C+#o@gGA^2U*R3k+v{^z|Hd%d9BkkLkJA|HuXKV&D=!vVW=GMbpDY$$Cv;> zA~s|msFclgwToRelrlr9zL0^sc12dASUoHMH;4Ve^im=!Pq^{KyVLU>QAvELxs;jfM>yA~vY*taCL+U|o9_6yiQXMt zUP-i|z;q}RR}*Et?KGCD2$U1l1|yPFTzr4XQHaqJbVSGn3Wz3wsCi#aXO~T0?o@!! z$Z6peJ_)qDuTQPXOjq>+-Ju1BFF3C+OS!}+b{7YumeTzbnN8uyrzWEP2q$bdb}X4DmbO!1?+@-Y7fIqD#lTh5zlOsSy_8 z*QM{5SBK!{QdLn%i!k52R>W5`>-n1Z8+Gm9g{Z_s4z6!lK8|C6VW?4v0IdwEnumt_%K(<)up)a5$8S5`#s0J&>lJ4`@6Y|rB)w5*w%|J z&*S~TLeze03YzW2%Ti%Jzq-yUKoY3qlC`utcYEZ|)*!yp z;k!3p-To`%Jt82s2$3QO=kDLA?@(U%fnBKWj2xhe8nwjbaJ^1=C=TS%>R z1AH0F!}#X7XeN;4hrrH0S-+;jOfsu?Q9S6~jSnB}KT8z9qmlF$dfMT7dU(E^*(V+f z;ZbKNx|JMT&Z?OQ*$28s1Om6=GrQiH82T}u)-Ks>fN8chJ`t&YqpGQMqwJCa`!HK) z7!cuxx|1Cf49)9fHNhA0M=vRuX!p*lhSkeJn_az0$K*+3JVLAZ4P^Y=F~TY%%hWiX z-|>$Yl~S2r_ENq*&{Q=QSwG2Ya-+ddN=n0#?z*Z2pD)Vi>$&HnW4}hkxTih&&k+ta zTgaq!*}(s8PrI3I7yF7_Q90eVtopW+$2DK7)8SUYkb_S*?-Y|E55T{LX~{lU-A%bI z$AQ;FrW3ewn=_%EIqJkuMXLOk!6lXP;BMCWZ`@zKF72jybP5@ym6+cBJ<@2CG&Am_Kv&`SczJEfyz+O57LG}{tR zKyhwWYD;rS%%gU>`!_}=RoxqP155$3i?6>3M(&U^A*ESW8M+as4YRxuTP9&Y7MRjf z1KENv@G}7bQAnyGnPZ<#DAW#5yjd{Z{1{R&u>P=8;|4A;RG5nJ;mo&g6PIUjm`Y%f zyN@DUhih%5Ew0LS-0O*3VmbFzg>M^W<$R;q%c{`U!OQ-6eGsS3iesMiCJFHXXiBz* z48J|rMXENaYs{CMF#^Dq?(*d~V8`k;;Q&Wft%R)>hN2ah97pHwwvpE_#dzn4qgtKJ zBWKKKZXD$eDw2WHJVYt!{sp3&HYGidKGV?V_G^E$vNI+Bp~p~-F8BguVOeUR+wVU4 zwja_hBjK=R@R0o&ZF;+mI2zjb9+>T=Q%eG$s>p8>Y2ieCjuEdOZmDtPVzwy4w1xDw za~XvpIv-1_21VU8q&1!2J|3Lj^~tE6{incFx(eu)X*B`+TO!l8TO zg?TRCxziVnmFH*gN#ER2s@!)_7o0Y@`f~ZG8o5A6E;6*m@aCy-U$a%LWxJ2hz}dTD zc~X0k0M{CklVU9;AvUiQhi7U^O-k;Q=2e5)>9Yo{W+bLtQx8K}3JhV7iO!(B!fT9< z=k$6^Vmb}KKS^Vr50Tq`&U>egsN;0%=ead#n6Kdi42(Fg}JOLd-+t+!pUY6W3!Ak)lIBqh;~ug%k@COubBdS(@bP{$t0)GwXvSQ!@7tvm zN%o*Nuc~p5pAU!lXAP}rprCH_h~9YQJ{n1x*Jp+f!FoB8c-;DNhX~RPGK)Fq+!vyI z_Ubt4T$9e#`Q?kLiS{n3DdECt*ILKWKJ?39l6uqcoL?)G15L1)NPCy z%6N%x3s-a*vTq{P3fYF@?r@!*H3&J&@-^RKY3m)LHbVQO1zI}`P<(eOeO6*c3t~!jRaA@{CO`0)GiM|IvS`S zI)LSDP?ykHGMDG#fj#bT;>CsiapYI&GD|0$bqR4FKB=vqb9cjkG2b2AJ|<*okt^6b zQiRl{4qIWE0#;7*Mc&^npaz=l=yXY*yZd~z~n$cvgKQ*qsf*SE@x1{W3$_1L)$j(euWCp`9X zlS*Bm8Zd3NrFhnuuShBnk5gPrigD zsbd3xjFGKC{zSja&db1^uJ+cDBhKJ^LD?!3ts%;!1l$WpP;i3nnnZv1(Us91sJdX1rqmQbwCu(cb@V*;OCH*mh0zMu$$$;|Ao^Z<(l1%h4P+WJo zF{#zZE&-Obnsq$ie28vep$`mmNYrnvuN1?@A+en1ALNUgDZafU^oPy&t0*8s(5tYV zGSLF^zfN-XaO{H3&WGKNbb95~98EXhlfd5-YR|MVrtPrLkH}m4>mGS%Xxs8^OLKhZ zJOZyUyFE`!@Ak_O>6kMV;3(X8mfJh$2=vEQh|6*`W6jfjDEWkGS52)^2j zhc^y)_m~EqO}7{f3@&0N)UEIY15E?qzj{;1Q$IV7{2f=whp%oFGRZb zeFlt3&Tx*7!S41K9NDwezMHARR_GVKGzksDJvd6jbZ1a&+kv-rz+r-+S|-LTs0JO( z8q~x(9_CM^dFFtAdPEJOg7`uD>?H$-!vpQsjTx_F3}(K5VLM}^h2u6PvLXt^Mr&iN zXv6nzezfFzQ|FSJh7JT^5n2yPitu&Q9(*#p0ToJj*$oUt>YmV$mI&C0r|>grGU zdwOOYDnXx-OE z3sxgQ6?i;Y`UjkOyO4JZ>3+Zo36F0exy=Xn7Ifz3wD#!+-#eQ~!0>${0x}11sFVZ{ z)u*nDLgw?zT@t9|&uBzih)5$5NqXnvj+&`&Hf{HV;_yKj)pb=SXtU|OU)+BecwV3m_ADUMt z)}P>}oA4QH?kN9;-elE$Gcz+go)w;`OI^0VotK$vilaKY}q3aE)XuuB_v&F@~Vusr}d#oBkzYK0lE{XW0y6K425Ie zpu|qHq}*T+pDybWRodL5puic3# z&tmYedR33u;o=bK2AHFP8RmTe+C4uHQp2lQW*jQHUKy(cL{jC#$6PxK;v0<>Lq|`1 zG(#T!`-%aOYYEQ6GbQgT0H5w{IHYT$Z1jl0t5F{UHhCawXyiQ=b7O0zvnuBuQ&a2i z#j#yu^hydjU#)R-vXV--$y02YOjhe0`e>bW$w$I=6XLNY9&)zQ?00^Y^KuwYz7E6w zo0|mOtp8N6OSYlDteOuV|2u(-Tu6x};R#`t4-M zMkC2ZG*$)f>_5(z^CCp+&JLn$zQq2-~Hvs$ols4*;*_bsE zI>oQOd+c|2nBy1alF`Y%#Ytfy$5PEx%lyuovQ65lzdS|OROE%XrSF+E#f@u^MO{1n z!K>!&w^_JTOsr1=uEK>Lwr+lxCL`E+Q!?l(N$r>0P27JxQ(+4=Zusy5rBId^jLG&Q@0JDgFePEuTMT| z*v3}@EP6=q^?)Asaf3HO7%c_@?cJW%>f3I+M|C-dN3-akOYFre4%o<8h~NHc1Od8= zv(;FZDI9V6({8SekSG;~KN^0rQi!3TNJdWER&-9%I_;1N@<-@o{oP6oQ0efC%kr?F zj_Ke>D~Z2|$dKBe|MkAEd;ENeJ=qwJjI>S_80Lzx*e4UT4i7ocf6Q~iN3iGoKeHlQ z%zEJwHl)YdwT^5F1W9M}A$w9=e@iB?a4E}@)JW072N`j!nT(-`CAPr}u<3c?7(eYDB!A9OCv6+H&v{v?JE_K;sco8kX zrEk7wMOsw16@9Ec`HFRUt?1|)Wm6b>`mDtY5+qdL{yq6$v;4nax!&p^wUjp%=&ncp z13dAW*?Q33i~QijVrQDgo2&|Ji2+IXQ-*{qyo{P`*8!pl;jM)Q4eY&AJ%szipY1wR6tpgdKlD!TlMNePg)MSMg+PzeSMlgNvXZe{ zPmRc8OFg|Tk5SjVA5wGzep8xK_Ffq?0(FDbm$TRbH_5+O&X`FTg|CVJb{tb&v=9wP zJd3oc7=|tHq3M&GuKSx&FF~Hu`bEVo)2F@D^L-dC{uue~ zacS42ZvGupej^1gqAuzadV^~s_v3Q3t99=-skkn- z%7ic7yWXYq@ZHwdY<|&Bvg^eGdo+PF@G^q{xwag@@Dk&l0A%-)WARIgXiM zPMY^i++IiQyrtbgMlCXrXyuNU=)C_jQQQk;Lt6}~K(oXiv|{@|=Wu$45U_`gv6|tv zNg{rxZqTkWq-HM?sWSD4e~5@%(PCV(Zb}K3a#LUbD0b)sNxS~hAhed8xh`Gw#tu1C zn)F7iX7&RC?&ir-PLLYdj?f6k|gEe{O=YLaGmOFWU?QW== z*COkydHL@5vODPQH@Am2`pMk2Y^BkZxI=nNL|?;6n_ZCRG+59FijWwu*#i~FyzV{T zw`gwvEK`8blaC5xfT! zBJ}AGXXrRUe^eh-|IhCk(OfPi`n?N1rVy+dOsTAzW)MilVPNj}y42gUj|M_W@!M#Y z%3|<~x{pR_2Z6;B5+2o>LnTpkQfMWY0sN&l=NTXUI3!^E9N|S6_e=Ul@Rab|b*bh9 zVbVB-=E`|_+@5^k!PK9>#=awmxNB99hjK_FWLdi$Qdu!Ap5By)7q$!cIH z)d!knmf%A)a{;m%$_JXn+h-oV4$(;U8;5gRJ1F`9 zrA{cJqd2^&VB^57|8K*^$yr?u5*Y z3d+PV;T#JdVTd)`_2TPcC+%Pn$cMBDVFh>l!%hU1_*Jg0XfT_sf-LngTNE*BQPq=R z@79NLixCoLHYgrp6;J1H5&6R3de@DOlgHO>R%Yzv>g6*CR;dl(7|EKC!EJIg<8^Y^ z>9(K#owj9@w2RwAd7GwbEb;4aHfatOuPST0lZ8#hqhC{PQ5)svjVG--<@s2iUD89C zIC-=@7QD)zyvq|KEXs+~s(u6>6zSxVBF?SF#eYn^*q^u}hiOIb?QO$+lKIWSBnVwH zXgDylVU;veni0PT^1oJ~w$I+G)q~KfG~}ytI!8-SifBT5M79`Ts}N5izSf+Y3mL$Q zj)MX+GV7s5Ny4i2!Rl`bUAm?m_pjOqe0Rjt-b+qyQeXMS!x9u?6CGBKyGlk^~T*jzBe2k8r*c8UDjp`C&g}4IC5x^)@50vg>f@t_TL0&WL^nOy%F>O z@`G(n4i*K>%PVjN69QV71Ol`3ocRiXC_IbU*`h26W>r1kKPG9ANzz@>@46`y3Uo(R zXG2y!X4AM&bfA8b7#?601175YI+(SSTYtj}cY?9EF)T?qX}Lh2czD2GajKjW2VH3g zhO;Q#IcV=4N}D>iJF;6J-+DNag2L|Cm-Nfd5BH-2<@j*ktT9zqeoIEhGaD+rp^^)F zt-G`AzUtQu^f~mc!Re;iC1?-NC=;2wK+p1Uo|{vpFtR8~dH15t#AYE_c-2C^#YOJY zRXWz?g7OE6E*A|)E)|i62t^$issHoq_J2z1`r2cpc{(DJfH1N*0#5Bh(^LCF6F&gu zrqdj%SWZPsB^YgyEPx*+yf(8&i%UTpcQk^H3p46xm;6QvN-v|n@SlC3Ek|PrKjyA9 zsrda}AO~n$Mw7x zQOD~gyn-K>#>LGEEe?6!QEb8R!3Kfgt;Vog1fS7WWt#nu$7Bj4mImqOx0nUtgKN=% zA-OUVfFEbh1(1=&e3d7cwr7~v*DhBi&hGty)>an}xIp zxL(z#{v+gPpkXT7^8__9OdfSJ1+0bCZ=iwqMJ7$g z)0ZDQzI0?VKq8CW6~zq;7Ic52d?Ag(32&LvaGr}bR-`{Fl+(pJ z^Uc6@Mgb1IyATIVTfezV+Yx8tQrlu5xD=pS3Ze4jqN8R%Klza6SBi7k$d1>1w0k6O zzf|NT^dCXc5OLdggbXl2v2A!US!mwyv)G33n~5votz@-1CJHUM`yMU_ZYa{w!OLhW z@7t1-{R}p*(;w8$l}0JT*Zh#fb7z!f1RU$*!oA~`&lW|HWu!S7V=YtPFuBN5fGwtu z9_HSW4)aeB#@{fi#BSX#vF0P`lvVPs^(n>I=sUU#R#@O9AgD9o$n+geb^Nfk{^gP;{x%7Dos-zKEfz2z*n8zn9F>?tyJVHQP%MGl-*YK3RW@#UK{bTx>3lTo zV@rE<@0%Zg>VMmmiPg)_J4PQw+u!tI+(hFyzKCyE@}VE%YRgX*%Sh^}{OChJv@-rK zbF03h#eU{hQt!5U5^r)J!K=|+M($pQX|#0^UM`&$mVlHNwoRrlN-NuIoA5fbwVOpX z>@Osrtt%?)b*=erKvb3~NKSqYmO^`qi@5!t7TG*XN_goNzDs0xlGi^h1CIl2D2hnz zrK8@zAq}H53-mxK<;ZUR^lptHU5C>|0dgv0tvFd)&?BxHbyjG@XN9kuvQx zSe84(lBk8I>?1b#l3RsOYn8;^EsdpCMR|Ilo_*@vYR}=*&5G!VpqR94CCRe;hqS(W zcIvUACMWj(@yPc{_7-SndiZj}J&IWiO)_sRQk!Hp7G(Q*=Ja2-a#yd$5%Rp;YM3>1 zzF9$ITTW)fgd2Uf2BJr$l$rf>y#aAqh};IhUAp=}DQUl6yd1aLdgAoS+G0<@$0tb2 z^@a83IlLp^>cyiR!T-1bKL=N;Wa1gJaRPO+lX4sXz2y3404-E@qm-` zt2I!NUA51$(?(V+t0mKhGI+p!sj!8QPgzBcq;8rJZ6QhJ0#3@qEX_#z>L?;6idwol zlH6AoHOEYJVrGG&tf&7Zh8RDR@44q~i(t`kDNiZ8|1^D*X7Ud|Z_fMoHDEuVEM{pJ?c z#*oCT-*19N6E_1sVFlZ;e6{tD5VN4@>a}{6^qeOvMs1rZ)${!_*5J1Yu~$EQyrl^V zV`X`nv+(i)_gKH-_5+=B^Rc`wy3`2K^qjNYh6w^SM@jik_!oV@kHrzI6=5EInwh~} zT_u9|fSPfC=Z+PjV6L=szcw7S*4N>bOAz=pZB1qwuQ}+GZ7%Zoz3Wl;NFXHZJT|7t2!$+MH9;*XnG{MfmYZx~0a>@s zoxlvNE;S3*B$7lzAbOJdZx_m<6~yH#iLCgSdQ8=a7SR??)Oz5ol*<7N9)F9MPAg53 z0B3vr{9tlhN9K~^jS3n>E_|Rei^!l})z2X)+hxdnyz}dhl)#~IH0g@98ZIjWX|uaTHT9EwmoHeO+W2}qpa~6$H#Ap zA6v_x(=C<=xXNsnx;$zNF89RCQP9(wC%yBi{KI1zya)6)i8MI*hE~^yr@*VELZ9fY zpY^%~9nBmAHJX&B#MP`(M7hM4SKAf8=uF{`)0_{Dj3O#i#7Z}YhZxP|Q>=onaGVk) z8};N>=4Bwt@W4q7p`!dbiD2~$bI+iJvMxqng}(4rHb2(lI7MT@vbW0R{|RR*4&nX$ zE$|K8o@ak>`Nm)2y(MoKF6ecVs@++EAmMLJsC*4ydFuTFdbPu~3Jl?y4mRN`BUHZC z%1VxpG%^W%4|x;Y4CfrA)$IfR>?E}EezJJxNHY-jtIv`%+t~`gp5sqJKW^HEgsQT! z*}zZn)5BcBC5%_VP0nvAle`$LiEo1jic-E9aG+qOiwMSp~$k4lIv8$6l>xh zQ26DPNdNEU9LHQ9eTr`{{JIHV#G(!DTu3p6C2frn7mM=+-%UUW2EoX`(wg>N55F;F z?HK#yPTG;K6JR#J@0~{bq0O#yyh||7@mrggr>yZ?FU5BUWgW&kTdAY6pb>gaWtMm5 zqvjSY>+?QO2KK|Lb48#a?c%fe$h0T9v?rWxgUkm<4+gtg)0HX}hSqP~jyvKv4QXCf zO57BN!KLtr0EYL?uspxSdqe*3R9;4MTI9W-g6i;;8B>*CZzn`}3Jf>WbuTF)g!7wS zTL2w<_;1R1Pa2GT(_nijfkwpgZDkZ}0n2&cY%@-<5cmHy_0?ffeb2*4NK2;(xO7Q( zEFefoDBYdXqI4)qmxwGSUDDkp-7Fy`uyl7W&3hL=zvunl=h=Vuo|ro`=S-eCXf{Kn zsmck|pUsz(C;Q`l703U-IGm`N`>vRtjtQ>Xr%6W)BLdL8H%Y)BS<_y+TE_!I^K&iO zYNo8nNNVP2RW`FkVQzAQD(Bl(h(cxG9TkU7JD#2zLP@tolr^c4z9cHT0f=u|{iL7R zMCS)>Y*CD;XQGC}hS^{7T(_C6&%&V}uNG*MG#XIA&HUF1 zhxi-d(y0;wNCd)V6y55F4deB$2b+Jx>?Mv;sLqd0s7g{pskmGs|8+2}XB~|*;f;Yk zy`lQY8-pYs0~rbQ@}BT|395DLvkwu^*_&$pxOM%y896)T4-ljxh+*UfQ+;Xwq_mXq z=R5Efg=`H~gv8&9rF*nnzFjVUfm=G_`K6Vh(-bUx$~I+ap<0!wNxia~fLh1Z8Rz(A z9XsA>1V(B6`h#Bz+l>u&r8zh_(3>caSb-L~3E?tK-x(nZoV)$;q^}%q(K{e0NNSE^wRyAVC8aY}8TM@Oj|a!5<^#Z%&&gx|L-oNw>V zm48{dnNZcfsq4}(zftqm#x<0MM`1k%2)YjJj|4GP<~CM+VSw|Azf|urIvUZ%+Th?_ zJd;hdr2V<}kMo&(D}x9YC)t%P?o2i>gTk#pCnE+T8}l_nfofwRjEqdcA}x5DOkN7d z-`>CJ?efCQSZWge&;Wb+O9+6w!peSDXZHPN*C|{;mEzW{p}3^}cc!nyy?Ul(238oV zndH$xR+#*dh6u*y?&hz4mvGxNOutGc*g)bNCU8uz@6BSq9L7C;MJEgddaXap3*q7K z@AS;kGi{&Wq}(fo%owu{9LdZQi3!XyEy6h5$8M$K62e22@Bx4d%&KHtOLBf<=K?@7 zJj*#^RgTDS^0Qp&YrlTAfgJY!8ge@(o)`o-Ct7K`cy%JEPD&8dZMookQcNPgsK_`A z0;w5)BR53;H)EVMis$s zl2=JNKf#40Q+-p?T;z0{iF<65Brg)2Lx1!q=#e|Fp_|QgUwxA1j$vgL=G$?WUubUL z8M& zwAHZ-&fr-X3m6|I(5!-|3z_>3GozX+QRkM$R!eA?AB+=YtU`d}{l`yi;Z8;lWw~#Z zWwJe|^^7?|Xm>P=;b+uedw*J%O6Dta>!JackKI(kmugw*YBgeP7-^*rt@gPvS$>56 znF|SWi6R$yAsnBT@jf~(a`0g6AbjG_uh!_orRIA?OkfzNEvJ(27gY zkY>ry!FP3rpIe?!jVU0)0!a^5nCu`BWkvq{G(;Rk-W)iZ1k_NG8(_@&3xEdv^#@T@ zL04mWTWHCNzeiJFra&3-Qi~|;a{xDDlrF?_BG7#fXncCi)p@`i8XSzk?y2?wKn#|i z{fvblbFO8q8s_UjGf9Ql%#}SrKLT6JhYAhv(rJmuD-`lG?GrTn2^Bw?ghvv%^G3g| zP6**kAK7s@qYen+L&!D|=wl`@h+PhQ2C8N_0GhnrL)ob@N#YO%ady(Mw&e-4^xSKZ znt0zcB1E?;{D*G1j^z?&cQDvsF*0|4rrH;7<|1;GK;SqTXp9_?3;-T( znu>NpQqSn;`Cc`nk6Va< zxZR3odmGO8NyK60_KzE{rssGid)*-ZNQa|#jw{+uP4Nqt-TtdLtD9lNY-2_LK3Eor zAXFtOqFKBVqaV08kV@?Rd+g3B-tKPXhXX#ea~q!DsU2Gw{bI{p@S_@0aVaE3BMu=* z*cfQPEI+4UX1240*b=(5%lyQTO7!$KTrg*hGhvKlo-P%q>L|BoBpgo&lG0}mGqx}t}T~~3~Dhb)iR$>yee=x@>91!0Hl1TA3n05mo!qk28=#hfp z$yKm@a*4d?cs^=u=oZ>Wcu;#)VCHnLtfV9;rC&U)#n z=r=et_vpJ(dD*U#a$G(TW~DGAS=Z@ojPgBx;7>Kz0gmKTfsd267NCi@@8ln|VfRa# z>e9KeBSyOD@~w5AuW3H*7AfZl553@vZapJh@Ht}oNg;|S=`V+8T(=TyAW)Zb4-Y*U zn}T(T$1n8Oz@$Jb30WJeN7_({UbMiuySnKhyyFg6^ld09W^t6;1 z&iT!Mob%|5E3!N2J~K!a_WI`3a)=)s6t#w2Hf;0M-Ovq%X2zWjC8fDjnn0~&U}QSw#LJ%`T3nap;sT;Ss!q>m{qsopq`4SH?%&u^b;Aoev7 zZYC{$axtlTU_y~BpwgySmEk~2*@3D(aRiTj1jeR#VtG2arYCDZFEs9`@9MTjZbY{Z zcLb;Q2ym3Zd{|nKV0h(O{zMO(Q>r2%>Z8|Lpqm=Gs4$DC?z|$Du8-bluLJ*7pa_D|4*H?=P2H*AEXHU8BqGCH$v) z9(in^X_s*%zpk}kA}guG#JE_IyN4`=0+X()Px*hk--=Q_yh_XxJMDH=V$7YH6aTF& zTC$wBa7)n?+|mt&2_s2g`YEpHE!54?Sh7^0+_)K5!^`hR-TPH{=WpX>%B;lj zwR>xDyeifDQLPbZuYPxTq0^zUbWL0zet5lbXATo~uh`uf#X~lL(wPO(%}TO=jPm^LjlZhIZx5d&BD#+7C@@$^;Tye5 z0LyX#mYtfHI0-^j%A=^8`^My~1#9Fy)*8@+v@L(8V1Jer#~Z~SOfLSRTIpkegWm45 zx#1S&MvucY>x=Q8maeY+!72XfnVz)!ZW`y4VP6ExpfD|fFpzJ4Tc>9Q6Vbi&Svxv7 zyqd`ZoQw{-A6}Wy)!iyO&bct4L#a%CtvP8Lwn?x4HeAH^+(Bqs&ObONt~8uGwtP6S z_B@CxtTTsxyx9xKixi};=R`wumI_#{v*3LoYO8meF^PVJ5 zX=&JBYtEk>?}t_bCIU5mjG`&|<9J6{`|oCP1L3;Zd2xM;RPv14;&8l!#y}a7zSip{ zZP%Wtpmratd-O{h$6N9#$N7!{COqE97ZwFw=S2(M#uC?bcgHg{-{teTaKBu0rY`w6 z-4X%3q3CztQ?%=9(+_AiY8Kz}2O}6EiyGmN= zE?>Ltuk1Gq9&RqBovfw##a6D6eNw_d+Y$5)fzBTj_+3M;FO6GIm@L83j~*Ec$OWhoegtdK6ZXs+d``(%tSeCFM@l(lur>pI+ z?s7pFl}s%ig?X?(G-ITfL}Z>jbC?2d@XBT<6m*rAxJD=!PO9(~t5b?-j6P`7i<*-f z+&Ls#YL%Xa{wZZgpxnK~?MbR|d-y?%?#P1O2de<|Ct}^tyh~QLhvJV@;;Fk*v{|Zt z?$qvC0$k3B^Tt)c<=fmmMSdajRvi-ZTrEs#D zX3MAXUj@0_QSlGIY^2fJHr6j<)21rEziFp;j}Vu1<3#o4O+LpQMj|c=fQGXkWt&J!Q+LD2NW?34 zJ_&VgBLL+0@^z_18&hd(@~oTjYki^q4?ISbCkaEpKyD$x>h5^W1fySjahEzfQXQ3Y zo9t=6Ngg~*J+QZPDS?nLG|lS*HK#?KSJSO&#e@S%DqX@K&dI$eowArF-@@u%r>}h| zwk&Q+ebBM98GysQ*GI#)*fr>eiSEuJ%+J%Yr+=PPU@9X!iwM-G z|7CX{)YQt*lm_-{kE>_Hs!{LH)?Z)Falpq(9H9K}3lpsrpUR%Gddz*`8J;-`um8kk z2jY(WEY;gDCg;0nSWmkPY({UF^V`?Y=gXhij|04|(22>dX=PJcZ!PYS!7MkN);`ck zXo`;t$hIUvvT}M12Ih0WP>CS3KM{-8_}j(9q2wySoXqEOmm@e`Y5BC(d!=+_lC+INU@%VFRobg^C=&nv}Xw}C1)Aq#n@(XIG zC#?fAW-ny;alZ^at|h>ht%LW&UFIj7(W1F=znnY&ICqY~HQdpvIwhc8$`ulKbDWvV zpd-u@oa`H4DdnN&w6{r<&-1ukUCLaVnjRzu_!b-T(yImff%UU((zMmbyc<20DLuW* z|D-3!Yv9bqS*?w;K(Z6LEsZ(5u)k}@H-!bIb@5q2QqycvBKn`XWqA|tHEqyV!pMyM zYIMqKrhTQR`*HsAVElc?-mzMMD|%V{RH8E~6?ZWEdxTOnkt)-XFIYQ=&$wTi%#d(n zqeL;`Qf&Eah>$6uMiw`Jk!5Q%5_1X3A|nmb$g#nb19Z21i=S%OO=N{(Siq*WTF{xf z#6{zOpRzk!9}Y;@`trAg`Sc|lWE^EC8&v_FY8&=Jz2A%^U189&}U_d~BNx({8 z?8WC+6K}4A>)h3&@3igxcghBZ16z8Ug-xk5;NK7CVhq1rMuL2-0*T7LH`EfA+>A3^ zs6x(pzL|N;ugBBBfOWg{su81s?jq{*0!>%AI|;SFAu$fd-pO9}DIK{&|BgC)#&k~j-+Qe4z8zi@M6bJl&6d_fLK7)kj=vo6@Cbk2X}FO39T&fAv3T43Ve}Pv{^wu5_`mFARF;=g zpB|A1)h|j6@Nus*NR@1G^YFH5r(URxhSe0g#^%6#lAzc(nM)c`=7fM##gx~zOR)!J zDF>0Khm+zE5|eJ+&|V*4{R@BFsDU(M2<;z z(vCCkOQb|^Ri@7M-YWqp#IcTtspHAam6QP5YOuFC=;BclYs$=^ksNu(2z+XUQu?xG zdrta5r&Bn-%&wBGfi^}fxSwC!Kt-Rgdn(oY>r^h3ko?i$6W)0%g3zy+AX3BTTU1DF z;UjEW^E&Tqtl_{F$Jkke~lcZ$`d|X@L9aGZ|etW%aeu zGd`=_B-Z~P%v|Z@vqGmEt$>9#wI8C_pw@DC5^Moa{ym^;fj;JvE zClDaXI(Mt5YjOOhPObtUu_-HsHM@i+zR%vQ4@*3*qw!4}rjzLf!%IEgHW*V>yVamAtJPD!_CS|`!%LD(^*p+o*D@dFp(3y(+L9#|(nKjlqK zkvCLv%zq~L1?n3*?Cow*X0!bbiaF$Z^_?6xce2c7Y!KX=ryfvzS=F(Pp5l%gZ;FeZ$3v+ z-*xodu|TQBd$rSUjAo!&^Xq0fj3y&JBD~cmH&*so9e7-f>N-6=iF{C37qcH6Zi2pK zOYMgSB<6Bek^1Oxt8*GvlV>zN+fF?pdC!+kQxn_!XBV(!xdiEXGIlq2@18Nfn(M;& zEy5ql|F%hSj6Upb#t6OC_mha>v+$(h)GWTU&6z0?R&|1SU);~R2iKb0@DzYJA%o^P zLnhReZDM=@x4XJOgQHi(e5iI#W%j}51xN9yAywZ|6;yaScc_YAJ0;18j4%4AyMqDQ z%wRA2)ghQoaDNqH^C83_5@6MtC$6dXz(m{w;$gnAk%l`LgLlRzu27_m8CUy*+1~j5 zTlVAzbS<&Fyr`!3(3t0r({92vt>;ewlRJdSOn>3Agy;PHY4t}J7uNBPB7+V(y1EwV zU9&d+dn&5g+{We<(bDErHqM#8%~kpsn~>2F)D7}JBQApIu@arjm8moa`{25R{$y9^ z>rPD9d;VIN%b?d-=O2Be0qrWt^!L0s+_fil=Y6TBu|C=Ta;kqPf3iE-fs{5{o*dN0 z;{sLNspZGh8epA9BcxHs=#Rgl01%~afIt!z~(58u6fv?hHXmt$QK{ge*2eo2pVOpSAzq$A^&TU(oeRJ)Lm1Pi?x*ihN($@W zkE_5W+-Ix7D3puwa+%3*MrH4m$2Nq%yUF-Xg+Eqem zTJLc1TJDre2>gYq#ScO84zt7aQ+w7uL6H&4%A-^BT^gWafA1@FgH~5g!Gne*)rA}E zCR4EC`4NrS1s`CnSRw3SZa1-;TF`rQfFdY>;GT)Q9ELVhD-(1l-?@I~~sg zR!QsS;f9dk5{`PGkm!}*D246HC}6idh2Gcgx)gN+Hi4MWrss=i)9qyY7xaJ<`6`I% z)%0jTw$*}9BqfWu6X~oaH?kKq=VLD zUWDtTkkXw^^Kr3eP{!a^|44mU=D$1 z!YyLKy}Iweh?eG7F&3^aJH(F82kKgS);JB?*PgnSl~+as%9fc$$dn3=saQ*y=WXw) z5V}fpS6|H1T+Ip@^q9u~W}*Ie`s40`pD^H}p&w)M`*3JW?RkP`QuubcvkB3&4{{*yOiPZVNRW`2lc1(5n~kR|gds zR}!Z-_tcp#PiTD8;Cr)js_vpJY(rowzo1~42gICg*!kTtl^^~HMI-^Ybj0H ztkESYtqz@za>jaQ*!+_QW^TUPBZE@(eHU||+i8>ITjLhMreeEhmpn5Bw6`$4VA z4qXj4OK12orpKpSSX4Oav~fNFk8ip^0ZzlYGA$S!U2flA<%q}I)$W@D_9Ea%1ib8B zT#FTLdvky>7iB0kG%jakIQo5rbMC0`JNy}?IJEYOnBL^k?eDzW;@C#`zP0te6}9M% z>#%av7IQsp$CsCz) zK*Ftl`&J}O;|n4t1jKH&RjSF;O_bjCqF4#FZ+YQmGc1NcUYECs64h)l)v_ z!VLI?aP0Ms0>0&Q0@rr(pf)AewvkTRAjTKVUa(_y*5&)FBV$O@!Oi2-9LiMkrAAJ0 z|4Gl2v1fazQ*NS|v45Yh+W{#cMInv|{rkgfTDuIu;RXYnMuM2mo=zDQUITgG~zQWqUvL|=Yt7B5L3aS#r=4j z8xd@ZlznhTglK5wi+4-5C4{gS?|pD;4yFZh0M!8zGW*Y_F;*V{h+fPC zItg^uA%)Z^XcoX2#WMe9>lMpEwMhR4*`aajnvggkIiAD{XawX&Ai{GY zMckKCy7eShWo7+1#6LqrJ(_|e20IK5HnXxCY*X(rppnioZJd!5(wp>eA<4*48kN7Re9tYw)7tVpO_ zcU-P^%1@TW4E#oT!7>_~BTc7&6&U`*EI|w;^S6x5u_n(?GJw5-CqJQ=ZPW`-N=EO~ zKN0~8kGxNn&zO^mz}8;x9C4Y$!}GD)!C8GGs`wv@0n&tO@Y4T++`(Fafc|=eXd{rt zAp6nn1CWTppYza24^q2vdq&+}(G)3a=U#HxRa#`70*|6ofjyG1 zZpSHwt~oqGF5|63!Nd7FhC=GmiNtxtK!!CQs}-N zZ*8qVGLrYH!3#u)awwa+OWsP{Np-o~piT?41tl{kr7Glm;)X#x{z7&N1NRV=im9SwO$@ST~MAU{<+RP%0( z2Df9fDecQlw9^$5(t59M#L`NA;}8*g7-84)<9oyLgHKey4H?l7U+39&v5Fq zf-B()BeBDGL&KV!upuDgjvw~Ec9+GW^{yC5N@*3gFm^`M`mORP)ics+!^`2~7zc{~aAzyz=J(!(o~)sOI}9rC7aeK_B>dd+@#(w>X`MKG1_eWKBb%yMrqBWb&VpFs1-1 z4t8tzdwEGmxmzo1G2`t755BImqvjl6PH*qAD~@O*^tS@xOpkKvSAwi;*RLlphTn2z z#5!r;Qi0Sw&p#GV$D6K3dPPfSXYea(%Fx+;4U1H?{qY8sI3h&jwE(JKq!kV^DQ=HU zzlI`LrP>6BMFGk0X((7LZUr)M+f0uM9zQ8ux$tkht8`A0qX#&4fO@A$Q#$0;6Rd6V zqbUnxnSu;LQ@NRqpT#Blef95j+SKia$}FIbm+EM7%8vJwxi~#~q3wwguQ08FMO8m7 z7e&o+EfqOt;>sPpa0NZZP6{dVJj0NKsO>Fgr)21K8T}3aIUcpoFPQnSCY~3wtkn}Xu}41DMK(4J z#abyD_%D-`S)^V~^q9Qb_VOFoVb9H{8FvO&^0w!lbzrS*++>;@09D;2u4%S}-usy> z-#Z!EfC#PRKV(^;Oz>M z?N_diP2e~@+F3PK(|6-^xlayXfSmu ze$&@?U`C`1mVdN(iOJ3zu)%a19n#CH^NJ4+$0ElO$({W+K*0Uc^DI^;qlazCm(1GYd1lCCfhih zvLg2Ma#pFMO<)$u`PNnqW+NWNGV*H8~Bt(6-gDujPXx2a0D9LN#@)w8;2_FzhlatfjOPTJ6c-SCI`J7oKYHU z{uP>Ar0~2jZ}Ij`1WmSrccLGqR~kanhR7FI*i{o}zAZ$7jA6u~Bz+@2ZW=s^F`P^Q zx1~Yx#uB?>si|_h`VcSU-v*mG@W6*&MQAmUAO+sno>|#Vqq0obxl7DQvHX_xk~$d= zib+Tjzg06jtr{ka6Y*5qi)o0%p#vpw$qC*-$fWHDP<6S+;o8+W{hTSkSaCY$@LF3Ny#KDvRB7kX!ixH0em{kj z3Wo5;u#-NCYB8lgEgcV$VU>%E0Q!x+YflSp7u*)dBCuru23gB##^i5^hX{ZdH75{g z;%hv#u2Opmv>%|(StHrGwWN%KNGOgE7&ScyU#OM-yZ9wW8WHbE`mw>Z4djd>o|qsY zg=Z2KEYC4*l^7!uA(Q={s?fDf0L=^mE(jEeP+h9B<1wI}lBwj{%>Ow-;RRJ+8k3FiX^niRBEQG3St2Toz z{0kXSwt&aN1*_FUnJe;5+lJq_NzEgGZCgvLBeehLWdhBUgrKa#WrgwA-bC0n!dlkP zUj2h`td7`EVE|iK9J{9e?gQ|znr{K}Lm_Db7C=AKOLeFLvPD6fOK3-#QYA^S@CTp< z0gZ~ISZ9Jvvj1uEk-SVn2cPtXR73h!GeqJa*#Fle9wMg5rcl=*x%6Ic+*#xHA0>H! zgFRL3n!bH{x!eEY7N-%0f}bDsZK5)Lo2`yJqXvg-=v#B|xyGG|QRQFv3$zGEjs&blKQEMxVI1@B*;6sNcqio3fPEAH+^g1bA#ix+n&P@uR6cMa|i!QCx5Z+hR)bJqLu z`~l}fWPU3%Yi93jwp@EA;YtdUD2N1zFfcGE(o*6oFfi{dq2CWaz(L{7aAiBl$O4T}WsDq~ z3Ad!Bjf_#`jF?k_D2SIYmg2H{>5|LVXk^G}ZwU%_~gV*olx zB@&_Cch^J_bZQ0fS{J`C6XFkLpOJouyP=RK|2tYW3_unp6Xi|CyK3k!PqE^EfBf4+ ziR<0eBD%ODfb`uWh5!;&J;oK%@n1iX3VmfD5BrJVeln1C2BQ~f{g2|R(WTVDEJZ$9X=kJic-cAW^}f>a zW;g&b=|{Di-0f$#HRY6+J?C)_GLLKu%fIuB(-*M@zDupeZykN#v`8iHRxN6_A>ZL4 zG&E1Sj{}`*uV{*V!10Z#?00X$MdG`$;CCSC)2~{|A9K!Fp^!@zJA;9YLO!3eH1Kzh zC4ckGebQ?}=N|!m^Y=%OB(NQ*K1cJVssH?^b7E5Ib~8O~^A~_iYd}ah=dx(P8zV;K^S8v;eO7;wKb% z8-nvEGL~6->VqTvQ2!T~cG!s!JeM(zs$$d*nUbBiFljg52fD3Z8n^Vp=!>U*MfOm| ziquaFg2nKP77ki(vQj%WJA95F)5tM0ky!n`9(N&o4w{xZ1eh_ZmEHFu^MFKAa!3_dd$YzttuU*7DeW zjJcoPy*jF-4~g?<5`RrY%DdWzaoUD32?fb>iNm*P;>LdP z6yi8Xk%{9FbUPh)7e7MwwJ4xN7gX{ZSqT15CDOOIhK0aA3K)OL$=TSI1r$&lwRW29 zCHUOA5fr43mUeK?Nj7Lsls};hTVV+P%)1=8VT0l#9P_61uX20Kt8Q1?yxRv@ntCtp zi38AUjY;2SCV+sSU6=sY-@Qw}zTFm=OjR^xdh1YO%*{L_we^j(x7+xp4mzW+X<3@P z-XGYFxeQaMp9v%B1N*z6W1961cr~j6;l>wnh|Eo3=-tgj(2aL%XeZjTZ4kfj@ik`2 z?jAHiJ8qhYY7-hw=KTZb71pvK$=H#55hiZ#(K}91(JOjGl@01wsDa>iYk^&CLX}xf zI5TP@hSBJ;>>hi%`K>)Da`pki?;m9M>Q&oO1&|5()tsDKbFErt74wrywc%qdjOD1g zbDOcf|GucJNJE^n_YvV=uu~<}PiKvc(K}=OF!%n>5KxA03|!n`L8ks^!$W_wNN=6M zkvsq5)*klxe>R2VGT#5%Y5c4g{CBM0ZWDa$hSyZH4O`(|y{f2I=!S{Hm+6MiBvt-W zRUK;azR1u{{F=NHOnh%C6gUz>Mi{tpk8CPWZoU@7D9)u48jLCWfi+{hs04kpP>WX< zD!VK4IQ(aGu6Lyg)lmX65#+&QRQjvWF26IXM{!_8bJe$lk#;?Ur>Wmm|Fehhckd*3LK!YUeT-%@p$?&bt6{wBiQp-(i=6M)^JOT>PwnCoM5#|qoS-HAe6 z`@}QEsaz3&C2h)`bU`JQ>PQXd;sgPUK@C}`%MstwBP_&?(xj1R-@gMK#NYjEFUa^; zS)~d50YYQh>3?<04js9Nvx~D6DV~j|2ZTTVA)bd$YKF!(PiZ~2RR`9JSdzIgPi(gr zp4uCELUmjID~8aLbUXZwi#|DPZaIKTmoGXJ~wZU^ik&2{UB1Pgp0@=?Z_ z(dUGHn__~O6p!G=k))Q?cvU4S=3g-x+x>M|mOrd8y(bFtTdc2HYuQCAKK4U=8HUM- zqQ7ZTg(8L8<~h7U8YXz*a@J$u$7-G9s3teULS)BM8#Rrm9ol-ojz(=2T548j`OXk+ zPcsplBUrs%G{3qGy?xIpm1+sXDu+2;z>-xGScDF391akw1{E% zLSZl7U=^`T@s0Cl`+aFPF zH6`je3V>5fY{f9%Yv$O4HO}v5(!k=s+VQJSrJ@5aRfa;}j}LExvusulvG>?SP}$g>HC}+p@~$b|Yq7 z?wlvsDk-7pN!2Ph{@6;D7jJ@Q)rkU(MW&`l?)efT7R*@1XtLs0Y5$}~IdH|AC}NB* zz>o;sKREcz%^mww!vg%iyjqMjFAhD;B|?ct+>b+?EUl9Zd(wkRfhq*Bh>U__6lS9Y z=jrKr*B+ao5YOgo{4uCCmqKjy6N4^MejAwFc88rO@iS4*LT96J!5hLtrhNnq9!>e4 zX1BxH-_k_V>;Fa&tVd7>-HVclkw1u#FcN8WCseG4=tDwoW1>ZXjb=g%yZqs;UI7;0 zmZ(KpSDnAQ!;xW;CByf*bt@7@YZfg0`L3EC4;_>JZx0D<$O7YNFL%W4Xoa8pTz!e= z2V8x9G|p^8=0a@UKqjT$`9Ur2x;GRaDcW!ZsB3Ja>Jc$awC6G+9NITu5TbFI;5c( zv{U%-ZBFNKObzvNGfJ-2DCIxrCjq&sVUOf#8>ayNpBKTI#wvG zOTGWko^JRG4cS({G*XM%8?ej{vLNS8(j)_N6Ul5md-E@<59E5(6wp`9Q%&o$OYiXE z0gLOUziRq{N`>JyBj3`a2q^%8y-~6hL|t5rD^WoJT?<1KZK32M1PSAwtqBWqaSpzA zl2NI+2$hH^?&PQ@tC^_LqQDCY<}Tb&Rv~~feNa?U5FJ@TCxitnm@&jWy|F#u?B1e0 zO(SjyYX&)kLNVDC-;?1^Hd=AX!grLn>6UW~lSk9vb{WTwW}n0qH-&X#UY>(M!rL>| zL!8V=G#5S82<|!LgTdJyQxHCEft&!g2t6S^M%RbG@H%R~Tk2H$nSq(#p!;!{KE&fa z3X0~R@?x{+OBDqJI|_|zI8DWT8?$8ntj;EbOSmsLg_XX=|60FI0%(-K372V_Zu;V| zUK%7WGBG&cJ>0P0Z)AfyjrBF~A&!{RApK`~5X>j|a(w}T3F1&&V+#p;vVbhPk1B9b zkdQ8a&Bc?Wa3De(hXqJT7x_$C#;SeYpmiuacy}}{bj~5iecUY8IJkKNYt$!5d~_y=Wz^c*N3;>&--Ser6$%3)Tse-RS&JPL zJVZeq<#(Y*>^csn5<#JzI$IAyF_>zS_wD_vMowGGILwBUnwq#Wv=uG|AcO`Lb@hN- zAHKvw|4ZVzD`VrEQ3t?ueG<2d>wgRu&EI$y_HEQS6mx|Hue0oBWl9vO7(0M-RJY(^#*;d?TV-t>DfcBR zjp~?@(e2!tPE!z}^vXY$??)`*KN?E5R6W+J^YEqVp~zB50GZn9NjqnKUIV?G&J&G0 z-#1B%3c8eU6@e#D5^WJ0QcWG|8?)WjLYKjHMdIMdq3(BQ2N*s)o$p&$xCps#ipKT#>Rdk&E8c%K$NY+kr2vDj?FSJ zJE!;f($2%Es4`igA>oL>MH!c?n%EAU1W}Mfd_0r9_hpPD7N>L_+Jb49gx1=YqE{18NR*U8gz-M-JM_6VFDl&Atb23 zYg#*Z-%O%X8_;5XzJw72!er%^nOSinGeeYx^P)Mj-1Ct@Y0KT%9ny?7N#C@97Sa;W@JPvDA}x|tS0j5G@_}6XN~Ye7Lu_80BVRj}RqA$s_x1I6fTRPP^i)ORug|#LoL_i4 z66^S{WC}v;D74uR)M$%=e+i6WbfnMt*qlq=%BgF;BIOsp5ng{?JjaSDa~g=s!8Ju)b#C>mw=%Dr zh1YZ-mF%tDAsy_(VqzPgcwv z4W&wZ9cmG1Ta%6REL?pPx`roBkg;4EM%K2LYQ+aWZ7NR4=Oahgq)p zx_v9e3G=N=XN3IEjFIIOTD zZy!yvxU!@`n26F0Ys-rm_$d$MILJ(w)8o$jI_+Q<|0^x67*i=bL&O_3+%)1PmjWhE zDtKy&O|&OTaQ^mVvzt2IK#<1=8_Yyrw{mA^C&w%fg%Xk<8k$zXOoEoe?oZ@ z)kePKY@77BTx7SIvJFhmqr0jLjx)W?d^WIlw(+cRW|@*(;v^2&ec$!CgRm^F=4Iz; zIg#M%>MSdhDPom;$eG#s3Wo*SGD~ML>90SZb0p7JyM~sm)&xBwrg1YWmiIk> zGe@%p?&*_==CTmZ&0VCycgV?lQw!fs#)b#yTMTzA76c^~*wtog1&<3CWC)8oH69 zKYxA%2EIi^MATB#mXYw}ElpOh_3d$ziMX_D#F(#-{t@skspyG_c%>zw#oY$3(@`)! zNU%3A4&(;gIaYMKgXVWX-Eb{LZIT8Tdu%YA0I~1C@`X!C(-!VODHNmPqmDAf=rK$T zWBQPfRH)#mo``!{z`WM8C)5&IZ=Ir~Z1BTqMLXwyG{frt+5g@%dDh^DU6Hn=G_vVz z4W&#=nRiDhJ-u10x;4J2!-1PVS+T7RN-Q>MLM7noIt!J+NZ?X4pPQhAF#UWvV5hms z3h;S1Q0=eVH;V8S3$unrOydyRj+lb3(ZhS zsvnehmZ8lyH@%zwwRc`FnvNl=)<_>^Z@l4h)V}SjuP@=jb(X78GIOQr@*K9nYxk(; zxPIeAHzdb14Ez#J?QyKSd`IFBK@18i)+Q=I-vmbV{lLN*T77)aRQc=s=B1O>(c!+8 zHSGFIc*2zcog;n3@UY}-vUM{HG@JdviniOqJ$ka~MKDZcP;Twfo(Z560OuFk|7;Jq zz-CLpo}roU%rR{$`xPsH9;ika@(Cs23^V$x0~M_)t6V}~sg=bkL1R5PXSkv7gOFU$ zIy^H;UW>oQ93&^YLSacykaMU;E^iVY%5`vXxlOFH^Nf>c>4&PQsbj^bcw0Yb5zTKc zR1Y67`-iUPXpP3@-?ZM(U1&ogx(Q^Lzl@0ZQ(l??^NQ-|>X0KxA%%=Q0bZt;ZhU`y zXpJ~AJ4ZFofdplke-KvHZJN!4lxeIYhVHMMS8dAl6fEsX@#lB+B+18fRtDfviq6C6 z8Rs+@cjiyMBYaL+|D%SDzu_h9Bx(E$6N1+t1VLfuS#>w!MW^DeGLY9La|+m<=*ZUTbLO~ zH1uNwR{|AvZWj-a1D<=Gw3(J=shnxeOICgdvS^cF;lWsgwE;}D6SKZ4tCx+Y`33)L zj2vH6Zryq2t(NijQGR&EH|RBt#4BxaVQ%)n>u7S;UP#vjUDAEw6)z@MGZvcdc)>oq zlnOa5JYGceS06%b+MiSv9nZ4$v2d{`CfNtC>_6??H^i{byeDkG^(20|$r(Tn`%}!Y zdt(10M9s`~W&Z*;-#=`rUt=ZIU@{))2M`H(ra@41NZN2*W$EwAD}}`S9q(hoPYC>T z^OtGx4NB@7U&zvoz#CUSkPt}I$`q&DbE5IilvB3fH50JB9O`2MENQ#feK^_PS05f@ z4KkDHvVPiD+uEWSdUz0)CTpOhEF)7)WwuU?pc(QGPS$Gn>qA;IX&_+rfqeH$b7=r8 z>GJRT+8oW>oNXw|O@DBh_3kRZ-XR??G$M=95_^4PM_cQNtKCb#KLI~mhhkVF7yK#J z?N#*mWImdoMUM?TIK|)Y?7Di|Uqs_^ZwEXKw;M`II}&%?A)(dUonX8?__xYY7+!W-_G7kA{7IdhvWt%pvZrM8^-^*Pr7vlH{mz&QI;k5KI3~%V0yeG;L zy*2NwTbc-`uzn@h9(m^4vKR{ZivfJml|9Pcjc~o#|uSYh-YTgLhnT_ z%5Qci>ttr*$A_J3G%5?bqpqB?!TR$@NfC0~Ew$I2(x(g>2gsil=a)zsg z-o~H`j2G3ErIr(Fu(BkYimj>)MO^WE7l#LQQOxf2`4}G&Fmbz1tjtBvrCU(+PRFkH zXlA#DMQ#1H2m~4Ypz-KxlWCb`wPc6=Z3(^k9u9d823m7ZyySezkAsFXbJ7l@;ue9N@kQ-^9qV{&YN@BAw4-Zd_b%s(i1!4mIYScAo&vkMUTzJGJJ+ zGH{rd3fWDahd`zW-NB(ijocVo_vysBWn z+ZX5j`;n*bdur9);?hQT*?ssXr{@NRAn73@&~R zjknZbF5Ry7=28K#NQlYe!rb#J`&~Fg&Yg3bGICARd&~)%W@e-H||H7;AhE zaE8`IC??FWawobWKgHF+^>>8$BuK0y(z2 z$+g}Pg7owjOUnad2yc3^6i07iw5+y{>R8^PG0@IHK~j>0T7e5{F1hSW0B3?nJPzwb zf;|Xv&FZsHxAsC^Yl24>cBi`&lDHO@2S(7%d)i_TyHVA*LEfcRUr9>~q84WEuO0Uv z)V0sqK97?{My4n(E#0lKrH4YwR#y|6+VeV=1entGTrMFJ`#E63qZ<5b%eQxF9b(a{ zX-r%y*vaHw7PrJ*Uuk>8p?IYQgRl0eEH{{o0<|rchg=S^nt%K$AxMlLkksNo^+Wf zR@S0bs?6?<{T@JVf1M=(0h4n9Gq`U1kM!m+BAw%C+Yyw@rH#AIxJM;d#s(;=8jw~IIAMg!~p_rY(P+o+w z-}NDUtMfWX#hy_*T*qyaq7wu-yW%{rbC|IN8V+}w@5jc%-adaig79Z) zhIPN#7UPG(J0M8FjC2~m=$lgmC~}^03qr zu`c@t&deSkuw8CYqcpO_$-8RwN;Mg`P9Uh~8Lx+mER2y-jwl&iWqX8*-~phk?7gG1 z&$VNwpNR?+VexoDNw)uj$0N^g#aRb_@7rRY3Pv$<$E*4H z#MEM#O4Xm%AO4Tb*~U=UX`QS-x#k<%hbwiB+-|D-+vhTb+&$wfrvoflGlyZ5STTAn+ zuq1Whbg^?|8s%y6)yI>=Q&l;B{PiXyXKU@m6)M9n5YlMt?F+5fLujMD_otL}KF{49 zSeIL5(O%>GO_lbG(wsc|&s`+X1LizHVV(+GU4f?ws`i(9c+bP|Pcw#g`2_`gg|L1o z+KxBaKcjsksVSMUbiL!{o_oQ2+{?h{fSiDU-{a;czf8X+xGz%n4m3>Sczg%=KDj#= z_e0**m392-8_BrPE9pU95FqU-($F`Gnz$o!K&UBti<&7mranJE)_G5N0ciVPU0s4m zP{&^t1b|j~N!`!R7*qhxdrc4NZ=K}r*|k@tfAFFMZ4O&>Jx-oTg)Dd^`jHCF@0N<% zi<0QuK5d7ZB=#fqw~evMXM4UfhK8PrTK+2a|1QgDyWO9+-5aRx4Xn^t5V6bj4I7K1 zvVaj7-0Zx^6S3b@3M@F_Js)4BXIKO}86?&)*hZzn-4oa%56Hy9^#;BOf zO;ksVsAA?`=2`XclIF&Q6y_T?y@;)?iVU*$1G21tNcOZgp1qT-sM}y3 zg67GRRCYD5YJyO=Q{}132;jc=@Bt~&^QXEFQ>^asX6}_gZKI=*nO2MbAPFF!xk|uGw zlPXhbP~%Ag2-((F(85qvTUngL?J*@5S9ByNE_k#8{?vTBBCAZVK|=#qXT74mu%>1r zOQho9gfa=r08Pu;9p6&H-%nn+(+<=Af_jJM8p>csLNQvW9@ad!A9Y9HGPXM2KVl-J zH}ek&?s^f2yATX>u#SFKuKHb*=rBk|jB+(`8oh;9@vD&~MQX6H@iVSiF+MoSpuP?f z41oquzAIbVXIE3pVV(ykJy_xcw+D~u6{i6R(mzf4*jJeQ2yB0N->P6nGiE^pEa&-9 zZ0LIBroYfiNJzg4RS6cmZG1K*N{PvSnKa-ehr^`hNSESS5W)b`(vEED`LeIJ!D8Mz zZo3H1?wHUM?(Fo^&@=tYZ;6#JO{uZDxT8&gVort@(a9v(Hqz9qc~~Y^7z}a=rDr@* zRWPDu9HKVW)w8l8bRVsot8<4;&MZkdikt?|*Soq*&Mr#|*i5stNO@ius}#RGh!PtF zvWzt8;*>SFq8DIAmkZ866CaSsI2M$9b11`fnOm~N^>d(z0(qM&Js3tnk&KuRFesE$ z9Q6=m8VO4y)WTc`YJEX#E2uoWs%3pnbIW}$65N%Q;|G%Fh?kllERKlRWpp9?-cV>x z)<)}D*!)d*Aa;fl97NqUa*2UM@ji(v`RelADh+jSr&$Ka!!Ku^GX?~U67#C^zH2dv zYRe-WYCSW`d%l&TWUs5cmeXQA*eu{88X(6&QPxToQ&q(k_Pi%YCFWCv+BXQeAwX&Y zI%VXZ&&096kR@n1+6?ja=JV^z%|&~*b91rUp(I0$Vz)&(KAzOne9o`mJSkcny%Rsn zE-88k;?zu6JS$G*XOH2bEU-Dtnv3`46 zfdqDAd)Se;M|-TT&bFkJ1xY4PmJv%95lLo#&}$3_gvbCyO-{Tz}t{Z{1uX&W=g? zZm{#Qmr(Ic?>o>!6C#jXJ^>m`_d7}}PU!*bou7Eo7I7w}e$;IG+}aqjGljF{RTm`0 zWCvJM^CdP@p z6lSI(z1D&E)NG!as)!xd`|Fi&5=C9&R-$0S@-E1;W9iUdKUpwCWP3nw@Vk&o&f+?; ze#dZ$ZoJS(G%w!R6K)BETC3>tzmycH+F6swAurpdUxJo~erT)s zv7xHij`hOghgyHvRp8lhNzGeiG5MoCQ6mH70;~*8W}_QdI(sG#;8rNglY}P=It5*Y z{-$?xJP27VJRF2Ne}hLPV}u76R}~FNE7Pw{l_XvpDM?bNDR3ZS-WSg2r0i=lC9+?d zm902RkdnK6=38O#sA;26MJ-kf^$-ZO9j>IR1*xe*lC`9eO*YjgZA|~@>OR|4q&l-O zEz7|=W4gq?yQ^N&i#hi9SBQb0T9k5v`}uD4Ed{;zs^4YCPjv3Qz)r)XG)@hD4ZXfS zuC?L3KotX_E7GE6LcAdgM}gQUsmz?FqXfK!cLLKD9{6jgc5{=n?maCR zO&^2uTJZ`kovHygB}23HCwj4GN0Yzgj}CSM5(DAg?KdwTfy&^SE+`M2SL*&93W<3k zG#_JFZ(w=aooKmvqItTqf{gXwBrh5g8=GhU%wfg7&+=X7W4i$q$l@hk1L0DCh-D7%UGJ9kB_37iIu$8H_ z1gUHZqIOeV6!jUnJG;E}?gc5#V`DU7p%8@W-Efr#&+YgiN>S}`J$Fehr7&>VM+)a5&*!d`Arwg>|@8B!OgUJ;y&hlt_17rD@{Z_80fpD zd8?wG7F%#xHOgi~9+4Ypg*Qyo%N6vl+=xbw-2ARhvU;?}F`&dYF`q@5PJ97+2##1b zDc2WsIRdk~6hRj=A+BLq?_Kp3Xqx?`Bzg7e{iUB?rS)O-u80nrLfa(rju#w@E9Zus z^lV=@Rd`y6d@1O&4B02wzmt)O)OU_<2WOksZOIG zI!s6clY%$%5~QoO@C-yzU2=lM&a%GgmA?IRbL4=~b&|V^Ci6P&Ne->lI#;*Z;_Pn77X5a9z@R{3&YVM zf1=u*F)l)qF4EsL``G6tXyElUH5G}N0)x0rPsZH#(d19CX?Kro-+rr>xc5MB!5{Xq z&)+`Q7Ik=Ka<6bxXOHzasXh zS|~sp?!qHgoJ`D^rl$r_V6)cvgWY`jZn9Rg$)(ttW7PcD2T8jZ&5%-9b;W_nJBt&A z58vvC23R=oxh0lP`fsSt>|OXrB+%)DQ+3!rJ_&1Kup^~V%;9h~`7LgZ$xN+uGsh#v z#f&gGo>za&&brD|r84X8cSUjOQWwOU+4m1TLB=G*(J5X(3uLKoCltj9bu5?^RV4G=to3hML` zw`|TAo6WH8Urq0rfFvu=C}Ai-JNm*uG`;+1hJ~g4ya(5T5e~!>W>^COQP^gJKV?My zc~X#YABxKc^DBVqCL}0v!iiMbhm_iJ!_N>#v(+Wz+cx)f)goQir#NR5WNMp!ErZO@ zBkWaAdN$zv&%!c>{^`Iutk4YhrMA|_k#C?pQJZ0LOU#0kjSl%Q(NymRIB|Z^XCdk2 zvM4R}OVfLKPjByPZ{vKC-CF=A1F9^2f2K|h^>M=O%mToA!hTLiRv zCg|lvonrLx{x04V9z46{jLyf}JsomrOBTSNhGo*hOfkz;fRxQrP76SM4WV>!|66Bl z#I007msS}QMsB2@#dxm2#Yb0H<;;14uY|&|+k0P&_4Iw z(w9KbWH=leBf*GCTgZy~LbQn+%~@URv4fGkrOfpZFMFVIn^W-?k#xRw-OkHq1esOJ zt}y{z#iZg8qF=G29MZ%co%E6wCE&ftYxsk#&9W9K=A__hy2U=4P?Z5=v$~BCVHtx+-=3Lj^}?>*)zM7uxcXpNXTIQ(?+`qq6V`h!1#!tC#UK+4eTIChl; zaJsy#lz)p)n&Mvkxq({rP`JF}8u9FbL$|es0#HJ5wn2?h*(xlh>46^*v;6dw<$#BW zN0BC7%b_RQ3Z~{ZwsavR47GXRwINfM%Nxr#r{A)uqT-RG$yO*UJkR+Dz^1 zKM?R!TbhH2LYt|NQ}Z$q5N-JME86?kCuCIjYSFzpV;VPo(d&R>IHhj^==^CG(A0Xa zL5@%wUWfgbqk{E||Mp;`335p3`7E6hT+jw4^1bC!%NZFrwT$#Ax_QeOOxNXdtj{H8 zFqz+k1rK+Z(mq3lZ364n#7sO;_W&){5RMmiT zIa3@TG29DC=XGj!K?+Ua5J;n0Gh6YI1O#`sN;wFk%_$tB?8dnCHnX?c-0ZZwV!=XR zbj^QC6*JJAo{jO58AY1XVN>`e233BgqvdEn%S((c`ZQ7%P^4nfy75dsIn*WnejqlK zv0FK%m%`W2tfac0u$&W`+fv_drR4@uGhZEeKP~_(LbC|1JWqnAznnK2)RskfH_SU$ z`d&H}W|LhFy{JOd8r$O)rD15XX0O0K7Pjk91+u0-peR_Am4KUW zK9e93Cifw2e*;Kv#UhyeM@lc62M$?E6c9go^eOWq(*I0m8J-BB}f_K{H-gVSbQhLwUJX91RH6YJ%r zv5VVng4~)O8ZnfR`8-YYU(kna#K=tj0TQlwVi^|-yl*GrfB{9_ET>K|_b8dji-tA` zPP)X&axxz41H&&fMVTOVDsh@4L-7(%Th$FeLdXQFPwj;2-EhlSSA$2+w^unT^Ye>h z&xBrapd91CUDLR5r{MCuLqT~)O`bsVyc!!%;&xV0k>yFFV|{NfJ0nBoP?0-}nC9z( z!0SVyTRWt?#piz7`>xHeO z;kQho&5ty6gFDPGql(U(qU^6=q({rc#`|K*o6#&}s3zs4V(XUsp2Jb$BQ&ExFxO-NQ|S2Rc&R- z`$;eeT758axm~e9+=@QPWZ@Hz7(NncQlGV4@^vYHk-$b z8hkBq4xeJd&nHDZ{?$p4HU3d&W}?Po)`2afl9GstFV3>u;oHX)OCjisVui{KHW&-c zHkZ#0=PSz46J2Jy==Mj18Xqh;D$e3u0(T1EK#9h?7Bv46^Eq(O!w?{G4@U*OI`n#V z=+3j?5xTS~lZ>mWtg8o#4^&Bi^p6<&L;2;mi?n5qiv^U@boOQ@qSsCd!E+ALV4}W!R%2eg9A6r(BN`; z*q%?s=Nb1SPNeu-U$P687!`YUwcUAUkP)7Uvk^+=nef*^pr-?b3R*3fQv`puKNjvM zJj?lI&mv;!DAdw02d!TddIG@8dh_H-j#LaFqGQ7ZIl!Q4=A7$Toy-wnP`4-9{#@caj%2?yRK6^7eL*{0WmueyytyAJ0_5K#x54{IGUI!PY zHGR`j%Q+9^;D$37hUPCgpbH=4$(MK6AK$9%cx4+sS%nrQQI_YJi}FijHE%y{ETnk} zT}@Q1JM##{38GT zHwFOn*bN zl4N%sGz=v!TZqToJl`#|d0wC1*yyW@dAkb>d+eYK`#sXYiqR%BGnt$L)dd{p=?vEV z5yv6Yzu8TR+*h>fL+96oCB&R@4ZUpOp|$=zU~};43n{cnPXiq<_@Qu2w?w8X9qnm9 z%jEZ`l%mtc!G3vJ&~N>}Jo?M-nL%Nj;N6na91?S@$Is0?J-1^m5VUBvwu(zp1l4z%oZ`b(=M@LY zG<2I2TMqzuU#6qoS0G!?!RZRVG*|h+`f5th*G(Pp-0glaf)5R55|^s3D)@IBa%Pu1J4^FyhBV*un*(-^ggbJ{S*t=Bm+TV_Mo|jD~?o=wZ zzp3ax58Auf^YDe9eftqZiAbb4ostSVltf$xn&0S&DhV3n!6jR6daVU-5ABhx_L-9` z_CaZe?Xw(TZ;e<%GOb*T<3?cdU?jo34J@r>!r(iE&gw(l5I`E9Ox#$MJ)*9<#^Ah= zxA1#U$M*XmO$!^F-z~y@eMq=c$S$=$j;wGIb@ocF7L3tZVt5)Xf`C7z;W>7E@*gJ> z49A4$%5r8QdJT1f9Zx-#PNz(n;MU`P3$C?HonfNe+i2ld(bNs`oVC)v&>vwzvy#Pd#NtjjZ!7)P3Rk;}_m=P{HkglFlC?a7=st%BFae*ij^oEKW zB_h({Po-U31n#==sDg)%NHWbFB|f4ZYx(vREcZQ4^BTD*;Q1>PH-8prXMM2MFwp3P z7H9X5_xE~&_9#WjdqtC_CgxWt5dPknm0*L`R*t0TbE39Jyy^$8EzD+q@4{)!sj29t z@}Hckv(rUB$xObSr>uC2NX!i1Y zdwM-keWY-9=RBt0h-H0bRZOX!%*Y!d7?T2uVh4G!pni)2$z>GzXc z#&Y~lwaKW3qilKdjP6O_&YH7=fnH67y2PB!r9nIx?Xx;Is2zf( zU3Lm~_TS44D34AyczxPg*1*l;n1Uw}oaz}^Ha~5-8}E1gZT~Wsa-B49sGQ#WFw0Lu z=dPejSo+Y@aRuN!1uS^3QY)lP^!+KYLzfKD76}$9^t4dlm1v>$5j=GJt{k zPDlRxP5-`Dk)7Tgs!jq@X#0JG;kqU`b1<{n6?a2>@;hV^YvmhuNc&53>y;IU)!{AM^E^pM?(5Z@VQB_HX3WM6mpc3w z4YmGe#oVP9+Xd=jC6^x(grA+CFNE(3UnbrCG+#FjpB?Oa+5yn?34d+Qn*dru)Vygs z^AodgziEFNMq8WN_$bT_y;UE~(fQtoQDsJ6VHHO-)y{o1*g5v~rNh5C=jD)F)9)$Y zoExmYdsv8jDzLgZ5AnYaUGqC5Z#!QJO}|Ocge*a)%?}Zt958RztvGChkG*Dwp7CMw z&4fsZUxKjTrb7=o-1-VGu1$kIb|lK{380$EQcy$_^2~z>J&Ak6+s-};$M*<_C?^gM zTfCl2RTIQ(RQOFHIE)>QulY#!OGSIpS*Km9CFk1}l5||eoC^DtxC?o>Ej~V^DCox_27>|Y3ZB|ZLHOl5~kLYUW?00!o=zI7^6z$qP4r% zLu5`zX-DeB1)TLlYIcIxeec_hoVJS!zuW#6OkNxqn9jVtSs}OB6;=8s*0nno-{`Pk-dX$M(F(#wHTv8ZVzHQy}NnO@?GiQJ_qF zG!IoJ1Cl7gI>7_V$4)8pp2S*yew4uU{A`j3c7y&*dwBw(nZ@#66Z)O!44<_G*023K zp7RNT%0<&jE?()xEYbib9%LApszEv-%QsqPMk9N(U$i*04_;Hg=AUxZ%nha{*rlN} zoq6#R!t6XB$T1yZ8SXV5-h^63C&w&hWuOr^7Sh=spnSU(@|D}8f|0|>;^?H@9iQ!6-51MD+yQvYCXu;yC= zf24~ke7d-2G9l0Y({)+K3Wf3}8AG}}DH#JJ?B`K%`}#el1(|^ zJ*Ww;MS77&S-Gv6Imx7b)2Zn=T+R7wlv(@!v;Mk&5=bE3zw19N+5-`9=h;B%(Cm)Wj)j ztMDp&;Roey^{Kfzoewa@o$)7Xt?p+0Oyxz%xV#cVCkA1X*OXw!ynrxEo@}3d6V?2@ z%s9Do>Z$8qVEzu~!WJp6x6@iuEn*Vu*@)a(&S^uh8PsFZ=E|KwY1fozMXxGzN<2)&{(wLWkYUfZ^x{Lu3UvloS%tS*f~|Yp^Jf_ zoUcH-)7{#Q;ZYeC%%IkXZ}&^_OIlf*Lw2f+cq3LhZSH@;FiPeWL?OMiQ@qN#(hi$c zjm;@c3HH9V+X<&TKb=oU#zooLEe8lLwFdlpE~~u1&))q)Xo)Mg@CUZBL9Jb7zkqG% zw?f)Q*Fr`l6Uzu4K2cc(V{z8V@By{Nk^8tHOB}|oC?h%9+fB+jak*Qf^Rct&tjqg~ z21ko;!{_{3KRvb*_YV>$hcPdQkK@)F_ob6-4O=Y=PQ%NjPw%TF9$98B1{FN`G=}G~ zoI6}Tos~n2n@&y6j;?mH9QyH3Tv!D0-L4=2AIAdoZ;ZV1C=n)w|4s1+uA!;nbPJE6 zM7hR}_-S;Ste9wV`>0~{Rp@%sjJfIB-|ao}O@g(n3qNl~$|gsO_g4RHNar5(5;bK~ zO?R;!G%2R6>ufb&xIUfj_uO+ryLrv$htDVX=H8k-&(2Ws5gbuQW=&aUO&}hZB}9=% z(sGOyofyOWz!WPZy=SbwU<1v1^Jtm7o03lc{${@QdftAGNTtj=6x9@VWoz?I$3rV3 z07!zdQ+m8MFq^n&oXw1sCv#?bQCedvQq}8yJt$rOf*CaC~Rvh$sc95U+9^Vm^p z8W7cx+RS-=0y;uMsOKWw7^ggEHdJDnJMW;E?=Ehm2Di=1i|6J|$uG_P;lGJgyoP&vSP`$SA!64x{Z(N%`wZwVvb{#^R|RoOY(H(esWJ1obx zfTt(jn39%Xv{HUG;hCIXF;15eXV*IVq?(s4STeILgF-d^ee~4em}^;|gi51btB&bC zXEB~?8V^*v=A-YAc)q{;)%7PEUN_}xvXY9|N|f9{-=c~n$jmRu~cg8kQ%lpb_XQa-% za)~auyuvabEmjpV-QA~Jmi~vnINIW=-nX)pLQbE&BA#7OA-W<409M1-M*!P5n%wz5 zxJ)A<-X@ExJ9_n_IvMbh*G9}did}ugIS9-y%q8Ml_@9{FvG)pP!+UogF$0T$b9{$It!U?Vuyl(!ztzG|Zb*V{~-tOKLWO!+n z6`fgmOLe&t+pE0XGNUAk$tkR%vmxF^;N?+u7Vh%Ak2>FEH=z5E2ba!s9YH};9n8u?QUkoqY8H90Ryc&@oiYNN$ z?r#Xx4tfpHFCCl%UB<+Ybn5Fuc1Y>FomAxv_fq`w;+-tcBUkg{mw$KZl+i9E4 z^_jut)s18WZP$=!Ntx{(76i5w5jX0^RFsh%c)p`>m{Tw{nP3(dL=II(*P#s~#UI)* z=0>9#qm+9-k18F@>ASQ(H4=_9_{L}-XQzIh`#+VuSl`1YbKf<)lEn8VuJ;V)HdN}? z^WNnsPwIU7an2Jhx(+vauje*y7M}aq_Z{7|vI;XV$T(ch(SxWm2=|O`okd3xfg=m~pg7%G}z@ zRO`~Tzj^LUeBL+p0Y-^ed8euh78V7WYUeE3B_&A4gtGGPhU{}qrD4;O*13=S+aJV6 zlQ0f?wY5oxMurhK&2xxxnxwd3omWQgMf2^}Q923qW}@P0l%X_qN*cV%vL`v|+{#r) zFO)u>pGOBMkI76;IJ@QkxP>_Rd0~^S5MJ6sij)(5Uy`^@D#ZO??>;gt6L}WKqS)zD zT~`KYl^s&i8GD!8o;t8+9bjd%t+KHEa+q?d)hG!@AsMz1CZG57q?y!BW)Ae(2M6b>Uej{jfK8XK_4Q zD4c8A(^lM2UwMG0RG`9_i(el%!SaXc2kt5ZPmMEq=})imN^qw&P*NsBhPY*1At9yQ zc!(J%spp!C&-<=F@<)??ey4o1$&l{E$#n%C#bFEMop^ohS2rKO_hjEt1sUHGw`Vwa zi`db=WeoqoUWT`>XgMli2d1R^X~MAD!e}*rrpOpMPC4}?I4>|UC+&kw=%;al#b8G>(qtN-Hy5V zTHY%?g|qfPw=C77=3-G5n8qELrH4;Hp^iTCL2pM(vUfjY-l#}7_sfX0-IuZN(L03O z*G5y}H&i~7Kl~VnxPN2AJ#OX)Psgs#LH1uNYOotb((~n2N^L*a4Cv?}+kUjWPbyG# z)N^2mlH#IzEON%vQTAtfJy>aAZt@}-e-vXy&Z@O4Y@I818a>{#-Hbs=N@4QKXZ#iY zTisZ^r~Mcumy&)r>a+T+sGC_}?%gGz^td`t?c$9Ng{CL0M*$mwUmlhBu@VB2qIGRj zUT0Q0<-0{Y5CK*aJz2q|{L zdDFZ3lhKb`eAl{4TfAm!N3lIS_4d&sssHshqzf)wd&p4(X3(f2C;=Pam@8SA5~N2r ziI{L#8(ooEMIa>atZGn_N{px&QL#w0;jT}C?V1Wl9zhV7DD$%NTJ!U-Pqt^q_z0O7 zY-|;nDrxQlKm#*7C13@w9%YfLb$-ys-a^nRMdg+^N^xDydpg^DM{S&kgt$7SAXd{sgTm(E2N&B zV}G;FHHuI6s(WXe{cHbny;AuDO~-x36=~CFuS}0I4`)*o&jxlV)5VL)1_+Wl@kTn$m9Kg#SGZ4+l!zc!@sm27-1P6w( zg7SAaQCS=QrIz^eGt0~7o5@yuMLIgJ1J+N85;k*=`>zmYyf_=)rWWBEULpnEm$$yy z46cm)@U$G}^8vV41ONr+#X_$0-%xMVMgFUm`jtTZu^Qv|eUmrxbU<|IJ+^#R60za- zrK&IwH`HZ(RhV}8)8mU3YAm8zCUb+QAQQ$Gq)R-U7o%A!f1X1Q~*D* z157@6%c1M-1j5JI0Nig5gVr2B^WkskM5*%S^Dp`%UrPUcdu6_vQo!qXrj#tp-O^$h z;95W)wTw|BVsQL*A#o@>Wh!yVFgh?0`k?Fh`YK?oYh7)4MB~m?QUK1T;A^kzWvlT< zXvkV^LpnM_H^agRHvPU_*Ml(mYOA{6sd3%qVbvuvmDInZ>tZ5gs56UKkYL8*Dg5T! z2j56CCAuuB!=#AbNTp7)DZrFFs2sJ|F_>6+qBwWAL5?59_RwAT(&;XmSNFgf+ly z24>m{1({HhgdQ?a)(RdI07;A>tN^rDtXr8=cf;GDcc4x{u+{b^lhPGlpa{a)!gEMa z{W|^!NL;`|DpRgQhYA4lO)LpOkIbkNRE1stN4+D@2mq>2psoOT4-$h^*`co8*aA|a zPxqR#VqG5G90C1n(6C-X(12EZU_S*2JCeBuDOx`k2T_gzB;I))BR&C3lp#|mehsp= z{RBJzAg*8d@$f+NquathP$vc)L_uQ^dy7?E{jUEpEd=BspW4i7yC$M2gqmdZs%g^zQqMgA>~>^w^ObO9N+iXvU1;;&TF&0 zO?Mpe$sLcKKHYQaJF7{99M@(H+U*`p_^MKSMyO!%n77=?hX$N|5I^WA4_dmDh%g%W zyyb5VxXJFJ8)+m@?=IDZu5q-+HU2mNUWc@)U% zU%bc~pob(=7!ItohC^gR57TN)IV%W~+E9VnwSm{sOvqMC>2Dpa`Yi=59}afgSQ2I4 zgg$}PaSv>v@@IF7+TQZ&0A)+AN+ccUe>YE}Ssk_dSV`QU{yH6&xW@#oqZJlBBXjuy z+$0;>OTU6aTw7x)pNClCd#8y|NC5p~lcKKhy8`65vp))Fc(nu`xHU|_pD0H{;@S6C z+dsfzqdDM$OC;gB^NB;x19B^}z~>1KXd&YZuYf0mpG95$^1F0?42oNP`J;%CWP{xI za3zD>)%XQNia)Y4>lvsvLZEt$`kzdV4h6Lu81)97u(Lm%c=1bChnTAlt91Xo!LJ@c zi0vKrtOR7Y0{_F;-+sZe_HU>ZGl=q4MRKHhmb#af%>DgWR>Vz6#+VGGfDslA&F2mr zN};wE@bnh|D4rpcDL+DX-hg7G!kffgOg#$ZHIRq=m^Alm4Do&llu8JJWEUbmKT?k7 zg5vj~I0ukFXMQ8-IY5fuLx|r)V~w6;Crs>yULMHv{U6WF$nBcA6b@o=k^hZvMc%0q zhaqzZ8J~HHd(QThOcl=6fN(9Mo?{dw-@?%3&e}>lZLVLFU?w?f>FB)r&As-b!?3 z(QX2TG+qf{kg279+l<+3>JKd6V(-tG+=*_DfeZs^(RG|_Cr1<){hk$^nH1<~wtIB@ z%=3o%6^>WyhXWI~@m_~(YErKf$?;gaAp-$FAwG2iIw%+b?W+zCh9+6e`_09PBw&AM zI#Y(8Zuu$&h)JKsDgMs5BJD`wb|!!4W$lUd#l|PDNHT!_Us?h5Nw;W^kkg_u_jr6M zfNUFA2$KGNp!tHIhg`z5SD`OKHv)D-2cde&e`mlDEG`8cmU6 zhgLQ3TAG&!tgcjr1xeh)e?8k6{iG+?)y4Koc)`u8X~_ zbKgl@hKL*n5L;?Y)Fm3CowT%4aAQ}#5&;iW`%h>6KW;q&Gi?j2?J;OW85E)K`4S*U zft!Y!I+`$u*e5e5>t}`yGZ5q%&|UCiYwo|8jR41=T?z1;Q+g7D!jZ8K0~-6icz8sO zC-KBWa>W6QVjcLm`@dC0?(8B_OUGrRypMygW=I#L{%}@3Tu?tSiK{ku<#RzMt^e1rt8cFKhQVkRa%W2B&h$Cn}=% zu^^tZmvxwd9#XT@R{zlYJ?(L&c^rJ@LR+TZyz^I3uUf8#ie%uIYcxYZL%0(f9x1!F z9Q;;=^x7M8AP8&SMC;%V$_em=NfD&=^t};ni+!}#UzknXXFEr+)z|N=+NPm11h$z@ zoOzGzuMwvGC_@~Fg>Q$KsNj0!1bpotHgb$=3(QFh4hiAY8dcck`sDvgVv#j^6=1Ae zjgUF5cITC4YvwRCyDi=~PG8?jhK zFdN#WBg)NAj1HagidYY>q^}$I*TUCqg)^NRXk_}rN{nyg_M~kZk-tC3YJR;ncN3DZ z5yqo;L#s#$u0`^xlDgouV{KBA^vHeimu~=|j}h<(+A2Ow8}3kR&5E_OdI-#ol+;I& zI&9|zaUX|mE@#~sf*2{@#gZhBdQD6AvSyfuI9AYi?TztRwMV6e_eMK{^fnvF3qJc= zgD~tkyo&o{Ithi#kfIkV&WaEME2zZC9(h76Dr<-BFyo3MOZnhAnnCsyBn7QJR1WE7 zautvkUKdu*{VwvBsGpetf`JNVGAC_c!5XEqLC@jw|JqvKtJ}KXged=H8i#u1SbU{i zMy+%n*98hj+NIG#LP#t~4tDbo`I8 zRO1_J#`sEzVnvvglW_!uh{m!Y#A}PJf$a_?{E(Pt#H#FMND6Ichv$mCl9Hk0!hd}R zqyT+kAcXRDhoUAGpi5!fH}_Nczs(ZM+Hs--2v;eaB_Rc|phb>vKZ%*dYtPuQ(};mP z6?6~C#{8%Se~ta$cvbDeKfK4lOP~)ds=PYVeveJa+HD1gG>V@zI-IhCgo+tZlhFWu uM literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index a8b7a670c881b..c11839f0356c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -140,6 +140,18 @@ class NormalLaneChange : public LaneChangeBase bool get_lane_change_paths(LaneChangePaths & candidate_paths) const; + bool get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + + bool get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + bool check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index 9e6b9d229d2f2..c844b6b218d10 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -269,6 +269,7 @@ struct CommonData LanesPolygonPtr lanes_polygon_ptr; TransientData transient_data; PathWithLaneId current_lanes_path; + PathWithLaneId target_lanes_path; ModuleType lc_type; Direction direction; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 589f2f20ba258..eb07d2f0d3704 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -39,6 +39,20 @@ struct MetricsDebug double max_lane_changing_length; }; +struct FrenetStateDebug +{ + LaneChangePhaseMetrics prep_metric; + frenet_planner::SamplingParameter sampling_parameter; + double max_lane_changing_length; + + FrenetStateDebug( + LaneChangePhaseMetrics prep_metric, frenet_planner::SamplingParameter sampling_param, + const double max_len) + : prep_metric(prep_metric), sampling_parameter(sampling_param), max_lane_changing_length(max_len) + { + } +}; + struct Debug { std::string module_type; @@ -52,6 +66,7 @@ struct Debug lanelet::ConstLanelets target_lanes; lanelet::ConstLanelets target_backward_lanes; std::vector lane_change_metrics; + std::vector frenet_states; double collision_check_object_debug_lifetime{0.0}; double distance_to_end_of_current_lane{std::numeric_limits::max()}; double distance_to_lane_change_finished{std::numeric_limits::max()}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index b25dbc99189e8..f0adcb1d69b42 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -113,6 +113,13 @@ struct SafetyParameters CollisionCheckParameters collision_check{}; }; +struct FrenetPlannerParameters +{ + bool enable{true}; + double th_yaw_diff_deg{10.0}; + double th_curvature_smoothing{0.1}; +}; + struct TrajectoryParameters { double max_prepare_duration{4.0}; @@ -124,6 +131,7 @@ struct TrajectoryParameters double th_lane_changing_length_diff{0.5}; double min_lane_changing_velocity{5.6}; double lane_changing_decel_factor{0.5}; + double th_prepare_curvature{0.03}; int lon_acc_sampling_num{10}; int lat_acc_sampling_num{10}; LateralAccelerationMap lat_acc_map{}; @@ -151,6 +159,7 @@ struct Parameters CancelParameters cancel{}; DelayParameters delay{}; TerminalPathParameters terminal_path{}; + FrenetPlannerParameters frenet{}; // lane change parameters double backward_lane_length{200.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp index 0fa0a9d977a26..0fa2c6cc8dfbc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp @@ -19,19 +19,53 @@ #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include +#include #include namespace autoware::behavior_path_planner::lane_change { +enum class PathType { ConstantJerk = 0, FrenetPlanner }; + using autoware::behavior_path_planner::TurnSignalInfo; using tier4_planning_msgs::msg::PathWithLaneId; +struct TrajectoryGroup +{ + PathWithLaneId prepare; + PathWithLaneId target_lane_ref_path; + std::vector target_lane_ref_path_dist; + LaneChangePhaseMetrics prepare_metric; + frenet_planner::Trajectory lane_changing; + frenet_planner::FrenetState initial_state; + double max_lane_changing_length{0.0}; + + TrajectoryGroup() = default; + TrajectoryGroup( + PathWithLaneId prepare, PathWithLaneId target_lane_ref_path, + std::vector target_lane_ref_path_dist, LaneChangePhaseMetrics prepare_metric, + frenet_planner::Trajectory lane_changing, frenet_planner::FrenetState initial_state, + const double max_lane_changing_length) + : prepare(std::move(prepare)), + target_lane_ref_path(std::move(target_lane_ref_path)), + target_lane_ref_path_dist(std::move(target_lane_ref_path_dist)), + prepare_metric(prepare_metric), + lane_changing(std::move(lane_changing)), + initial_state(initial_state), + max_lane_changing_length(max_lane_changing_length) + { + } +}; + struct Path { + Info info; PathWithLaneId path; ShiftedPath shifted_path; - Info info; + TrajectoryGroup frenet_path; + PathType type = PathType::ConstantJerk; }; struct Status @@ -39,7 +73,6 @@ struct Status Path lane_change_path; bool is_safe{false}; bool is_valid_path{false}; - double start_distance{0.0}; }; } // namespace autoware::behavior_path_planner::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index 77ba8fe68a653..42586e7b1df92 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -11,7 +11,6 @@ // 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__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ @@ -26,6 +25,7 @@ namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::LaneChangePath; using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::TrajectoryGroup; /** * @brief Generates a prepare segment for a lane change maneuver. @@ -98,5 +98,65 @@ LaneChangePath construct_candidate_path( const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids); + +/** + * @brief Generates candidate trajectories in the Frenet frame for a lane change maneuver. + * + * This function computes a set of candidate trajectories for the ego vehicle in the Frenet frame, + * based on the provided metrics, target lane reference path, and preparation segments. It ensures + * that the generated trajectories adhere to specified constraints, such as lane boundaries and + * velocity limits, while optimizing for smoothness and curvature. + * + * @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient + * information. + * @param prev_module_path The previous module's path used as a base for preparation segments. + * @param prep_metric Metrics for the preparation phase, including path length and velocity. + * + * @return std::vector A vector of trajectory groups representing + * valid lane change candidates, each containing the prepare segment, target reference path, and + * Frenet trajectory. + */ +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics); + +/** + * @brief Constructs a lane change path candidate based on a Frenet trajectory group. + * + * This function generates a candidate lane change path by converting a Frenet trajectory group + * into a shifted path and combining it with a prepare segment. It validates the path's feasibility + * by ensuring yaw differences are within allowable thresholds and calculates lane change + * information, such as acceleration, velocity, and duration. + * + * @param trajectory_group A Frenet trajectory group containing the prepared path and Frenet + * trajectory data. + * @param common_data_ptr Shared pointer to CommonData providing parameters and constraints for lane + * changes. + * @param sorted_lane_ids A vector of sorted lane IDs used to update the lane IDs in the path. + * + * @return std::optional The constructed candidate lane change path if valid, or + * std::nullopt if the path is not feasible. + * + * @throws std::logic_error If the yaw difference exceeds the threshold, or other critical errors + * occur. + */ +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids); + +/** + * @brief Appends the target lane reference path to the candidate lane change path. + * + * This function extends the lane change candidate path by appending points from the + * target lane reference path beyond the lane change end position. The appending process + * is constrained by a curvature threshold to ensure smooth transitions and avoid sharp turns. + * + * @param frenet_candidate The candidate lane change path to which the target reference path is + * appended. This includes the lane change path and associated Frenet trajectory data. + * @param th_curvature_smoothing A threshold for the allowable curvature during the extension + * process. Points with curvature exceeding this threshold are excluded. + */ +void append_target_ref_to_candidate(LaneChangePath & frenet_candidate, const double th_curvature); } // namespace autoware::behavior_path_planner::utils::lane_change + #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 69362994dbbac..422c392cac462 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -24,6 +24,8 @@ #include #include +#include +#include #include #include @@ -56,6 +58,7 @@ using behavior_path_planner::lane_change::LCParamPtr; using behavior_path_planner::lane_change::ModuleType; using behavior_path_planner::lane_change::PathSafetyStatus; using behavior_path_planner::lane_change::TargetLaneLeadingObjects; +using behavior_path_planner::lane_change::TrajectoryGroup; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; @@ -69,9 +72,27 @@ bool is_mandatory_lane_change(const ModuleType lc_type); void set_prepare_velocity( PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity); -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids); +/** + * @brief Replaces the current lane IDs with a sorted set of IDs based on a predefined mapping. + * + * This function checks if the current lane IDs match the previously processed lane IDs. + * If they do, it returns the previously sorted IDs for efficiency. Otherwise, it matches + * the current lane IDs to the appropriate sorted IDs from the provided mapping and updates + * the cached values. + * + * @param current_lane_ids The current lane IDs to be replaced or verified. + * @param sorted_lane_ids A vector of sorted lane ID groups, each representing a predefined + * order of IDs for specific conditions. + * @param prev_lane_ids Reference to the previously processed lane IDs for caching purposes. + * @param prev_sorted_lane_ids Reference to the previously sorted lane IDs for caching purposes. + * + * @return std::vector The sorted lane IDs if a match is found, or the original + * `current_lane_ids` if no match exists. + */ +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids); std::vector> get_sorted_lane_ids(const CommonDataPtr & common_data_ptr); @@ -432,5 +453,24 @@ std::vector> convert_to_predicted_paths( * @return true if the pose is within the target or target neighbor polygons, false otherwise. */ bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose); + +/** + * @brief Converts a lane change frenet candidate into a predicted path for the ego vehicle. + * + * This function generates a predicted path based on the provided Frenet candidate, + * simulating the vehicle's trajectory during the preparation and lane-changing phases. + * It interpolates poses and velocities over the duration of the prediction, considering + * the ego vehicle's initial conditions and the candidate's trajectory data. + * + * @param common_data_ptr Shared pointer to CommonData containing parameters and ego vehicle state. + * @param frenet_candidate A Frenet trajectory group representing the lane change candidate. + * @param deceleration_sampling_num Unused parameter for deceleration sampling count. + * + * @return std::vector The predicted path as a series of stamped poses + * with associated velocities over the prediction time. + */ +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml index fad98ecf8f8e1..cf7600556080e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common + autoware_frenet_planner autoware_motion_utils autoware_rtc_interface autoware_universe_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index ec000b8fee97c..06a9d505f90ad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -63,6 +63,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("trajectory.min_lane_changing_velocity")); p.trajectory.lane_changing_decel_factor = getOrDeclareParameter(*node, parameter("trajectory.lane_changing_decel_factor")); + p.trajectory.th_prepare_curvature = + getOrDeclareParameter(*node, parameter("trajectory.th_prepare_curvature")); p.trajectory.lon_acc_sampling_num = getOrDeclareParameter(*node, parameter("trajectory.lon_acc_sampling_num")); p.trajectory.lat_acc_sampling_num = @@ -213,6 +215,12 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s p.delay.th_parked_vehicle_shift_ratio = getOrDeclareParameter( *node, parameter("delay_lane_change.th_parked_vehicle_shift_ratio")); + // trajectory generation near terminal using frenet planner + p.frenet.enable = getOrDeclareParameter(*node, parameter("frenet.enable")); + p.frenet.th_yaw_diff_deg = getOrDeclareParameter(*node, parameter("frenet.th_yaw_diff")); + p.frenet.th_curvature_smoothing = + getOrDeclareParameter(*node, parameter("frenet.th_curvature_smoothing")); + // lane change cancel p.cancel.enable_on_prepare_phase = getOrDeclareParameter(*node, parameter("cancel.enable_on_prepare_phase")); @@ -338,6 +346,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.max_longitudinal_acc); updateParam( parameters, ns + "lane_changing_decel_factor", p->trajectory.lane_changing_decel_factor); + updateParam( + parameters, ns + "th_prepare_curvature", p->trajectory.th_prepare_curvature); int longitudinal_acc_sampling_num = 0; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { @@ -356,6 +366,14 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.th_lane_changing_length_diff); } + { + const std::string ns = "lane_change.frenet."; + updateParam(parameters, ns + "enable", p->frenet.enable); + updateParam(parameters, ns + "th_yaw_diff", p->frenet.th_yaw_diff_deg); + updateParam( + parameters, ns + "th_curvature_smoothing", p->frenet.th_curvature_smoothing); + } + { const std::string ns = "lane_change.safety_check.lane_expansion."; updateParam(parameters, ns + "left_offset", p->safety.lane_expansion_left_offset); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 88f58debb886a..7748795851865 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -28,7 +28,10 @@ #include #include #include +#include #include +#include +#include #include #include #include @@ -36,8 +39,11 @@ #include #include +#include + #include #include +#include #include #include @@ -104,6 +110,9 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->current_lanes_path = route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->target_lanes_path = + route_handler_ptr->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->lanes_ptr->target_neighbor = utils::lane_change::get_target_neighbor_lanes( *route_handler_ptr, current_lanes, common_data_ptr_->lc_type); @@ -232,8 +241,6 @@ void NormalLaneChange::updateLaneChangeStatus() // Update status status_.is_valid_path = found_valid_path; status_.is_safe = found_safe_path; - - status_.start_distance = common_data_ptr_->transient_data.target_lanes_ego_arc.length; status_.lane_change_path.path.header = getRouteHeader(); } @@ -1124,15 +1131,92 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } const auto & current_lanes = get_current_lanes(); - const auto & target_lanes = get_target_lanes(); - const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); const auto target_objects = get_target_objects(filtered_objects_, current_lanes); const auto prepare_phase_metrics = get_prepare_metrics(); + const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); + if ( + common_data_ptr_->lc_param_ptr->frenet.enable && + common_data_ptr_->transient_data.is_ego_near_current_terminal_start) { + return get_path_using_frenet( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); + } + + return get_path_using_path_shifter( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); +} + +bool NormalLaneChange::get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + stop_watch_.tic("frenet_candidates"); + constexpr auto found_safe_path = true; + const auto frenet_candidates = utils::lane_change::generate_frenet_candidates( + common_data_ptr_, prev_module_output_.path, prepare_metrics); + RCLCPP_DEBUG( + logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + + candidate_paths.reserve(frenet_candidates.size()); + lane_change_debug_.frenet_states.clear(); + lane_change_debug_.frenet_states.reserve(frenet_candidates.size()); + for (const auto & frenet_candidate : frenet_candidates) { + lane_change_debug_.frenet_states.emplace_back( + frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter, + frenet_candidate.max_lane_changing_length); + + std::optional candidate_path_opt; + try { + candidate_path_opt = + utils::lane_change::get_candidate_path(frenet_candidate, common_data_ptr_, sorted_lane_ids); + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + if (!candidate_path_opt) { + continue; + } + + try { + if (check_candidate_path_safety(*candidate_path_opt, target_objects)) { + RCLCPP_DEBUG( + logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]", + frenet_candidates.size(), stop_watch_.toc("frenet_candidates")); + utils::lane_change::append_target_ref_to_candidate( + *candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing); + candidate_paths.push_back(*candidate_path_opt); + return found_safe_path; + } + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + // appending all paths affect performance + if (candidate_paths.empty()) { + candidate_paths.push_back(*candidate_path_opt); + } + } + + RCLCPP_DEBUG( + logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + return !found_safe_path; +} + +bool NormalLaneChange::get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + const auto & target_lanes = get_target_lanes(); candidate_paths.reserve( - prepare_phase_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); + prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time; const auto dist_to_next_regulatory_element = @@ -1151,7 +1235,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff; }; - for (const auto & prep_metric : prepare_phase_metrics) { + for (const auto & prep_metric : prepare_metrics) { const auto debug_print = [&](const std::string & s) { RCLCPP_DEBUG( logger_, "%s | prep_time: %.5f | lon_acc: %.5f | prep_len: %.5f", s.c_str(), @@ -1195,7 +1279,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { - debug_metrics.lc_metrics.push_back({lc_metric, -1}); + debug_metrics.lc_metrics.emplace_back(lc_metric, -1); const auto debug_print_lat = [&](const std::string & s) { RCLCPP_DEBUG( @@ -1218,7 +1302,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } candidate_paths.push_back(candidate_path); - debug_metrics.lc_metrics.back().second = candidate_paths.size() - 1; + debug_metrics.lc_metrics.back().second = static_cast(candidate_paths.size()) - 1; try { if (check_candidate_path_safety(candidate_path, target_objects)) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index ef899cceea0d4..bf0af0d133dc7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -73,6 +73,34 @@ MarkerArray showAllValidLaneChangePath( marker.points.push_back(point.point.pose.position); } + const auto & info = lc_path.info; + auto text_marker = createDefaultMarker( + "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); + const auto prep_idx = points.size() / 4; + text_marker.pose = points.at(prep_idx).point.pose; + text_marker.pose.position.z += 2.0; + text_marker.text = fmt::format( + "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | t: {time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("vel", info.velocity.prepare), + fmt::arg("lon_acc", info.longitudinal_acceleration.prepare), + fmt::arg("time", info.duration.prepare), fmt::arg("length", info.length.prepare)); + marker_array.markers.push_back(text_marker); + + const auto lc_idx = points.size() / 2; + text_marker.id = ++id; + text_marker.pose = points.at(lc_idx).point.pose; + text_marker.text = fmt::format( + "type: {type} | vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | lat_acc: " + "{lat_acc:.3f}[m/s2] | t: " + "{time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("type", magic_enum::enum_name(lc_path.type)), + fmt::arg("vel", info.velocity.lane_changing), + fmt::arg("lon_acc", info.longitudinal_acceleration.lane_changing), + fmt::arg("lat_acc", info.lateral_acceleration), fmt::arg("time", info.duration.lane_changing), + fmt::arg("length", info.length.lane_changing)); + marker_array.markers.push_back(text_marker); + marker_array.markers.push_back(marker); } return marker_array; @@ -171,43 +199,78 @@ MarkerArray ShowLaneChangeMetricsInfo( const Debug & debug_data, const geometry_msgs::msg::Pose & pose) { MarkerArray marker_array; - if (debug_data.lane_change_metrics.empty()) { - return marker_array; - } auto text_marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "sampling_metrics", 0, Marker::TEXT_VIEW_FACING, createMarkerScale(0.6, 0.6, 0.6), colors::yellow()); text_marker.pose = autoware::universe_utils::calcOffsetPose(pose, 10.0, 15.0, 0.0); - text_marker.text = - fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + - fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + - fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + - fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); - for (const auto & metrics : debug_data.lane_change_metrics) { - text_marker.text += fmt::format("{:-<190}\n", ""); - const auto & p_m = metrics.prep_metric; - text_marker.text += - fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + - fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + - fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + - fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); - text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); - for (const auto & lc_m : metrics.lc_metrics) { - const auto & metric = lc_m.first; - const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); - text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + - fmt::format("{:^21.3f}", metric.actual_lon_accel) + - fmt::format("{:^12.3f}", metric.velocity) + - fmt::format("{:^15.3f}", metric.duration) + - fmt::format("{:^15.3f}", metric.length) + - fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + - fmt::format("{:^15}\n", path_index); + if (!debug_data.lane_change_metrics.empty()) { + text_marker.text = + fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + + fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); + for (const auto & metrics : debug_data.lane_change_metrics) { + text_marker.text += fmt::format("{:-<190}\n", ""); + const auto & p_m = metrics.prep_metric; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + + fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + + fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + + fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); + text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); + for (const auto & lc_m : metrics.lc_metrics) { + const auto & metric = lc_m.first; + const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); + text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + + fmt::format("{:^21.3f}", metric.actual_lon_accel) + + fmt::format("{:^12.3f}", metric.velocity) + + fmt::format("{:^15.3f}", metric.duration) + + fmt::format("{:^15.3f}", metric.length) + + fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + + fmt::format("{:^15}\n", path_index); + } } + marker_array.markers.push_back(text_marker); + } + + if (!debug_data.frenet_states.empty()) { + text_marker.text = fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lon_accel[m/s2]") + + fmt::format("{:^17}|", "lon_vel[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^17}|", "lat_accel[m/s2]") + + fmt::format("{:^15}|", "lat_vel[m/s2]") + fmt::format("{:^15}|", "s[m]") + + fmt::format("{:^15}|", "d[m]") + fmt::format("{:^20}\n", "max_length_th[m]"); + for (const auto & metrics : debug_data.frenet_states) { + text_marker.text += fmt::format("{:-<250}\n", ""); + const auto & p_m = metrics.prep_metric; + const auto max_len = metrics.max_lane_changing_length; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^13.3f}", p_m.actual_lon_accel) + + fmt::format("{:^15.3f}", p_m.velocity) + fmt::format("{:^15.3f}", p_m.duration) + + fmt::format("{:^12.3f}", p_m.length) + + fmt::format("{:^13}", "") + // Empty string for lat_accel + fmt::format("{:^13}", "") + // Empty string for lat_vel + fmt::format("{:^15}", "") + // Empty string for s + fmt::format("{:^15}", "") + // Empty string for d // Empty string for d + fmt::format("{:^20.3f}\n", max_len); // Empty string for max_length_t + const auto & lc_m = metrics.sampling_parameter.target_state; // Assuming lc_metric exists + const auto duration = metrics.sampling_parameter.target_duration; + text_marker.text += + fmt::format("{:<17}", "frenet_state:") + + fmt::format("{:^15.3f}", lc_m.longitudinal_acceleration) + + fmt::format("{:^13.3f}", lc_m.longitudinal_velocity) + fmt::format("{:^17.3f}", duration) + + fmt::format("{:^10.3f}", lc_m.position.s) + + fmt::format("{:^19.3f}", lc_m.lateral_acceleration) + + fmt::format("{:^10.3f}", lc_m.lateral_velocity) + + fmt::format("{:^18.3f}", lc_m.position.s) + fmt::format("{:^15.3f}", lc_m.position.d) + + fmt::format("{:^16.3f}\n", max_len); // Empty string for max_length_t + } + + marker_array.markers.push_back(text_marker); } - marker_array.markers.push_back(text_marker); return marker_array; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp index 44ee1624f0f51..df45da3f08fa1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp @@ -15,17 +15,22 @@ #include "autoware/behavior_path_lane_change_module/utils/path.hpp" #include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include #include +#include #include +#include #include #include #include +#include + #include #include #include @@ -42,8 +47,22 @@ using autoware::behavior_path_planner::lane_change::LCParamPtr; using autoware::behavior_path_planner::LaneChangePhaseMetrics; using autoware::behavior_path_planner::ShiftLine; +using autoware::behavior_path_planner::lane_change::TrajectoryGroup; +using autoware::frenet_planner::FrenetState; +using autoware::frenet_planner::SamplingParameters; +using autoware::route_handler::Direction; +using autoware::sampler_common::FrenetPoint; +using autoware::sampler_common::transform::Spline2D; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using geometry_msgs::msg::Pose; +template +T sign(const Direction direction) +{ + return static_cast(direction == Direction::LEFT ? 1.0 : -1.0); +} + double calc_resample_interval( const double lane_changing_length, const double lane_changing_velocity) { @@ -53,7 +72,7 @@ double calc_resample_interval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } -PathWithLaneId get_reference_path_from_target_Lane( +PathWithLaneId get_reference_path_from_target_lane( const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, const double lane_changing_length, const double resample_interval) { @@ -146,11 +165,197 @@ std::optional exceed_yaw_threshold( } return std::nullopt; } + +Spline2D init_reference_spline(const std::vector & target_lanes_ref_path) +{ + std::vector xs; + std::vector ys; + xs.reserve(target_lanes_ref_path.size()); + ys.reserve(target_lanes_ref_path.size()); + for (const auto & p : target_lanes_ref_path) { + xs.push_back(p.point.pose.position.x); + ys.push_back(p.point.pose.position.y); + } + + return {xs, ys}; +} + +FrenetState init_frenet_state( + const FrenetPoint & start_position, const LaneChangePhaseMetrics & prepare_metrics) +{ + FrenetState initial_state; + initial_state.position = start_position; + initial_state.longitudinal_velocity = prepare_metrics.velocity; + initial_state.lateral_velocity = + 0.0; // TODO(Maxime): this can be sampled if we want but it would impact the LC duration + initial_state.longitudinal_acceleration = prepare_metrics.sampled_lon_accel; + initial_state.lateral_acceleration = prepare_metrics.lat_accel; + return initial_state; +} + +std::optional init_sampling_parameters( + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prepare_metrics, + const FrenetState & initial_state, const Spline2D & ref_spline, const Pose & lc_start_pose) +{ + const auto & trajectory = common_data_ptr->lc_param_ptr->trajectory; + const auto min_lc_vel = trajectory.min_lane_changing_velocity; + const auto [min_lateral_acc, max_lateral_acc] = + trajectory.lat_acc_map.find(std::max(min_lc_vel, prepare_metrics.velocity)); + const auto duration = autoware::motion_utils::calc_shift_time_from_jerk( + std::abs(initial_state.position.d), trajectory.lateral_jerk, max_lateral_acc); + const auto final_velocity = + std::max(min_lc_vel, prepare_metrics.velocity + prepare_metrics.sampled_lon_accel * duration); + const auto lc_length = duration * (prepare_metrics.velocity + final_velocity) * 0.5; + const auto target_s = initial_state.position.s + lc_length; + const auto initial_yaw = tf2::getYaw(lc_start_pose.orientation); + const auto target_lat_vel = + (1.0 - ref_spline.curvature(target_s + 1e-3) * initial_state.position.d) * + std::tan(initial_yaw - ref_spline.yaw(target_s)); + + if (std::isnan(target_lat_vel)) { + return std::nullopt; + } + + SamplingParameters sampling_parameters; + const auto & safety = common_data_ptr->lc_param_ptr->safety; + sampling_parameters.resolution = safety.collision_check.prediction_time_resolution; + sampling_parameters.parameters.emplace_back(); + sampling_parameters.parameters.back().target_duration = duration; + sampling_parameters.parameters.back().target_state.position = {target_s, 0.0}; + // TODO(Maxime): not sure if we should use curvature at initial or target s + sampling_parameters.parameters.back().target_state.lateral_velocity = + sign(common_data_ptr->direction) * target_lat_vel; + sampling_parameters.parameters.back().target_state.lateral_acceleration = 0.0; + sampling_parameters.parameters.back().target_state.longitudinal_velocity = final_velocity; + sampling_parameters.parameters.back().target_state.longitudinal_acceleration = + prepare_metrics.sampled_lon_accel; + return sampling_parameters; +} + +std::vector calc_curvatures( + const std::vector & points, const Pose & current_pose) +{ + const auto nearest_segment_idx = + autoware::motion_utils::findNearestSegmentIndex(points, current_pose.position); + + // Ignore all path points behind ego vehicle. + if (points.size() <= nearest_segment_idx + 2) { + return {}; + } + + std::vector curvatures; + curvatures.reserve(points.size() - nearest_segment_idx + 2); + for (const auto & [p1, p2, p3] : ranges::views::zip( + points | ranges::views::drop(nearest_segment_idx), + points | ranges::views::drop(nearest_segment_idx + 1), + points | ranges::views::drop(nearest_segment_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(p1); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + + curvatures.push_back(autoware::universe_utils::calcCurvature(point1, point2, point3)); + } + + return curvatures; +} + +double calc_average_curvature(const std::vector & curvatures) +{ + const auto filter_zeros = [](const auto & k) { return k != 0.0; }; + auto filtered_k = curvatures | ranges::views::filter(filter_zeros); + if (filtered_k.empty()) { + return 0.0; + } + const auto sums_of_curvatures = [](float sum, const double k) { return sum + std::abs(k); }; + const auto sum_of_k = ranges::accumulate(filtered_k, 0.0, sums_of_curvatures); + const auto count_k = static_cast(ranges::distance(filtered_k)); + return sum_of_k / count_k; +} + +LineString2d get_linestring_bound(const lanelet::ConstLanelets & lanes, const Direction direction) +{ + LineString2d line_string; + const auto & get_bound = [&](const lanelet::ConstLanelet & lane) { + return (direction == Direction::LEFT) ? lane.leftBound2d() : lane.rightBound2d(); + }; + + const auto reserve_size = ranges::accumulate( + lanes, 0UL, + [&](auto sum, const lanelet::ConstLanelet & lane) { return sum + get_bound(lane).size(); }); + line_string.reserve(reserve_size); + for (const auto & lane : lanes) { + ranges::for_each(get_bound(lane), [&line_string](const auto & point) { + boost::geometry::append(line_string, Point2d(point.x(), point.y())); + }); + } + return line_string; +} + +Point2d shift_point(const Point2d & p1, const Point2d & p2, const double offset) +{ + // Calculate the perpendicular vector + double dx = p2.x() - p1.x(); + double dy = p2.y() - p1.y(); + double length = std::sqrt(dx * dx + dy * dy); + + // Normalize and find the perpendicular direction + double nx = -dy / length; + double ny = dx / length; + + return {p1.x() + nx * offset, p1.y() + ny * offset}; +} + +bool check_out_of_bound_paths( + const CommonDataPtr & common_data_ptr, const std::vector & lane_changing_poses, + const LineString2d & lane_boundary, const Direction direction) +{ + const auto distance = (0.5 * common_data_ptr->bpp_param_ptr->vehicle_width + 0.1); + const auto offset = sign(direction) * distance; // invert direction + if (lane_changing_poses.size() <= 2) { + return true; // Remove candidates with insufficient poses + } + + LineString2d path_ls; + path_ls.reserve(lane_changing_poses.size()); + + const auto segments = lane_changing_poses | ranges::views::sliding(2); + ranges::for_each(segments | ranges::views::drop(1), [&](const auto & segment) { + const auto & p1 = segment[0].position; + const auto & p2 = segment[1].position; + boost::geometry::append(path_ls, shift_point({p2.x, p2.y}, {p1.x, p1.y}, offset)); + }); + + return boost::geometry::disjoint(path_ls, lane_boundary); // Remove if disjoint +} + +double calc_limit(const CommonDataPtr & common_data_ptr, const Pose & lc_end_pose) +{ + const auto dist_to_target_end = std::invoke([&]() { + if (common_data_ptr->lanes_ptr->target_lane_in_goal_section) { + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->route_handler_ptr->getGoalPose().position); + } + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->target_lanes_path.points.back().point.pose.position); + }); + + // v2 = u2 + 2ad + // u = sqrt(2ad) + return std::clamp( + std::sqrt( + std::abs(2.0 * common_data_ptr->bpp_param_ptr->min_acc * std::max(dist_to_target_end, 0.0))), + common_data_ptr->lc_param_ptr->trajectory.min_lane_changing_velocity, + common_data_ptr->bpp_param_ptr->max_vel); +} + }; // namespace namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::PathType; bool get_prepare_segment( const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, @@ -187,7 +392,17 @@ bool get_prepare_segment( throw std::logic_error("lane change start is behind target lanelet!"); } - return true; + const auto curvatures = calc_curvatures(prepare_segment.points, common_data_ptr->get_ego_pose()); + + // curvatures may be empty if ego is near the terminal start of the path. + if (curvatures.empty()) { + return true; + } + + const auto average_curvature = calc_average_curvature(curvatures); + + RCLCPP_DEBUG(get_logger(), "average curvature: %.3f", average_curvature); + return average_curvature <= common_data_ptr->lc_param_ptr->trajectory.th_prepare_curvature; } LaneChangePath get_candidate_path( @@ -205,7 +420,7 @@ LaneChangePath get_candidate_path( } const auto & lc_start_pose = prep_segment.points.back().point.pose; - const auto target_lane_reference_path = get_reference_path_from_target_Lane( + const auto target_lane_reference_path = get_reference_path_from_target_lane( common_data_ptr, lc_start_pose, lc_metric.length, resample_interval); if (target_lane_reference_path.points.empty()) { @@ -259,10 +474,14 @@ LaneChangePath construct_candidate_path( throw std::logic_error("Lane change end idx not found on target path."); } + std::vector prev_ids; + std::vector prev_sorted_ids; for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { auto & point = shifted_path.path.points.at(i); if (i < *lc_end_idx_opt) { - point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); + const auto & current_ids = point.lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); point.point.longitudinal_velocity_mps = std::min( point.point.longitudinal_velocity_mps, static_cast(terminal_lane_changing_velocity)); continue; @@ -286,7 +505,251 @@ LaneChangePath construct_candidate_path( candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); candidate_path.shifted_path = shifted_path; candidate_path.info = lane_change_info; + candidate_path.type = PathType::ConstantJerk; return candidate_path; } + +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics) +{ + std::vector trajectory_groups; + universe_utils::StopWatch sw; + + const auto & transient_data = common_data_ptr->transient_data; + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto direction = common_data_ptr->direction; + const auto current_lane_boundary = get_linestring_bound(current_lanes, direction); + + for (const auto & metric : prep_metrics) { + PathWithLaneId prepare_segment; + try { + if (!utils::lane_change::get_prepare_segment( + common_data_ptr, prev_module_path, metric.length, prepare_segment)) { + RCLCPP_DEBUG(get_logger(), "Reject: failed to get valid prepare segment!"); + continue; + } + } catch (const std::exception & e) { + RCLCPP_WARN(get_logger(), "%s", e.what()); + break; + } + const auto lc_start_pose = prepare_segment.points.back().point.pose; + + const auto dist_to_end_from_lc_start = + calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr, target_lanes, lc_start_pose) - + common_data_ptr->lc_param_ptr->lane_change_finish_judge_buffer; + const auto max_lc_len = transient_data.lane_changing_length.max; + const auto max_lane_changing_length = std::min(dist_to_end_from_lc_start, max_lc_len); + + constexpr auto resample_interval = 0.5; + const auto target_lane_reference_path = get_reference_path_from_target_lane( + common_data_ptr, lc_start_pose, max_lane_changing_length, resample_interval); + if (target_lane_reference_path.points.empty()) { + continue; + } + + std::vector target_ref_path_sums{0.0}; + target_ref_path_sums.reserve(target_lane_reference_path.points.size() - 1); + double ref_s = 0.0; + for (auto it = target_lane_reference_path.points.begin(); + std::next(it) != target_lane_reference_path.points.end(); ++it) { + ref_s += universe_utils::calcDistance2d(*it, *std::next(it)); + target_ref_path_sums.push_back(ref_s); + } + + const auto reference_spline = init_reference_spline(target_lane_reference_path.points); + + const auto initial_state = init_frenet_state( + reference_spline.frenet({lc_start_pose.position.x, lc_start_pose.position.y}), metric); + + RCLCPP_DEBUG( + get_logger(), "Initial state [s=%2.2f, d=%2.2f, s'=%2.2f, d'=%2.2f, s''=%2.2f, d''=%2.2f]", + initial_state.position.s, initial_state.position.d, initial_state.longitudinal_velocity, + initial_state.lateral_velocity, initial_state.longitudinal_acceleration, + initial_state.lateral_acceleration); + + const auto sampling_parameters_opt = init_sampling_parameters( + common_data_ptr, metric, initial_state, reference_spline, lc_start_pose); + + if (!sampling_parameters_opt) { + continue; + } + + auto frenet_trajectories = frenet_planner::generateTrajectories( + reference_spline, initial_state, *sampling_parameters_opt); + + trajectory_groups.reserve(trajectory_groups.size() + frenet_trajectories.size()); + for (const auto & traj : frenet_trajectories) { + if (!trajectory_groups.empty()) { + const auto diff = std::abs( + traj.frenet_points.back().s - + trajectory_groups.back().lane_changing.frenet_points.back().s); + if (diff < common_data_ptr->lc_param_ptr->trajectory.th_lane_changing_length_diff) { + continue; + } + } + + const auto out_of_bound = + check_out_of_bound_paths(common_data_ptr, traj.poses, current_lane_boundary, direction); + + if (out_of_bound) { + continue; + } + + trajectory_groups.emplace_back( + prepare_segment, target_lane_reference_path, target_ref_path_sums, metric, traj, + initial_state, max_lane_changing_length); + } + } + + const auto limit_vel = [&](TrajectoryGroup & group) { + const auto max_vel = calc_limit(common_data_ptr, group.lane_changing.poses.back()); + for (auto & vel : group.lane_changing.longitudinal_velocities) { + vel = std::clamp(vel, 0.0, max_vel); + } + }; + + ranges::for_each(trajectory_groups, limit_vel); + + ranges::sort(trajectory_groups, [&](const auto & p1, const auto & p2) { + return calc_average_curvature(p1.lane_changing.curvatures) < + calc_average_curvature(p2.lane_changing.curvatures); + }); + + return trajectory_groups; +} + +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids) +{ + if (trajectory_group.lane_changing.frenet_points.empty()) { + return std::nullopt; + } + + ShiftedPath shifted_path; + std::vector prev_ids; + std::vector prev_sorted_ids; + const auto & lane_changing_candidate = trajectory_group.lane_changing; + const auto & target_lane_ref_path = trajectory_group.target_lane_ref_path; + const auto & prepare_segment = trajectory_group.prepare; + const auto & prepare_metric = trajectory_group.prepare_metric; + const auto & initial_state = trajectory_group.initial_state; + const auto & target_ref_sums = trajectory_group.target_lane_ref_path_dist; + auto zipped_candidates = ranges::views::zip( + lane_changing_candidate.poses, lane_changing_candidate.frenet_points, + lane_changing_candidate.longitudinal_velocities, lane_changing_candidate.lateral_velocities, + lane_changing_candidate.curvatures); + + shifted_path.path.points.reserve(zipped_candidates.size()); + shifted_path.shift_length.reserve(zipped_candidates.size()); + for (const auto & [pose, frenet_point, longitudinal_velocity, lateral_velocity, curvature] : + zipped_candidates) { + // Find the reference index + const auto & s = frenet_point.s; + auto ref_i_itr = std::find_if( + target_ref_sums.begin(), target_ref_sums.end(), + [s](const double ref_s) { return ref_s > s; }); + auto ref_i = std::distance(target_ref_sums.begin(), ref_i_itr); + + PathPointWithLaneId point; + point.point.pose = pose; + point.point.longitudinal_velocity_mps = static_cast(longitudinal_velocity); + point.point.lateral_velocity_mps = static_cast(lateral_velocity); + point.point.heading_rate_rps = static_cast(curvature); + point.point.pose.position.z = target_lane_ref_path.points[ref_i].point.pose.position.z; + const auto & current_ids = target_lane_ref_path.points[ref_i].lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); + + // Add to shifted path + shifted_path.shift_length.push_back(frenet_point.d); + shifted_path.path.points.push_back(point); + } + + if (shifted_path.path.points.empty()) { + return std::nullopt; + } + + for (auto & point : shifted_path.path.points) { + point.point.longitudinal_velocity_mps = std::min( + point.point.longitudinal_velocity_mps, + static_cast(shifted_path.path.points.back().point.longitudinal_velocity_mps)); + } + + const auto th_yaw_diff_deg = common_data_ptr->lc_param_ptr->frenet.th_yaw_diff_deg; + if ( + const auto yaw_diff_opt = exceed_yaw_threshold( + prepare_segment, shifted_path.path, autoware::universe_utils::deg2rad(th_yaw_diff_deg))) { + const auto yaw_diff_deg = autoware::universe_utils::rad2deg(yaw_diff_opt.value()); + const auto err_msg = fmt::format( + "Excessive yaw difference {yaw_diff:2.2f}[deg]. The threshold is {th_yaw_diff:2.2f}[deg].", + fmt::arg("yaw_diff", yaw_diff_deg), fmt::arg("th_yaw_diff", th_yaw_diff_deg)); + throw std::logic_error(err_msg); + } + + LaneChangeInfo info; + info.longitudinal_acceleration = { + prepare_metric.actual_lon_accel, lane_changing_candidate.longitudinal_accelerations.front()}; + info.velocity = {prepare_metric.velocity, initial_state.longitudinal_velocity}; + info.duration = { + prepare_metric.duration, lane_changing_candidate.sampling_parameter.target_duration}; + info.length = {prepare_metric.length, lane_changing_candidate.lengths.back()}; + info.lane_changing_start = prepare_segment.points.back().point.pose; + info.lane_changing_end = lane_changing_candidate.poses.back(); + + ShiftLine sl; + + sl.start = lane_changing_candidate.poses.front(); + sl.end = lane_changing_candidate.poses.back(); + sl.start_shift_length = 0.0; + sl.end_shift_length = initial_state.position.d; + sl.start_idx = 0UL; + sl.end_idx = shifted_path.shift_length.size() - 1; + + info.shift_line = sl; + info.terminal_lane_changing_velocity = lane_changing_candidate.longitudinal_velocities.back(); + info.lateral_acceleration = lane_changing_candidate.lateral_accelerations.front(); + + LaneChangePath candidate_path; + candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); + candidate_path.info = info; + candidate_path.shifted_path = shifted_path; + candidate_path.frenet_path = trajectory_group; + candidate_path.type = PathType::FrenetPlanner; + + return candidate_path; +} + +void append_target_ref_to_candidate( + LaneChangePath & frenet_candidate, const double th_curvature_smoothing) +{ + const auto & target_lane_ref_path = frenet_candidate.frenet_path.target_lane_ref_path.points; + const auto & lc_end_pose = frenet_candidate.info.lane_changing_end; + const auto lc_end_idx = + motion_utils::findNearestIndex(target_lane_ref_path, lc_end_pose.position); + auto & candidate_path = frenet_candidate.path.points; + if (target_lane_ref_path.size() <= lc_end_idx + 2) { + return; + } + const auto add_size = target_lane_ref_path.size() - (lc_end_idx + 1); + candidate_path.reserve(candidate_path.size() + add_size); + const auto & points = target_lane_ref_path; + for (const auto & [p2, p3] : ranges::views::zip( + points | ranges::views::drop(lc_end_idx + 1), + points | ranges::views::drop(lc_end_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(candidate_path.back().point.pose); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + const auto curvature = + std::abs(autoware::universe_utils::calcCurvature(point1, point2, point3)); + if (curvature < th_curvature_smoothing) { + candidate_path.push_back(p2); + } + } + candidate_path.push_back(target_lane_ref_path.back()); +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 9360435891632..9002270185847 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -24,12 +24,18 @@ #include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" +// for the geometry types +#include +#include +// for the svg mapper #include #include #include #include #include #include +#include +#include #include #include #include @@ -40,9 +46,10 @@ #include #include -#include - +#include #include +#include +#include #include #include @@ -64,9 +71,11 @@ namespace autoware::behavior_path_planner::utils::lane_change { using autoware::route_handler::RouteHandler; using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; +using behavior_path_planner::lane_change::PathType; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -382,18 +391,26 @@ std::vector> get_sorted_lane_ids(const CommonDataPtr & comm return sorted_lane_ids; } -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids) +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids) { - for (const auto original_id : original_lane_ids) { + if (current_lane_ids == prev_lane_ids) { + return prev_sorted_lane_ids; + } + + for (const auto original_id : current_lane_ids) { for (const auto & sorted_id : sorted_lane_ids) { if (std::find(sorted_id.cbegin(), sorted_id.cend(), original_id) != sorted_id.cend()) { - return sorted_id; + prev_lane_ids = current_lane_ids; + prev_sorted_lane_ids = sorted_id; + return prev_sorted_lane_ids; } } } - return original_lane_ids; + + return current_lane_ids; } CandidateOutput assignToCandidate( @@ -475,6 +492,7 @@ std::vector convert_to_predicted_path( 0.5 * lane_changing_acceleration * delta_t * delta_t + offset; const auto pose = autoware::motion_utils::calcInterpolatedPose( path.points, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); } @@ -1127,6 +1145,10 @@ std::vector> convert_to_predicted_paths( const auto acc_resolution = (min_acc - lane_changing_acc) / static_cast(sampling_num); const auto ego_predicted_path = [&](size_t n) { + if (lane_change_path.type == PathType::FrenetPlanner) { + return convert_to_predicted_path( + common_data_ptr, lane_change_path.frenet_path, deceleration_sampling_num); + } auto acc = lane_changing_acc + static_cast(n) * acc_resolution; return utils::lane_change::convert_to_predicted_path(common_data_ptr, lane_change_path, acc); }; @@ -1135,6 +1157,48 @@ std::vector> convert_to_predicted_paths( ranges::to(); } +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num) +{ + const auto initial_velocity = common_data_ptr->get_ego_speed(); + const auto prepare_time = frenet_candidate.prepare_metric.duration; + const auto resolution = + common_data_ptr->lc_param_ptr->safety.collision_check.prediction_time_resolution; + const auto prepare_acc = frenet_candidate.prepare_metric.sampled_lon_accel; + std::vector predicted_path; + const auto & path = frenet_candidate.prepare.points; + const auto & vehicle_pose = common_data_ptr->get_ego_pose(); + const auto & bpp_param_ptr = common_data_ptr->bpp_param_ptr; + const auto nearest_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path, vehicle_pose, bpp_param_ptr->ego_nearest_dist_threshold, + bpp_param_ptr->ego_nearest_yaw_threshold); + + const auto vehicle_pose_frenet = + convertToFrenetPoint(path, vehicle_pose.position, nearest_seg_idx); + + for (double t = 0.0; t < prepare_time; t += resolution) { + const auto velocity = + std::clamp(initial_velocity + prepare_acc * t, 0.0, frenet_candidate.prepare_metric.velocity); + const auto length = initial_velocity * t + 0.5 * prepare_acc * t * t; + const auto pose = + autoware::motion_utils::calcInterpolatedPose(path, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); + } + + const auto & poses = frenet_candidate.lane_changing.poses; + const auto & velocities = frenet_candidate.lane_changing.longitudinal_velocities; + const auto & times = frenet_candidate.lane_changing.times; + + for (const auto [t, pose, velocity] : + ranges::views::zip(times, poses, velocities) | ranges::views::drop(1)) { + predicted_path.emplace_back(prepare_time + t, pose, velocity); + } + + return predicted_path; +} + bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) { const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); diff --git a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index cab4acfbb8556..54d4bc2e90714 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -197,6 +197,15 @@ void calculateCartesian( trajectory.longitudinal_accelerations.push_back(0.0); trajectory.lateral_accelerations.push_back(0.0); } + for (auto i = 0UL; i < trajectory.points.size(); ++i) { + geometry_msgs::msg::Pose pose; + pose.position.x = trajectory.points[i].x(); + pose.position.y = trajectory.points[i].y(); + pose.position.z = 0.0; + pose.orientation = + autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, trajectory.yaws[i]); + trajectory.poses.push_back(pose); + } } } From 96998925ad72498c77e0e6a52f5132bb2cb8a92b Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:23:20 +0900 Subject: [PATCH 25/59] fix(learning_based_vehicle_model): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9506) Signed-off-by: Y.Hisaki --- .../learning_based_vehicle_model/src/interconnected_model.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp index d2fef15aa4e88..e495aceb8da9c 100644 --- a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp +++ b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp @@ -79,8 +79,7 @@ void InterconnectedModel::addSubmodel( std::tuple submodel_desc) { const auto [lib_path, param_path, class_name] = submodel_desc; - auto new_model = new SimplePyModel(lib_path, param_path, class_name); - submodels.push_back(std::unique_ptr(new_model)); + submodels.emplace_back(std::make_unique(lib_path, param_path, class_name)); } void InterconnectedModel::initState(std::vector new_state) From 215cae29afaa5923e8c74e216d99e6549980990d Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Tue, 14 Jan 2025 11:31:53 +0300 Subject: [PATCH 26/59] feat(remaining_distance_time_calculator): skip calculation during parking (#9013) Signed-off-by: ismetatabay --- .../README.md | 1 + ...aining_distance_time_calculator.launch.xml | 2 ++ ...emaining_distance_time_calculator_node.cpp | 21 ++++++++++++++++++- ...emaining_distance_time_calculator_node.hpp | 5 +++++ 4 files changed, 28 insertions(+), 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 694c6764de91c..c227b73b87448 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -8,6 +8,7 @@ This package aims to provide mission remaining distance and remaining time calcu - The calculations are activated once we have a route planned for a mission in Autoware. - The calculations are triggered timely based on the `update_rate` parameter. +- The calculations are skipped if the scenario is PARKING, and the remaining time and distance values are set to 0.0. ### Module Parameters diff --git a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml index cfb456c57ca41..be7898bdd8913 100644 --- a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -4,6 +4,7 @@ + @@ -13,6 +14,7 @@ + diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 383e85731604e..7932a2531185f 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -37,6 +37,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( : Node("remaining_distance_time_calculator", options), is_graph_ready_{false}, has_received_route_{false}, + has_received_scenario_{false}, velocity_limit_{99.99}, remaining_distance_{0.0}, remaining_time_{0.0} @@ -57,6 +58,8 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( sub_planning_velocity_ = create_subscription( "/planning/scenario_planning/current_max_velocity", qos_transient_local, std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); + sub_scenario_ = this->create_subscription( + "~/input/scenario", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_scenario, this, _1)); pub_mission_remaining_distance_time_ = create_publisher( "~/output/mission_remaining_distance_time", @@ -100,9 +103,25 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit( } } +void RemainingDistanceTimeCalculatorNode::on_scenario( + const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg) +{ + scenario_ = msg; + has_received_scenario_ = true; +} + void RemainingDistanceTimeCalculatorNode::on_timer() { - if (is_graph_ready_ && has_received_route_) { + if (!has_received_scenario_) { + return; + } + + // check if the scenario is parking or not + if (scenario_->current_scenario == tier4_planning_msgs::msg::Scenario::PARKING) { + remaining_distance_ = 0.0; + remaining_time_ = 0.0; + publish_mission_remaining_distance_time(); + } else if (is_graph_ready_ && has_received_route_) { calculate_remaining_distance(); calculate_remaining_time(); publish_mission_remaining_distance_time(); diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index d6c900af4dfed..b7af8861bf524 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -59,6 +60,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_odometry_; rclcpp::Subscription::SharedPtr sub_planning_velocity_; + rclcpp::Subscription::SharedPtr sub_scenario_; rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; @@ -75,7 +77,9 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node geometry_msgs::msg::Pose current_vehicle_pose_; geometry_msgs::msg::Vector3 current_vehicle_velocity_; geometry_msgs::msg::Pose goal_pose_; + tier4_planning_msgs::msg::Scenario::ConstSharedPtr scenario_; bool has_received_route_; + bool has_received_scenario_; double velocity_limit_; double remaining_distance_; @@ -90,6 +94,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node void on_route(const LaneletRoute::ConstSharedPtr & msg); void on_map(const HADMapBin::ConstSharedPtr & msg); void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg); + void on_scenario(const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg); /** * @brief calculate mission remaining distance From 36b74c23311d677c06600a55d37bfed36e01d163 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:35:13 +0900 Subject: [PATCH 27/59] =?UTF-8?q?feat(autoware=5Fobject=5Fmerger):=20tier4?= =?UTF-8?q?=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Finternal=5Fdebug=5F?= =?UTF-8?q?msgs=20in=20fil=E2=80=A6=20(#9893)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_object_merger Signed-off-by: vish0012 Co-authored-by: Taekjin LEE --- .../src/object_association_merger_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_object_merger/src/object_association_merger_node.cpp b/perception/autoware_object_merger/src/object_association_merger_node.cpp index 0e2b88f4aa566..40bdd0a7d6938 100644 --- a/perception/autoware_object_merger/src/object_association_merger_node.cpp +++ b/perception/autoware_object_merger/src/object_association_merger_node.cpp @@ -235,9 +235,9 @@ void ObjectAssociationMergerNode::objectsCallback( merged_object_pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(merged_object_pub_, output_msg.header.stamp); // publish processing time - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } } // namespace autoware::object_merger From 9c0e183d25c1a76a8091f7c210c95ac32f94d5f4 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:50:46 +0900 Subject: [PATCH 28/59] feat(lane_change_module): add update paramter function for non defined paramters (#9887) * feat(lane_change_module): add new parameters for collision check and delay lane change functionality Signed-off-by: Kyoichi Sugahara * feat(lane_change_module): add validation for longitudinal and lateral acceleration sampling parameters Signed-off-by: Kyoichi Sugahara * feat(lane_change): update parameter handling and add lateral acceleration mapping Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../src/manager.cpp | 125 +++++++++++++++++- 1 file changed, 122 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 06a9d505f90ad..07b05ab0ea131 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -324,10 +324,12 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorlane_change_finish_judge_buffer); updateParam( parameters, ns + "enable_stopped_vehicle_buffer", p->enable_stopped_vehicle_buffer); - updateParam( parameters, ns + "finish_judge_lateral_threshold", p->th_finish_judge_lateral_diff); updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); + updateParam( + parameters, ns + "min_length_for_turn_signal_activation", + p->min_length_for_turn_signal_activation); } { @@ -338,8 +340,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.min_prepare_duration); updateParam(parameters, ns + "lateral_jerk", p->trajectory.lateral_jerk); updateParam( - parameters, ns + ".min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); - // longitudinal acceleration + parameters, ns + "min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); updateParam( parameters, ns + "min_longitudinal_acc", p->trajectory.min_longitudinal_acc); updateParam( @@ -352,12 +353,22 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not positive", + longitudinal_acc_sampling_num); } int lateral_acc_sampling_num = 0; updateParam(parameters, ns + "lat_acc_sampling_num", lateral_acc_sampling_num); if (lateral_acc_sampling_num > 0) { p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not positive", + lateral_acc_sampling_num); } updateParam( @@ -380,6 +391,57 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "right_offset", p->safety.lane_expansion_right_offset); } + { + const std::string ns = "lane_change.lateral_acceleration."; + std::vector velocity = p->trajectory.lat_acc_map.base_vel; + std::vector min_values = p->trajectory.lat_acc_map.base_min_acc; + std::vector max_values = p->trajectory.lat_acc_map.base_max_acc; + + updateParam>(parameters, ns + "velocity", velocity); + updateParam>(parameters, ns + "min_values", min_values); + updateParam>(parameters, ns + "max_values", max_values); + if ( + velocity.size() >= 2 && velocity.size() == min_values.size() && + velocity.size() == max_values.size()) { + LateralAccelerationMap lat_acc_map; + for (size_t i = 0; i < velocity.size(); ++i) { + lat_acc_map.add(velocity.at(i), min_values.at(i), max_values.at(i)); + } + p->trajectory.lat_acc_map = lat_acc_map; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Mismatched size for lateral acceleration. Expected size: %lu, but velocity: %lu, " + "min_values: %lu, max_values: %lu", + std::max(2ul, velocity.size()), velocity.size(), min_values.size(), max_values.size()); + } + } + + { + const std::string ns = "lane_change.collision_check."; + updateParam( + parameters, ns + "enable_for_prepare_phase.general_lanes", + p->safety.collision_check.enable_for_prepare_phase_in_general_lanes); + updateParam( + parameters, ns + "enable_for_prepare_phase.intersection", + p->safety.collision_check.enable_for_prepare_phase_in_intersection); + updateParam( + parameters, ns + "enable_for_prepare_phase.turns", + p->safety.collision_check.enable_for_prepare_phase_in_turns); + updateParam( + parameters, ns + "check_current_lanes", p->safety.collision_check.check_current_lane); + updateParam( + parameters, ns + "check_other_lanes", p->safety.collision_check.check_other_lanes); + updateParam( + parameters, ns + "use_all_predicted_paths", + p->safety.collision_check.use_all_predicted_paths); + updateParam( + parameters, ns + "prediction_time_resolution", + p->safety.collision_check.prediction_time_resolution); + updateParam( + parameters, ns + "yaw_diff_threshold", p->safety.collision_check.th_yaw_diff); + } + { const std::string ns = "lane_change.target_object."; updateParam(parameters, ns + "car", p->safety.target_object_types.check_car); @@ -407,6 +469,50 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "stop_time", p->th_stop_time); } + auto update_rss_params = [¶meters](const std::string & prefix, auto & params) { + using autoware::universe_utils::updateParam; + updateParam( + parameters, prefix + "longitudinal_distance_min_threshold", + params.longitudinal_distance_min_threshold); + updateParam( + parameters, prefix + "longitudinal_velocity_delta_time", + params.longitudinal_velocity_delta_time); + updateParam( + parameters, prefix + "expected_front_deceleration", params.front_vehicle_deceleration); + updateParam( + parameters, prefix + "expected_rear_deceleration", params.rear_vehicle_deceleration); + updateParam( + parameters, prefix + "rear_vehicle_reaction_time", params.rear_vehicle_reaction_time); + updateParam( + parameters, prefix + "rear_vehicle_safety_time_margin", + params.rear_vehicle_safety_time_margin); + updateParam( + parameters, prefix + "lateral_distance_max_threshold", params.lateral_distance_max_threshold); + }; + + update_rss_params("lane_change.safety_check.execution.", p->safety.rss_params); + update_rss_params("lane_change.safety_check.parked.", p->safety.rss_params_for_parked); + update_rss_params("lane_change.safety_check.cancel.", p->safety.rss_params_for_abort); + update_rss_params("lane_change.safety_check.stuck.", p->safety.rss_params_for_stuck); + + { + const std::string ns = "lane_change.delay_lane_change."; + updateParam(parameters, ns + "enable", p->delay.enable); + updateParam( + parameters, ns + "check_only_parked_vehicle", p->delay.check_only_parked_vehicle); + updateParam( + parameters, ns + "min_road_shoulder_width", p->delay.min_road_shoulder_width); + updateParam( + parameters, ns + "th_parked_vehicle_shift_ratio", p->delay.th_parked_vehicle_shift_ratio); + } + + { + const std::string ns = "lane_change.terminal_path."; + updateParam(parameters, ns + "enable", p->terminal_path.enable); + updateParam(parameters, ns + "disable_near_goal", p->terminal_path.disable_near_goal); + updateParam(parameters, ns + "stop_at_boundary", p->terminal_path.stop_at_boundary); + } + { const std::string ns = "lane_change.cancel."; bool enable_on_prepare_phase = true; @@ -424,6 +530,18 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorcancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase; } + int deceleration_sampling_num = 0; + updateParam(parameters, ns + "deceleration_sampling_num", deceleration_sampling_num); + if (deceleration_sampling_num > 0) { + p->cancel.deceleration_sampling_num = deceleration_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'deceleration_sampling_num' is not updated because the value (%d) is not " + "positive", + deceleration_sampling_num); + } + updateParam(parameters, ns + "delta_time", p->cancel.delta_time); updateParam(parameters, ns + "duration", p->cancel.duration); updateParam(parameters, ns + "max_lateral_jerk", p->cancel.max_lateral_jerk); @@ -431,6 +549,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector( parameters, ns + "unsafe_hysteresis_threshold", p->cancel.th_unsafe_hysteresis); } + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { if (!observer.expired()) observer.lock()->updateModuleParams(p); }); From 6e0e6c09f422063d72a727229bf34daffef279a9 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 14 Jan 2025 19:23:19 +0900 Subject: [PATCH 29/59] fix(behavior_velocity_planner_common): fix unregister process (#9913) Signed-off-by: yuki-takagi-66 --- .../behavior_velocity_planner_common/scene_module_interface.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index d8d640a078267..a891b011dbab8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -228,6 +228,7 @@ class SceneModuleManagerInterface auto itr = scene_modules_.begin(); while (itr != scene_modules_.end()) { if (isModuleExpired(*itr)) { + registered_module_id_set_.erase((*itr)->getModuleId()); itr = scene_modules_.erase(itr); } else { itr++; From 5f88055f48c885733cfa6217c811a17a21470a36 Mon Sep 17 00:00:00 2001 From: Kirill Glinskiy <56448851+PurplePegasuss@users.noreply.github.com> Date: Tue, 14 Jan 2025 19:10:07 +0300 Subject: [PATCH 30/59] docs(autoware_mission_planner): added odometry input in README.md (#7281) added odometry input in README.md Signed-off-by: Ryohsuke Mitsudome --- planning/autoware_mission_planner/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_mission_planner/README.md b/planning/autoware_mission_planner/README.md index b5993d0106add..720ecd976f65f 100644 --- a/planning/autoware_mission_planner/README.md +++ b/planning/autoware_mission_planner/README.md @@ -53,6 +53,7 @@ It distributes route requests and planning results according to current MRM oper | `input/vector_map` | autoware_map_msgs/msg/LaneletMapBin | vector map of Lanelet2 | | `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | | `input/operation_mode_state` | autoware_adapi_v1_msgs/OperationModeState | operation mode state | +| `input/odometry` | nav_msgs/msg/Odometry | vehicle odometry | ### Publications From 951b1df19373a57c813ece9dd15dcd6a6f6bb0cf Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 15 Jan 2025 00:22:37 +0800 Subject: [PATCH 31/59] fix(autoware_tensorrt_yolox): modify tensorrt_yolox_node name (#9156) Signed-off-by: liu cui --- .../launch/multiple_yolox.launch.xml | 16 ++++++++++++++++ .../launch/yolox_s_plus_opt.launch.xml | 6 ++++-- 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml index a7952b12414b1..606fd1299cf35 100644 --- a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml @@ -11,34 +11,50 @@ + + + + + + + + + + + + + + + + diff --git a/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml index 0096a219c8573..6d40905d78127 100644 --- a/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -1,6 +1,8 @@ + + @@ -15,13 +17,13 @@ - + - + From bc0dcccbec3131cea2bde0761f811f971f0f10e4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:25:04 +0900 Subject: [PATCH 32/59] test(external_velocity_limit_selector): add node test (#8944) add node smoke test Signed-off-by: Maxime CLEMENT --- .../CMakeLists.txt | 7 + .../package.xml | 1 + .../external_velocity_limit_selector_node.cpp | 1 - ...nal_velocity_limit_selector_node_launch.py | 178 ++++++++++++++++++ 4 files changed, 186 insertions(+), 1 deletion(-) create mode 100644 planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py diff --git a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt index ca758d1262b48..aa8d07d91135e 100644 --- a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt +++ b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt @@ -21,6 +21,13 @@ rclcpp_components_register_node(external_velocity_limit_selector_node EXECUTABLE external_velocity_limit_selector ) +if(BUILD_TESTING) + add_launch_test( + test/test_external_velocity_limit_selector_node_launch.py + TIMEOUT "30" + ) +endif() + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index b75a4fab72d7c..5bfd3fa936d50 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -28,6 +28,7 @@ ament_lint_auto autoware_lint_common + ros_testing ament_cmake diff --git a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp index cf42763fc6b60..cc2b134900a31 100644 --- a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp +++ b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp @@ -14,7 +14,6 @@ #include "autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp" -#include #include #include #include diff --git a/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py b/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py new file mode 100644 index 0000000000000..1c7e882fbc81f --- /dev/null +++ b/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py @@ -0,0 +1,178 @@ +#!/usr/bin/env python3 + +# Copyright 2024 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.actions import IncludeLaunchDescription +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.logging import get_logger +import launch_testing +import pytest +from rcl_interfaces.msg import Parameter +from rcl_interfaces.msg import ParameterType +from rcl_interfaces.msg import ParameterValue +from rcl_interfaces.srv import SetParameters +import rclpy +import rclpy.qos +from tier4_planning_msgs.msg import VelocityLimit +from tier4_planning_msgs.msg import VelocityLimitClearCommand + +logger = get_logger(__name__) + + +@pytest.mark.launch_test +def generate_test_description(): + test_external_velocity_limit_selector_launch_file = os.path.join( + get_package_share_directory("autoware_external_velocity_limit_selector"), + "launch", + "external_velocity_limit_selector.launch.xml", + ) + external_velocity_limit_selector = IncludeLaunchDescription( + AnyLaunchDescriptionSource(test_external_velocity_limit_selector_launch_file), + ) + + return launch.LaunchDescription( + [ + external_velocity_limit_selector, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +class TestExternalVelocityLimitSelector(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 velocity_limit_callback(self, msg): + self.msg_buffer_ = msg + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + qos = rclpy.qos.QoSProfile(depth=1, durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL) + self.pub_api_limit_ = self.test_node.create_publisher( + VelocityLimit, "/planning/scenario_planning/max_velocity_default", qos + ) + self.pub_internal_limit_ = self.test_node.create_publisher( + VelocityLimit, "/planning/scenario_planning/max_velocity_candidates", qos + ) + self.pub_clear_limit_ = self.test_node.create_publisher( + VelocityLimitClearCommand, "/planning/scenario_planning/clear_velocity_limit", qos + ) + self.msg_buffer_ = None + self.velocity_limit_output_ = None + self.test_node.create_subscription( + VelocityLimit, + "/planning/scenario_planning/max_velocity", + self.velocity_limit_callback, + 1, + ) + + def wait_for_output(self): + while not self.msg_buffer_: + rclpy.spin_once(self.test_node, timeout_sec=0.1) + self.velocity_limit_output_ = self.msg_buffer_ + self.msg_buffer_ = None + + def tearDown(self): + self.test_node.destroy_node() + + def update_max_vel_param(self, max_vel): + set_params_client = self.test_node.create_client( + SetParameters, "/external_velocity_limit_selector/set_parameters" + ) + while not set_params_client.wait_for_service(timeout_sec=1.0): + continue + set_params_request = SetParameters.Request() + set_params_request.parameters = [ + Parameter( + name="max_vel", + value=ParameterValue(type=ParameterType.PARAMETER_DOUBLE, double_value=max_vel), + ), + ] + future = set_params_client.call_async(set_params_request) + rclpy.spin_until_future_complete(self.test_node, future) + + if future.result() is None: + self.test_node.get_logger().error( + "Exception while calling service: %r" % future.exception() + ) + raise self.failureException("setting of initial parameters failed") + + @staticmethod + def make_velocity_limit_msg(vel): + msg = VelocityLimit() + msg.use_constraints = False + msg.max_velocity = vel + return msg + + def test_external_velocity_limit_selector_node(self): + self.update_max_vel_param(15.0) + # clear velocity limit to trigger first output + clear_cmd = VelocityLimitClearCommand(command=True) + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + # velocity limit is 0 before any limit is set + self.assertEqual(self.velocity_limit_output_.max_velocity, 0.0) + + # Send velocity limits + # new API velocity limit: higher than the node param -> limit is set to the param value + api_limit = self.make_velocity_limit_msg(20.0) + self.pub_api_limit_.publish(api_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 15.0) + # new API velocity limit + api_limit = self.make_velocity_limit_msg(10.0) + self.pub_api_limit_.publish(api_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) + # new INTERNAL velocity limit + internal_limit = self.make_velocity_limit_msg(5.0) + self.pub_internal_limit_.publish(internal_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 5.0) + # CLEAR: back to API velocity limit + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) + # lower the max_vel node parameter + self.update_max_vel_param(2.5) + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) + # velocity limit set by internal limit is no longer applied since above max_vel parameter + internal_limit = self.make_velocity_limit_msg(5.0) + self.pub_internal_limit_.publish(internal_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) + + +@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 bc409a755a2d0abce18f73c9d84aa05d851cdc5d Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:32:12 +0900 Subject: [PATCH 33/59] feat(remaining_distance_time_calculator): integrate generate_parameter_library (#8826) * add parameter description Signed-off-by: mitukou1109 * use parameter listener Signed-off-by: mitukou1109 * supress deprecated error Signed-off-by: mitukou1109 * change scope of compile option to private Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 --- .../CMakeLists.txt | 12 ++++++++++++ .../package.xml | 1 + ...emaining_distance_time_calculator_parameters.yaml | 4 ++++ .../src/remaining_distance_time_calculator_node.cpp | 6 ++++-- .../src/remaining_distance_time_calculator_node.hpp | 8 ++------ 5 files changed, 23 insertions(+), 8 deletions(-) create mode 100644 planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml diff --git a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt index d29a153a0ce5d..31fc4b1572f33 100644 --- a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt +++ b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt @@ -4,10 +4,22 @@ project(autoware_remaining_distance_time_calculator) find_package(autoware_cmake REQUIRED) autoware_package() +generate_parameter_library(remaining_distance_time_calculator_parameters + param/remaining_distance_time_calculator_parameters.yaml +) + ament_auto_add_library(${PROJECT_NAME} SHARED src/remaining_distance_time_calculator_node.cpp ) +target_link_libraries(${PROJECT_NAME} + remaining_distance_time_calculator_parameters +) + +target_compile_options(${PROJECT_NAME} PRIVATE + -Wno-error=deprecated-declarations +) + rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode" EXECUTABLE ${PROJECT_NAME}_node diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 924e6d62d6aba..568f677a0c13d 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -18,6 +18,7 @@ autoware_route_handler autoware_test_utils autoware_universe_utils + generate_parameter_library geometry_msgs nav_msgs rclcpp diff --git a/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml b/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml new file mode 100644 index 0000000000000..0f1b1b9efbb6d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml @@ -0,0 +1,4 @@ +remaining_distance_time_calculator: + update_rate: + type: double + description: Timer callback period. [Hz] diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 7932a2531185f..74f3f2f43077d 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -65,9 +65,11 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( "~/output/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); - node_param_.update_rate = declare_parameter("update_rate"); + param_listener_ = std::make_shared<::remaining_distance_time_calculator::ParamListener>( + this->get_node_parameters_interface()); + const auto param = param_listener_->get_params(); - const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); + const auto period_ns = rclcpp::Rate(param.update_rate).period(); timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); } diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index b7af8861bf524..8a38941d383ee 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -39,11 +40,6 @@ namespace autoware::remaining_distance_time_calculator { -struct NodeParam -{ - double update_rate{0.0}; -}; - class RemainingDistanceTimeCalculatorNode : public rclcpp::Node { public: @@ -86,7 +82,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node double remaining_time_; // Parameter - NodeParam node_param_; + std::shared_ptr<::remaining_distance_time_calculator::ParamListener> param_listener_; // Callbacks void on_timer(); From 87d7988fae3ac1b135caa6de0c6911da8e4e154d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E5=BF=83=E5=88=9A?= <90366790+liuXinGangChina@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:41:50 +0800 Subject: [PATCH 34/59] feat(autoware_localization_util): porting from universe to core, autoware_localization_util, remove from universe repo (#9888) task: porting from universe to core, autoware_localization_util, remove from universe repo : v0.0 Signed-off-by: liuXinGangChina --- .../autoware_localization_util/CHANGELOG.rst | 51 ---- .../autoware_localization_util/CMakeLists.txt | 29 -- .../autoware_localization_util/README.md | 5 - .../localization_util/covariance_ellipse.hpp | 44 --- .../localization_util/matrix_type.hpp | 26 -- .../localization_util/smart_pose_buffer.hpp | 71 ----- .../tree_structured_parzen_estimator.hpp | 87 ------ .../autoware/localization_util/util_func.hpp | 88 ------ .../autoware_localization_util/package.xml | 35 --- .../src/covariance_ellipse.cpp | 92 ------- .../src/smart_pose_buffer.cpp | 158 ----------- .../src/tree_structured_parzen_estimator.cpp | 185 ------------- .../src/util_func.cpp | 257 ------------------ .../test/test_smart_pose_buffer.cpp | 109 -------- .../test/test_tpe.cpp | 75 ----- 15 files changed, 1312 deletions(-) delete mode 100644 localization/autoware_localization_util/CHANGELOG.rst delete mode 100644 localization/autoware_localization_util/CMakeLists.txt delete mode 100644 localization/autoware_localization_util/README.md delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp delete mode 100644 localization/autoware_localization_util/package.xml delete mode 100644 localization/autoware_localization_util/src/covariance_ellipse.cpp delete mode 100644 localization/autoware_localization_util/src/smart_pose_buffer.cpp delete mode 100644 localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp delete mode 100644 localization/autoware_localization_util/src/util_func.cpp delete mode 100644 localization/autoware_localization_util/test/test_smart_pose_buffer.cpp delete mode 100644 localization/autoware_localization_util/test/test_tpe.cpp diff --git a/localization/autoware_localization_util/CHANGELOG.rst b/localization/autoware_localization_util/CHANGELOG.rst deleted file mode 100644 index be40e3ee8560e..0000000000000 --- a/localization/autoware_localization_util/CHANGELOG.rst +++ /dev/null @@ -1,51 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_localization_util -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - localization (`#9567 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(localization_util)!: prefix package and namespace with autoware (`#8922 `_) - add autoware prefix to localization_util -* Contributors: Masaki Baba, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/localization/autoware_localization_util/CMakeLists.txt b/localization/autoware_localization_util/CMakeLists.txt deleted file mode 100644 index de62633124f3d..0000000000000 --- a/localization/autoware_localization_util/CMakeLists.txt +++ /dev/null @@ -1,29 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_localization_util) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/util_func.cpp - src/smart_pose_buffer.cpp - src/tree_structured_parzen_estimator.cpp - src/covariance_ellipse.cpp -) - -if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) - ament_auto_add_gtest(test_smart_pose_buffer - test/test_smart_pose_buffer.cpp - src/smart_pose_buffer.cpp - ) - - ament_auto_add_gtest(test_tpe - test/test_tpe.cpp - src/tree_structured_parzen_estimator.cpp - ) -endif() - -ament_auto_package( - INSTALL_TO_SHARE -) diff --git a/localization/autoware_localization_util/README.md b/localization/autoware_localization_util/README.md deleted file mode 100644 index f7fddd9eebf05..0000000000000 --- a/localization/autoware_localization_util/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# autoware_localization_util - -`autoware_localization_util` is a localization utility package. - -This package does not have a node, it is just a library. diff --git a/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp b/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp deleted file mode 100644 index abd0af46856b0..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright 2024 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 AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ - -#include - -#include -#include - -namespace autoware::localization_util -{ - -struct Ellipse -{ - double long_radius; - double short_radius; - double yaw; - Eigen::Matrix2d P; - double size_lateral_direction; -}; - -Ellipse calculate_xy_ellipse( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double scale); - -visualization_msgs::msg::Marker create_ellipse_marker( - const Ellipse & ellipse, const std_msgs::msg::Header & header, - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance); - -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp b/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp deleted file mode 100644 index bda6ff19f2867..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2021 TierIV -// -// 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__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ - -#include - -namespace autoware::localization_util -{ -using Matrix6d = Eigen::Matrix; -using RowMatrixXd = Eigen::Matrix; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp b/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp deleted file mode 100644 index 8c10506c36753..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp +++ /dev/null @@ -1,71 +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 AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ - -#include "autoware/localization_util/util_func.hpp" - -#include - -#include - -#include - -namespace autoware::localization_util -{ -class SmartPoseBuffer -{ -private: - using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; - -public: - struct InterpolateResult - { - PoseWithCovarianceStamped old_pose; - PoseWithCovarianceStamped new_pose; - PoseWithCovarianceStamped interpolated_pose; - }; - - SmartPoseBuffer() = delete; - SmartPoseBuffer( - const rclcpp::Logger & logger, const double & pose_timeout_sec, - const double & pose_distance_tolerance_meters); - - std::optional interpolate(const rclcpp::Time & target_ros_time); - - void push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr); - - void pop_old(const rclcpp::Time & target_ros_time); - - void clear(); - -private: - rclcpp::Logger logger_; - std::deque pose_buffer_; - std::mutex mutex_; // This mutex is for pose_buffer_ - - const double pose_timeout_sec_; - const double pose_distance_tolerance_meters_; - - [[nodiscard]] bool validate_time_stamp_difference( - const rclcpp::Time & target_time, const rclcpp::Time & reference_time, - const double time_tolerance_sec) const; - [[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; -}; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp b/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp deleted file mode 100644 index ddf7625c202ec..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp +++ /dev/null @@ -1,87 +0,0 @@ -// 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 AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ - -/* -A implementation of tree-structured parzen estimator (TPE) -See below pdf for the TPE algorithm detail. -https://papers.nips.cc/paper_files/paper/2011/file/86e8f7ab32cfd12577bc2619bc635690-Paper.pdf - -Optuna is also used as a reference for implementation. -https://github.com/optuna/optuna -*/ - -#include -#include -#include - -namespace autoware::localization_util -{ -class TreeStructuredParzenEstimator -{ -public: - using Input = std::vector; - using Score = double; - struct Trial - { - Input input; - Score score; - }; - - enum Direction { - MINIMIZE = 0, - MAXIMIZE = 1, - }; - - enum Index { - TRANS_X = 0, - TRANS_Y = 1, - TRANS_Z = 2, - ANGLE_X = 3, - ANGLE_Y = 4, - ANGLE_Z = 5, - INDEX_NUM = 6, - }; - - TreeStructuredParzenEstimator() = delete; - TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector sample_mean, - std::vector sample_stddev); - void add_trial(const Trial & trial); - [[nodiscard]] Input get_next_input() const; - -private: - static constexpr double max_good_rate = 0.10; - static constexpr int64_t n_ei_candidates = 100; - - static std::mt19937_64 engine; - - [[nodiscard]] double compute_log_likelihood_ratio(const Input & input) const; - [[nodiscard]] static double log_gaussian_pdf( - const Input & input, const Input & mu, const Input & sigma); - - std::vector trials_; - int64_t above_num_; - const Direction direction_; - const int64_t n_startup_trials_; - const int64_t input_dimension_; - const std::vector sample_mean_; - const std::vector sample_stddev_; - Input base_stddev_; -}; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp b/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp deleted file mode 100644 index bef9968f34b6f..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp +++ /dev/null @@ -1,88 +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 AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ - -#include -#include -#include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#include -#else -#include - -#include -#endif - -#include -#include -#include -#include -#include -#include - -namespace autoware::localization_util -{ -// ref by http://takacity.blog.fc2.com/blog-entry-69.html -std_msgs::msg::ColorRGBA exchange_color_crc(double x); - -double calc_diff_for_radian(const double lhs_rad, const double rhs_rad); - -// x: roll, y: pitch, z: yaw -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose); -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose); -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); - -geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( - const double r_rad, const double p_rad, const double y_rad); -geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( - const double r_deg, const double p_deg, const double y_deg); - -geometry_msgs::msg::Twist calc_twist( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b); - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, - const rclcpp::Time & time_stamp); - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp); - -Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose); -Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose); -geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix); -Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos); - -template -T transform(const T & input, const geometry_msgs::msg::TransformStamped & transform) -{ - T output; - tf2::doTransform(input, output, transform); - return output; -} - -double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2); - -void output_pose_with_cov_to_log( - const rclcpp::Logger & logger, const std::string & prefix, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov); - -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ diff --git a/localization/autoware_localization_util/package.xml b/localization/autoware_localization_util/package.xml deleted file mode 100644 index 89ad7c24840dd..0000000000000 --- a/localization/autoware_localization_util/package.xml +++ /dev/null @@ -1,35 +0,0 @@ - - - - autoware_localization_util - 0.40.0 - The autoware_localization_util package - Yamato Ando - Masahiro Sakamoto - Shintaro Sakoda - Kento Yabuuchi - NGUYEN Viet Anh - Taiki Yamada - Ryu Yamamoto - Apache License 2.0 - Yamato Ando - - ament_cmake_auto - autoware_cmake - - diagnostic_msgs - geometry_msgs - rclcpp - std_msgs - tf2 - tf2_eigen - tf2_geometry_msgs - visualization_msgs - - ament_cmake_cppcheck - ament_lint_auto - - - ament_cmake - - diff --git a/localization/autoware_localization_util/src/covariance_ellipse.cpp b/localization/autoware_localization_util/src/covariance_ellipse.cpp deleted file mode 100644 index 847f89e0da9b3..0000000000000 --- a/localization/autoware_localization_util/src/covariance_ellipse.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// Copyright 2024 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 "autoware/localization_util/covariance_ellipse.hpp" - -#include - -#include -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -namespace autoware::localization_util -{ - -Ellipse calculate_xy_ellipse( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double scale) -{ - // input geometry_msgs::PoseWithCovariance contain 6x6 matrix - Eigen::Matrix2d xy_covariance; - const auto cov = pose_with_covariance.covariance; - xy_covariance(0, 0) = cov[0 * 6 + 0]; - xy_covariance(0, 1) = cov[0 * 6 + 1]; - xy_covariance(1, 0) = cov[1 * 6 + 0]; - xy_covariance(1, 1) = cov[1 * 6 + 1]; - - Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); - - Ellipse ellipse; - - // eigen values and vectors are sorted in ascending order - ellipse.long_radius = scale * std::sqrt(eigensolver.eigenvalues()(1)); - ellipse.short_radius = scale * std::sqrt(eigensolver.eigenvalues()(0)); - - // principal component vector - const Eigen::Vector2d pc_vector = eigensolver.eigenvectors().col(1); - ellipse.yaw = std::atan2(pc_vector.y(), pc_vector.x()); - - // ellipse size along lateral direction (body-frame) - ellipse.P = xy_covariance; - const double yaw_vehicle = tf2::getYaw(pose_with_covariance.pose.orientation); - const Eigen::Matrix2d & p_inv = ellipse.P.inverse(); - Eigen::MatrixXd e(2, 1); - e(0, 0) = std::cos(yaw_vehicle); - e(1, 0) = std::sin(yaw_vehicle); - const double d = std::sqrt((e.transpose() * p_inv * e)(0, 0) / p_inv.determinant()); - ellipse.size_lateral_direction = scale * d; - - return ellipse; -} - -visualization_msgs::msg::Marker create_ellipse_marker( - const Ellipse & ellipse, const std_msgs::msg::Header & header, - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance) -{ - tf2::Quaternion quat; - quat.setEuler(0, 0, ellipse.yaw); - - const double ellipse_long_radius = std::min(ellipse.long_radius, 30.0); - const double ellipse_short_radius = std::min(ellipse.short_radius, 30.0); - visualization_msgs::msg::Marker marker; - marker.header = header; - marker.ns = "error_ellipse"; - marker.id = 0; - marker.type = visualization_msgs::msg::Marker::SPHERE; - marker.action = visualization_msgs::msg::Marker::ADD; - marker.pose = pose_with_covariance.pose; - marker.pose.orientation = tf2::toMsg(quat); - marker.scale.x = ellipse_long_radius * 2; - marker.scale.y = ellipse_short_radius * 2; - marker.scale.z = 0.01; - marker.color.a = 0.1; - marker.color.r = 0.0; - marker.color.g = 0.0; - marker.color.b = 1.0; - return marker; -} - -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/smart_pose_buffer.cpp b/localization/autoware_localization_util/src/smart_pose_buffer.cpp deleted file mode 100644 index 3b529d68cf6c5..0000000000000 --- a/localization/autoware_localization_util/src/smart_pose_buffer.cpp +++ /dev/null @@ -1,158 +0,0 @@ -// 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 "autoware/localization_util/smart_pose_buffer.hpp" - -namespace autoware::localization_util -{ -SmartPoseBuffer::SmartPoseBuffer( - const rclcpp::Logger & logger, const double & pose_timeout_sec, - const double & pose_distance_tolerance_meters) -: logger_(logger), - pose_timeout_sec_(pose_timeout_sec), - pose_distance_tolerance_meters_(pose_distance_tolerance_meters) -{ -} - -std::optional SmartPoseBuffer::interpolate( - const rclcpp::Time & target_ros_time) -{ - InterpolateResult result; - - { - std::lock_guard lock(mutex_); - - if (pose_buffer_.size() < 2) { - RCLCPP_INFO(logger_, "pose_buffer_.size() < 2"); - return std::nullopt; - } - - const rclcpp::Time time_first = pose_buffer_.front()->header.stamp; - const rclcpp::Time time_last = pose_buffer_.back()->header.stamp; - - if (target_ros_time < time_first) { - RCLCPP_INFO(logger_, "Mismatch between pose timestamp and current timestamp"); - return std::nullopt; - } - - // [time_last < target_ros_time] is acceptable here. - // It is possible that the target_ros_time (often sensor timestamp) is newer than the latest - // timestamp of buffered pose (often EKF). - // However, if the timestamp difference is too large, - // it will later be rejected by validate_time_stamp_difference. - - // get the nearest poses - result.old_pose = *pose_buffer_.front(); - for (const PoseWithCovarianceStamped::ConstSharedPtr & pose_cov_msg_ptr : pose_buffer_) { - result.new_pose = *pose_cov_msg_ptr; - const rclcpp::Time pose_time_stamp = result.new_pose.header.stamp; - if (pose_time_stamp > target_ros_time) { - break; - } - result.old_pose = *pose_cov_msg_ptr; - } - } - - // check the time stamp - const bool is_old_pose_valid = validate_time_stamp_difference( - result.old_pose.header.stamp, target_ros_time, pose_timeout_sec_); - const bool is_new_pose_valid = validate_time_stamp_difference( - result.new_pose.header.stamp, target_ros_time, pose_timeout_sec_); - - // check the position jumping (ex. immediately after the initial pose estimation) - const bool is_pose_diff_valid = validate_position_difference( - result.old_pose.pose.pose.position, result.new_pose.pose.pose.position, - pose_distance_tolerance_meters_); - - // all validations must be true - if (!(is_old_pose_valid && is_new_pose_valid && is_pose_diff_valid)) { - return std::nullopt; - } - - // interpolate the pose - const geometry_msgs::msg::PoseStamped interpolated_pose_msg = - interpolate_pose(result.old_pose, result.new_pose, target_ros_time); - result.interpolated_pose.header = interpolated_pose_msg.header; - result.interpolated_pose.pose.pose = interpolated_pose_msg.pose; - // This does not interpolate the covariance. - // interpolated_pose.pose.covariance is always set to old_pose.covariance - result.interpolated_pose.pose.covariance = result.old_pose.pose.covariance; - return result; -} - -void SmartPoseBuffer::push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr) -{ - std::lock_guard lock(mutex_); - if (!pose_buffer_.empty()) { - // Check for non-chronological timestamp order - // This situation can arise when replaying a rosbag multiple times - const rclcpp::Time end_time = pose_buffer_.back()->header.stamp; - const rclcpp::Time msg_time = pose_msg_ptr->header.stamp; - if (msg_time < end_time) { - // Clear the buffer if timestamps are reversed to maintain chronological order - pose_buffer_.clear(); - } - } - pose_buffer_.push_back(pose_msg_ptr); -} - -void SmartPoseBuffer::pop_old(const rclcpp::Time & target_ros_time) -{ - std::lock_guard lock(mutex_); - while (!pose_buffer_.empty()) { - if (rclcpp::Time(pose_buffer_.front()->header.stamp) >= target_ros_time) { - break; - } - pose_buffer_.pop_front(); - } -} - -void SmartPoseBuffer::clear() -{ - std::lock_guard lock(mutex_); - pose_buffer_.clear(); -} - -bool SmartPoseBuffer::validate_time_stamp_difference( - const rclcpp::Time & target_time, const rclcpp::Time & reference_time, - const double time_tolerance_sec) const -{ - const double dt = std::abs((target_time - reference_time).seconds()); - const bool success = dt < time_tolerance_sec; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The reference time is %lf[sec], but the target time is %lf[sec]. The " - "difference is %lf[sec] (the tolerance is %lf[sec]).", - reference_time.seconds(), target_time.seconds(), dt, time_tolerance_sec); - } - return success; -} - -bool SmartPoseBuffer::validate_position_difference( - const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point, - const double distance_tolerance_m_) const -{ - const double distance = norm(target_point, reference_point); - const bool success = distance < distance_tolerance_m_; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The distance from reference position to target position is %lf[m] (the " - "tolerance is %lf[m]).", - distance, distance_tolerance_m_); - } - return success; -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp b/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp deleted file mode 100644 index e9f0318d1e06d..0000000000000 --- a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp +++ /dev/null @@ -1,185 +0,0 @@ -// 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 "autoware/localization_util/tree_structured_parzen_estimator.hpp" - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::localization_util -{ -// random number generator -std::mt19937_64 TreeStructuredParzenEstimator::engine(0); - -TreeStructuredParzenEstimator::TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector sample_mean, - std::vector sample_stddev) -: above_num_(0), - direction_(direction), - n_startup_trials_(n_startup_trials), - input_dimension_(INDEX_NUM), - sample_mean_(std::move(sample_mean)), - sample_stddev_(std::move(sample_stddev)) -{ - if (sample_mean_.size() != ANGLE_Z) { - std::cerr << "sample_mean size is invalid" << std::endl; - throw std::runtime_error("sample_mean size is invalid"); - } - if (sample_stddev_.size() != ANGLE_Z) { - std::cerr << "sample_stddev size is invalid" << std::endl; - throw std::runtime_error("sample_stddev size is invalid"); - } - // base_stddev_ is defined as the stable convergence range of ndt_scan_matcher. - base_stddev_.resize(input_dimension_); - base_stddev_[TRANS_X] = 0.25; // [m] - base_stddev_[TRANS_Y] = 0.25; // [m] - base_stddev_[TRANS_Z] = 0.25; // [m] - base_stddev_[ANGLE_X] = 1.0 / 180.0 * M_PI; // [rad] - base_stddev_[ANGLE_Y] = 1.0 / 180.0 * M_PI; // [rad] - base_stddev_[ANGLE_Z] = 2.5 / 180.0 * M_PI; // [rad] -} - -void TreeStructuredParzenEstimator::add_trial(const Trial & trial) -{ - trials_.push_back(trial); - std::sort(trials_.begin(), trials_.end(), [this](const Trial & lhs, const Trial & rhs) { - return (direction_ == Direction::MAXIMIZE ? lhs.score > rhs.score : lhs.score < rhs.score); - }); - above_num_ = std::min( - {static_cast(10), - static_cast(static_cast(trials_.size()) * max_good_rate)}); -} - -TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_input() const -{ - std::normal_distribution dist_normal_trans_x( - sample_mean_[TRANS_X], sample_stddev_[TRANS_X]); - std::normal_distribution dist_normal_trans_y( - sample_mean_[TRANS_Y], sample_stddev_[TRANS_Y]); - std::normal_distribution dist_normal_trans_z( - sample_mean_[TRANS_Z], sample_stddev_[TRANS_Z]); - std::normal_distribution dist_normal_angle_x( - sample_mean_[ANGLE_X], sample_stddev_[ANGLE_X]); - std::normal_distribution dist_normal_angle_y( - sample_mean_[ANGLE_Y], sample_stddev_[ANGLE_Y]); - std::uniform_real_distribution dist_uniform_angle_z(-M_PI, M_PI); - - if (static_cast(trials_.size()) < n_startup_trials_ || above_num_ == 0) { - // Random sampling based on prior until the number of trials reaches `n_startup_trials_`. - Input input(input_dimension_); - input[TRANS_X] = dist_normal_trans_x(engine); - input[TRANS_Y] = dist_normal_trans_y(engine); - input[TRANS_Z] = dist_normal_trans_z(engine); - input[ANGLE_X] = dist_normal_angle_x(engine); - input[ANGLE_Y] = dist_normal_angle_y(engine); - input[ANGLE_Z] = dist_uniform_angle_z(engine); - return input; - } - - Input best_input; - double best_log_likelihood_ratio = std::numeric_limits::lowest(); - for (int64_t i = 0; i < n_ei_candidates; i++) { - Input input(input_dimension_); - input[TRANS_X] = dist_normal_trans_x(engine); - input[TRANS_Y] = dist_normal_trans_y(engine); - input[TRANS_Z] = dist_normal_trans_z(engine); - input[ANGLE_X] = dist_normal_angle_x(engine); - input[ANGLE_Y] = dist_normal_angle_y(engine); - input[ANGLE_Z] = dist_uniform_angle_z(engine); - const double log_likelihood_ratio = compute_log_likelihood_ratio(input); - if (log_likelihood_ratio > best_log_likelihood_ratio) { - best_log_likelihood_ratio = log_likelihood_ratio; - best_input = input; - } - } - return best_input; -} - -double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input & input) const -{ - const auto n = static_cast(trials_.size()); - - // The above KDE and the below KDE are calculated respectively, and the ratio is the criteria to - // select best sample. - std::vector above_logs; - std::vector below_logs; - - for (int64_t i = 0; i < n; i++) { - const double log_p = log_gaussian_pdf(input, trials_[i].input, base_stddev_); - if (i < above_num_) { - const double w = 1.0 / static_cast(above_num_); - const double log_w = std::log(w); - above_logs.push_back(log_p + log_w); - } else { - const double w = 1.0 / static_cast(n - above_num_); - const double log_w = std::log(w); - below_logs.push_back(log_p + log_w); - } - } - - auto log_sum_exp = [](const std::vector & log_vec) { - const double max = *std::max_element(log_vec.begin(), log_vec.end()); - double sum = std::accumulate( - log_vec.begin(), log_vec.end(), 0.0, - [max](double total, double log_v) { return total + std::exp(log_v - max); }); - return max + std::log(sum); - }; - - const double above = log_sum_exp(above_logs); - const double below = log_sum_exp(below_logs); - - // Multiply by a constant so that the score near the "below sample" becomes lower. - // cspell:disable-line TODO(Shintaro Sakoda): It's theoretically incorrect, consider it again - // later. - const double r = above - below * 5.0; - return r; -} - -double TreeStructuredParzenEstimator::log_gaussian_pdf( - const Input & input, const Input & mu, const Input & sigma) -{ - const double log_2pi = std::log(2.0 * M_PI); - auto log_gaussian_pdf_1d = [&](const double diff, const double sigma) { - return -0.5 * log_2pi - std::log(sigma) - (diff * diff) / (2.0 * sigma * sigma); - }; - - const auto n = static_cast(input.size()); - - double result = 0.0; - for (int64_t i = 0; i < n; i++) { - double diff = input[i] - mu[i]; - if (i == ANGLE_Z) { - // Normalize the loop variable to [-pi, pi) - while (diff >= M_PI) { - diff -= 2 * M_PI; - } - while (diff < -M_PI) { - diff += 2 * M_PI; - } - } - // Experimentally, it is better to consider only trans_xy and yaw, so ignore trans_z, angle_x, - // angle_y. - if (i == TRANS_Z || i == ANGLE_X || i == ANGLE_Y) { - continue; - } - result += log_gaussian_pdf_1d(diff, sigma[i]); - } - return result; -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/util_func.cpp b/localization/autoware_localization_util/src/util_func.cpp deleted file mode 100644 index 17187a8d732f0..0000000000000 --- a/localization/autoware_localization_util/src/util_func.cpp +++ /dev/null @@ -1,257 +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. - -#include "autoware/localization_util/util_func.hpp" - -#include "autoware/localization_util/matrix_type.hpp" - -#include -#include - -namespace autoware::localization_util -{ -// ref by http://takacity.blog.fc2.com/blog-entry-69.html -std_msgs::msg::ColorRGBA exchange_color_crc(double x) -{ - std_msgs::msg::ColorRGBA color; - - x = std::max(x, 0.0); - x = std::min(x, 0.9999); - - if (x <= 0.25) { - color.b = 1.0; - color.g = static_cast(std::sin(x * 2.0 * M_PI)); - color.r = 0; - } else if (x <= 0.5) { - color.b = static_cast(std::sin(x * 2 * M_PI)); - color.g = 1.0; - color.r = 0; - } else if (x <= 0.75) { - color.b = 0; - color.g = 1.0; - color.r = static_cast(-std::sin(x * 2.0 * M_PI)); - } else { - color.b = 0; - color.g = static_cast(-std::sin(x * 2.0 * M_PI)); - color.r = 1.0; - } - color.a = 0.999; - return color; -} - -double calc_diff_for_radian(const double lhs_rad, const double rhs_rad) -{ - double diff_rad = lhs_rad - rhs_rad; - if (diff_rad > M_PI) { - diff_rad = diff_rad - 2 * M_PI; - } else if (diff_rad < -M_PI) { - diff_rad = diff_rad + 2 * M_PI; - } - return diff_rad; -} - -Eigen::Map make_eigen_covariance(const std::array & covariance) -{ - return {covariance.data(), 6, 6}; -} - -// x: roll, y: pitch, z: yaw -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose) -{ - geometry_msgs::msg::Vector3 rpy; - tf2::Quaternion q(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); - tf2::Matrix3x3(q).getRPY(rpy.x, rpy.y, rpy.z); - return rpy; -} - -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose) -{ - return get_rpy(pose.pose); -} - -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) -{ - return get_rpy(pose.pose.pose); -} - -geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( - const double r_rad, const double p_rad, const double y_rad) -{ - tf2::Quaternion q; - q.setRPY(r_rad, p_rad, y_rad); - geometry_msgs::msg::Quaternion quaternion_msg; - quaternion_msg.x = q.x(); - quaternion_msg.y = q.y(); - quaternion_msg.z = q.z(); - quaternion_msg.w = q.w(); - return quaternion_msg; -} - -geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( - const double r_deg, const double p_deg, const double y_deg) -{ - const double r_rad = r_deg * M_PI / 180.0; - const double p_rad = p_deg * M_PI / 180.0; - const double y_rad = y_deg * M_PI / 180.0; - return rpy_rad_to_quaternion(r_rad, p_rad, y_rad); -} - -geometry_msgs::msg::Twist calc_twist( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b) -{ - const rclcpp::Duration dt = rclcpp::Time(pose_b.header.stamp) - rclcpp::Time(pose_a.header.stamp); - const double dt_s = dt.seconds(); - - if (dt_s == 0) { - return geometry_msgs::msg::Twist(); - } - - const auto pose_a_rpy = get_rpy(pose_a); - const auto pose_b_rpy = get_rpy(pose_b); - - geometry_msgs::msg::Vector3 diff_xyz; - geometry_msgs::msg::Vector3 diff_rpy; - - diff_xyz.x = pose_b.pose.position.x - pose_a.pose.position.x; - diff_xyz.y = pose_b.pose.position.y - pose_a.pose.position.y; - diff_xyz.z = pose_b.pose.position.z - pose_a.pose.position.z; - diff_rpy.x = calc_diff_for_radian(pose_b_rpy.x, pose_a_rpy.x); - diff_rpy.y = calc_diff_for_radian(pose_b_rpy.y, pose_a_rpy.y); - diff_rpy.z = calc_diff_for_radian(pose_b_rpy.z, pose_a_rpy.z); - - geometry_msgs::msg::Twist twist; - twist.linear.x = diff_xyz.x / dt_s; - twist.linear.y = diff_xyz.y / dt_s; - twist.linear.z = diff_xyz.z / dt_s; - twist.angular.x = diff_rpy.x / dt_s; - twist.angular.y = diff_rpy.y / dt_s; - twist.angular.z = diff_rpy.z / dt_s; - - return twist; -} - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, - const rclcpp::Time & time_stamp) -{ - const rclcpp::Time pose_a_time_stamp = pose_a.header.stamp; - const rclcpp::Time pose_b_time_stamp = pose_b.header.stamp; - if ( - (pose_a_time_stamp.seconds() == 0.0) || (pose_b_time_stamp.seconds() == 0.0) || - (time_stamp.seconds() == 0.0)) { - return geometry_msgs::msg::PoseStamped(); - } - - const auto twist = calc_twist(pose_a, pose_b); - const double dt = (time_stamp - pose_a_time_stamp).seconds(); - - const auto pose_a_rpy = get_rpy(pose_a); - - geometry_msgs::msg::Vector3 xyz; - geometry_msgs::msg::Vector3 rpy; - xyz.x = pose_a.pose.position.x + twist.linear.x * dt; - xyz.y = pose_a.pose.position.y + twist.linear.y * dt; - xyz.z = pose_a.pose.position.z + twist.linear.z * dt; - rpy.x = pose_a_rpy.x + twist.angular.x * dt; - rpy.y = pose_a_rpy.y + twist.angular.y * dt; - rpy.z = pose_a_rpy.z + twist.angular.z * dt; - - tf2::Quaternion tf_quaternion; - tf_quaternion.setRPY(rpy.x, rpy.y, rpy.z); - - geometry_msgs::msg::PoseStamped pose; - pose.header = pose_a.header; - pose.header.stamp = time_stamp; - pose.pose.position.x = xyz.x; - pose.pose.position.y = xyz.y; - pose.pose.position.z = xyz.z; - pose.pose.orientation = tf2::toMsg(tf_quaternion); - return pose; -} - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp) -{ - geometry_msgs::msg::PoseStamped tmp_pose_a; - tmp_pose_a.header = pose_a.header; - tmp_pose_a.pose = pose_a.pose.pose; - - geometry_msgs::msg::PoseStamped tmp_pose_b; - tmp_pose_b.header = pose_b.header; - tmp_pose_b.pose = pose_b.pose.pose; - - return interpolate_pose(tmp_pose_a, tmp_pose_b, time_stamp); -} - -Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose) -{ - Eigen::Affine3d eigen_pose; - tf2::fromMsg(ros_pose, eigen_pose); - return eigen_pose; -} - -Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose) -{ - Eigen::Affine3d eigen_pose_affine = pose_to_affine3d(ros_pose); - Eigen::Matrix4f eigen_pose_matrix = eigen_pose_affine.matrix().cast(); - return eigen_pose_matrix; -} - -Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos) -{ - Eigen::Vector3d eigen_pos; - eigen_pos.x() = ros_pos.x; - eigen_pos.y() = ros_pos.y; - eigen_pos.z() = ros_pos.z; - return eigen_pos; -} - -geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix) -{ - Eigen::Affine3d eigen_pose_affine; - eigen_pose_affine.matrix() = eigen_pose_matrix.cast(); - geometry_msgs::msg::Pose ros_pose = tf2::toMsg(eigen_pose_affine); - return ros_pose; -} - -double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) -{ - const double dx = p1.x - p2.x; - const double dy = p1.y - p2.y; - const double dz = p1.z - p2.z; - return std::sqrt(dx * dx + dy * dy + dz * dz); -} - -void output_pose_with_cov_to_log( - const rclcpp::Logger & logger, const std::string & prefix, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov) -{ - const Eigen::Map covariance = - make_eigen_covariance(pose_with_cov.pose.covariance); - const geometry_msgs::msg::Pose pose = pose_with_cov.pose.pose; - geometry_msgs::msg::Vector3 rpy = get_rpy(pose); - rpy.x = rpy.x * 180.0 / M_PI; - rpy.y = rpy.y * 180.0 / M_PI; - rpy.z = rpy.z * 180.0 / M_PI; - - RCLCPP_DEBUG_STREAM( - logger, std::fixed << prefix << "," << pose.position.x << "," << pose.position.y << "," - << pose.position.z << "," << pose.orientation.x << "," << pose.orientation.y - << "," << pose.orientation.z << "," << pose.orientation.w << "," << rpy.x - << "," << rpy.y << "," << rpy.z << "," << covariance(0, 0) << "," - << covariance(1, 1) << "," << covariance(2, 2) << "," << covariance(3, 3) - << "," << covariance(4, 4) << "," << covariance(5, 5)); -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp b/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp deleted file mode 100644 index d55555682be84..0000000000000 --- a/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// 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 "autoware/localization_util/smart_pose_buffer.hpp" -#include "autoware/localization_util/util_func.hpp" - -#include -#include - -#include -#include - -#include -#include -#include - -using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; -using SmartPoseBuffer = autoware::localization_util::SmartPoseBuffer; - -bool compare_pose( - const PoseWithCovarianceStamped & pose_a, const PoseWithCovarianceStamped & pose_b) -{ - return pose_a.header.stamp == pose_b.header.stamp && - pose_a.header.frame_id == pose_b.header.frame_id && - pose_a.pose.covariance == pose_b.pose.covariance && - pose_a.pose.pose.position.x == pose_b.pose.pose.position.x && - pose_a.pose.pose.position.y == pose_b.pose.pose.position.y && - pose_a.pose.pose.position.z == pose_b.pose.pose.position.z && - pose_a.pose.pose.orientation.x == pose_b.pose.pose.orientation.x && - pose_a.pose.pose.orientation.y == pose_b.pose.pose.orientation.y && - pose_a.pose.pose.orientation.z == pose_b.pose.pose.orientation.z && - pose_a.pose.pose.orientation.w == pose_b.pose.pose.orientation.w; -} - -TEST(TestSmartPoseBuffer, interpolate_pose) // NOLINT -{ - rclcpp::Logger logger = rclcpp::get_logger("test_logger"); - const double pose_timeout_sec = 10.0; - const double pose_distance_tolerance_meters = 100.0; - SmartPoseBuffer smart_pose_buffer(logger, pose_timeout_sec, pose_distance_tolerance_meters); - - // first data - PoseWithCovarianceStamped::SharedPtr old_pose_ptr = std::make_shared(); - old_pose_ptr->header.stamp.sec = 10; - old_pose_ptr->header.stamp.nanosec = 0; - old_pose_ptr->pose.pose.position.x = 10.0; - old_pose_ptr->pose.pose.position.y = 20.0; - old_pose_ptr->pose.pose.position.z = 0.0; - old_pose_ptr->pose.pose.orientation = - autoware::localization_util::rpy_deg_to_quaternion(0.0, 0.0, 0.0); - smart_pose_buffer.push_back(old_pose_ptr); - - // second data - PoseWithCovarianceStamped::SharedPtr new_pose_ptr = std::make_shared(); - new_pose_ptr->header.stamp.sec = 20; - new_pose_ptr->header.stamp.nanosec = 0; - new_pose_ptr->pose.pose.position.x = 20.0; - new_pose_ptr->pose.pose.position.y = 40.0; - new_pose_ptr->pose.pose.position.z = 0.0; - new_pose_ptr->pose.pose.orientation = - autoware::localization_util::rpy_deg_to_quaternion(0.0, 0.0, 90.0); - smart_pose_buffer.push_back(new_pose_ptr); - - // interpolate - builtin_interfaces::msg::Time target_ros_time_msg; - target_ros_time_msg.sec = 15; - target_ros_time_msg.nanosec = 0; - const std::optional & interpolate_result = - smart_pose_buffer.interpolate(target_ros_time_msg); - ASSERT_TRUE(interpolate_result.has_value()); - const SmartPoseBuffer::InterpolateResult result = interpolate_result.value(); - - // check old - EXPECT_TRUE(compare_pose(result.old_pose, *old_pose_ptr)); - - // check new - EXPECT_TRUE(compare_pose(result.new_pose, *new_pose_ptr)); - - // check interpolated - EXPECT_EQ(result.interpolated_pose.header.stamp.sec, 15); - EXPECT_EQ(result.interpolated_pose.header.stamp.nanosec, static_cast(0)); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.x, 15.0); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.y, 30.0); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.z, 0.0); - const auto rpy = autoware::localization_util::get_rpy(result.interpolated_pose.pose.pose); - EXPECT_NEAR(rpy.x * 180 / M_PI, 0.0, 1e-6); - EXPECT_NEAR(rpy.y * 180 / M_PI, 0.0, 1e-6); - EXPECT_NEAR(rpy.z * 180 / M_PI, 45.0, 1e-6); -} - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int result = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return result; -} diff --git a/localization/autoware_localization_util/test/test_tpe.cpp b/localization/autoware_localization_util/test/test_tpe.cpp deleted file mode 100644 index 2d71a385246b7..0000000000000 --- a/localization/autoware_localization_util/test/test_tpe.cpp +++ /dev/null @@ -1,75 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// 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 "autoware/localization_util/tree_structured_parzen_estimator.hpp" - -#include - -#include -#include -#include -#include -#include - -using TreeStructuredParzenEstimator = autoware::localization_util::TreeStructuredParzenEstimator; - -TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphere_function) -{ - auto sphere_function = [](const TreeStructuredParzenEstimator::Input & input) { - double value = 0.0; - const auto n = static_cast(input.size()); - for (int64_t i = 0; i < n; i++) { - const double v = input[i] * 10; - value += v * v; - } - return value; - }; - - constexpr int64_t k_outer_trials_num = 20; - constexpr int64_t k_inner_trials_num = 200; - std::cout << std::fixed; - std::vector mean_scores; - std::vector sample_mean(5, 0.0); - std::vector sample_stddev{1.0, 1.0, 0.1, 0.1, 0.1}; - - for (const int64_t n_startup_trials : {k_inner_trials_num, k_inner_trials_num / 2}) { - const std::string method = ((n_startup_trials == k_inner_trials_num) ? "Random" : "TPE"); - - std::vector scores; - for (int64_t i = 0; i < k_outer_trials_num; i++) { - double best_score = std::numeric_limits::lowest(); - TreeStructuredParzenEstimator estimator( - TreeStructuredParzenEstimator::Direction::MAXIMIZE, n_startup_trials, sample_mean, - sample_stddev); - for (int64_t trial = 0; trial < k_inner_trials_num; trial++) { - const TreeStructuredParzenEstimator::Input input = estimator.get_next_input(); - const double score = -sphere_function(input); - estimator.add_trial({input, score}); - best_score = std::max(best_score, score); - } - scores.push_back(best_score); - } - - const double sum = std::accumulate(scores.begin(), scores.end(), 0.0); - const double mean = sum / static_cast(scores.size()); - mean_scores.push_back(mean); - double sq_sum = std::accumulate( - scores.begin(), scores.end(), 0.0, - [mean](double total, double score) { return total + (score - mean) * (score - mean); }); - const double stddev = std::sqrt(sq_sum / static_cast(scores.size())); - - std::cout << method << ", mean = " << mean << ", stddev = " << stddev << std::endl; - } - ASSERT_LT(mean_scores[0], mean_scores[1]); -} From 557a71e16695083aa40091b60f17c1daa90a257d Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:52:13 +0900 Subject: [PATCH 35/59] fix(dummy_infrastructure): fix bugprone-reserved-identifier (#9919) Signed-off-by: kobayu858 Co-authored-by: kobayu858 --- .../src/dummy_infrastructure_node/dummy_infrastructure_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp b/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp index 485d85c926268..4760c9366da46 100644 --- a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp +++ b/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp @@ -24,7 +24,6 @@ using namespace std::literals; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -using std::placeholders::_1; namespace dummy_infrastructure { @@ -84,6 +83,7 @@ boost::optional findCommand( DummyInfrastructureNode::DummyInfrastructureNode(const rclcpp::NodeOptions & node_options) : Node("dummy_infrastructure", node_options) { + using std::placeholders::_1; // Parameter Server set_param_res_ = this->add_on_set_parameters_callback(std::bind(&DummyInfrastructureNode::onSetParam, this, _1)); From 6939a3da23a41781a6d973a8267e2ea1cb3a600d Mon Sep 17 00:00:00 2001 From: NorahXiong <103234047+NorahXiong@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:57:09 +0800 Subject: [PATCH 36/59] feat(autoware_qp_interface): porting autoware_qp_interface package to autoware.core (#9824) Signed-off-by: NorahXiong --- common/autoware_qp_interface/CHANGELOG.rst | 81 ---- common/autoware_qp_interface/CMakeLists.txt | 64 --- .../design/qp_interface-design.md | 48 --- .../qp_interface/osqp_csc_matrix_conv.hpp | 46 -- .../autoware/qp_interface/osqp_interface.hpp | 147 ------- .../qp_interface/proxqp_interface.hpp | 57 --- .../autoware/qp_interface/qp_interface.hpp | 61 --- common/autoware_qp_interface/package.xml | 30 -- .../src/osqp_csc_matrix_conv.cpp | 134 ------ .../src/osqp_interface.cpp | 394 ------------------ .../src/proxqp_interface.cpp | 157 ------- .../src/qp_interface.cpp | 70 ---- .../test/test_csc_matrix_conv.cpp | 181 -------- .../test/test_osqp_interface.cpp | 170 -------- .../test/test_proxqp_interface.cpp | 85 ---- 15 files changed, 1725 deletions(-) delete mode 100644 common/autoware_qp_interface/CHANGELOG.rst delete mode 100644 common/autoware_qp_interface/CMakeLists.txt delete mode 100644 common/autoware_qp_interface/design/qp_interface-design.md delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp delete mode 100644 common/autoware_qp_interface/package.xml delete mode 100644 common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp delete mode 100644 common/autoware_qp_interface/src/osqp_interface.cpp delete mode 100644 common/autoware_qp_interface/src/proxqp_interface.cpp delete mode 100644 common/autoware_qp_interface/src/qp_interface.cpp delete mode 100644 common/autoware_qp_interface/test/test_csc_matrix_conv.cpp delete mode 100644 common/autoware_qp_interface/test/test_osqp_interface.cpp delete mode 100644 common/autoware_qp_interface/test/test_proxqp_interface.cpp diff --git a/common/autoware_qp_interface/CHANGELOG.rst b/common/autoware_qp_interface/CHANGELOG.rst deleted file mode 100644 index f76dac861e1e6..0000000000000 --- a/common/autoware_qp_interface/CHANGELOG.rst +++ /dev/null @@ -1,81 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_qp_interface -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* fix: fix package names in changelog files (`#9500 `_) -* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) -* 0.39.0 -* update changelog -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* fix(qp_interface): fix unreadVariable (`#8349 `_) - * fix:unreadVariable - * fix:unreadVariable - * fix:unreadVariable - --------- -* perf(velocity_smoother): use ProxQP for faster optimization (`#8028 `_) - * perf(velocity_smoother): use ProxQP for faster optimization - * consider max_iteration - * disable warm start - * fix test - --------- -* refactor(qp_interface): clean up the code (`#8029 `_) - * refactor qp_interface - * variable names: m_XXX -> XXX\_ - * update - * update - --------- -* fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions (`#7855 `_) - * fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* Contributors: Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, kobayu858 - -0.26.0 (2024-04-03) -------------------- -* feat(qp_interface): support proxqp (`#3699 `_) - * feat(qp_interface): add proxqp interface - * update - --------- -* feat(qp_interface): add new package which will contain various qp solvers (`#3697 `_) -* Contributors: Takayuki Murooka diff --git a/common/autoware_qp_interface/CMakeLists.txt b/common/autoware_qp_interface/CMakeLists.txt deleted file mode 100644 index 1df75d2d719a0..0000000000000 --- a/common/autoware_qp_interface/CMakeLists.txt +++ /dev/null @@ -1,64 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_qp_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Eigen3 REQUIRED) -find_package(proxsuite REQUIRED) - -# after find_package(osqp_vendor) in ament_auto_find_build_dependencies -find_package(osqp REQUIRED) -get_target_property(OSQP_INCLUDE_SUB_DIR osqp::osqp INTERFACE_INCLUDE_DIRECTORIES) -get_filename_component(OSQP_INCLUDE_DIR ${OSQP_INCLUDE_SUB_DIR} PATH) - -set(QP_INTERFACE_LIB_SRC - src/qp_interface.cpp - src/osqp_interface.cpp - src/osqp_csc_matrix_conv.cpp - src/proxqp_interface.cpp -) - -set(QP_INTERFACE_LIB_HEADERS - include/autoware/qp_interface/qp_interface.hpp - include/autoware/qp_interface/osqp_interface.hpp - include/autoware/qp_interface/osqp_csc_matrix_conv.hpp - include/autoware/qp_interface/proxqp_interface.hpp -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - ${QP_INTERFACE_LIB_SRC} - ${QP_INTERFACE_LIB_HEADERS} -) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) - -target_include_directories(${PROJECT_NAME} - SYSTEM PUBLIC - "${OSQP_INCLUDE_DIR}" - "${EIGEN3_INCLUDE_DIR}" -) - -ament_target_dependencies(${PROJECT_NAME} - Eigen3 - osqp_vendor - proxsuite -) - -# crucial so downstream package builds because osqp_interface exposes osqp.hpp -ament_export_include_directories("${OSQP_INCLUDE_DIR}") -# crucial so the linking order is correct in a downstream package: libosqp_interface.a should come before libosqp.a -ament_export_libraries(osqp::osqp) - -if(BUILD_TESTING) - set(TEST_SOURCES - test/test_osqp_interface.cpp - test/test_csc_matrix_conv.cpp - test/test_proxqp_interface.cpp - ) - set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) - target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) -endif() - -ament_auto_package(INSTALL_TO_SHARE -) diff --git a/common/autoware_qp_interface/design/qp_interface-design.md b/common/autoware_qp_interface/design/qp_interface-design.md deleted file mode 100644 index edc7fa9845206..0000000000000 --- a/common/autoware_qp_interface/design/qp_interface-design.md +++ /dev/null @@ -1,48 +0,0 @@ -# Interface for QP solvers - -This is the design document for the `autoware_qp_interface` package. - -## Purpose / Use cases - -This packages provides a C++ interface for QP solvers. -Currently, supported QP solvers are - -- [OSQP library](https://osqp.org/docs/solver/index.html) - -## Design - -The class `QPInterface` takes a problem formulation as Eigen matrices and vectors, converts these objects into -C-style Compressed-Column-Sparse matrices and dynamic arrays, loads the data into the QP workspace dataholder, and runs the optimizer. - -## Inputs / Outputs / API - -The interface can be used in several ways: - -1. Initialize the interface, and load the problem formulation at the optimization call. - - ```cpp - QPInterface qp_interface; - qp_interface.optimize(P, A, q, l, u); - ``` - -2. WARM START OPTIMIZATION by modifying the problem formulation between optimization runs. - - ```cpp - QPInterface qp_interface(true); - qp_interface.optimize(P, A, q, l, u); - qp_interface.optimize(P_new, A_new, q_new, l_new, u_new); - ``` - - The optimization results are returned as a vector by the optimization function. - - ```cpp - const auto solution = qp_interface.optimize(); - double x_0 = solution[0]; - double x_1 = solution[1]; - ``` - -## References / External links - -- OSQP library: - -## Related issues diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp deleted file mode 100644 index 9575d9d18c69f..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp +++ /dev/null @@ -1,46 +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 AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ -#define AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ - -#include "osqp/glob_opts.h" - -#include - -#include - -namespace autoware::qp_interface -{ -/// \brief Compressed-Column-Sparse Matrix -struct CSC_Matrix -{ - /// Vector of non-zero values. Ex: [4,1,1,2] - std::vector vals_; - /// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner') - std::vector row_idxs_; - /// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer') - std::vector col_idxs_; -}; - -/// \brief Calculate CSC matrix from Eigen matrix -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat); -/// \brief Calculate upper trapezoidal CSC matrix from square Eigen matrix -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat); -/// \brief Print the given CSC matrix to the standard output -void printCSCMatrix(const CSC_Matrix & csc_mat); - -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp deleted file mode 100644 index a5777dd545e9f..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp +++ /dev/null @@ -1,147 +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 AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" -#include "autoware/qp_interface/qp_interface.hpp" -#include "osqp/osqp.h" - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -constexpr c_float OSQP_INF = 1e30; - -class OSQPInterface : public QPInterface -{ -public: - /// \brief Constructor without problem formulation - OSQPInterface( - const bool enable_warm_start = false, const int max_iteration = 20000, - const c_float eps_abs = std::numeric_limits::epsilon(), - const c_float eps_rel = std::numeric_limits::epsilon(), const bool polish = true, - const bool verbose = false); - /// \brief Constructor with problem setup - /// \param P: (n,n) matrix defining relations between parameters. - /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q: (n) vector defining the linear cost of the problem. - /// \param l: (m) vector defining the lower bound problem constraint. - /// \param u: (m) vector defining the upper bound problem constraint. - /// \param eps_abs: Absolute convergence tolerance. - OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, - const bool enable_warm_start = false, - const c_float eps_abs = std::numeric_limits::epsilon()); - OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, - const bool enable_warm_start = false, - const c_float eps_abs = std::numeric_limits::epsilon()); - ~OSQPInterface(); - - static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; - - std::vector optimize( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - int getIterationNumber() const override; - bool isSolved() const override; - std::string getStatus() const override; - - int getPolishStatus() const; - std::vector getDualSolution() const; - - void updateEpsAbs(const double eps_abs) override; - void updateEpsRel(const double eps_rel) override; - void updateVerbose(const bool verbose) override; - - // Updates problem parameters while keeping solution in memory. - // - // Args: - // P_new: (n,n) matrix defining relations between parameters. - // A_new: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - // q_new: (n) vector defining the linear cost of the problem. - // l_new: (m) vector defining the lower bound problem constraint. - // u_new: (m) vector defining the upper bound problem constraint. - void updateP(const Eigen::MatrixXd & P_new); - void updateCscP(const CSC_Matrix & P_csc); - void updateA(const Eigen::MatrixXd & A_new); - void updateCscA(const CSC_Matrix & A_csc); - void updateQ(const std::vector & q_new); - void updateL(const std::vector & l_new); - void updateU(const std::vector & u_new); - void updateBounds(const std::vector & l_new, const std::vector & u_new); - - void updateMaxIter(const int iter); - void updateRhoInterval(const int rho_interval); - void updateRho(const double rho); - void updateAlpha(const double alpha); - void updateScaling(const int scaling); - void updatePolish(const bool polish); - void updatePolishRefinementIteration(const int polish_refine_iter); - void updateCheckTermination(const int check_termination); - - /// \brief Get the number of iteration taken to solve the problem - inline int64_t getTakenIter() const { return static_cast(latest_work_info_.iter); } - /// \brief Get the status message for the latest problem solved - inline std::string getStatusMessage() const - { - return static_cast(latest_work_info_.status); - } - /// \brief Get the runtime of the latest problem solved - inline double getRunTime() const { return latest_work_info_.run_time; } - /// \brief Get the objective value the latest problem solved - inline double getObjVal() const { return latest_work_info_.obj_val; } - /// \brief Returns flag asserting interface condition (Healthy condition: 0). - inline int64_t getExitFlag() const { return exitflag_; } - - // Setter functions for warm start - bool setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables); - bool setPrimalVariables(const std::vector & primal_variables); - bool setDualVariables(const std::vector & dual_variables); - -private: - std::unique_ptr> work_; - std::unique_ptr settings_; - std::unique_ptr data_; - // store last work info since work is cleaned up at every execution to prevent memory leak. - OSQPInfo latest_work_info_; - // Number of parameters to optimize - int64_t param_n_; - // Flag to check if the current work exists - bool work__initialized = false; - // Exitflag - int64_t exitflag_; - - void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) override; - - void initializeCSCProblemImpl( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - std::vector optimizeImpl() override; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp deleted file mode 100644 index 324da4b18c6fd..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp +++ /dev/null @@ -1,57 +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 AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ - -#include "autoware/qp_interface/qp_interface.hpp" - -#include -#include - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -class ProxQPInterface : public QPInterface -{ -public: - explicit ProxQPInterface( - const bool enable_warm_start, const int max_iteration, const double eps_abs, - const double eps_rel, const bool verbose = false); - - int getIterationNumber() const override; - bool isSolved() const override; - std::string getStatus() const override; - - void updateEpsAbs(const double eps_abs) override; - void updateEpsRel(const double eps_rel) override; - void updateVerbose(const bool verbose) override; - -private: - proxsuite::proxqp::Settings settings_{}; - std::shared_ptr> qp_ptr_{nullptr}; - - void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) override; - - std::vector optimizeImpl() override; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp deleted file mode 100644 index be3c598512bf6..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp +++ /dev/null @@ -1,61 +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 AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ - -#include - -#include -#include -#include - -namespace autoware::qp_interface -{ -class QPInterface -{ -public: - explicit QPInterface(const bool enable_warm_start) : enable_warm_start_(enable_warm_start) {} - - std::vector optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - virtual bool isSolved() const = 0; - virtual int getIterationNumber() const = 0; - virtual std::string getStatus() const = 0; - - virtual void updateEpsAbs([[maybe_unused]] const double eps_abs) = 0; - virtual void updateEpsRel([[maybe_unused]] const double eps_rel) = 0; - virtual void updateVerbose([[maybe_unused]] const bool verbose) {} - -protected: - bool enable_warm_start_{false}; - - void initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - virtual void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) = 0; - - virtual std::vector optimizeImpl() = 0; - - std::optional variables_num_{std::nullopt}; - std::optional constraints_num_{std::nullopt}; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/package.xml b/common/autoware_qp_interface/package.xml deleted file mode 100644 index b61d03a36db72..0000000000000 --- a/common/autoware_qp_interface/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - autoware_qp_interface - 0.40.0 - Interface for the QP solvers - Takayuki Murooka - Fumiya Watanabe - Maxime CLEMENT - Satoshi Ota - Apache 2.0 - - ament_cmake_auto - autoware_cmake - - eigen - osqp_vendor - proxsuite - rclcpp - rclcpp_components - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - eigen - - - ament_cmake - - diff --git a/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp b/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp deleted file mode 100644 index 15314a9e4a5fa..0000000000000 --- a/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp +++ /dev/null @@ -1,134 +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. - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" - -#include -#include - -#include -#include -#include - -namespace autoware::qp_interface -{ -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i < rows; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - if (rows != cols) { - throw std::invalid_argument("Matrix must be square (n, n)"); - } - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - Eigen::Index trap_last_idx = 0; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i <= trap_last_idx; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - trap_last_idx += 1; - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -void printCSCMatrix(const CSC_Matrix & csc_mat) -{ - std::cout << "["; - for (const c_float & val : csc_mat.vals_) { - std::cout << val << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & row : csc_mat.row_idxs_) { - std::cout << row << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & col : csc_mat.col_idxs_) { - std::cout << col << ", "; - } - std::cout << "]\n"; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/osqp_interface.cpp b/common/autoware_qp_interface/src/osqp_interface.cpp deleted file mode 100644 index fbb8e71f4c251..0000000000000 --- a/common/autoware_qp_interface/src/osqp_interface.cpp +++ /dev/null @@ -1,394 +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. - -#include "autoware/qp_interface/osqp_interface.hpp" - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" - -#include - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -OSQPInterface::OSQPInterface( - const bool enable_warm_start, const int max_iteration, const c_float eps_abs, - const c_float eps_rel, const bool polish, const bool verbose) -: QPInterface(enable_warm_start), work_{nullptr, OSQPWorkspaceDeleter} -{ - settings_ = std::make_unique(); - data_ = std::make_unique(); - - if (settings_) { - osqp_set_default_settings(settings_.get()); - settings_->alpha = 1.6; // Change alpha parameter - settings_->eps_rel = eps_rel; - settings_->eps_abs = eps_abs; - settings_->eps_prim_inf = 1.0E-4; - settings_->eps_dual_inf = 1.0E-4; - settings_->warm_start = enable_warm_start; - settings_->max_iter = max_iteration; - settings_->verbose = verbose; - settings_->polish = polish; - } - exitflag_ = 0; -} - -OSQPInterface::OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const bool enable_warm_start, - const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const bool enable_warm_start, - const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) -{ - initializeCSCProblemImpl(P, A, q, l, u); -} - -OSQPInterface::~OSQPInterface() -{ - if (data_->P) free(data_->P); - if (data_->A) free(data_->A); -} - -void OSQPInterface::initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - initializeCSCProblemImpl(P_csc, A_csc, q, l, u); -} - -void OSQPInterface::initializeCSCProblemImpl( - CSC_Matrix P_csc, CSC_Matrix A_csc, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - // Dynamic float arrays - std::vector q_tmp(q.begin(), q.end()); - std::vector l_tmp(l.begin(), l.end()); - std::vector u_tmp(u.begin(), u.end()); - double * q_dyn = q_tmp.data(); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - - /********************** - * OBJECTIVE FUNCTION - **********************/ - param_n_ = static_cast(q.size()); - data_->m = static_cast(l.size()); - - /***************** - * POPULATE DATA - *****************/ - data_->n = param_n_; - if (data_->P) free(data_->P); - data_->P = csc_matrix( - data_->n, data_->n, static_cast(P_csc.vals_.size()), P_csc.vals_.data(), - P_csc.row_idxs_.data(), P_csc.col_idxs_.data()); - data_->q = q_dyn; - if (data_->A) free(data_->A); - data_->A = csc_matrix( - data_->m, data_->n, static_cast(A_csc.vals_.size()), A_csc.vals_.data(), - A_csc.row_idxs_.data(), A_csc.col_idxs_.data()); - data_->l = l_dyn; - data_->u = u_dyn; - - // Setup workspace - OSQPWorkspace * workspace; - exitflag_ = osqp_setup(&workspace, data_.get(), settings_.get()); - work_.reset(workspace); - work__initialized = true; -} - -void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept -{ - if (ptr != nullptr) { - osqp_cleanup(ptr); - } -} - -void OSQPInterface::updateEpsAbs(const double eps_abs) -{ - settings_->eps_abs = eps_abs; // for default setting - if (work__initialized) { - osqp_update_eps_abs(work_.get(), eps_abs); // for current work - } -} - -void OSQPInterface::updateEpsRel(const double eps_rel) -{ - settings_->eps_rel = eps_rel; // for default setting - if (work__initialized) { - osqp_update_eps_rel(work_.get(), eps_rel); // for current work - } -} - -void OSQPInterface::updateMaxIter(const int max_iter) -{ - settings_->max_iter = max_iter; // for default setting - if (work__initialized) { - osqp_update_max_iter(work_.get(), max_iter); // for current work - } -} - -void OSQPInterface::updateVerbose(const bool is_verbose) -{ - settings_->verbose = is_verbose; // for default setting - if (work__initialized) { - osqp_update_verbose(work_.get(), is_verbose); // for current work - } -} - -void OSQPInterface::updateRhoInterval(const int rho_interval) -{ - settings_->adaptive_rho_interval = rho_interval; // for default setting -} - -void OSQPInterface::updateRho(const double rho) -{ - settings_->rho = rho; - if (work__initialized) { - osqp_update_rho(work_.get(), rho); - } -} - -void OSQPInterface::updateAlpha(const double alpha) -{ - settings_->alpha = alpha; - if (work__initialized) { - osqp_update_alpha(work_.get(), alpha); - } -} - -void OSQPInterface::updateScaling(const int scaling) -{ - settings_->scaling = scaling; -} - -void OSQPInterface::updatePolish(const bool polish) -{ - settings_->polish = polish; - if (work__initialized) { - osqp_update_polish(work_.get(), polish); - } -} - -void OSQPInterface::updatePolishRefinementIteration(const int polish_refine_iter) -{ - if (polish_refine_iter < 0) { - std::cerr << "Polish refinement iterations must be positive" << std::endl; - return; - } - - settings_->polish_refine_iter = polish_refine_iter; - if (work__initialized) { - osqp_update_polish_refine_iter(work_.get(), polish_refine_iter); - } -} - -void OSQPInterface::updateCheckTermination(const int check_termination) -{ - if (check_termination < 0) { - std::cerr << "Check termination must be positive" << std::endl; - return; - } - - settings_->check_termination = check_termination; - if (work__initialized) { - osqp_update_check_termination(work_.get(), check_termination); - } -} - -bool OSQPInterface::setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables) -{ - return setPrimalVariables(primal_variables) && setDualVariables(dual_variables); -} - -bool OSQPInterface::setPrimalVariables(const std::vector & primal_variables) -{ - if (!work__initialized) { - return false; - } - - const auto result = osqp_warm_start_x(work_.get(), primal_variables.data()); - if (result != 0) { - std::cerr << "Failed to set primal variables for warm start" << std::endl; - return false; - } - - return true; -} - -bool OSQPInterface::setDualVariables(const std::vector & dual_variables) -{ - if (!work__initialized) { - return false; - } - - const auto result = osqp_warm_start_y(work_.get(), dual_variables.data()); - if (result != 0) { - std::cerr << "Failed to set dual variables for warm start" << std::endl; - return false; - } - - return true; -} - -void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) -{ - /* - // Transform 'P' into an 'upper trapezoidal matrix' - Eigen::MatrixXd P_trap = P_new.triangularView(); - // Transform 'P' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix P_sparse = P_trap.sparseView(); - double *P_val_ptr = P_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int P_elem_N = P_sparse.nonZeros(); - */ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P_new); - osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); -} - -void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) -{ - osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); -} - -void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) -{ - /* - // Transform 'A' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix A_sparse = A_new.sparseView(); - double *A_val_ptr = A_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int A_elem_N = A_sparse.nonZeros(); - */ - CSC_Matrix A_csc = calCSCMatrix(A_new); - osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); - return; -} - -void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) -{ - osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); -} - -void OSQPInterface::updateQ(const std::vector & q_new) -{ - std::vector q_tmp(q_new.begin(), q_new.end()); - double * q_dyn = q_tmp.data(); - osqp_update_lin_cost(work_.get(), q_dyn); -} - -void OSQPInterface::updateL(const std::vector & l_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - double * l_dyn = l_tmp.data(); - osqp_update_lower_bound(work_.get(), l_dyn); -} - -void OSQPInterface::updateU(const std::vector & u_new) -{ - std::vector u_tmp(u_new.begin(), u_new.end()); - double * u_dyn = u_tmp.data(); - osqp_update_upper_bound(work_.get(), u_dyn); -} - -void OSQPInterface::updateBounds( - const std::vector & l_new, const std::vector & u_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - std::vector u_tmp(u_new.begin(), u_new.end()); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - osqp_update_bounds(work_.get(), l_dyn, u_dyn); -} - -int OSQPInterface::getIterationNumber() const -{ - return work_->info->iter; -} - -std::string OSQPInterface::getStatus() const -{ - return "OSQP_SOLVED"; -} - -bool OSQPInterface::isSolved() const -{ - return latest_work_info_.status_val == 1; -} - -int OSQPInterface::getPolishStatus() const -{ - return static_cast(latest_work_info_.status_polish); -} - -std::vector OSQPInterface::getDualSolution() const -{ - double * sol_y = work_->solution->y; - std::vector dual_solution(sol_y, sol_y + data_->m); - return dual_solution; -} - -std::vector OSQPInterface::optimizeImpl() -{ - osqp_solve(work_.get()); - - double * sol_x = work_->solution->x; - std::vector sol_primal(sol_x, sol_x + param_n_); - - latest_work_info_ = *(work_->info); - - if (!enable_warm_start_) { - work_.reset(); - work__initialized = false; - } - - return sol_primal; -} - -std::vector OSQPInterface::optimize( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - initializeCSCProblemImpl(P, A, q, l, u); - const auto result = optimizeImpl(); - - // show polish status if not successful - const int status_polish = static_cast(latest_work_info_.status_polish); - if (status_polish != 1) { - const auto msg = status_polish == 0 ? "unperformed" - : status_polish == -1 ? "unsuccessful" - : "unknown"; - std::cerr << "osqp polish process failed : " << msg << ". The result may be inaccurate" - << std::endl; - } - - return result; -} - -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/proxqp_interface.cpp b/common/autoware_qp_interface/src/proxqp_interface.cpp deleted file mode 100644 index a0ebbf0db0510..0000000000000 --- a/common/autoware_qp_interface/src/proxqp_interface.cpp +++ /dev/null @@ -1,157 +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. - -#include "autoware/qp_interface/proxqp_interface.hpp" - -#include -#include -#include - -namespace autoware::qp_interface -{ -using proxsuite::proxqp::QPSolverOutput; - -ProxQPInterface::ProxQPInterface( - const bool enable_warm_start, const int max_iteration, const double eps_abs, const double eps_rel, - const bool verbose) -: QPInterface(enable_warm_start) -{ - settings_.max_iter = max_iteration; - settings_.eps_abs = eps_abs; - settings_.eps_rel = eps_rel; - settings_.verbose = verbose; -} - -void ProxQPInterface::initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - const size_t variables_num = q.size(); - const size_t constraints_num = l.size(); - - const bool enable_warm_start = [&]() { - if ( - !enable_warm_start_ // Warm start is designated - || !qp_ptr_ // QP pointer is initialized - // The number of variables is the same as the previous one. - || !variables_num_ || - *variables_num_ != variables_num - // The number of constraints is the same as the previous one - || !constraints_num_ || *constraints_num_ != constraints_num) { - return false; - } - return true; - }(); - - if (!enable_warm_start) { - qp_ptr_ = std::make_shared>( - variables_num, 0, constraints_num); - } - - settings_.initial_guess = - enable_warm_start ? proxsuite::proxqp::InitialGuessStatus::WARM_START_WITH_PREVIOUS_RESULT - : proxsuite::proxqp::InitialGuessStatus::NO_INITIAL_GUESS; - - qp_ptr_->settings = settings_; - - Eigen::SparseMatrix P_sparse(variables_num, constraints_num); - P_sparse = P.sparseView(); - - // NOTE: const std vector cannot be converted to eigen vector - std::vector non_const_q = q; - Eigen::VectorXd eigen_q = - Eigen::Map(non_const_q.data(), non_const_q.size()); - std::vector l_std_vec = l; - Eigen::VectorXd eigen_l = - Eigen::Map(l_std_vec.data(), l_std_vec.size()); - std::vector u_std_vec = u; - Eigen::VectorXd eigen_u = - Eigen::Map(u_std_vec.data(), u_std_vec.size()); - - if (enable_warm_start) { - qp_ptr_->update( - P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); - } else { - qp_ptr_->init( - P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); - } -} - -void ProxQPInterface::updateEpsAbs(const double eps_abs) -{ - settings_.eps_abs = eps_abs; -} - -void ProxQPInterface::updateEpsRel(const double eps_rel) -{ - settings_.eps_rel = eps_rel; -} - -void ProxQPInterface::updateVerbose(const bool is_verbose) -{ - settings_.verbose = is_verbose; -} - -bool ProxQPInterface::isSolved() const -{ - if (qp_ptr_) { - return qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED; - } - return false; -} - -int ProxQPInterface::getIterationNumber() const -{ - if (qp_ptr_) { - return qp_ptr_->results.info.iter; - } - return 0; -} - -std::string ProxQPInterface::getStatus() const -{ - if (qp_ptr_) { - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED) { - return "PROXQP_SOLVED"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_MAX_ITER_REACHED) { - return "PROXQP_MAX_ITER_REACHED"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_PRIMAL_INFEASIBLE) { - return "PROXQP_PRIMAL_INFEASIBLE"; - } - // if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE) { - // return "PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE"; - // } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_DUAL_INFEASIBLE) { - return "PROXQP_DUAL_INFEASIBLE"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_NOT_RUN) { - return "PROXQP_NOT_RUN"; - } - } - return "None"; -} - -std::vector ProxQPInterface::optimizeImpl() -{ - qp_ptr_->solve(); - - std::vector result; - for (Eigen::Index i = 0; i < qp_ptr_->results.x.size(); ++i) { - result.push_back(qp_ptr_->results.x[i]); - } - return result; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/qp_interface.cpp b/common/autoware_qp_interface/src/qp_interface.cpp deleted file mode 100644 index f01e57772dc4f..0000000000000 --- a/common/autoware_qp_interface/src/qp_interface.cpp +++ /dev/null @@ -1,70 +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. - -#include "autoware/qp_interface/qp_interface.hpp" - -#include -#include -#include - -namespace autoware::qp_interface -{ -void QPInterface::initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // check if arguments are valid - std::stringstream ss; - if (P.rows() != P.cols()) { - ss << "P.rows() and P.cols() are not the same. P.rows() = " << P.rows() - << ", P.cols() = " << P.cols(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != static_cast(q.size())) { - ss << "P.rows() and q.size() are not the same. P.rows() = " << P.rows() - << ", q.size() = " << q.size(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != A.cols()) { - ss << "P.rows() and A.cols() are not the same. P.rows() = " << P.rows() - << ", A.cols() = " << A.cols(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(l.size())) { - ss << "A.rows() and l.size() are not the same. A.rows() = " << A.rows() - << ", l.size() = " << l.size(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(u.size())) { - ss << "A.rows() and u.size() are not the same. A.rows() = " << A.rows() - << ", u.size() = " << u.size(); - throw std::invalid_argument(ss.str()); - } - - initializeProblemImpl(P, A, q, l, u); - - variables_num_ = q.size(); - constraints_num_ = l.size(); -} - -std::vector QPInterface::optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - initializeProblem(P, A, q, l, u); - const auto result = optimizeImpl(); - - return result; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp b/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp deleted file mode 100644 index 1f377a1a24535..0000000000000 --- a/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp +++ /dev/null @@ -1,181 +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. - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -TEST(TestCscMatrixConv, Nominal) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::CSC_Matrix; - - Eigen::MatrixXd rect1(1, 2); - rect1 << 0.0, 1.0; - - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - ASSERT_EQ(rect_m1.vals_.size(), size_t(1)); - EXPECT_EQ(rect_m1.vals_[0], 1.0); - ASSERT_EQ(rect_m1.row_idxs_.size(), size_t(1)); - EXPECT_EQ(rect_m1.row_idxs_[0], c_int(0)); - ASSERT_EQ(rect_m1.col_idxs_.size(), size_t(3)); // nb of columns + 1 - EXPECT_EQ(rect_m1.col_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m1.col_idxs_[1], c_int(0)); - EXPECT_EQ(rect_m1.col_idxs_[2], c_int(1)); - - Eigen::MatrixXd rect2(2, 4); - rect2 << 1.0, 0.0, 3.0, 0.0, 0.0, 6.0, 7.0, 0.0; - - const CSC_Matrix rect_m2 = calCSCMatrix(rect2); - ASSERT_EQ(rect_m2.vals_.size(), size_t(4)); - EXPECT_EQ(rect_m2.vals_[0], 1.0); - EXPECT_EQ(rect_m2.vals_[1], 6.0); - EXPECT_EQ(rect_m2.vals_[2], 3.0); - EXPECT_EQ(rect_m2.vals_[3], 7.0); - ASSERT_EQ(rect_m2.row_idxs_.size(), size_t(4)); - EXPECT_EQ(rect_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(rect_m2.row_idxs_[2], c_int(0)); - EXPECT_EQ(rect_m2.row_idxs_[3], c_int(1)); - ASSERT_EQ(rect_m2.col_idxs_.size(), size_t(5)); // nb of columns + 1 - EXPECT_EQ(rect_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m2.col_idxs_[1], c_int(1)); - EXPECT_EQ(rect_m2.col_idxs_[2], c_int(2)); - EXPECT_EQ(rect_m2.col_idxs_[3], c_int(4)); - EXPECT_EQ(rect_m2.col_idxs_[4], c_int(4)); - - // Example from http://netlib.org/linalg/html_templates/node92.html - Eigen::MatrixXd square2(6, 6); - square2 << 10.0, 0.0, 0.0, 0.0, -2.0, 0.0, 3.0, 9.0, 0.0, 0.0, 0.0, 3.0, 0.0, 7.0, 8.0, 7.0, 0.0, - 0.0, 3.0, 0.0, 8.0, 7.0, 5.0, 0.0, 0.0, 8.0, 0.0, 9.0, 9.0, 13.0, 0.0, 4.0, 0.0, 0.0, 2.0, -1.0; - - const CSC_Matrix square_m2 = calCSCMatrix(square2); - ASSERT_EQ(square_m2.vals_.size(), size_t(19)); - EXPECT_EQ(square_m2.vals_[0], 10.0); - EXPECT_EQ(square_m2.vals_[1], 3.0); - EXPECT_EQ(square_m2.vals_[2], 3.0); - EXPECT_EQ(square_m2.vals_[3], 9.0); - EXPECT_EQ(square_m2.vals_[4], 7.0); - EXPECT_EQ(square_m2.vals_[5], 8.0); - EXPECT_EQ(square_m2.vals_[6], 4.0); - EXPECT_EQ(square_m2.vals_[7], 8.0); - EXPECT_EQ(square_m2.vals_[8], 8.0); - EXPECT_EQ(square_m2.vals_[9], 7.0); - EXPECT_EQ(square_m2.vals_[10], 7.0); - EXPECT_EQ(square_m2.vals_[11], 9.0); - EXPECT_EQ(square_m2.vals_[12], -2.0); - EXPECT_EQ(square_m2.vals_[13], 5.0); - EXPECT_EQ(square_m2.vals_[14], 9.0); - EXPECT_EQ(square_m2.vals_[15], 2.0); - EXPECT_EQ(square_m2.vals_[16], 3.0); - EXPECT_EQ(square_m2.vals_[17], 13.0); - EXPECT_EQ(square_m2.vals_[18], -1.0); - ASSERT_EQ(square_m2.row_idxs_.size(), size_t(19)); - EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[2], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[3], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[4], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[5], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[6], c_int(5)); - EXPECT_EQ(square_m2.row_idxs_[7], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[8], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[9], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[10], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[11], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[12], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[13], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[14], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[15], c_int(5)); - EXPECT_EQ(square_m2.row_idxs_[16], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[17], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[18], c_int(5)); - ASSERT_EQ(square_m2.col_idxs_.size(), size_t(7)); // nb of columns + 1 - EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[1], c_int(3)); - EXPECT_EQ(square_m2.col_idxs_[2], c_int(7)); - EXPECT_EQ(square_m2.col_idxs_[3], c_int(9)); - EXPECT_EQ(square_m2.col_idxs_[4], c_int(12)); - EXPECT_EQ(square_m2.col_idxs_[5], c_int(16)); - EXPECT_EQ(square_m2.col_idxs_[6], c_int(19)); -} -TEST(TestCscMatrixConv, Trapezoidal) -{ - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd square2(3, 3); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - square2 << 0.0, 2.0, 0.0, 4.0, 5.0, 6.0, 0.0, 0.0, 0.0; - rect1 << 0.0, 1.0; - - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - // Trapezoidal: skip the lower left triangle (2.0 in this example) - ASSERT_EQ(square_m1.vals_.size(), size_t(3)); - EXPECT_EQ(square_m1.vals_[0], 1.0); - EXPECT_EQ(square_m1.vals_[1], 2.0); - EXPECT_EQ(square_m1.vals_[2], 4.0); - ASSERT_EQ(square_m1.row_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m1.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m1.row_idxs_[1], c_int(0)); - EXPECT_EQ(square_m1.row_idxs_[2], c_int(1)); - ASSERT_EQ(square_m1.col_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m1.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m1.col_idxs_[1], c_int(1)); - EXPECT_EQ(square_m1.col_idxs_[2], c_int(3)); - - const CSC_Matrix square_m2 = calCSCMatrixTrapezoidal(square2); - ASSERT_EQ(square_m2.vals_.size(), size_t(3)); - EXPECT_EQ(square_m2.vals_[0], 2.0); - EXPECT_EQ(square_m2.vals_[1], 5.0); - EXPECT_EQ(square_m2.vals_[2], 6.0); - ASSERT_EQ(square_m2.row_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[2], c_int(1)); - ASSERT_EQ(square_m2.col_idxs_.size(), size_t(4)); - EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[1], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[2], c_int(2)); - EXPECT_EQ(square_m2.col_idxs_[3], c_int(3)); - - try { - const CSC_Matrix rect_m1 = calCSCMatrixTrapezoidal(rect1); - FAIL() << "calCSCMatrixTrapezoidal should fail with non-square inputs"; - } catch (const std::invalid_argument & e) { - EXPECT_EQ(e.what(), std::string("Matrix must be square (n, n)")); - } -} -TEST(TestCscMatrixConv, Print) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - using autoware::qp_interface::printCSCMatrix; - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - rect1 << 0.0, 1.0; - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - printCSCMatrix(square_m1); - printCSCMatrix(rect_m1); -} diff --git a/common/autoware_qp_interface/test/test_osqp_interface.cpp b/common/autoware_qp_interface/test/test_osqp_interface.cpp deleted file mode 100644 index f97cc2888afa0..0000000000000 --- a/common/autoware_qp_interface/test/test_osqp_interface.cpp +++ /dev/null @@ -1,170 +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. - -#include "autoware/qp_interface/osqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include -#include - -namespace -{ -// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestOsqpInterface, BasicQp) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - - auto check_result = - [](const auto & solution, const std::string & status, const int polish_status) { - EXPECT_EQ(status, "OSQP_SOLVED"); - EXPECT_EQ(polish_status, 1); - - static const auto ep = 1.0e-8; - - ASSERT_EQ(solution.size(), size_t(2)); - EXPECT_NEAR(solution[0], 0.3, ep); - EXPECT_NEAR(solution[1], 0.7, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -autoware::qp_interface::OSQP_INF}; - const std::vector u = {1.0, 0.7, 0.7, autoware::qp_interface::OSQP_INF}; - - { - // Define problem during optimization - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - // Define problem during initialization - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem - Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - osqp.QPInterface::optimize(P_ini, A_ini, q_ini, l_ini, u_ini); - } - - { - // Define problem during initialization with csc matrix - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - // add warm startup - { - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(true, 4000, 1e-6); // enable warm start - osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - { - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - - osqp.updateCheckTermination(1); - const auto primal_val = solution; - const auto dual_val = osqp.getDualSolution(); - for (size_t i = 0; i < primal_val.size(); ++i) { - std::cerr << primal_val.at(i) << std::endl; - } - osqp.setWarmStart(primal_val, dual_val); - } - - { - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - // NOTE: This should be true, but currently optimize function reset the workspace, which - // disables warm start. - // EXPECT_EQ(osqp.getTakenIter(), 1); - } -} -} // namespace diff --git a/common/autoware_qp_interface/test/test_proxqp_interface.cpp b/common/autoware_qp_interface/test/test_proxqp_interface.cpp deleted file mode 100644 index e47af10c7aabd..0000000000000 --- a/common/autoware_qp_interface/test/test_proxqp_interface.cpp +++ /dev/null @@ -1,85 +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. - -#include "autoware/qp_interface/proxqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include -#include - -namespace -{ -// Problem taken from -// https://github.com/proxqp/proxqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestProxqpInterface, BasicQp) -{ - auto check_result = [](const auto & solution, const std::string & status) { - EXPECT_EQ(status, "PROXQP_SOLVED"); - - static const auto ep = 1.0e-8; - ASSERT_EQ(solution.size(), size_t(2)); - EXPECT_NEAR(solution[0], 0.3, ep); - EXPECT_NEAR(solution[1], 0.7, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -std::numeric_limits::max()}; - const std::vector u = {1.0, 0.7, 0.7, std::numeric_limits::max()}; - - { - // Define problem during optimization - autoware::qp_interface::ProxQPInterface proxqp(false, 4000, 1e-9, 1e-9, false); - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - } - - { - // Define problem during optimization with warm start - autoware::qp_interface::ProxQPInterface proxqp(true, 4000, 1e-9, 1e-9, false); - { - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - EXPECT_NE(proxqp.getIterationNumber(), 1); - } - { - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - EXPECT_EQ(proxqp.getIterationNumber(), 0); - } - } -} -} // namespace From 997146c94c4f5eaa0547206981b1566879c0a266 Mon Sep 17 00:00:00 2001 From: NorahXiong <103234047+NorahXiong@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:11:09 +0800 Subject: [PATCH 37/59] feat(autoware_osqp_interface): porting autoware_osqp_interface package to autoware.core (#9890) Signed-off-by: NorahXiong --- common/autoware_osqp_interface/CHANGELOG.rst | 51 -- common/autoware_osqp_interface/CMakeLists.txt | 58 --- .../design/osqp_interface-design.md | 70 --- .../osqp_interface/csc_matrix_conv.hpp | 47 -- .../osqp_interface/osqp_interface.hpp | 194 -------- .../osqp_interface/visibility_control.hpp | 37 -- common/autoware_osqp_interface/package.xml | 29 -- .../src/csc_matrix_conv.cpp | 135 ------ .../src/osqp_interface.cpp | 435 ------------------ .../test/test_csc_matrix_conv.cpp | 181 -------- .../test/test_osqp_interface.cpp | 164 ------- 11 files changed, 1401 deletions(-) delete mode 100644 common/autoware_osqp_interface/CHANGELOG.rst delete mode 100644 common/autoware_osqp_interface/CMakeLists.txt delete mode 100644 common/autoware_osqp_interface/design/osqp_interface-design.md delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp delete mode 100644 common/autoware_osqp_interface/package.xml delete mode 100644 common/autoware_osqp_interface/src/csc_matrix_conv.cpp delete mode 100644 common/autoware_osqp_interface/src/osqp_interface.cpp delete mode 100644 common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp delete mode 100644 common/autoware_osqp_interface/test/test_osqp_interface.cpp diff --git a/common/autoware_osqp_interface/CHANGELOG.rst b/common/autoware_osqp_interface/CHANGELOG.rst deleted file mode 100644 index d400b77f4bf61..0000000000000 --- a/common/autoware_osqp_interface/CHANGELOG.rst +++ /dev/null @@ -1,51 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_osqp_interface -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(osqp_interface): added autoware prefix to osqp_interface (`#8958 `_) -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/common/autoware_osqp_interface/CMakeLists.txt b/common/autoware_osqp_interface/CMakeLists.txt deleted file mode 100644 index b770af659e52a..0000000000000 --- a/common/autoware_osqp_interface/CMakeLists.txt +++ /dev/null @@ -1,58 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_osqp_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Eigen3 REQUIRED) - -# after find_package(osqp_vendor) in ament_auto_find_build_dependencies -find_package(osqp REQUIRED) -get_target_property(OSQP_INCLUDE_SUB_DIR osqp::osqp INTERFACE_INCLUDE_DIRECTORIES) -get_filename_component(OSQP_INCLUDE_DIR ${OSQP_INCLUDE_SUB_DIR} PATH) - -set(OSQP_INTERFACE_LIB_SRC - src/csc_matrix_conv.cpp - src/osqp_interface.cpp -) - -set(OSQP_INTERFACE_LIB_HEADERS - include/autoware/osqp_interface/csc_matrix_conv.hpp - include/autoware/osqp_interface/osqp_interface.hpp - include/autoware/osqp_interface/visibility_control.hpp -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - ${OSQP_INTERFACE_LIB_SRC} - ${OSQP_INTERFACE_LIB_HEADERS} -) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) - -target_include_directories(${PROJECT_NAME} - SYSTEM PUBLIC - "${OSQP_INCLUDE_DIR}" - "${EIGEN3_INCLUDE_DIR}" -) - -ament_target_dependencies(${PROJECT_NAME} - Eigen3 - osqp_vendor -) - -# crucial so downstream package builds because autoware_osqp_interface exposes osqp.hpp -ament_export_include_directories("${OSQP_INCLUDE_DIR}") -# crucial so the linking order is correct in a downstream package: libosqp_interface.a should come before libosqp.a -ament_export_libraries(osqp::osqp) - -if(BUILD_TESTING) - set(TEST_SOURCES - test/test_osqp_interface.cpp - test/test_csc_matrix_conv.cpp - ) - set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) - target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) -endif() - -ament_auto_package(INSTALL_TO_SHARE -) diff --git a/common/autoware_osqp_interface/design/osqp_interface-design.md b/common/autoware_osqp_interface/design/osqp_interface-design.md deleted file mode 100644 index 887a4b4d9af3f..0000000000000 --- a/common/autoware_osqp_interface/design/osqp_interface-design.md +++ /dev/null @@ -1,70 +0,0 @@ -# Interface for the OSQP library - -This is the design document for the `autoware_osqp_interface` package. - -## Purpose / Use cases - - - - -This packages provides a C++ interface for the [OSQP library](https://osqp.org/docs/solver/index.html). - -## Design - - - - -The class `OSQPInterface` takes a problem formulation as Eigen matrices and vectors, converts these objects into -C-style Compressed-Column-Sparse matrices and dynamic arrays, loads the data into the OSQP workspace dataholder, and runs the optimizer. - -## Inputs / Outputs / API - - - - -The interface can be used in several ways: - -1. Initialize the interface WITHOUT data. Load the problem formulation at the optimization call. - - ```cpp - osqp_interface = OSQPInterface(); - osqp_interface.optimize(P, A, q, l, u); - ``` - -2. Initialize the interface WITH data. - - ```cpp - osqp_interface = OSQPInterface(P, A, q, l, u); - osqp_interface.optimize(); - ``` - -3. WARM START OPTIMIZATION by modifying the problem formulation between optimization runs. - - ```cpp - osqp_interface = OSQPInterface(P, A, q, l, u); - osqp_interface.optimize(); - osqp.initializeProblem(P_new, A_new, q_new, l_new, u_new); - osqp_interface.optimize(); - ``` - - The optimization results are returned as a vector by the optimization function. - - ```cpp - std::tuple, std::vector> result = osqp_interface.optimize(); - std::vector param = std::get<0>(result); - double x_0 = param[0]; - double x_1 = param[1]; - ``` - -## References / External links - - - -- OSQP library: - -## Related issues - - diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp deleted file mode 100644 index 8c21553152d70..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ -#define AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ - -#include "autoware/osqp_interface/visibility_control.hpp" -#include "osqp/glob_opts.h" // for 'c_int' type ('long' or 'long long') - -#include - -#include - -namespace autoware::osqp_interface -{ -/// \brief Compressed-Column-Sparse Matrix -struct OSQP_INTERFACE_PUBLIC CSC_Matrix -{ - /// Vector of non-zero values. Ex: [4,1,1,2] - std::vector m_vals; - /// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner') - std::vector m_row_idxs; - /// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer') - std::vector m_col_idxs; -}; - -/// \brief Calculate CSC matrix from Eigen matrix -OSQP_INTERFACE_PUBLIC CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat); -/// \brief Calculate upper trapezoidal CSC matrix from square Eigen matrix -OSQP_INTERFACE_PUBLIC CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat); -/// \brief Print the given CSC matrix to the standard output -OSQP_INTERFACE_PUBLIC void printCSCMatrix(const CSC_Matrix & csc_mat); - -} // namespace autoware::osqp_interface - -#endif // AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp deleted file mode 100644 index ff3013bd61514..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ -#define AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "autoware/osqp_interface/visibility_control.hpp" -#include "osqp/osqp.h" - -#include -#include - -#include -#include -#include -#include -#include - -namespace autoware::osqp_interface -{ -constexpr c_float INF = 1e30; - -/** - * Implementation of a native C++ interface for the OSQP solver. - * - */ -class OSQP_INTERFACE_PUBLIC OSQPInterface -{ -private: - std::unique_ptr> m_work; - std::unique_ptr m_settings; - std::unique_ptr m_data; - // store last work info since work is cleaned up at every execution to prevent memory leak. - OSQPInfo m_latest_work_info; - // Number of parameters to optimize - int64_t m_param_n; - // Flag to check if the current work exists - bool m_work_initialized = false; - // Exitflag - int64_t m_exitflag; - - // Runs the solver on the stored problem. - std::tuple, std::vector, int64_t, int64_t, int64_t> solve(); - - static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; - -public: - /// \brief Constructor without problem formulation - explicit OSQPInterface( - const c_float eps_abs = std::numeric_limits::epsilon(), const bool polish = true); - /// \brief Constructor with problem setup - /// \param P: (n,n) matrix defining relations between parameters. - /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q: (n) vector defining the linear cost of the problem. - /// \param l: (m) vector defining the lower bound problem constraint. - /// \param u: (m) vector defining the upper bound problem constraint. - /// \param eps_abs: Absolute convergence tolerance. - OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs); - OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs); - ~OSQPInterface(); - - /**************** - * OPTIMIZATION - ****************/ - /// \brief Solves the stored convex quadratic program (QP) problem using the OSQP solver. - // - /// \return The function returns a tuple containing the solution as two float vectors. - /// \return The first element of the tuple contains the 'primal' solution. - /// \return The second element contains the 'lagrange multiplier' solution. - /// \return The third element contains an integer with solver polish status information. - - /// \details How to use: - /// \details 1. Generate the Eigen matrices P, A and vectors q, l, u according to the problem. - /// \details 2. Initialize the interface and set up the problem. - /// \details osqp_interface = OSQPInterface(P, A, q, l, u, 1e-6); - /// \details 3. Call the optimization function. - /// \details std::tuple, std::vector> result; - /// \details result = osqp_interface.optimize(); - /// \details 4. Access the optimized parameters. - /// \details std::vector param = std::get<0>(result); - /// \details double x_0 = param[0]; - /// \details double x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t, int64_t> optimize(); - - /// \brief Solves convex quadratic programs (QPs) using the OSQP solver. - /// \return The function returns a tuple containing the solution as two float vectors. - /// \return The first element of the tuple contains the 'primal' solution. - /// \return The second element contains the 'lagrange multiplier' solution. - /// \return The third element contains an integer with solver polish status information. - /// \details How to use: - /// \details 1. Generate the Eigen matrices P, A and vectors q, l, u according to the problem. - /// \details 2. Initialize the interface. - /// \details osqp_interface = OSQPInterface(1e-6); - /// \details 3. Call the optimization function with the problem formulation. - /// \details std::tuple, std::vector> result; - /// \details result = osqp_interface.optimize(P, A, q, l, u, 1e-6); - /// \details 4. Access the optimized parameters. - /// \details std::vector param = std::get<0>(result); - /// \details double x_0 = param[0]; - /// \details double x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t, int64_t> optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - /// \brief Converts the input data and sets up the workspace object. - /// \param P (n,n) matrix defining relations between parameters. - /// \param A (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q (n) vector defining the linear cost of the problem. - /// \param l (m) vector defining the lower bound problem constraint. - /// \param u (m) vector defining the upper bound problem constraint. - int64_t initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - int64_t initializeProblem( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - // Setter functions for warm start - bool setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables); - bool setPrimalVariables(const std::vector & primal_variables); - bool setDualVariables(const std::vector & dual_variables); - - // Updates problem parameters while keeping solution in memory. - // - // Args: - // P_new: (n,n) matrix defining relations between parameters. - // A_new: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - // q_new: (n) vector defining the linear cost of the problem. - // l_new: (m) vector defining the lower bound problem constraint. - // u_new: (m) vector defining the upper bound problem constraint. - void updateP(const Eigen::MatrixXd & P_new); - void updateCscP(const CSC_Matrix & P_csc); - void updateA(const Eigen::MatrixXd & A_new); - void updateCscA(const CSC_Matrix & A_csc); - void updateQ(const std::vector & q_new); - void updateL(const std::vector & l_new); - void updateU(const std::vector & u_new); - void updateBounds(const std::vector & l_new, const std::vector & u_new); - void updateEpsAbs(const double eps_abs); - void updateEpsRel(const double eps_rel); - void updateMaxIter(const int iter); - void updateVerbose(const bool verbose); - void updateRhoInterval(const int rho_interval); - void updateRho(const double rho); - void updateAlpha(const double alpha); - void updateScaling(const int scaling); - void updatePolish(const bool polish); - void updatePolishRefinementIteration(const int polish_refine_iter); - void updateCheckTermination(const int check_termination); - - /// \brief Get the number of iteration taken to solve the problem - inline int64_t getTakenIter() const { return static_cast(m_latest_work_info.iter); } - /// \brief Get the status message for the latest problem solved - inline std::string getStatusMessage() const - { - return static_cast(m_latest_work_info.status); - } - /// \brief Get the status value for the latest problem solved - inline int64_t getStatus() const { return static_cast(m_latest_work_info.status_val); } - /// \brief Get the status polish for the latest problem solved - inline int64_t getStatusPolish() const - { - return static_cast(m_latest_work_info.status_polish); - } - /// \brief Get the runtime of the latest problem solved - inline double getRunTime() const { return m_latest_work_info.run_time; } - /// \brief Get the objective value the latest problem solved - inline double getObjVal() const { return m_latest_work_info.obj_val; } - /// \brief Returns flag asserting interface condition (Healthy condition: 0). - inline int64_t getExitFlag() const { return m_exitflag; } - - void logUnsolvedStatus(const std::string & prefix_message = "") const; -}; - -} // namespace autoware::osqp_interface - -#endif // AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp deleted file mode 100644 index a6cdaa8a0a74e..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp +++ /dev/null @@ -1,37 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ -#define AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ - -//////////////////////////////////////////////////////////////////////////////// -#if defined(__WIN32) -#if defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#define OSQP_INTERFACE_PUBLIC __declspec(dllexport) -#define OSQP_INTERFACE_LOCAL -#else // defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#define OSQP_INTERFACE_PUBLIC __declspec(dllimport) -#define OSQP_INTERFACE_LOCAL -#endif // defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#elif defined(__linux__) -#define OSQP_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define OSQP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#elif defined(__APPLE__) -#define OSQP_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define OSQP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#else -#error "Unsupported Build Configuration" -#endif - -#endif // AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_osqp_interface/package.xml b/common/autoware_osqp_interface/package.xml deleted file mode 100644 index 92a2afeccc4e0..0000000000000 --- a/common/autoware_osqp_interface/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - autoware_osqp_interface - 0.40.0 - Interface for the OSQP solver - Maxime CLEMENT - Takayuki Murooka - Fumiya Watanabe - Satoshi Ota - Apache 2.0 - - ament_cmake_auto - autoware_cmake - - eigen - osqp_vendor - rclcpp - rclcpp_components - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - eigen - - - ament_cmake - - diff --git a/common/autoware_osqp_interface/src/csc_matrix_conv.cpp b/common/autoware_osqp_interface/src/csc_matrix_conv.cpp deleted file mode 100644 index c6e1a0a42d938..0000000000000 --- a/common/autoware_osqp_interface/src/csc_matrix_conv.cpp +++ /dev/null @@ -1,135 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" - -#include -#include - -#include -#include -#include - -namespace autoware::osqp_interface -{ -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i < rows; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - if (rows != cols) { - throw std::invalid_argument("Matrix must be square (n, n)"); - } - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - Eigen::Index trap_last_idx = 0; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i <= trap_last_idx; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - trap_last_idx += 1; - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -void printCSCMatrix(const CSC_Matrix & csc_mat) -{ - std::cout << "["; - for (const c_float & val : csc_mat.m_vals) { - std::cout << val << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & row : csc_mat.m_row_idxs) { - std::cout << row << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & col : csc_mat.m_col_idxs) { - std::cout << col << ", "; - } - std::cout << "]\n"; -} - -} // namespace autoware::osqp_interface diff --git a/common/autoware_osqp_interface/src/osqp_interface.cpp b/common/autoware_osqp_interface/src/osqp_interface.cpp deleted file mode 100644 index ceeae626222ca..0000000000000 --- a/common/autoware_osqp_interface/src/osqp_interface.cpp +++ /dev/null @@ -1,435 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/osqp_interface.hpp" - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "osqp/osqp.h" - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::osqp_interface -{ -OSQPInterface::OSQPInterface(const c_float eps_abs, const bool polish) -: m_work{nullptr, OSQPWorkspaceDeleter} -{ - m_settings = std::make_unique(); - m_data = std::make_unique(); - - if (m_settings) { - osqp_set_default_settings(m_settings.get()); - m_settings->alpha = 1.6; // Change alpha parameter - m_settings->eps_rel = 1.0E-4; - m_settings->eps_abs = eps_abs; - m_settings->eps_prim_inf = 1.0E-4; - m_settings->eps_dual_inf = 1.0E-4; - m_settings->warm_start = true; - m_settings->max_iter = 4000; - m_settings->verbose = false; - m_settings->polish = polish; - } - m_exitflag = 0; -} - -OSQPInterface::OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs) -: OSQPInterface(eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs) -: OSQPInterface(eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::~OSQPInterface() -{ - if (m_data->P) free(m_data->P); - if (m_data->A) free(m_data->A); -} - -void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept -{ - if (ptr != nullptr) { - osqp_cleanup(ptr); - } -} - -void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) -{ - /* - // Transform 'P' into an 'upper trapezoidal matrix' - Eigen::MatrixXd P_trap = P_new.triangularView(); - // Transform 'P' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix P_sparse = P_trap.sparseView(); - double *P_val_ptr = P_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int P_elem_N = P_sparse.nonZeros(); - */ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P_new); - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); -} - -void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) -{ - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); -} - -void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) -{ - /* - // Transform 'A' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix A_sparse = A_new.sparseView(); - double *A_val_ptr = A_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int A_elem_N = A_sparse.nonZeros(); - */ - CSC_Matrix A_csc = calCSCMatrix(A_new); - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); - return; -} - -void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) -{ - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); -} - -void OSQPInterface::updateQ(const std::vector & q_new) -{ - std::vector q_tmp(q_new.begin(), q_new.end()); - double * q_dyn = q_tmp.data(); - osqp_update_lin_cost(m_work.get(), q_dyn); -} - -void OSQPInterface::updateL(const std::vector & l_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - double * l_dyn = l_tmp.data(); - osqp_update_lower_bound(m_work.get(), l_dyn); -} - -void OSQPInterface::updateU(const std::vector & u_new) -{ - std::vector u_tmp(u_new.begin(), u_new.end()); - double * u_dyn = u_tmp.data(); - osqp_update_upper_bound(m_work.get(), u_dyn); -} - -void OSQPInterface::updateBounds( - const std::vector & l_new, const std::vector & u_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - std::vector u_tmp(u_new.begin(), u_new.end()); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - osqp_update_bounds(m_work.get(), l_dyn, u_dyn); -} - -void OSQPInterface::updateEpsAbs(const double eps_abs) -{ - m_settings->eps_abs = eps_abs; // for default setting - if (m_work_initialized) { - osqp_update_eps_abs(m_work.get(), eps_abs); // for current work - } -} - -void OSQPInterface::updateEpsRel(const double eps_rel) -{ - m_settings->eps_rel = eps_rel; // for default setting - if (m_work_initialized) { - osqp_update_eps_rel(m_work.get(), eps_rel); // for current work - } -} - -void OSQPInterface::updateMaxIter(const int max_iter) -{ - m_settings->max_iter = max_iter; // for default setting - if (m_work_initialized) { - osqp_update_max_iter(m_work.get(), max_iter); // for current work - } -} - -void OSQPInterface::updateVerbose(const bool is_verbose) -{ - m_settings->verbose = is_verbose; // for default setting - if (m_work_initialized) { - osqp_update_verbose(m_work.get(), is_verbose); // for current work - } -} - -void OSQPInterface::updateRhoInterval(const int rho_interval) -{ - m_settings->adaptive_rho_interval = rho_interval; // for default setting -} - -void OSQPInterface::updateRho(const double rho) -{ - m_settings->rho = rho; - if (m_work_initialized) { - osqp_update_rho(m_work.get(), rho); - } -} - -void OSQPInterface::updateAlpha(const double alpha) -{ - m_settings->alpha = alpha; - if (m_work_initialized) { - osqp_update_alpha(m_work.get(), alpha); - } -} - -void OSQPInterface::updateScaling(const int scaling) -{ - m_settings->scaling = scaling; -} - -void OSQPInterface::updatePolish(const bool polish) -{ - m_settings->polish = polish; - if (m_work_initialized) { - osqp_update_polish(m_work.get(), polish); - } -} - -void OSQPInterface::updatePolishRefinementIteration(const int polish_refine_iter) -{ - if (polish_refine_iter < 0) { - std::cerr << "Polish refinement iterations must be positive" << std::endl; - return; - } - - m_settings->polish_refine_iter = polish_refine_iter; - if (m_work_initialized) { - osqp_update_polish_refine_iter(m_work.get(), polish_refine_iter); - } -} - -void OSQPInterface::updateCheckTermination(const int check_termination) -{ - if (check_termination < 0) { - std::cerr << "Check termination must be positive" << std::endl; - return; - } - - m_settings->check_termination = check_termination; - if (m_work_initialized) { - osqp_update_check_termination(m_work.get(), check_termination); - } -} - -bool OSQPInterface::setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables) -{ - return setPrimalVariables(primal_variables) && setDualVariables(dual_variables); -} - -bool OSQPInterface::setPrimalVariables(const std::vector & primal_variables) -{ - if (!m_work_initialized) { - return false; - } - - const auto result = osqp_warm_start_x(m_work.get(), primal_variables.data()); - if (result != 0) { - std::cerr << "Failed to set primal variables for warm start" << std::endl; - return false; - } - - return true; -} - -bool OSQPInterface::setDualVariables(const std::vector & dual_variables) -{ - if (!m_work_initialized) { - return false; - } - - const auto result = osqp_warm_start_y(m_work.get(), dual_variables.data()); - if (result != 0) { - std::cerr << "Failed to set dual variables for warm start" << std::endl; - return false; - } - - return true; -} - -int64_t OSQPInterface::initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // check if arguments are valid - std::stringstream ss; - if (P.rows() != P.cols()) { - ss << "P.rows() and P.cols() are not the same. P.rows() = " << P.rows() - << ", P.cols() = " << P.cols(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != static_cast(q.size())) { - ss << "P.rows() and q.size() are not the same. P.rows() = " << P.rows() - << ", q.size() = " << q.size(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != A.cols()) { - ss << "P.rows() and A.cols() are not the same. P.rows() = " << P.rows() - << ", A.cols() = " << A.cols(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(l.size())) { - ss << "A.rows() and l.size() are not the same. A.rows() = " << A.rows() - << ", l.size() = " << l.size(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(u.size())) { - ss << "A.rows() and u.size() are not the same. A.rows() = " << A.rows() - << ", u.size() = " << u.size(); - throw std::invalid_argument(ss.str()); - } - - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - return initializeProblem(P_csc, A_csc, q, l, u); -} - -int64_t OSQPInterface::initializeProblem( - CSC_Matrix P_csc, CSC_Matrix A_csc, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - // Dynamic float arrays - std::vector q_tmp(q.begin(), q.end()); - std::vector l_tmp(l.begin(), l.end()); - std::vector u_tmp(u.begin(), u.end()); - double * q_dyn = q_tmp.data(); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - - /********************** - * OBJECTIVE FUNCTION - **********************/ - m_param_n = static_cast(q.size()); - m_data->m = static_cast(l.size()); - - /***************** - * POPULATE DATA - *****************/ - m_data->n = m_param_n; - if (m_data->P) free(m_data->P); - m_data->P = csc_matrix( - m_data->n, m_data->n, static_cast(P_csc.m_vals.size()), P_csc.m_vals.data(), - P_csc.m_row_idxs.data(), P_csc.m_col_idxs.data()); - m_data->q = q_dyn; - if (m_data->A) free(m_data->A); - m_data->A = csc_matrix( - m_data->m, m_data->n, static_cast(A_csc.m_vals.size()), A_csc.m_vals.data(), - A_csc.m_row_idxs.data(), A_csc.m_col_idxs.data()); - m_data->l = l_dyn; - m_data->u = u_dyn; - - // Setup workspace - OSQPWorkspace * workspace; - m_exitflag = osqp_setup(&workspace, m_data.get(), m_settings.get()); - m_work.reset(workspace); - m_work_initialized = true; - - return m_exitflag; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::solve() -{ - // Solve Problem - osqp_solve(m_work.get()); - - /******************** - * EXTRACT SOLUTION - ********************/ - double * sol_x = m_work->solution->x; - double * sol_y = m_work->solution->y; - std::vector sol_primal(sol_x, sol_x + m_param_n); - std::vector sol_lagrange_multiplier(sol_y, sol_y + m_data->m); - - int64_t status_polish = m_work->info->status_polish; - int64_t status_solution = m_work->info->status_val; - int64_t status_iteration = m_work->info->iter; - - // Result tuple - std::tuple, std::vector, int64_t, int64_t, int64_t> result = - std::make_tuple( - sol_primal, sol_lagrange_multiplier, status_polish, status_solution, status_iteration); - - m_latest_work_info = *(m_work->info); - - return result; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::optimize() -{ - // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); - return result; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // Allocate memory for problem - initializeProblem(P, A, q, l, u); - - // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); - - m_work.reset(); - m_work_initialized = false; - - return result; -} - -void OSQPInterface::logUnsolvedStatus(const std::string & prefix_message) const -{ - const int status = getStatus(); - if (status == 1) { - // No need to log since optimization was solved. - return; - } - - // create message - std::string output_message = ""; - if (prefix_message != "") { - output_message = prefix_message + " "; - } - - const auto status_message = getStatusMessage(); - output_message += "Optimization failed due to " + status_message; - - // log with warning - RCLCPP_WARN(rclcpp::get_logger("osqp_interface"), "%s", output_message.c_str()); -} -} // namespace autoware::osqp_interface diff --git a/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp b/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp deleted file mode 100644 index a63f979a966bf..0000000000000 --- a/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp +++ /dev/null @@ -1,181 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -TEST(TestCscMatrixConv, Nominal) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::CSC_Matrix; - - Eigen::MatrixXd rect1(1, 2); - rect1 << 0.0, 1.0; - - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - ASSERT_EQ(rect_m1.m_vals.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_vals[0], 1.0); - ASSERT_EQ(rect_m1.m_row_idxs.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_row_idxs[0], c_int(0)); - ASSERT_EQ(rect_m1.m_col_idxs.size(), size_t(3)); // nb of columns + 1 - EXPECT_EQ(rect_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[1], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[2], c_int(1)); - - Eigen::MatrixXd rect2(2, 4); - rect2 << 1.0, 0.0, 3.0, 0.0, 0.0, 6.0, 7.0, 0.0; - - const CSC_Matrix rect_m2 = calCSCMatrix(rect2); - ASSERT_EQ(rect_m2.m_vals.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_vals[0], 1.0); - EXPECT_EQ(rect_m2.m_vals[1], 6.0); - EXPECT_EQ(rect_m2.m_vals[2], 3.0); - EXPECT_EQ(rect_m2.m_vals[3], 7.0); - ASSERT_EQ(rect_m2.m_row_idxs.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_row_idxs[2], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[3], c_int(1)); - ASSERT_EQ(rect_m2.m_col_idxs.size(), size_t(5)); // nb of columns + 1 - EXPECT_EQ(rect_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_col_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(rect_m2.m_col_idxs[3], c_int(4)); - EXPECT_EQ(rect_m2.m_col_idxs[4], c_int(4)); - - // Example from http://netlib.org/linalg/html_templates/node92.html - Eigen::MatrixXd square2(6, 6); - square2 << 10.0, 0.0, 0.0, 0.0, -2.0, 0.0, 3.0, 9.0, 0.0, 0.0, 0.0, 3.0, 0.0, 7.0, 8.0, 7.0, 0.0, - 0.0, 3.0, 0.0, 8.0, 7.0, 5.0, 0.0, 0.0, 8.0, 0.0, 9.0, 9.0, 13.0, 0.0, 4.0, 0.0, 0.0, 2.0, -1.0; - - const CSC_Matrix square_m2 = calCSCMatrix(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(19)); - EXPECT_EQ(square_m2.m_vals[0], 10.0); - EXPECT_EQ(square_m2.m_vals[1], 3.0); - EXPECT_EQ(square_m2.m_vals[2], 3.0); - EXPECT_EQ(square_m2.m_vals[3], 9.0); - EXPECT_EQ(square_m2.m_vals[4], 7.0); - EXPECT_EQ(square_m2.m_vals[5], 8.0); - EXPECT_EQ(square_m2.m_vals[6], 4.0); - EXPECT_EQ(square_m2.m_vals[7], 8.0); - EXPECT_EQ(square_m2.m_vals[8], 8.0); - EXPECT_EQ(square_m2.m_vals[9], 7.0); - EXPECT_EQ(square_m2.m_vals[10], 7.0); - EXPECT_EQ(square_m2.m_vals[11], 9.0); - EXPECT_EQ(square_m2.m_vals[12], -2.0); - EXPECT_EQ(square_m2.m_vals[13], 5.0); - EXPECT_EQ(square_m2.m_vals[14], 9.0); - EXPECT_EQ(square_m2.m_vals[15], 2.0); - EXPECT_EQ(square_m2.m_vals[16], 3.0); - EXPECT_EQ(square_m2.m_vals[17], 13.0); - EXPECT_EQ(square_m2.m_vals[18], -1.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(19)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[3], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[4], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[5], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[6], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[7], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[8], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[9], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[10], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[11], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[12], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[13], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[14], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[15], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[16], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[17], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[18], c_int(5)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(7)); // nb of columns + 1 - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(3)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(7)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(9)); - EXPECT_EQ(square_m2.m_col_idxs[4], c_int(12)); - EXPECT_EQ(square_m2.m_col_idxs[5], c_int(16)); - EXPECT_EQ(square_m2.m_col_idxs[6], c_int(19)); -} -TEST(TestCscMatrixConv, Trapezoidal) -{ - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd square2(3, 3); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - square2 << 0.0, 2.0, 0.0, 4.0, 5.0, 6.0, 0.0, 0.0, 0.0; - rect1 << 0.0, 1.0; - - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - // Trapezoidal: skip the lower left triangle (2.0 in this example) - ASSERT_EQ(square_m1.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m1.m_vals[0], 1.0); - EXPECT_EQ(square_m1.m_vals[1], 2.0); - EXPECT_EQ(square_m1.m_vals[2], 4.0); - ASSERT_EQ(square_m1.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[1], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m1.m_col_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_col_idxs[1], c_int(1)); - EXPECT_EQ(square_m1.m_col_idxs[2], c_int(3)); - - const CSC_Matrix square_m2 = calCSCMatrixTrapezoidal(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m2.m_vals[0], 2.0); - EXPECT_EQ(square_m2.m_vals[1], 5.0); - EXPECT_EQ(square_m2.m_vals[2], 6.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(4)); - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(3)); - - try { - const CSC_Matrix rect_m1 = calCSCMatrixTrapezoidal(rect1); - FAIL() << "calCSCMatrixTrapezoidal should fail with non-square inputs"; - } catch (const std::invalid_argument & e) { - EXPECT_EQ(e.what(), std::string("Matrix must be square (n, n)")); - } -} -TEST(TestCscMatrixConv, Print) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - using autoware::osqp_interface::printCSCMatrix; - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - rect1 << 0.0, 1.0; - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - printCSCMatrix(square_m1); - printCSCMatrix(rect_m1); -} diff --git a/common/autoware_osqp_interface/test/test_osqp_interface.cpp b/common/autoware_osqp_interface/test/test_osqp_interface.cpp deleted file mode 100644 index f65b07e6d792d..0000000000000 --- a/common/autoware_osqp_interface/test/test_osqp_interface.cpp +++ /dev/null @@ -1,164 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/osqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -namespace -{ -// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestOsqpInterface, BasicQp) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - - auto check_result = - [](const std::tuple, std::vector, int, int, int> & result) { - EXPECT_EQ(std::get<2>(result), 1); // polish succeeded - EXPECT_EQ(std::get<3>(result), 1); // solution succeeded - - static const auto ep = 1.0e-8; - - const auto prime_val = std::get<0>(result); - ASSERT_EQ(prime_val.size(), size_t(2)); - EXPECT_NEAR(prime_val[0], 0.3, ep); - EXPECT_NEAR(prime_val[1], 0.7, ep); - - const auto dual_val = std::get<1>(result); - ASSERT_EQ(dual_val.size(), size_t(4)); - EXPECT_NEAR(dual_val[0], -2.9, ep); - EXPECT_NEAR(dual_val[1], 0.0, ep); - EXPECT_NEAR(dual_val[2], 0.2, ep); - EXPECT_NEAR(dual_val[3], 0.0, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -autoware::osqp_interface::INF}; - const std::vector u = {1.0, 0.7, 0.7, autoware::osqp_interface::INF}; - - { - // Define problem during optimization - autoware::osqp_interface::OSQPInterface osqp; - std::tuple, std::vector, int, int, int> result = - osqp.optimize(P, A, q, l, u); - check_result(result); - } - - { - // Define problem during initialization - autoware::osqp_interface::OSQPInterface osqp(P, A, q, l, u, 1e-6); - std::tuple, std::vector, int, int, int> result = osqp.optimize(); - check_result(result); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem - Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini, A_ini, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - osqp.initializeProblem(P, A, q, l, u); - result = osqp.optimize(); - check_result(result); - } - - { - // Define problem during initialization with csc matrix - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - autoware::osqp_interface::OSQPInterface osqp(P_csc, A_csc, q, l, u, 1e-6); - std::tuple, std::vector, int, int, int> result = osqp.optimize(); - check_result(result); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - osqp.initializeProblem(P_csc, A_csc, q, l, u); - result = osqp.optimize(); - check_result(result); - } - - // add warm startup - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - osqp.initializeProblem(P_csc, A_csc, q, l, u); - result = osqp.optimize(); - check_result(result); - - osqp.updateCheckTermination(1); - const auto primal_val = std::get<0>(result); - const auto dual_val = std::get<1>(result); - for (size_t i = 0; i < primal_val.size(); ++i) { - std::cerr << primal_val.at(i) << std::endl; - } - osqp.setWarmStart(primal_val, dual_val); - result = osqp.optimize(); - check_result(result); - EXPECT_EQ(osqp.getTakenIter(), 1); - } -} -} // namespace From a6b5f3c6992e6978eec4c110d1956df99c0219ca Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:17:04 +0800 Subject: [PATCH 38/59] feat(autoware_kalman_filter): move autoware_kalman_filter to autowar.core (#9872) feat(autoware_kalman_filter): move autoware_kalman_filter to autoware.core Signed-off-by: liu cui --- common/autoware_kalman_filter/CHANGELOG.rst | 55 ----- common/autoware_kalman_filter/CMakeLists.txt | 29 --- common/autoware_kalman_filter/README.md | 9 - .../autoware/kalman_filter/kalman_filter.hpp | 214 ------------------ .../time_delay_kalman_filter.hpp | 89 -------- common/autoware_kalman_filter/package.xml | 28 --- .../src/kalman_filter.cpp | 161 ------------- .../src/time_delay_kalman_filter.cpp | 109 --------- .../test/test_kalman_filter.cpp | 96 -------- .../test/test_time_delay_kalman_filter.cpp | 123 ---------- 10 files changed, 913 deletions(-) delete mode 100644 common/autoware_kalman_filter/CHANGELOG.rst delete mode 100644 common/autoware_kalman_filter/CMakeLists.txt delete mode 100644 common/autoware_kalman_filter/README.md delete mode 100644 common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp delete mode 100644 common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp delete mode 100644 common/autoware_kalman_filter/package.xml delete mode 100644 common/autoware_kalman_filter/src/kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/test/test_kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp diff --git a/common/autoware_kalman_filter/CHANGELOG.rst b/common/autoware_kalman_filter/CHANGELOG.rst deleted file mode 100644 index a7e68f8843e74..0000000000000 --- a/common/autoware_kalman_filter/CHANGELOG.rst +++ /dev/null @@ -1,55 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_kalman_filter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(kalman_filter): prefix package and namespace with autoware (`#7787 `_) - * refactor(kalman_filter): prefix package and namespace with autoware - * move headers to include/autoware/ - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/common/autoware_kalman_filter/CMakeLists.txt b/common/autoware_kalman_filter/CMakeLists.txt deleted file mode 100644 index 076d2d3cad4e8..0000000000000 --- a/common/autoware_kalman_filter/CMakeLists.txt +++ /dev/null @@ -1,29 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_kalman_filter) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(eigen3_cmake_module REQUIRED) -find_package(Eigen3 REQUIRED) - -include_directories( - SYSTEM - ${EIGEN3_INCLUDE_DIR} -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/kalman_filter.cpp - src/time_delay_kalman_filter.cpp - include/autoware/kalman_filter/kalman_filter.hpp - include/autoware/kalman_filter/time_delay_kalman_filter.hpp -) - -if(BUILD_TESTING) - file(GLOB_RECURSE test_files test/*.cpp) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${test_files}) - - target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) -endif() - -ament_auto_package() diff --git a/common/autoware_kalman_filter/README.md b/common/autoware_kalman_filter/README.md deleted file mode 100644 index 7c0feb9c2a61a..0000000000000 --- a/common/autoware_kalman_filter/README.md +++ /dev/null @@ -1,9 +0,0 @@ -# kalman_filter - -## Purpose - -This common package contains the kalman filter with time delay and the calculation of the kalman filter. - -## Assumptions / Known limits - -TBD. diff --git a/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp b/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp deleted file mode 100644 index 74db04f6e838b..0000000000000 --- a/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// Copyright 2018-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 AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ -#define AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ - -#include -#include - -namespace autoware::kalman_filter -{ - -/** - * @file kalman_filter.h - * @brief kalman filter class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - KalmanFilter(); - - /** - * @brief constructor with initialization - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariance matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief destructor - */ - ~KalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariance matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - bool init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P initial covariance of estimated state - */ - bool init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0); - - /** - * @brief set A of process model - * @param A coefficient matrix of x for process model - */ - void setA(const Eigen::MatrixXd & A); - - /** - * @brief set B of process model - * @param B coefficient matrix of u for process model - */ - void setB(const Eigen::MatrixXd & B); - - /** - * @brief set C of measurement model - * @param C coefficient matrix of x for measurement model - */ - void setC(const Eigen::MatrixXd & C); - - /** - * @brief set covariance matrix Q for process model - * @param Q covariance matrix for process model - */ - void setQ(const Eigen::MatrixXd & Q); - - /** - * @brief set covariance matrix R for measurement model - * @param R covariance matrix for measurement model - */ - void setR(const Eigen::MatrixXd & R); - - /** - * @brief get current kalman filter state - * @param x kalman filter state - */ - void getX(Eigen::MatrixXd & x) const; - - /** - * @brief get current kalman filter covariance - * @param P kalman filter covariance - */ - void getP(Eigen::MatrixXd & P) const; - - /** - * @brief get component of current kalman filter state - * @param i index of kalman filter state - * @return value of i's component of the kalman filter state x[i] - */ - double getXelement(unsigned int i) const; - - /** - * @brief calculate kalman filter state and covariance by prediction model with A, B, Q matrix. - * This is mainly for EKF with variable matrix. - * @param u input for model - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param Q covariance matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is - * mainly for EKF with variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @param Q covariance matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is - * mainly for EKF with variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A); - - /** - * @brief calculate kalman filter state by prediction model with A, B and Q being class member - * variables. - * @param u input for the model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & u); - - /** - * @brief calculate kalman filter state by measurement model with y_pred, C and R matrix. This is - * mainly for EKF with variable matrix. - * @param y measured values - * @param y output values expected from measurement model - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R matrix. This is mainly - * for EKF with variable matrix. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R being class member - * variables. - * @param y measured values - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y); - -protected: - Eigen::MatrixXd x_; //!< @brief current estimated state - Eigen::MatrixXd - A_; //!< @brief coefficient matrix of x for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd - B_; //!< @brief coefficient matrix of u for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd C_; //!< @brief coefficient matrix of x for measurement model y[k] = C * x[k] - Eigen::MatrixXd Q_; //!< @brief covariance matrix for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd R_; //!< @brief covariance matrix for measurement model y[k] = C * x[k] - Eigen::MatrixXd P_; //!< @brief covariance of estimated state -}; -} // namespace autoware::kalman_filter -#endif // AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ diff --git a/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp b/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp deleted file mode 100644 index 80375b7579e62..0000000000000 --- a/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// Copyright 2018-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 AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ -#define AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ - -#include "autoware/kalman_filter/kalman_filter.hpp" - -#include -#include - -#include - -namespace autoware::kalman_filter -{ -/** - * @file time_delay_kalman_filter.h - * @brief kalman filter with delayed measurement class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class TimeDelayKalmanFilter : public KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - TimeDelayKalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P0 initial covariance of estimated state - * @param max_delay_step Maximum number of delay steps, which determines the dimension of the - * extended kalman filter - */ - void init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P, const int max_delay_step); - - /** - * @brief get latest time estimated state - */ - Eigen::MatrixXd getLatestX() const; - - /** - * @brief get latest time estimation covariance - */ - Eigen::MatrixXd getLatestP() const; - - /** - * @brief calculate kalman filter covariance by precision model with time delay. This is mainly - * for EKF of nonlinear process model. - * @param x_next predicted state by prediction model - * @param A coefficient matrix of x for process model - * @param Q covariance matrix for process model - */ - bool predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance by measurement model with time delay. This is mainly - * for EKF of nonlinear process model. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @param delay_step measurement delay - */ - bool updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step); - -private: - int max_delay_step_; //!< @brief maximum number of delay steps - int dim_x_; //!< @brief dimension of latest state - int dim_x_ex_; //!< @brief dimension of extended state with dime delay -}; -} // namespace autoware::kalman_filter -#endif // AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ diff --git a/common/autoware_kalman_filter/package.xml b/common/autoware_kalman_filter/package.xml deleted file mode 100644 index e51bb06e9de43..0000000000000 --- a/common/autoware_kalman_filter/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - autoware_kalman_filter - 0.40.0 - The kalman filter package - Yukihiro Saito - Takeshi Ishita - Koji Minoda - Apache License 2.0 - - Takamasa Horibe - - ament_cmake_auto - autoware_cmake - - eigen - eigen3_cmake_module - - ament_cmake_cppcheck - ament_cmake_ros - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/common/autoware_kalman_filter/src/kalman_filter.cpp b/common/autoware_kalman_filter/src/kalman_filter.cpp deleted file mode 100644 index bbd963675f9e2..0000000000000 --- a/common/autoware_kalman_filter/src/kalman_filter.cpp +++ /dev/null @@ -1,161 +0,0 @@ -// Copyright 2018-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. - -#include "autoware/kalman_filter/kalman_filter.hpp" - -namespace autoware::kalman_filter -{ -KalmanFilter::KalmanFilter() -{ -} -KalmanFilter::KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - init(x, A, B, C, Q, R, P); -} -KalmanFilter::~KalmanFilter() -{ -} -bool KalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - if ( - x.cols() == 0 || x.rows() == 0 || A.cols() == 0 || A.rows() == 0 || B.cols() == 0 || - B.rows() == 0 || C.cols() == 0 || C.rows() == 0 || Q.cols() == 0 || Q.rows() == 0 || - R.cols() == 0 || R.rows() == 0 || P.cols() == 0 || P.rows() == 0) { - return false; - } - x_ = x; - A_ = A; - B_ = B; - C_ = C; - Q_ = Q; - R_ = R; - P_ = P; - return true; -} -bool KalmanFilter::init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0) -{ - if (x.cols() == 0 || x.rows() == 0 || P0.cols() == 0 || P0.rows() == 0) { - return false; - } - x_ = x; - P_ = P0; - return true; -} - -void KalmanFilter::setA(const Eigen::MatrixXd & A) -{ - A_ = A; -} -void KalmanFilter::setB(const Eigen::MatrixXd & B) -{ - B_ = B; -} -void KalmanFilter::setC(const Eigen::MatrixXd & C) -{ - C_ = C; -} -void KalmanFilter::setQ(const Eigen::MatrixXd & Q) -{ - Q_ = Q; -} -void KalmanFilter::setR(const Eigen::MatrixXd & R) -{ - R_ = R; -} -void KalmanFilter::getX(Eigen::MatrixXd & x) const -{ - x = x_; -} -void KalmanFilter::getP(Eigen::MatrixXd & P) const -{ - P = P_; -} -double KalmanFilter::getXelement(unsigned int i) const -{ - return x_(i); -} - -bool KalmanFilter::predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - if ( - x_.rows() != x_next.rows() || A.cols() != P_.rows() || Q.cols() != Q.rows() || - A.rows() != Q.cols()) { - return false; - } - x_ = x_next; - P_ = A * P_ * A.transpose() + Q; - return true; -} -bool KalmanFilter::predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A) -{ - return predict(x_next, A, Q_); -} - -bool KalmanFilter::predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q) -{ - if (A.cols() != x_.rows() || B.cols() != u.rows()) { - return false; - } - const Eigen::MatrixXd x_next = A * x_ + B * u; - return predict(x_next, A, Q); -} -bool KalmanFilter::predict(const Eigen::MatrixXd & u) -{ - return predict(u, A_, B_, Q_); -} - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R) -{ - if ( - P_.cols() != C.cols() || R.rows() != R.cols() || R.rows() != C.rows() || - y.rows() != y_pred.rows() || y.rows() != C.rows()) { - return false; - } - const Eigen::MatrixXd PCT = P_ * C.transpose(); - const Eigen::MatrixXd K = PCT * ((R + C * PCT).inverse()); - - if (isnan(K.array()).any() || isinf(K.array()).any()) { - return false; - } - - x_ = x_ + K * (y - y_pred); - P_ = P_ - K * (C * P_); - return true; -} - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R) -{ - if (C.cols() != x_.rows()) { - return false; - } - const Eigen::MatrixXd y_pred = C * x_; - return update(y, y_pred, C, R); -} -bool KalmanFilter::update(const Eigen::MatrixXd & y) -{ - return update(y, C_, R_); -} -} // namespace autoware::kalman_filter diff --git a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp b/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp deleted file mode 100644 index 4d1dd8f33b7a6..0000000000000 --- a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// Copyright 2018-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. - -#include "autoware/kalman_filter/time_delay_kalman_filter.hpp" - -#include - -namespace autoware::kalman_filter -{ -TimeDelayKalmanFilter::TimeDelayKalmanFilter() -{ -} - -void TimeDelayKalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0, const int max_delay_step) -{ - max_delay_step_ = max_delay_step; - dim_x_ = x.rows(); - dim_x_ex_ = dim_x_ * max_delay_step; - - x_ = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - P_ = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - - for (int i = 0; i < max_delay_step_; ++i) { - x_.block(i * dim_x_, 0, dim_x_, 1) = x; - P_.block(i * dim_x_, i * dim_x_, dim_x_, dim_x_) = P0; - } -} - -Eigen::MatrixXd TimeDelayKalmanFilter::getLatestX() const -{ - return x_.block(0, 0, dim_x_, 1); -} - -Eigen::MatrixXd TimeDelayKalmanFilter::getLatestP() const -{ - return P_.block(0, 0, dim_x_, dim_x_); -} - -bool TimeDelayKalmanFilter::predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - /* - * time delay model: - * - * [A 0 0] [P11 P12 P13] [Q 0 0] - * A = [I 0 0], P = [P21 P22 P23], Q = [0 0 0] - * [0 I 0] [P31 P32 P33] [0 0 0] - * - * covariance calculation in prediction : P = A * P * A' + Q - * - * [A*P11*A'*+Q A*P11 A*P12] - * P = [ P11*A' P11 P12] - * [ P21*A' P21 P22] - */ - - const int d_dim_x = dim_x_ex_ - dim_x_; - - /* slide states in the time direction */ - Eigen::MatrixXd x_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - x_tmp.block(0, 0, dim_x_, 1) = x_next; - x_tmp.block(dim_x_, 0, d_dim_x, 1) = x_.block(0, 0, d_dim_x, 1); - x_ = x_tmp; - - /* update P with delayed measurement A matrix structure */ - Eigen::MatrixXd P_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - P_tmp.block(0, 0, dim_x_, dim_x_) = A * P_.block(0, 0, dim_x_, dim_x_) * A.transpose() + Q; - P_tmp.block(0, dim_x_, dim_x_, d_dim_x) = A * P_.block(0, 0, dim_x_, d_dim_x); - P_tmp.block(dim_x_, 0, d_dim_x, dim_x_) = P_.block(0, 0, d_dim_x, dim_x_) * A.transpose(); - P_tmp.block(dim_x_, dim_x_, d_dim_x, d_dim_x) = P_.block(0, 0, d_dim_x, d_dim_x); - P_ = P_tmp; - - return true; -} - -bool TimeDelayKalmanFilter::updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step) -{ - if (delay_step >= max_delay_step_) { - std::cerr << "delay step is larger than max_delay_step. ignore update." << std::endl; - return false; - } - - const int dim_y = y.rows(); - - /* set measurement matrix */ - Eigen::MatrixXd C_ex = Eigen::MatrixXd::Zero(dim_y, dim_x_ex_); - C_ex.block(0, dim_x_ * delay_step, dim_y, dim_x_) = C; - - /* update */ - if (!update(y, C_ex, R)) { - return false; - } - - return true; -} -} // namespace autoware::kalman_filter diff --git a/common/autoware_kalman_filter/test/test_kalman_filter.cpp b/common/autoware_kalman_filter/test/test_kalman_filter.cpp deleted file mode 100644 index 34e23ef9d06e2..0000000000000 --- a/common/autoware_kalman_filter/test/test_kalman_filter.cpp +++ /dev/null @@ -1,96 +0,0 @@ -// Copyright 2023 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/kalman_filter.hpp" - -#include - -using autoware::kalman_filter::KalmanFilter; - -TEST(kalman_filter, kf) -{ - KalmanFilter kf_; - - Eigen::MatrixXd x_t(2, 1); - x_t << 1, 2; - - Eigen::MatrixXd P_t(2, 2); - P_t << 1, 0, 0, 1; - - Eigen::MatrixXd Q_t(2, 2); - Q_t << 0.01, 0, 0, 0.01; - - Eigen::MatrixXd R_t(2, 2); - R_t << 0.09, 0, 0, 0.09; - - Eigen::MatrixXd C_t(2, 2); - C_t << 1, 0, 0, 1; - - Eigen::MatrixXd A_t(2, 2); - A_t << 1, 0, 0, 1; - - Eigen::MatrixXd B_t(2, 2); - B_t << 1, 0, 0, 1; - - // Initialize the filter and check if initialization was successful - EXPECT_TRUE(kf_.init(x_t, A_t, B_t, C_t, Q_t, R_t, P_t)); - - // Perform prediction - Eigen::MatrixXd u_t(2, 1); - u_t << 0.1, 0.1; - EXPECT_TRUE(kf_.predict(u_t)); - - // Check the updated state and covariance matrix - Eigen::MatrixXd x_predict_expected = A_t * x_t + B_t * u_t; - Eigen::MatrixXd P_predict_expected = A_t * P_t * A_t.transpose() + Q_t; - - Eigen::MatrixXd x_predict; - kf_.getX(x_predict); - Eigen::MatrixXd P_predict; - kf_.getP(P_predict); - - EXPECT_NEAR(x_predict(0, 0), x_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(x_predict(1, 0), x_predict_expected(1, 0), 1e-5); - EXPECT_NEAR(P_predict(0, 0), P_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(P_predict(1, 1), P_predict_expected(1, 1), 1e-5); - - // Perform update - Eigen::MatrixXd y_t(2, 1); - y_t << 1.05, 2.05; - EXPECT_TRUE(kf_.update(y_t)); - - // Check the updated state and covariance matrix - const Eigen::MatrixXd PCT_t = P_predict_expected * C_t.transpose(); - const Eigen::MatrixXd K_t = PCT_t * ((R_t + C_t * PCT_t).inverse()); - const Eigen::MatrixXd y_pred = C_t * x_predict_expected; - Eigen::MatrixXd x_update_expected = x_predict_expected + K_t * (y_t - y_pred); - Eigen::MatrixXd P_update_expected = P_predict_expected - K_t * (C_t * P_predict_expected); - - Eigen::MatrixXd x_update; - kf_.getX(x_update); - Eigen::MatrixXd P_update; - kf_.getP(P_update); - - EXPECT_NEAR(x_update(0, 0), x_update_expected(0, 0), 1e-5); - EXPECT_NEAR(x_update(1, 0), x_update_expected(1, 0), 1e-5); - EXPECT_NEAR(P_update(0, 0), P_update_expected(0, 0), 1e-5); - EXPECT_NEAR(P_update(1, 1), P_update_expected(1, 1), 1e-5); -} - -int main(int argc, char * argv[]) -{ - testing::InitGoogleTest(&argc, argv); - bool result = RUN_ALL_TESTS(); - return result; -} diff --git a/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp b/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp deleted file mode 100644 index 50c22fae123bc..0000000000000 --- a/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp +++ /dev/null @@ -1,123 +0,0 @@ -// Copyright 2023 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/time_delay_kalman_filter.hpp" - -#include - -using autoware::kalman_filter::TimeDelayKalmanFilter; - -TEST(time_delay_kalman_filter, td_kf) -{ - TimeDelayKalmanFilter td_kf_; - - Eigen::MatrixXd x_t(3, 1); - x_t << 1.0, 2.0, 3.0; - Eigen::MatrixXd P_t(3, 3); - P_t << 0.1, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.3; - const int max_delay_step = 5; - const int dim_x = x_t.rows(); - const int dim_x_ex = dim_x * max_delay_step; - // Initialize the filter - td_kf_.init(x_t, P_t, max_delay_step); - - // Check if initialization was successful - Eigen::MatrixXd x_init = td_kf_.getLatestX(); - Eigen::MatrixXd P_init = td_kf_.getLatestP(); - Eigen::MatrixXd x_ex_t = Eigen::MatrixXd::Zero(dim_x_ex, 1); - Eigen::MatrixXd P_ex_t = Eigen::MatrixXd::Zero(dim_x_ex, dim_x_ex); - for (int i = 0; i < max_delay_step; ++i) { - x_ex_t.block(i * dim_x, 0, dim_x, 1) = x_t; - P_ex_t.block(i * dim_x, i * dim_x, dim_x, dim_x) = P_t; - } - - EXPECT_EQ(x_init.rows(), 3); - EXPECT_EQ(x_init.cols(), 1); - EXPECT_EQ(P_init.rows(), 3); - EXPECT_EQ(P_init.cols(), 3); - EXPECT_NEAR(x_init(0, 0), x_t(0, 0), 1e-5); - EXPECT_NEAR(x_init(1, 0), x_t(1, 0), 1e-5); - EXPECT_NEAR(x_init(2, 0), x_t(2, 0), 1e-5); - EXPECT_NEAR(P_init(0, 0), P_t(0, 0), 1e-5); - EXPECT_NEAR(P_init(1, 1), P_t(1, 1), 1e-5); - EXPECT_NEAR(P_init(2, 2), P_t(2, 2), 1e-5); - - // Define prediction parameters - Eigen::MatrixXd A_t(3, 3); - A_t << 2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0; - Eigen::MatrixXd Q_t(3, 3); - Q_t << 0.01, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0, 0.03; - Eigen::MatrixXd x_next(3, 1); - x_next << 2.0, 4.0, 6.0; - - // Perform prediction - EXPECT_TRUE(td_kf_.predictWithDelay(x_next, A_t, Q_t)); - - // Check the prediction state and covariance matrix - Eigen::MatrixXd x_predict = td_kf_.getLatestX(); - Eigen::MatrixXd P_predict = td_kf_.getLatestP(); - Eigen::MatrixXd x_tmp = Eigen::MatrixXd::Zero(dim_x_ex, 1); - x_tmp.block(0, 0, dim_x, 1) = A_t * x_t; - x_tmp.block(dim_x, 0, dim_x_ex - dim_x, 1) = x_ex_t.block(0, 0, dim_x_ex - dim_x, 1); - x_ex_t = x_tmp; - Eigen::MatrixXd x_predict_expected = x_ex_t.block(0, 0, dim_x, 1); - Eigen::MatrixXd P_tmp = Eigen::MatrixXd::Zero(dim_x_ex, dim_x_ex); - P_tmp.block(0, 0, dim_x, dim_x) = A_t * P_ex_t.block(0, 0, dim_x, dim_x) * A_t.transpose() + Q_t; - P_tmp.block(0, dim_x, dim_x, dim_x_ex - dim_x) = - A_t * P_ex_t.block(0, 0, dim_x, dim_x_ex - dim_x); - P_tmp.block(dim_x, 0, dim_x_ex - dim_x, dim_x) = - P_ex_t.block(0, 0, dim_x_ex - dim_x, dim_x) * A_t.transpose(); - P_tmp.block(dim_x, dim_x, dim_x_ex - dim_x, dim_x_ex - dim_x) = - P_ex_t.block(0, 0, dim_x_ex - dim_x, dim_x_ex - dim_x); - P_ex_t = P_tmp; - Eigen::MatrixXd P_predict_expected = P_ex_t.block(0, 0, dim_x, dim_x); - EXPECT_NEAR(x_predict(0, 0), x_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(x_predict(1, 0), x_predict_expected(1, 0), 1e-5); - EXPECT_NEAR(x_predict(2, 0), x_predict_expected(2, 0), 1e-5); - EXPECT_NEAR(P_predict(0, 0), P_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(P_predict(1, 1), P_predict_expected(1, 1), 1e-5); - EXPECT_NEAR(P_predict(2, 2), P_predict_expected(2, 2), 1e-5); - - // Define update parameters - Eigen::MatrixXd C_t(3, 3); - C_t << 0.5, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.5; - Eigen::MatrixXd R_t(3, 3); - R_t << 0.001, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.003; - Eigen::MatrixXd y_t(3, 1); - y_t << 1.05, 2.05, 3.05; - const int delay_step = 2; // Choose an appropriate delay step - const int dim_y = y_t.rows(); - - // Perform update - EXPECT_TRUE(td_kf_.updateWithDelay(y_t, C_t, R_t, delay_step)); - - // Check the updated state and covariance matrix - Eigen::MatrixXd x_update = td_kf_.getLatestX(); - Eigen::MatrixXd P_update = td_kf_.getLatestP(); - - Eigen::MatrixXd C_ex_t = Eigen::MatrixXd::Zero(dim_y, dim_x_ex); - const Eigen::MatrixXd PCT_t = P_ex_t * C_ex_t.transpose(); - const Eigen::MatrixXd K_t = PCT_t * ((R_t + C_ex_t * PCT_t).inverse()); - const Eigen::MatrixXd y_pred = C_ex_t * x_ex_t; - x_ex_t = x_ex_t + K_t * (y_t - y_pred); - P_ex_t = P_ex_t - K_t * (C_ex_t * P_ex_t); - Eigen::MatrixXd x_update_expected = x_ex_t.block(0, 0, dim_x, 1); - Eigen::MatrixXd P_update_expected = P_ex_t.block(0, 0, dim_x, dim_x); - EXPECT_NEAR(x_update(0, 0), x_update_expected(0, 0), 1e-5); - EXPECT_NEAR(x_update(1, 0), x_update_expected(1, 0), 1e-5); - EXPECT_NEAR(x_update(2, 0), x_update_expected(2, 0), 1e-5); - EXPECT_NEAR(P_update(0, 0), P_update_expected(0, 0), 1e-5); - EXPECT_NEAR(P_update(1, 1), P_update_expected(1, 1), 1e-5); - EXPECT_NEAR(P_update(2, 2), P_update_expected(2, 2), 1e-5); -} From 7f496888b6ef10eb5ee9e9897505220d92415164 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:18:06 +0900 Subject: [PATCH 39/59] feat(autoware_costmap_generator): tier4_debug_msgs changed to autoware_internal-debug_msgs in autoware_costmap_generator (#9901) feat: tier4_debug_msgs changed to autoware_internal-debug_msgs in files planning/autoware_costmap_generator Signed-off-by: vish0012 --- .../autoware/costmap_generator/costmap_generator.hpp | 5 +++-- .../autoware_costmap_generator/src/costmap_generator.cpp | 7 ++++--- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp index 4fed5bcb6cff3..b6749117a6177 100644 --- a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp +++ b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp @@ -58,10 +58,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -99,7 +99,8 @@ class CostmapGenerator : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_costmap_; rclcpp::Publisher::SharedPtr pub_occupancy_grid_; rclcpp::Publisher::SharedPtr pub_processing_time_; - rclcpp::Publisher::SharedPtr pub_processing_time_ms_; + rclcpp::Publisher::SharedPtr + pub_processing_time_ms_; rclcpp::Subscription::SharedPtr sub_lanelet_bin_map_; autoware::universe_utils::InterProcessPollingSubscriber diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index 081a6ead91cda..70b8051bcdc12 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -176,7 +176,8 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options) create_publisher("processing_time", 1); time_keeper_ = std::make_shared(pub_processing_time_); pub_processing_time_ms_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher( + "~/debug/processing_time_ms", 1); // Timer const auto period_ns = rclcpp::Rate(param_->update_rate).period(); @@ -269,7 +270,7 @@ void CostmapGenerator::onTimer() if (!isActive()) { // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_ms_->publish(processing_time_msg); @@ -485,7 +486,7 @@ void CostmapGenerator::publishCostmap( pub_costmap_->publish(*out_gridmap_msg); // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_ms_->publish(processing_time_msg); From 9a2ebcc9f1f55f3aa28ad46a6d0b825f52e45cea Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:21:18 +0900 Subject: [PATCH 40/59] feat(autoware_surround_obstacle_checker): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_surround_obstacle_checker (#9915) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_surround_obstacle_checker Signed-off-by: vish0012 --- planning/autoware_surround_obstacle_checker/src/node.cpp | 6 +++--- planning/autoware_surround_obstacle_checker/src/node.hpp | 5 +++-- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 0adca312ca733..b3881a8f4fbd9 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -81,8 +81,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio "~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local()); pub_velocity_limit_ = this->create_publisher( "~/output/max_velocity", rclcpp::QoS{1}.transient_local()); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( @@ -231,7 +231,7 @@ void SurroundObstacleCheckerNode::onTimer() debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); } - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index f84ad3a8f5987..b6d6bffefed1a 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -24,12 +24,12 @@ #include #include +#include #include #include #include #include #include -#include #include #include #include @@ -106,7 +106,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node this, "~/input/objects"}; rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; // parameter callback result OnSetParametersCallbackHandle::SharedPtr set_param_res_; From 2028af955d261cc3dfd4836f7501b60a5e030a59 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:23:07 +0900 Subject: [PATCH 41/59] feat(autoware_freespace_planner): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_freespace_planner (#9903) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in flies planning/autoware_freespace_planner Signed-off-by: vish0012 --- .../autoware/freespace_planner/freespace_planner_node.hpp | 5 +++-- .../autoware_freespace_planner/freespace_planner_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp index 1f5a52ca040a0..bd431372b70dc 100644 --- a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp +++ b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp @@ -39,13 +39,13 @@ #include #include +#include #include #include #include #include #include #include -#include #include #ifdef ROS_DISTRO_GALACTIC @@ -112,7 +112,8 @@ class FreespacePlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pose_array_pub_; rclcpp::Publisher::SharedPtr debug_partial_pose_array_pub_; rclcpp::Publisher::SharedPtr parking_state_pub_; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; rclcpp::Subscription::SharedPtr route_sub_; diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index a937114e653c6..2749408bedb7b 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -95,8 +95,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti debug_pose_array_pub_ = create_publisher("~/debug/pose_array", qos); debug_partial_pose_array_pub_ = create_publisher("~/debug/partial_pose_array", qos); parking_state_pub_ = create_publisher("is_completed", qos); - processing_time_pub_ = - create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = create_publisher( + "~/debug/processing_time_ms", 1); } // TF @@ -362,7 +362,7 @@ void FreespacePlannerNode::onTimer() is_new_parking_cycle_ = false; // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); From e96b361fc3d6f49bc4b097ca402ffbd3b590bb89 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:24:36 +0900 Subject: [PATCH 42/59] feat(autoware_scenario_selector): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_scenario_selector (#9914) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_scenario_selector Signed-off-by: vish0012 --- .../include/autoware/scenario_selector/node.hpp | 5 +++-- planning/autoware_scenario_selector/src/node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp index 244876ee2cb22..7e215fcfef8dd 100644 --- a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp +++ b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp @@ -19,13 +19,13 @@ #include #include +#include #include #include #include #include #include #include -#include #include #include @@ -97,7 +97,8 @@ class ScenarioSelectorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_parking_trajectory_; rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_scenario_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; // polling subscribers universe_utils::InterProcessPollingSubscriber< diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index defbde4f6aabc..91e86bfea6dba 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -390,7 +390,7 @@ void ScenarioSelectorNode::onTimer() pub_scenario_->publish(scenario); // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); @@ -490,8 +490,8 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti this, get_clock(), period_ns, std::bind(&ScenarioSelectorNode::onTimer, this)); published_time_publisher_ = std::make_unique(this); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); } } // namespace autoware::scenario_selector From 9b8b3fc3280a678ea0205009339c587b5febf096 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:44:22 +0900 Subject: [PATCH 43/59] =?UTF-8?q?feat(autoware=5Foccupancy=5Fgrid=5Fmap=5F?= =?UTF-8?q?outlier=5Ffilter):=20tier4=5Fdebug=5Fmsgs=20changed=20to=20auto?= =?UTF-8?q?ware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(#9894)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_occupancy_grid_map_outlier_filter Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/occupancy_grid_map_outlier_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp index eb52b903b90ca..094825056e62c 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp +++ b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp @@ -420,9 +420,9 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From b7ce209a911eac03593240b8b42676b688991626 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:47:29 +0900 Subject: [PATCH 44/59] =?UTF-8?q?feat(autoware=5Flidar=5Fapollo=5Finstance?= =?UTF-8?q?=5Fsegmentation):=20tier4=5Fdebug=5Fmsgs=20to=20autoware=5Finte?= =?UTF-8?q?rnal=5Fdebug=5Fmsgs=20in=20files=20perce=E2=80=A6=20(#9876)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_lidar_apollo_instance_segmentation Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../CMakeLists.txt | 4 ++-- .../autoware_lidar_apollo_instance_segmentation/package.xml | 2 +- .../autoware_lidar_apollo_instance_segmentation/src/node.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt index 16ab7ecccae60..0555cedc235d9 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt @@ -9,7 +9,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(tf2_eigen REQUIRED) find_package(autoware_universe_utils REQUIRED) -find_package(tier4_debug_msgs REQUIRED) +find_package(autoware_internal_debug_msgs REQUIRED) find_package(tier4_perception_msgs REQUIRED) find_package(autoware_tensorrt_common) @@ -50,7 +50,7 @@ target_link_libraries(${PROJECT_NAME} rclcpp_components::component tf2_eigen::tf2_eigen ${autoware_tensorrt_common_TARGETS} - ${tier4_debug_msgs_TARGETS} + ${autoware_internal_debug_msgs_TARGETS} ${tier4_perception_msgs_TARGETS} ) diff --git a/perception/autoware_lidar_apollo_instance_segmentation/package.xml b/perception/autoware_lidar_apollo_instance_segmentation/package.xml index 8a3d5a7ea6f76..8ff7ce77d943d 100755 --- a/perception/autoware_lidar_apollo_instance_segmentation/package.xml +++ b/perception/autoware_lidar_apollo_instance_segmentation/package.xml @@ -14,6 +14,7 @@ ament_cmake autoware_cuda_utils + autoware_internal_debug_msgs autoware_perception_msgs autoware_tensorrt_common autoware_universe_utils @@ -22,7 +23,6 @@ rclcpp rclcpp_components tf2_eigen - tier4_debug_msgs tier4_perception_msgs ament_lint_auto diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp index 9a3e13b81120f..c535fc6762e1f 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp @@ -62,9 +62,9 @@ void LidarInstanceSegmentationNode::pointCloudCallback( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From acaa40c95a109e21687fe7f2e7f4b37f2ebb1d6b Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:03 +0900 Subject: [PATCH 45/59] =?UTF-8?q?feat(autoware=5Fground=5Fsegmentation):?= =?UTF-8?q?=20tier4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Finternal=5F?= =?UTF-8?q?debug=5Fmsgs=20in=20fil=E2=80=A6=20(#9878)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_ground_segmentation Signed-off-by: vish0012 --- .../src/scan_ground_filter/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp index 74b4edbe595ea..8fda0c1395caf 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp @@ -369,9 +369,9 @@ void ScanGroundFilterComponent::faster_filter( if (debug_publisher_ptr_ && stop_watch_ptr_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); } } From b65e042ebd1df00a09d6a47648dfb07df3e0f68a Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:22 +0900 Subject: [PATCH 46/59] feat(autoware_image_diagnostics): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_image_diagnostics (#9918) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_image_diagnostics Signed-off-by: vish0012 --- sensing/autoware_image_diagnostics/README.md | 14 +++++++------- sensing/autoware_image_diagnostics/package.xml | 2 +- .../src/image_diagnostics_node.cpp | 4 ++-- .../src/image_diagnostics_node.hpp | 11 ++++++----- 4 files changed, 16 insertions(+), 15 deletions(-) diff --git a/sensing/autoware_image_diagnostics/README.md b/sensing/autoware_image_diagnostics/README.md index 03858088564b3..42fcbdc8dc612 100644 --- a/sensing/autoware_image_diagnostics/README.md +++ b/sensing/autoware_image_diagnostics/README.md @@ -28,13 +28,13 @@ After all image's blocks state are evaluated, the whole image status is summariz ### Output -| Name | Type | Description | -| ----------------------------------- | --------------------------------------- | ------------------------------------- | -| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image | -| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image | -| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization | -| `image_diag/image_state_diag` | `tier4_debug_msgs::msg::Int32Stamped` | image diagnostics status value | -| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | +| Name | Type | Description | +| ----------------------------------- | ------------------------------------------------- | ------------------------------------- | +| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image | +| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image | +| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization | +| `image_diag/image_state_diag` | `autoware_internal_debug_msgs::msg::Int32Stamped` | image diagnostics status value | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | ## Parameters diff --git a/sensing/autoware_image_diagnostics/package.xml b/sensing/autoware_image_diagnostics/package.xml index 2e4556de2b92b..3140b87e1f1b9 100644 --- a/sensing/autoware_image_diagnostics/package.xml +++ b/sensing/autoware_image_diagnostics/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto + autoware_internal_debug_msgs autoware_universe_utils cv_bridge diagnostic_updater @@ -19,7 +20,6 @@ rclcpp rclcpp_components sensor_msgs - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp index 1625cba5b72aa..57e53aee46328 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp @@ -33,7 +33,7 @@ ImageDiagNode::ImageDiagNode(const rclcpp::NodeOptions & node_options) dft_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/dft_image"); gray_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/gray_image"); - image_state_pub_ = create_publisher( + image_state_pub_ = create_publisher( "image_diag/image_state_diag", rclcpp::SensorDataQoS()); updater_.setHardwareID("Image_Diagnostics"); @@ -225,7 +225,7 @@ void ImageDiagNode::ImageChecker(const sensor_msgs::msg::Image::ConstSharedPtr i } else { params_.diagnostic_status = 0; } - tier4_debug_msgs::msg::Int32Stamped image_state_out; + autoware_internal_debug_msgs::msg::Int32Stamped image_state_out; image_state_out.data = params_.diagnostic_status; image_state_pub_->publish(image_state_out); diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp index 325624062b90b..9383da33160f9 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp @@ -21,10 +21,10 @@ #include #include +#include +#include +#include #include -#include -#include -#include #if __has_include() #include @@ -95,8 +95,9 @@ class ImageDiagNode : public rclcpp::Node image_transport::Publisher block_diag_image_pub_; image_transport::Publisher dft_image_pub_; image_transport::Publisher gray_image_pub_; - rclcpp::Publisher::SharedPtr average_pub_; - rclcpp::Publisher::SharedPtr image_state_pub_; + rclcpp::Publisher::SharedPtr + average_pub_; + rclcpp::Publisher::SharedPtr image_state_pub_; }; } // namespace autoware::image_diagnostics From 221a7bc0eb333f27638d5bdc5a9d7ecc4fd79be0 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:56 +0900 Subject: [PATCH 47/59] =?UTF-8?q?feat(autoware=5Fcompare=5Fmap=5Fsegmentat?= =?UTF-8?q?ion):=20tier4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Fintern?= =?UTF-8?q?al=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(#9869)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_compare_map_segmentation Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/distance_based_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_based_approximate_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_based_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_distance_based_compare_map_filter/node.cpp | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp index ae07d54ad53d6..ac759504de557 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp @@ -173,9 +173,9 @@ void DistanceBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp index 9f325b36676be..5794cfe37a45b 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp @@ -141,9 +141,9 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index a31d5ec5dd6d6..db5e46a0eff5a 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -100,9 +100,9 @@ void VoxelBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp index d0bcf381cd62f..775a931ac4c4c 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp @@ -173,9 +173,9 @@ void VoxelDistanceBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From cee6ef912154312c3a4e6eff3ee04013cb9d7175 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:54:14 +0900 Subject: [PATCH 48/59] feat(autoware_probabilistic_occupancy_grid_map): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_probabilistic_occupancy_grid_map (#9895) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_probabilistic_occupancy_grid_map Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/fusion/synchronized_grid_map_fusion_node.cpp | 6 +++--- .../pointcloud_based_occupancy_grid_map_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp index 880dfda03c495..7cde04ca9614b 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -332,11 +332,11 @@ void GridMapFusionNode::publish() std::chrono::duration( std::chrono::nanoseconds((this->get_clock()->now() - latest_stamp).nanoseconds())) .count(); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index 4d442ad2c33db..ff836a1ddf760 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -261,11 +261,11 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( std::chrono::nanoseconds( (this->get_clock()->now() - input_raw_msg->header.stamp).nanoseconds())) .count(); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } From 95e7939e7e3b6164913ce5b5119247de94a89ac8 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 16:06:17 +0900 Subject: [PATCH 49/59] feat(autoware_pointcloud_preprocessor): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_pointcloud_preprocessor (#9920) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_pointcloud_preprocessor Signed-off-by: vish0012 --- .../docs/blockage-diag.md | 20 +++++++++---------- .../docs/dual-return-outlier-filter.md | 10 +++++----- .../blockage_diag/blockage_diag_node.hpp | 13 +++++++----- .../concatenate_and_time_sync_nodelet.hpp | 4 ++-- .../concatenate_pointclouds.hpp | 4 ++-- .../dual_return_outlier_filter_node.hpp | 4 ++-- .../ring_outlier_filter_node.hpp | 2 +- .../time_synchronizer_node.hpp | 4 ++-- .../package.xml | 2 +- .../src/blockage_diag/blockage_diag_node.cpp | 12 +++++------ .../concatenate_and_time_sync_nodelet.cpp | 6 +++--- .../concatenate_pointclouds.cpp | 6 +++--- .../crop_box_filter/crop_box_filter_node.cpp | 6 +++--- .../distortion_corrector_node.cpp | 6 +++--- ...ased_voxel_grid_downsample_filter_node.cpp | 6 +++--- .../dual_return_outlier_filter_node.cpp | 4 ++-- .../ring_outlier_filter_node.cpp | 10 +++++----- .../time_synchronizer_node.cpp | 6 +++--- 18 files changed, 64 insertions(+), 61 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md b/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md index 911cda3823021..a9dcb8437ec67 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md @@ -38,16 +38,16 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Output -| Name | Type | Description | -| :-------------------------------------------------------- | :-------------------------------------- | ------------------------------------------------------------------------------------------------ | -| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage | -| `~/output/blockage_diag/debug/ground_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region | -| `~/output/blockage_diag/debug/sky_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region | -| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud | -| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame | -| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area | -| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results | -| `~/output/blockage_diag/debug/ground_dust_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. | +| Name | Type | Description | +| :-------------------------------------------------------- | :-------------------------------------------------- | ------------------------------------------------------------------------------------------------ | +| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage | +| `~/output/blockage_diag/debug/ground_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region | +| `~/output/blockage_diag/debug/sky_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region | +| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud | +| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame | +| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area | +| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results | +| `~/output/blockage_diag/debug/ground_dust_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. | ## Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 8f4da273861a3..0d0423d40ab83 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -36,11 +36,11 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Output -| Name | Type | Description | -| ---------------------------------------------- | --------------------------------------- | ------------------------------------------------------- | -| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility | -| `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | -| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | +| Name | Type | Description | +| ---------------------------------------------- | --------------------------------------------------- | ------------------------------------------------------- | +| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility | +| `/dual_return_outlier_filter/visibility` | `autoware_internal_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | +| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | ## Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp index 3601b492c4fe3..2dbda770f6cec 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp @@ -22,10 +22,10 @@ #include #include +#include #include #include #include -#include #if __has_include() #include @@ -58,10 +58,13 @@ class BlockageDiagComponent : public autoware::pointcloud_preprocessor::Filter image_transport::Publisher single_frame_dust_mask_pub; image_transport::Publisher multi_frame_dust_mask_pub; image_transport::Publisher blockage_dust_merged_pub; - rclcpp::Publisher::SharedPtr ground_blockage_ratio_pub_; - rclcpp::Publisher::SharedPtr sky_blockage_ratio_pub_; - rclcpp::Publisher::SharedPtr ground_dust_ratio_pub_; - rclcpp::Publisher::SharedPtr blockage_type_pub_; + rclcpp::Publisher::SharedPtr + ground_blockage_ratio_pub_; + rclcpp::Publisher::SharedPtr + sky_blockage_ratio_pub_; + rclcpp::Publisher::SharedPtr + ground_dust_ratio_pub_; + rclcpp::Publisher::SharedPtr blockage_type_pub_; private: void onBlockageChecker(DiagnosticStatusWrapper & stat); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 40adad3521f8d..6164e85c35717 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -69,14 +69,14 @@ #include #include +#include +#include #include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index 0e959eedae1b6..d57e44431a8d2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -68,13 +68,13 @@ #include #include +#include +#include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp index ef33e88ef5c98..fa55222fb6530 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp @@ -22,9 +22,9 @@ #include #include +#include #include #include -#include #if __has_include() #include @@ -54,7 +54,7 @@ class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocesso /** \brief Parameter service callback */ rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector & p); image_transport::Publisher image_pub_; - rclcpp::Publisher::SharedPtr visibility_pub_; + rclcpp::Publisher::SharedPtr visibility_pub_; rclcpp::Publisher::SharedPtr noise_cloud_pub_; private: diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp index c898cbacf33ea..96bd2fb2411a0 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp @@ -53,7 +53,7 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, const TransformInfo & transform_info) override; - rclcpp::Publisher::SharedPtr visibility_pub_; + rclcpp::Publisher::SharedPtr visibility_pub_; private: /** \brief publisher of excluded pointcloud for debug reason. **/ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp index d36fcb36a7be1..f4921be66a7e2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp @@ -68,14 +68,14 @@ #include #include +#include +#include #include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 4511c5497a3a0..525b1f3eb0699 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -26,6 +26,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_pcl_extensions autoware_point_types @@ -51,7 +52,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp index 5021a3551c939..e05d5f789f680 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp @@ -68,7 +68,7 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options std::string(this->get_namespace()) + ": dust_validation", this, &BlockageDiagComponent::dustChecker); - ground_dust_ratio_pub_ = create_publisher( + ground_dust_ratio_pub_ = create_publisher( "blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS()); if (publish_debug_image_) { single_frame_dust_mask_pub = @@ -86,9 +86,9 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options blockage_mask_pub_ = image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image"); } - ground_blockage_ratio_pub_ = create_publisher( + ground_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/ground_blockage_ratio", rclcpp::SensorDataQoS()); - sky_blockage_ratio_pub_ = create_publisher( + sky_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/sky_blockage_ratio", rclcpp::SensorDataQoS()); using std::placeholders::_1; set_param_res_ = this->add_on_set_parameters_callback( @@ -315,7 +315,7 @@ void BlockageDiagComponent::filter( cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1); cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img); - tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; ground_dust_ratio_ = static_cast(cv::countNonZero(single_dust_ground_img)) / (single_dust_ground_img.cols * single_dust_ground_img.rows); ground_dust_ratio_msg.data = ground_dust_ratio_; @@ -386,12 +386,12 @@ void BlockageDiagComponent::filter( } } - tier4_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg; ground_blockage_ratio_msg.data = ground_blockage_ratio_; ground_blockage_ratio_msg.stamp = now(); ground_blockage_ratio_pub_->publish(ground_blockage_ratio_msg); - tier4_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg; sky_blockage_ratio_msg.data = sky_blockage_ratio_; sky_blockage_ratio_msg.stamp = now(); sky_blockage_ratio_pub_->publish(sky_blockage_ratio_msg); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index f8baae3405873..b49e21b8f30be 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -455,9 +455,9 @@ void PointCloudConcatenateDataSynchronizerComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } for (const auto & e : cloud_stdmap_) { @@ -468,7 +468,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index ba29389b88bf7..ba5e2eb51997a 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -271,7 +271,7 @@ void PointCloudConcatenationComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } } @@ -297,9 +297,9 @@ void PointCloudConcatenationComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp index ecbc5b8fd13ef..54c940d414db8 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp @@ -194,9 +194,9 @@ void CropBoxFilterComponent::faster_filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -204,7 +204,7 @@ void CropBoxFilterComponent::faster_filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp index 9eaafeae9dbc7..cc05a6cc2765c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -123,7 +123,7 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po std::chrono::nanoseconds( (this->get_clock()->now() - pointcloud_msg->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } @@ -133,9 +133,9 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp index 3d2bc0a206c94..0c467234d6591 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp @@ -142,9 +142,9 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -152,7 +152,7 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp index a8024e02de2c1..bac3a59e09528 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp @@ -65,7 +65,7 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( image_pub_ = image_transport::create_publisher(this, "dual_return_outlier_filter/debug/frequency_image"); - visibility_pub_ = create_publisher( + visibility_pub_ = create_publisher( "dual_return_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); { rclcpp::PublisherOptions pub_options; @@ -322,7 +322,7 @@ void DualReturnOutlierFilterComponent::filter( frequency_image_msg->header = input->header; // Publish histogram image image_pub_.publish(frequency_image_msg); - tier4_debug_msgs::msg::Float32Stamped visibility_msg; + autoware_internal_debug_msgs::msg::Float32Stamped visibility_msg; visibility_msg.data = (1.0f - filled); visibility_msg.stamp = now(); visibility_pub_->publish(visibility_msg); diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp index fae9043143ba4..fcea299ba5aff 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp @@ -41,7 +41,7 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions outlier_pointcloud_publisher_ = this->create_publisher("debug/ring_outlier_filter", 1, pub_options); } - visibility_pub_ = create_publisher( + visibility_pub_ = create_publisher( "ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); @@ -262,7 +262,7 @@ void RingOutlierFilterComponent::faster_filter( outlier.header = input->header; outlier_pointcloud_publisher_->publish(outlier); - tier4_debug_msgs::msg::Float32Stamped visibility_msg; + autoware_internal_debug_msgs::msg::Float32Stamped visibility_msg; visibility_msg.data = calculateVisibilityScore(outlier); visibility_msg.stamp = input->header.stamp; visibility_pub_->publish(visibility_msg); @@ -272,9 +272,9 @@ void RingOutlierFilterComponent::faster_filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -282,7 +282,7 @@ void RingOutlierFilterComponent::faster_filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp index 42170fd88ee36..e5bd4a955590f 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp @@ -378,7 +378,7 @@ void PointCloudDataSynchronizerComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } auto output = std::make_unique(*e.second); @@ -400,9 +400,9 @@ void PointCloudDataSynchronizerComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From b20d7f05df2da1dd1580e824c82316ed77f49059 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 15 Jan 2025 16:20:10 +0900 Subject: [PATCH 50/59] chore(autoware_test_utils): move rviz config to autoware_launch (#9925) Signed-off-by: Mamoru Sobue --- common/autoware_test_utils/CMakeLists.txt | 1 - .../launch/psim_intersection.launch.xml | 2 +- .../launch/psim_road_shoulder.launch.xml | 2 +- .../rviz/psim_test_map.rviz | 4569 ----------------- 4 files changed, 2 insertions(+), 4572 deletions(-) delete mode 100644 common/autoware_test_utils/rviz/psim_test_map.rviz diff --git a/common/autoware_test_utils/CMakeLists.txt b/common/autoware_test_utils/CMakeLists.txt index 8bfa44f7bf0ba..20b8f964f879f 100644 --- a/common/autoware_test_utils/CMakeLists.txt +++ b/common/autoware_test_utils/CMakeLists.txt @@ -25,5 +25,4 @@ ament_auto_package(INSTALL_TO_SHARE test_map test_data launch - rviz ) diff --git a/common/autoware_test_utils/launch/psim_intersection.launch.xml b/common/autoware_test_utils/launch/psim_intersection.launch.xml index 723dd7352219d..dc3e75cca1d96 100644 --- a/common/autoware_test_utils/launch/psim_intersection.launch.xml +++ b/common/autoware_test_utils/launch/psim_intersection.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml index 7dd888a036f9d..58b71524e72b8 100644 --- a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml +++ b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/common/autoware_test_utils/rviz/psim_test_map.rviz b/common/autoware_test_utils/rviz/psim_test_map.rviz deleted file mode 100644 index 8475c94b86bb4..0000000000000 --- a/common/autoware_test_utils/rviz/psim_test_map.rviz +++ /dev/null @@ -1,4569 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 - Splitter Ratio: 0.557669460773468 - Tree Height: 225 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: ~ - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: AutowareDateTimePanel - Name: AutowareDateTimePanel - - Class: rviz_plugins::AutowareStatePanel - Name: AutowareStatePanel - - Class: rviz_plugins::SimulatedClockPanel - Name: SimulatedClockPanel - - Class: rviz_plugins::TrafficLightPublishPanel - Name: TrafficLightPublishPanel -Visualization Manager: - Class: "" - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: false - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: false - - Class: rviz_common/Group - Displays: - - Alpha: 0.30000001192092896 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - ars408_front_center: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera1/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera1/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera2/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera2/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera3/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera3/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera4/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera4/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera5/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera5/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera6/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera6/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera7/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera7/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - gnss_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - livox_front_left: - Alpha: 1 - Show Axes: false - Show Trail: false - livox_front_left_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - livox_front_right: - Alpha: 1 - Show Axes: false - Show Trail: false - livox_front_right_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - sensor_kit_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - tamagawa/imu_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_left: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_left_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Mass Properties: - Inertia: false - Mass: false - Name: VehicleModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_plugins/PolarGridDisplay - Color: 255; 255; 255 - Delta Range: 10 - Enabled: true - Max Alpha: 0.5 - Max Range: 100 - Max Wave Alpha: 0.5 - Min Alpha: 0.009999999776482582 - Min Wave Alpha: 0.009999999776482582 - Name: PolarGridDisplay - Reference Frame: base_link - Value: true - Wave Color: 255; 255; 255 - Wave Velocity: 40 - - Background Alpha: 0.5 - Background Color: 23; 28; 31 - Class: autoware_overlay_rviz_plugin/SignalDisplay - Dark Traffic Color: 255; 51; 51 - Enabled: true - Gear Topic Test: /vehicle/status/gear_status - Handle Angle Scale: 17 - Hazard Lights Topic: /vehicle/status/hazard_lights_status - Height: 100 - Left: 0 - Light Traffic Color: 255; 153; 153 - Name: SignalDisplay - Primary Color: 174; 174; 174 - Signal Color: 0; 230; 120 - Speed Limit Topic: /planning/scenario_planning/current_max_velocity - Speed Topic: /vehicle/status/velocity_status - Steering Topic: /vehicle/status/steering_status - Top: 10 - Traffic Topic: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal - Turn Signals Topic: /vehicle/status/turn_indicators_status - Value: true - Width: 550 - Enabled: true - Name: Vehicle - - Class: rviz_plugins/MrmSummaryOverlayDisplay - Enabled: false - Font Size: 10 - Left: 512 - Max Letter Num: 100 - Name: MRM Summary - Text Color: 25; 255; 240 - Top: 64 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /system/emergency/hazard_status - Value: false - Value height offset: 0 - Enabled: true - Name: System - - Class: rviz_common/Group - Displays: - - Alpha: 0.20000000298023224 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 - Min Intensity: 0 - Name: PointCloudMap - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/pointcloud_map - Use Fixed Frame: true - Use rainbow: false - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Lanelet2VectorMap - Namespaces: - bus_stop_area: true - center_lane_line: false - center_line_arrows: false - curbstone: true - lane_start_bound: false - lanelet direction: true - lanelet_id: false - left_lane_bound: true - no_parking_area: true - parking_lots: true - parking_space: true - partitions: true - right_lane_bound: true - road_lanelets: false - shoulder_center_lane_line: false - shoulder_center_line_arrows: true - shoulder_lane_start_bound: true - shoulder_left_lane_bound: true - shoulder_right_lane_bound: true - shoulder_road_lanelets: false - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/vector_map_marker - Value: true - Enabled: true - Name: Map - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.4000000059604645 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 5 - Min Value: -1 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: false - Use rainbow: true - Value: true - - Alpha: 0.9990000128746033 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: MeasurementRange - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/lidar/crop_box_filter/crop_box_polygon - Value: false - Enabled: true - Name: LiDAR - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 233; 185; 110 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: false - Position: - Alpha: 0.20000000298023224 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.699999988079071 - Head Radius: 1.2000000476837158 - Name: PoseWithCovariance - Shaft Length: 1 - Shaft Radius: 0.5 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/gnss/pose_with_covariance - Value: true - Enabled: false - Name: GNSS - Enabled: true - Name: Sensing - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 170; 255 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovInitial - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/initial_pose_with_covariance - Value: false - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 255; 0 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovAligned - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose_with_covariance - Value: false - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: false - Line: - Alpha: 0.9990000128746033 - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose - Value: false - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 0; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Initial - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /localization/util/downsample/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Aligned - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/points_aligned - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MonteCarloInitialPose - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/monte_carlo_initial_pose_marker - Value: true - Enabled: true - Name: NDT - - Class: rviz_common/Group - Displays: - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: EKF - Enabled: true - Name: Localization - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false - Axis: Z - Channel Name: z - Class: rviz_default_plugins/PointCloud2 - Color: 200; 200; 200 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 15 - Min Color: 0; 0; 0 - Min Intensity: -5 - Name: NoGroundPointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/obstacle_segmentation/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: Segmentation - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/TrackedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Dynamic Status: All - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/PredictedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Maneuver - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/prediction/maneuver - Value: false - Enabled: true - Name: Prediction - Enabled: true - Name: ObjectRecognition - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/Image - Enabled: false - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/traffic_light_recognition/traffic_light/debug/rois - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MapBasedDetectionResult - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers - Value: true - Enabled: true - Name: TrafficLight - - Class: rviz_common/Group - Displays: - - Alpha: 0.5 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false - Enabled: true - Name: Map - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/occupancy_grid_map/map - Update Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/occupancy_grid_map/map_updates - Use Timestamp: false - Value: true - Enabled: false - Name: OccupancyGrid - Enabled: true - Name: Perception - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: RouteArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/route_marker - Value: true - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.30000001192092896 - Class: rviz_default_plugins/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.5 - Name: GoalPose - Shaft Length: 3 - Shaft Radius: 0.20000000298023224 - Shape: Axes - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/echo_back_goal_pose - Value: true - - Background Alpha: 0.5 - Background Color: 23; 28; 31 - Class: autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay - Enabled: true - Height: 100 - Name: MissionDetailsDisplay - Remaining Distance and Time Topic: /planning/mission_remaining_distance_time - Right: 10 - Text Color: 194; 194; 194 - Top: 10 - Value: true - Width: 170 - Enabled: true - Name: MissionPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: ScenarioTrajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/trajectory - Value: true - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.9990000128746033 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.9990000128746033 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: Path - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/path - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.4000000059604645 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_AvoidanceByLC - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/avoidance_by_lane_change - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_Avoidance - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/static_obstacle_avoidance - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_LaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/lane_change_right - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_LaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/lane_change_left - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_GoalPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/goal_planner - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_StartPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/start_planner - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_AvoidanceByLC - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/avoidance_by_lane_change - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: (old)PathChangeCandidate_LaneChange - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_LaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change_right - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_LaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change_left - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/external_request_lane_change_right - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/external_request_lane_change_left - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_Avoidance - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/static_obstacle_avoidance - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_StartPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/start_planner - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_GoalPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/goal_planner - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Bound - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StaticObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/static_obstacle_avoidance - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (AvoidanceByLC) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance_by_lane_change - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (LaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (LaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ExtLaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ExtLaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (GoalPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/goal_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StartPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/start_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (BlindSpot) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Crosswalk) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Walkway) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/walkway - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (DetectionArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Intersection) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (MergeFromPrivateArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/merge_from_private - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (NoStoppingArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_stopping_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (OcclusionSpot) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/occlusion_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StopLine) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/stop_line - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (TrafficLight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (VirtualTrafficLight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/virtual_traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (RunOut) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/run_out - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (SpeedBump) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/speed_bump - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (NoDrivableLane) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Crosswalk - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Intersection - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Blind Spot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: TrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: VirtualTrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StopLine - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: DetectionArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: OcclusionSpot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: NoStoppingArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: RunOut - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/run_out - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StaticObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/static_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: LeftLaneChange - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: RightLaneChange - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: LaneFollowing - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_following - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: GoalPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/goal_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StartPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/start_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: SideShift - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/side_shift - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: SpeedBump - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/speed_bump - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: DynamicObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: NoDrivableLane - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_drivable_lane - Value: false - Enabled: false - Name: DebugMarker - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (StaticObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/static_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (AvoidanceByLC) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance_by_lane_change - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (LaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (LaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (ExtLaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (ExtLaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (GoalPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/goal_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (StartPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/start_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (DynamicObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/dynamic_obstacle_avoidance - Value: false - Enabled: false - Name: InfoMarker - Enabled: true - Name: BehaviorPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/trajectory - Value: false - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.9990000128746033 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.9990000128746033 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleStop) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (SurroundObstacle) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleCruise) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (MotionVelocitySmoother) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/velocity_smoother/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (OutOfLane) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/virtual_walls - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleVelocityLimiter) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/virtual_walls - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (DynamicObstacleStop) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/virtual_walls - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: SurroundObstacleCheck - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Value: true - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: Footprint - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint - Value: false - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 239; 41; 41 - Enabled: false - Name: FootprintOffset - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_offset - Value: false - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 10; 21; 255 - Enabled: false - Name: FootprintRecoverOffset - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_recover_offset - Value: false - Enabled: false - Name: SurroundObstacleChecker - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: ObstacleStop - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: CruiseVirtualWall - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: SlowDownVirtualWall - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/slow_down/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DebugMarker - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker - Value: true - Enabled: false - Name: ObstacleCruise - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: ObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: OutOfLane - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/debug_markers - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleVelocityLimiter - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/debug_markers - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DynamicObstacleStop - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/debug_markers - Value: true - Enabled: false - Name: MotionVelocityPlanner - Enabled: false - Name: DebugMarker - Enabled: true - Name: MotionPlanning - Enabled: true - Name: LaneDriving - - Class: rviz_common/Group - Displays: - - Alpha: 0.699999988079071 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false - Enabled: false - Name: Costmap - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid - Update Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates - Use Timestamp: false - Value: false - - Alpha: 0.9990000128746033 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 255; 25; 0 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PartialPoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (3D) - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array - Value: true - - Alpha: 0.9990000128746033 - Arrow Length: 0.5 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 0; 0; 255 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (Flat) - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array - Value: true - Enabled: true - Name: Parking - - Class: rviz_plugins/PoseWithUuidStamped - Enabled: true - Length: 1.5 - Name: ModifiedGoal - Radius: 0.5 - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/modified_goal - UUID: - Scale: 0.30000001192092896 - Value: false - Value: true - Enabled: true - Name: ScenarioPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: PlanningErrorMarker - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker - Value: true - Enabled: false - Name: Diagnostic - Enabled: true - Name: Planning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: Predicted Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/predicted_trajectory_in_frenet_coordinate - Value: true - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Constant Width: true - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 0.05000000074505806 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Resampled Reference Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/resampled_reference_trajectory - Value: false - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Constant Width: true - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: false - Width: 0.20000000298023224 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: true - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (AEB) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/autonomous_emergency_braking/virtual_wall - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_default_plugins/Marker - Enabled: false - Name: Stop Reason - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/longitudinal/stop_reason - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/MPC - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/mpc_follower/debug/markers - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/PurePursuit - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/markers - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/AEB - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/autonomous_emergency_braking/debug/markers - Value: false - Enabled: true - Name: Control - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: ~ - Enabled: true - Name: Map - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/Camera - Enabled: true - Far Plane Distance: 100 - Image Rendering: background and overlay - Name: PointcloudOnCamera - Overlay Alpha: 0.5 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/camera/camera6/image_raw - Value: true - Visibility: - Control: - Debug/AEB: true - Debug/MPC: true - Debug/PurePursuit: true - Predicted Trajectory: true - Resampled Reference Trajectory: true - Stop Reason: true - Value: false - VirtualWall: - Value: true - VirtualWall (AEB): true - Debug: - Control: true - Localization: - "": true - Value: true - Map: true - Perception: - "": true - Value: true - Planning: - "": - "": true - Value: true - Value: true - Sensing: - ConcatenatePointCloud: true - RadarRawObjects(white): true - Value: true - Value: true - Localization: - EKF: - PoseHistory: true - Value: true - NDT: - Aligned: true - Initial: true - MonteCarloInitialPose: true - PoseHistory: true - PoseWithCovAligned: true - PoseWithCovInitial: true - Value: true - Value: false - Map: - Lanelet2VectorMap: true - PointCloudMap: true - Value: false - Perception: - ObjectRecognition: - Detection: - DetectedObjects: true - Value: true - Prediction: - Maneuver: true - PredictedObjects: true - Value: true - Tracking: - TrackedObjects: true - Value: true - Value: true - OccupancyGrid: - Map: true - Value: true - Segmentation: - NoGroundPointCloud: true - Value: true - TrafficLight: - MapBasedDetectionResult: true - RecognitionResultOnImage: true - Value: true - Value: false - Planning: - Diagnostic: - PlanningErrorMarker: true - Value: true - MissionPlanning: - GoalPose: true - MissionDetailsDisplay: true - RouteArea: true - Value: true - ScenarioPlanning: - LaneDriving: - BehaviorPlanning: - (old)PathChangeCandidate_LaneChange: true - Bound: true - DebugMarker: - Arrow: true - Blind Spot: true - Crosswalk: true - DetectionArea: true - DynamicObstacleAvoidance: true - GoalPlanner: true - Intersection: true - LaneFollowing: true - LeftLaneChange: true - NoDrivableLane: true - NoStoppingArea: true - OcclusionSpot: true - RightLaneChange: true - RunOut: true - SideShift: true - SpeedBump: true - StartPlanner: true - StaticObstacleAvoidance: true - StopLine: true - TrafficLight: true - Value: true - VirtualTrafficLight: true - InfoMarker: - Info (AvoidanceByLC): true - Info (DynamicObstacleAvoidance): true - Info (ExtLaneChangeLeft): true - Info (ExtLaneChangeRight): true - Info (GoalPlanner): true - Info (LaneChangeLeft): true - Info (LaneChangeRight): true - Info (StartPlanner): true - Info (StaticObstacleAvoidance): true - Value: true - Path: true - PathChangeCandidate_Avoidance: true - PathChangeCandidate_AvoidanceByLC: true - PathChangeCandidate_ExternalRequestLaneChangeLeft: true - PathChangeCandidate_ExternalRequestLaneChangeRight: true - PathChangeCandidate_GoalPlanner: true - PathChangeCandidate_LaneChangeLeft: true - PathChangeCandidate_LaneChangeRight: true - PathChangeCandidate_StartPlanner: true - PathReference_Avoidance: true - PathReference_AvoidanceByLC: true - PathReference_GoalPlanner: true - PathReference_LaneChangeLeft: true - PathReference_LaneChangeRight: true - PathReference_StartPlanner: true - Value: true - VirtualWall: - Value: true - VirtualWall (AvoidanceByLC): true - VirtualWall (BlindSpot): true - VirtualWall (Crosswalk): true - VirtualWall (DetectionArea): true - VirtualWall (ExtLaneChangeLeft): true - VirtualWall (ExtLaneChangeRight): true - VirtualWall (GoalPlanner): true - VirtualWall (Intersection): true - VirtualWall (LaneChangeLeft): true - VirtualWall (LaneChangeRight): true - VirtualWall (MergeFromPrivateArea): true - VirtualWall (NoDrivableLane): true - VirtualWall (NoStoppingArea): true - VirtualWall (OcclusionSpot): true - VirtualWall (RunOut): true - VirtualWall (SpeedBump): true - VirtualWall (StartPlanner): true - VirtualWall (StaticObstacleAvoidance): true - VirtualWall (StopLine): true - VirtualWall (TrafficLight): true - VirtualWall (VirtualTrafficLight): true - VirtualWall (Walkway): true - MotionPlanning: - DebugMarker: - MotionVelocityPlanner: - DynamicObstacleStop: true - ObstacleVelocityLimiter: true - OutOfLane: true - Value: true - ObstacleAvoidance: true - ObstacleCruise: - CruiseVirtualWall: true - DebugMarker: true - SlowDownVirtualWall: true - Value: true - ObstacleStop: true - SurroundObstacleChecker: - Footprint: true - FootprintOffset: true - FootprintRecoverOffset: true - SurroundObstacleCheck: true - Value: true - Value: true - Trajectory: true - Value: true - VirtualWall: - Value: true - VirtualWall (DynamicObstacleStop): true - VirtualWall (MotionVelocitySmoother): true - VirtualWall (ObstacleAvoidance): true - VirtualWall (ObstacleCruise): true - VirtualWall (ObstacleStop): true - VirtualWall (ObstacleVelocityLimiter): true - VirtualWall (OutOfLane): true - VirtualWall (SurroundObstacle): true - Value: true - ModifiedGoal: true - Parking: - Costmap: true - PartialPoseArray: true - PoseArray: true - Value: true - ScenarioTrajectory: true - Value: true - Value: false - Sensing: - GNSS: - PoseWithCovariance: true - Value: true - LiDAR: - ConcatenatePointCloud: true - MeasurementRange: true - Value: true - Value: true - System: - Grid: true - MRM Summary: true - TF: true - Value: false - Vehicle: - PolarGridDisplay: true - SignalDisplay: true - Value: true - VehicleModel: true - Value: true - Zoom Factor: 1 - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 5 - Min Value: -1 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: false - Use rainbow: true - Value: true - - BUS: - Alpha: 0.5 - Color: 255; 255; 255 - CAR: - Alpha: 0.5 - Color: 255; 255; 255 - CYCLIST: - Alpha: 0.5 - Color: 255; 255; 255 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.5 - Color: 255; 255; 255 - Name: RadarRawObjects(white) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.5 - Color: 255; 255; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.5 - Color: 255; 255; 255 - TRUCK: - Alpha: 0.5 - Color: 255; 255; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/radar/detected_objects - UNKNOWN: - Alpha: 0.5 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Sensing - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NDT pointclouds - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/points_aligned - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NDTLoadedPCDMap - Position Transformer: "" - Selectable: true - Size (Pixels): 3 - Size (m): 0.10000000149011612 - Style: Flat Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/debug/loaded_pointcloud_map - Use Fixed Frame: true - Use rainbow: true - Value: true - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: NDTPoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose - Value: true - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: EKFPoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: Localization - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Name: Centerpoint(red1) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Name: CenterpointROIFusion(red2) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/roi_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Name: CenterpointValidator(red3) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/validation/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - CAR: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Name: PointPainting(light_green1) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - TRUCK: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - CAR: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Name: PointPaintingROIFusion(light_green2) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - TRUCK: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/roi_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - CAR: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Name: PointPaintingValidator(light_green3) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - TRUCK: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/validation/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Name: DetectionByTracker(orange) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/detection_by_tracker/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - CAR: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Name: CameraLidarFusion(purple) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - TRUCK: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/clustering/camera_lidar_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Name: RadarFarObjects(white) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/radar/far_objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Name: Detection(yellow) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - CAR: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Class: autoware_perception_rviz_plugin/TrackedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Dynamic Status: All - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Name: Tracking(green) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - TRUCK: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Class: autoware_perception_rviz_plugin/PredictedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Name: Prediction(light_blue) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Value: true - Visualization Type: Normal - Enabled: true - Name: Perception - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: LaneChangeLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: LaneChangeRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceByLCLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/avoidance_by_lc_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceByLCRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/avoidance_by_lc_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: StartPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/start_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: GoalPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/goal_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Crosswalk - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Intersection - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: BlindSpot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DetectionArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: NoStoppingArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/no_stopping_area - Value: true - Enabled: true - Name: Objects Of Interest - Enabled: true - Name: Planning - - Class: rviz_common/Group - Displays: ~ - Enabled: true - Name: Control - Enabled: false - Name: Debug - Enabled: true - Global Options: - Background Color: 15; 20; 23 - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Covariance x: 0.25 - Covariance y: 0.25 - Covariance yaw: 0.06853891909122467 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/goal - - Class: tier4_adapi_rviz_plugins::RouteTool - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /rviz/routing/rough_goal - - Acceleration: 0 - Class: rviz_plugins/PedestrianInitialPoseTool - Interactive: false - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 1 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/CarInitialPoseTool - H vehicle height: 2 - Interactive: false - L vehicle length: 4 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 3 - W vehicle width: 1.7999999523162842 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/BusInitialPoseTool - H vehicle height: 3.5 - Interactive: false - L vehicle length: 10.5 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - W vehicle width: 2.5 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Class: rviz_plugins/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint - Theta std deviation: 0.2617993950843811 - X std deviation: 0.5 - Y std deviation: 0.5 - Z position: 0 - - Class: rviz_plugins/DeleteAllObjectsTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz_default_plugins) - X: 0 - Y: 0 - Saved: - - Class: rviz_default_plugins/ThirdPersonFollower - Distance: 18 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: ThirdPersonFollower - Near Clip Distance: 0.009999999776482582 - Pitch: 0.20000000298023224 - Target Frame: base_link - Value: ThirdPersonFollower (rviz) - Yaw: 3.141592025756836 - - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: TopDownOrtho - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 -Window Geometry: - AutowareDateTimePanel: - collapsed: false - AutowareStatePanel: - collapsed: false - Displays: - collapsed: false - Height: 939 - Hide Left Dock: false - Hide Right Dock: false - PointcloudOnCamera: - collapsed: false - QMainWindow State: 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 - RecognitionResultOnImage: - collapsed: false - Selection: - collapsed: false - SimulatedClockPanel: - collapsed: false - Tool Properties: - collapsed: false - TrafficLightPublishPanel: - collapsed: false - Views: - collapsed: false - Width: 1920 - X: 0 - Y: 34 From 87537bd02e6479e0bb5f95d874822c8e81181c13 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:13 +0900 Subject: [PATCH 51/59] chore(autoware_traffic_light_occlusion_predictor): modify docs (#9820) * fix docs Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 25 +++++++++++-------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_occlusion_predictor/README.md b/perception/autoware_traffic_light_occlusion_predictor/README.md index bc57dbea76c97..5d2e320dfc72a 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/README.md +++ b/perception/autoware_traffic_light_occlusion_predictor/README.md @@ -1,8 +1,10 @@ -# The `autoware_traffic_light_occlusion_predictor` Package +# autoware_traffic_light_occlusion_predictor ## Overview `autoware_traffic_light_occlusion_predictor` receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud. +If that rois is judged as occlusion, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `UNKNOWN`, and `0.0`. +This node publishes when each car and pedestrian `traffic_signals` is arrived and processed. For each traffic light roi, hundreds of pixels would be selected and projected into the 3D space. Then from the camera point of view, the number of projected pixels that are occluded by the point cloud is counted and used for calculating the occlusion ratio for the roi. As shown in follow image, the red pixels are occluded and the occlusion ratio is the number of red pixels divided by the total pixel numbers. @@ -12,18 +14,20 @@ If no point cloud is received or all point clouds have very large stamp differen ## Input topics -| Name | Type | Description | -| -------------------- | ---------------------------------------------- | ------------------------ | -| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | -| `~/input/rois` | autoware_perception_msgs::TrafficLightRoiArray | traffic light detections | -| `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | -| `~/input/cloud` | sensor_msgs::PointCloud2 | LiDAR point cloud | +| Name | Type | Description | +| ------------------------------------ | ------------------------------------------------ | -------------------------------- | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/car/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | vehicular traffic light signals | +| `~/input/pedestrian/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | pedestrian traffic light signals | +| `~/input/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | traffic light detections | +| `~/input/camera_info` | sensor_msgs::msg::CameraInfo | target camera parameter | +| `~/input/cloud` | sensor_msgs::msg::PointCloud2 | LiDAR point cloud | ## Output topics -| Name | Type | Description | -| -------------------- | ---------------------------------------------------- | ---------------------------- | -| `~/output/occlusion` | autoware_perception_msgs::TrafficLightOcclusionArray | occlusion ratios of each roi | +| Name | Type | Description | +| -------------------------- | --------------------------------------------- | -------------------------------------------------------------- | +| `~/output/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | traffic light signals which occluded image results overwritten | ## Node parameters @@ -34,3 +38,4 @@ If no point cloud is received or all point clouds have very large stamp differen | `max_valid_pt_dist` | double | The points within this distance would be used for calculation | | `max_image_cloud_delay` | double | The maximum delay between LiDAR point cloud and camera image | | `max_wait_t` | double | The maximum time waiting for the LiDAR point cloud | +| `max_occlusion_ratio` | int | The maximum occlusion ratio for setting signal as unknown | From ab6c3b5bd159a723f7ed6836671d370a30929226 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:27 +0900 Subject: [PATCH 52/59] chore(autoware_traffic_light_multi_camera_fusion): modify docs (#9821) * fix docs Signed-off-by: MasatoSaeki * add condition Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 31 ++++++++++++------- 1 file changed, 19 insertions(+), 12 deletions(-) diff --git a/perception/autoware_traffic_light_multi_camera_fusion/README.md b/perception/autoware_traffic_light_multi_camera_fusion/README.md index f7ee294cda147..b54c623f5d750 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/README.md +++ b/perception/autoware_traffic_light_multi_camera_fusion/README.md @@ -1,29 +1,36 @@ -# The `traffic_light_multi_camera_fusion` Package +# autoware_traffic_light_multi_camera_fusion ## Overview -`traffic_light_multi_camera_fusion` performs traffic light signal fusion which can be summarized as the following two tasks: +`autoware_traffic_light_multi_camera_fusion` performs traffic light signal fusion which can be summarized as the following two tasks: -1. Multi-Camera-Fusion: performed on single traffic light signal detected by different cameras. -2. Group-Fusion: performed on traffic light signals within the same group, which means traffic lights sharing the same regulatory element id defined in lanelet2 map. +1. Multi-Camera-Fusion: fusion each traffic light signal detected by different cameras. +2. Group-Fusion: Fusion each traffic light signal within the same group, which means traffic lights share the same regulatory element ID defined in lanelet2 map. + +The fusion method is below. + +1. Use the results of the new timestamp if the results are from the same sensor +2. Use the results that are not `elements.size() == 1 && color == UNKNOWN && shape == UNKNOWN` +3. Use the results that each vertex of ROI is not at the edge of the image +4. Use the results of high confidence ## Input topics 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 | +| Name | Type | Description | +| ----------------------------------------------------- | ------------------------------------------------ | ------------------------------------- | +| `~//camera_info` | sensor_msgs::msg::CameraInfo | camera info from map_based_detector | +| `~//detection/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | detection roi from fine_detector | +| `~//classification/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | classification result from 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. ## Output topics -| Name | Type | Description | -| -------------------------- | ------------------------------------------------- | ---------------------------------- | -| `~/output/traffic_signals` | autoware_perception_msgs::TrafficLightSignalArray | traffic light signal fusion result | +| Name | Type | Description | +| -------------------------- | ----------------------------------------------------- | ---------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light signal fusion result | ## Node parameters From 65f6417db4bf4bda100eb961a841f6d31c94c05b Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:41 +0900 Subject: [PATCH 53/59] chore(autoware_traffic_light_classifier): modify docs (#9819) * modify docs Signed-off-by: MasatoSaeki * style(pre-commit): autofix * fix docs Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 32 +++++++++++++------ 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_classifier/README.md b/perception/autoware_traffic_light_classifier/README.md index 6e720aabc7593..7dcd4a73380bb 100644 --- a/perception/autoware_traffic_light_classifier/README.md +++ b/perception/autoware_traffic_light_classifier/README.md @@ -1,22 +1,33 @@ -# traffic_light_classifier +# autoware_traffic_light_classifier ## Purpose -traffic_light_classifier is a package for classifying traffic light labels using cropped image around a traffic light. This package has two classifier models: `cnn_classifier` and `hsv_classifier`. +`autoware_traffic_light_classifier` is a package for classifying traffic light labels using cropped image around a traffic light. This package has two classifier models: `cnn_classifier` and `hsv_classifier`. ## Inner-workings / Algorithms +If height and width of `~/input/rois` is `0`, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `CIRCLE`, and `0.0`. +If `~/input/rois` is judged as backlight, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `UNKNOWN`, and `0.0`. + ### cnn_classifier -Traffic light labels are classified by EfficientNet-b1 or MobileNet-v2. -Totally 83400 (58600 for training, 14800 for evaluation and 10000 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. -The information of the models is listed here: +Traffic light labels are classified by EfficientNet-b1 or MobileNet-v2. +We trained classifiers for vehicular signals and pedestrian signals separately. +For vehicular signals, a total of 83400 (58600 for training, 14800 for evaluation and 10000 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. | Name | Input Size | Test Accuracy | | --------------- | ---------- | ------------- | | EfficientNet-b1 | 128 x 128 | 99.76% | | MobileNet-v2 | 224 x 224 | 99.81% | +For pedestrian signals, a total of 21199 (17860 for training, 2114 for evaluation and 1225 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. +The information of the models is listed here: + +| Name | Input Size | Test Accuracy | +| --------------- | ---------- | ------------- | +| EfficientNet-b1 | 128 x 128 | 97.89% | +| MobileNet-v2 | 224 x 224 | 99.10% | + ### hsv_classifier Traffic light colors (green, yellow and red) are classified in HSV model. @@ -52,11 +63,12 @@ These colors and shapes are assigned to the message as follows: ### Node Parameters -| Name | Type | Description | -| --------------------- | ----- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `classifier_type` | int | if the value is `1`, cnn_classifier is used | -| `data_path` | str | packages data and artifacts directory path | -| `backlight_threshold` | float | If the intensity get grater than this overwrite with UNKNOWN in corresponding RoI. Note that, if the value is much higher, the node only overwrites in the harsher backlight situations. Therefore, If you wouldn't like to use this feature set this value to `1.0`. The value can be `[0.0, 1.0]`. The confidence of overwritten signal is set to `0.0`. | +| Name | Type | Description | +| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `classifier_type` | int | If the value is `1`, cnn_classifier is used | +| `data_path` | str | Packages data and artifacts directory path | +| `backlight_threshold` | double | If the intensity of light is grater than this threshold, the color and shape of the corresponding ROI will be overwritten with UNKNOWN, and the confidence of the overwritten signal will be set to `0.0`. The value should be set in the range of `[0.0, 1.0]`. If you wouldn't like to use this feature, please set it to `1.0`. | +| `classify_traffic_light_type` | int | If the value is `0`, vehicular signals are classified. If the value is `1`, pedestrian signals are classified. | ### Core Parameters From b69241f6659c042a05bc9362c3d254e25fbaa290 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:56 +0900 Subject: [PATCH 54/59] chore(autoware_crosswalk_traffic_light_estimator): fix docs (#9822) * fix docs Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki * add tlr output image Signed-off-by: MasatoSaeki * modify sentense Signed-off-by: MasatoSaeki * modify sentense Signed-off-by: MasatoSaeki * refactor readme Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki * fix Signed-off-by: MasatoSaeki * style(pre-commit): autofix --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 81 ++++++++++++++---- .../images/flashing_state.png | Bin 0 -> 24574 bytes .../images/traffic_light.png | Bin 0 -> 54297 bytes 3 files changed, 63 insertions(+), 18 deletions(-) create mode 100644 perception/autoware_crosswalk_traffic_light_estimator/images/flashing_state.png create mode 100644 perception/autoware_crosswalk_traffic_light_estimator/images/traffic_light.png diff --git a/perception/autoware_crosswalk_traffic_light_estimator/README.md b/perception/autoware_crosswalk_traffic_light_estimator/README.md index b14fefbd43beb..1b24b115f5812 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/README.md +++ b/perception/autoware_crosswalk_traffic_light_estimator/README.md @@ -1,40 +1,85 @@ -# crosswalk_traffic_light_estimator +# autoware_crosswalk_traffic_light_estimator ## Purpose -`crosswalk_traffic_light_estimator` is a module that estimates pedestrian traffic signals from HDMap and detected vehicle traffic signals. +`autoware_crosswalk_traffic_light_estimator` estimates pedestrian traffic signals which can be summarized as the following two tasks: + +- Estimate pedestrian traffic signals that are not subject to be detected by perception pipeline. +- Estimate whether pedestrian traffic signals are flashing and modify the result. + +This module works without `~/input/route`, but its behavior is outputting the subscribed results as is. ## Inputs / Outputs ### Input -| Name | Type | Description | -| ------------------------------------ | ------------------------------------------------ | ------------------ | -| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | -| `~/input/route` | `autoware_planning_msgs::msg::LaneletRoute` | route | -| `~/input/classified/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | classified signals | +| Name | Type | Description | +| ------------------------------------ | ----------------------------------------------------- | ------------------ | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/route` | autoware_planning_msgs::msg::LaneletRoute | optional: route | +| `~/input/classified/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | classified signals | ### Output -| Name | Type | Description | -| -------------------------- | ------------------------------------------------------- | --------------------------------------------------------- | -| `~/output/traffic_signals` | `autoware_perception_msgs::msg::TrafficLightGroupArray` | output that contains estimated pedestrian traffic signals | +| Name | Type | Description | +| -------------------------- | ----------------------------------------------------- | --------------------------------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | output that contains estimated pedestrian traffic signals | ## Parameters -| Name | Type | Description | Default value | -| :---------------------------- | :------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| `use_last_detect_color` | `bool` | If this parameter is `true`, this module estimates pedestrian's traffic signal as RED not only when vehicle's traffic signal is detected as GREEN/AMBER but also when detection results change GREEN/AMBER to UNKNOWN. (If detection results change RED or AMBER to UNKNOWN, this module estimates pedestrian's traffic signal as UNKNOWN.) If this parameter is `false`, this module use only latest detection results for estimation. (Only when the detection result is GREEN/AMBER, this module estimates pedestrian's traffic signal as RED.) | `true` | -| `last_detect_color_hold_time` | `double` | The time threshold to hold for last detect color. | `2.0` | +| Name | Type | Description | Default value | +| :---------------------------- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| `use_last_detect_color` | bool | If this parameter is `true`, this module estimates pedestrian's traffic signal as RED not only when vehicle's traffic signal is detected as GREEN/AMBER but also when detection results change GREEN/AMBER to UNKNOWN. (If detection results change RED or AMBER to UNKNOWN, this module estimates pedestrian's traffic signal as UNKNOWN.) If this parameter is `false`, this module use only latest detection results for estimation. (Only when the detection result is GREEN/AMBER, this module estimates pedestrian's traffic signal as RED.) | true | +| `last_detect_color_hold_time` | double | The time threshold to hold for last detect color. The unit is second. | 2.0 | +| `last_colors_hold_time` | double | The time threshold to hold for history detected pedestrian traffic light color. The unit is second. | 1.0 | ## Inner-workings / Algorithms +When the pedestrian traffic signals **are detected** by perception pipeline + +- If estimates the pedestrian traffic signals are flashing, overwrite the results +- Prefer the output from perception pipeline, but overwrite it if the pedestrian traffic signals are invalid(`no detection`, `backlight`, or `occlusion`) + +When the pedestrian traffic signals **are NOT detected** by perception pipeline + +- Estimate the color of pedestrian traffic signals based on detected vehicle traffic signals, HDMap, and route + +### Estimate whether pedestrian traffic signals are flashing + +```plantumul +start +if (the pedestrian traffic light classification result exists)then + : update the flashing flag according to the classification result(in_signal) and last_signals + if (the traffic light is flashing?)then(yes) + : update the traffic light state + else(no) + : the traffic light state is the same with the classification result +if (the classification result not exists) + : the traffic light state is the same with the estimation + : output the current traffic light state +end +``` + +#### Update flashing flag + +

+ +
+ +#### Update traffic light status + +
+ +
+ +### Estimate the color of pedestrian traffic signals + ```plantuml start -:subscribe detected traffic signals & HDMap; +:subscribe detected traffic signals, HDMap, and route; :extract crosswalk lanelets from HDMap; -:extract road lanelets that conflicts crosswalk; +:extract road lanelets that conflicts crosswalk from route; :initialize non_red_lanelets(lanelet::ConstLanelets); if (Latest detection result is **GREEN** or **AMBER**?) then (yes) :push back non_red_lanelets; @@ -58,7 +103,7 @@ end If traffic between pedestrians and vehicles is controlled by traffic signals, the crosswalk traffic signal maybe **RED** in order to prevent pedestrian from crossing when the following conditions are satisfied. -### Situation1 +#### Situation1 - crosswalk conflicts **STRAIGHT** lanelet - the lanelet refers **GREEN** or **AMBER** traffic signal (The following pictures show only **GREEN** case) @@ -70,7 +115,7 @@ If traffic between pedestrians and vehicles is controlled by traffic signals, th -### Situation2 +#### Situation2 - crosswalk conflicts different turn direction lanelets (STRAIGHT and LEFT, LEFT and RIGHT, RIGHT and STRAIGHT) - the lanelets refer **GREEN** or **AMBER** traffic signal (The following pictures show only **GREEN** case) diff --git a/perception/autoware_crosswalk_traffic_light_estimator/images/flashing_state.png b/perception/autoware_crosswalk_traffic_light_estimator/images/flashing_state.png new file mode 100644 index 0000000000000000000000000000000000000000..7686f3842e75c92cfd27f9de08ef1ecf6eb3651f GIT binary patch literal 24574 zcmd43WmFtdw>C&ZfB?bW-Q696LvVL@cemg!!L^a#8r&hcySr;+jXTqM@4espW@gR5 znYE^Vbam}Ib!4A?PVN2dr#n(nUJ?Ng7Y+gf0zq0zOc?^=GXVU(<0~}yb0)Sr9DMrX zA|kE&6@2)9HH`pYzlPMH*n2k&=^$+o8Nu z`gs_lbZBi*%w$xD#JbCDw_?ty_x$4nk4jC7c2_K^F&xwO=1+M`&$mZXXp+Ofd%7lE z66Jjg`g^q|SOYw5bN2N21^8U}9I`$52|citc6D_Tl7t|Od?oQ--tI#D{`KF*E4$P# z&3_3)$pPSdA;<+9{~wFEJZnx*dPBxi9jl)?~=@vhx9(%{-=$ z3hh6)A=frMw&YAr3q@bt%ZJd2Sy*QB(P01eJtB~SkFQ?mAjg3|8j#rUI-nD{2bPDQ;ez+IyTNqovHi)AB zX%jlE>k`zUR(t>P8XUtGcmDncg6IFZ_rR|NZvNrj7olLPe2Z%|&@F7aMTN1`z+PQ- zKPn$tb_zV3)9|KF@Q(7xHkpx3IpeLq)&Nr2mjAeqgSUMhD+2Hob*7$ubo^ZvY21+O z<}1D$ln)I~5kULzRs}CX{5L{ympau~m7+cdJKKTqXYcmpN*nkZ;jf)x!B{)*UP4rK zx6qybgk)0bm*Wij0x3rZyLkt!X}XfvJvO{S;gDE#TJxe7z)GExIOBz{EmMs(WGLV< zi5Z;U^t%wNEYQufrh^F2(f5vb#02;|jy{(`s)gp8ggHtg0S1+-0nNz3l_jPBm`%-{ zY?%Hvfpg7)DbwPoBlR!iTat{ay7OCz&3zk>Z?Am!{(mc6MN)u`c27$_fy(R=YoX$ zh#8|(=#+al#rj%v8>;sXgR@1;p`=W_wuYNEAo;-P$c3zyDxhU^wwk`+kkYx3vPp zW|SSa{daM+2GEV^H$`->=F+b|#e9zZ`GRQTdU_|uF5AQBPzH|)S zAtscoer(G0u@%pjR24NxAUD=wSS!jAU*QT*mylCnY_9q*k3snfWQ*dL*uzk1T8Fb{ zwijuS0)Ad4{eK33%qEcLsjddHZj03u4MTbPYiS&=w-ZwoRk^{5m`l{(wT#l@)8aU# z$v1Ft7ei3f<59rY2QjHnd{G6Dk5f(Z?9ZS?mVdpb?N0C>m{J0q?l|nhU+R%fXGX74 zPEkqAZV|27nbg4xuba}}<~qR|78RX;(=L$c$*3v!{OGI4=RfLciZJ4m5(GX0hb$sj zs(M>?`orS(7suSM5jAR^&&A(6Eb$%Q<_rhpmYBs`dxdobE`;W`eJarQ^j2x%`39)e zF4C2@cIvEzcjR@&kT6lNKS-60t)Z>i827P$jtL7M7{vV*T5L0j~*Jz1eB}29Nm-v2CBic zem{RQt!${?JC-@jv-vSm<(y!NeJhY)}XaSniDk2S0TUMz-7VYAgO{ zT5JSTJr3HF_O=jRe$L%{XUONXeyl76@O-d`Y!9uM^1ng)s39ob3_5qC{WYs= zQcLg+jkS;{cv) zwGVZPMWQJ-pD4Z_r1*neiPzxD8ej_$%f7==Vdzr*QgOxgmhsK0If2=M`cz}#)vezV zbHYK2uyuL2IF~o2%E#tW-vge9X+7$4Vf@}m<6?yR;Hg`G-|@hbvSsn+sFzkA0e7-Z zjKBrAIXbf}kZX)bT{#$+`Fg1TaTa-3J&tVWbmO^Rmv~@sb2mEMTegqDZa~i?R7Jy{ z1el`J+U?~1eSL$oms7R&W2&*k^@zE&g5*Z1f}6vdoTzdhWqp~fo%&B=NWcrA)2}f( z@ZV01KkMSrXal`Big7JiL3}AofMAt?rUdJKt?$|{Y|Ig{Jq$VvSP5=%nn>a~x1`c7 zJyN#wTRUQ?G5+AXi@75h@Qp8i;X}b^Pi$`;w-~V7iu4=w{Y7@)6A~KRmg@SM+4)N} z(JXVrDQSD$*7hsGj^m1JU{Y8J2HJ9W|M^fM+E3vaH@i~kltzS)MeA(b3+=5N$bimi z&#FGjYxQ!#MlD&^-5_G89r=u0S_H0O%*#+;5iMWJc_q7Jb1ty45be85JG=*9@U`e( zT+zZA1I!jo!&0I=gll#G)5Bj>rT-X}lEC6#S*s8G*k##HN)6MWV<7xDH-g?b4+M*Q zp;+>9$vy-JM?%36zUtC_KmWjPU!M%Nrm<{ZkH|#$yM}h|X(2|Fvf$C*N0Hv=zBk=^ zt-Tq%f6c?yVd{ZAD()FF@}gI`0e(n_%aNi^k_Ryph}?ij*D~9-?|Zx-Tf;NE+V1&Fkj^#^I1zys<^`o&Pn~Jy9fUIvP9z-V#;;iWWGTplE)q$ z&z`c(BaeopNnI-``Hdl)ua8f61Z|%@g2x{5blpv0wx$=af0PI#0A2M@cD=LpsPTsM z@*npCu4;%Xe1$BTJzjmkdc+eAuH*ck$zilGQ%aJPjNh-);1DA!+f}&{zmBUodv{3L z_|OYev8mFy7O{|8t@YPFC7iE536Lq=e8^lS7oBlZKsdfd-c_ zOfhY=j+TBbDr@u&3aKmen_^d}dn2!zw&*dmN!j^Oxw)AKq0PU)V(MoKRSwhw%T#;Z zJaukZV0HvYBlF$dCzBz6>*y+EN&}ioSUS`ph?#AIk9^f;O$l) z8J;{aa8{SpEy8a7oOy(fIixs!dN-x8X-ZCdD}g_IK5#VlFD>B{{x!U9<19du7AOgkC_r&+364n)$=Z8W{ZxEE)|EYCA5aeAt>W^ zoI~|-Q&BdpU*;FNPGIrA>Fx}X?;rJjbqrMrcna)@o=|W)ys77ZeC6uD=w3Hp_mCwR z{BpV+@F(*SX|;7+62_*~6?fE6PxouroY@?~yHli!o8!>@FS$hd?^PsI&QL9%H6R#o zda|~*UnF>7YGO^1jL&ka$1`@n+&Pw=?*jD!WM3DBK|4PXIsKR_%7(d-z@BQ)`i0ZX`=CwHoWAQt+w)KFDa48zK_pnn9AA)K?_qad?u0h?jHzCcsxdp(jdV(c*IC46B*u@M(xgs5Rd+RC4+Rj2tPZ7^p0`O=jUoG= z2&KBoWAJ}$<^8g7_!mAv4(2^SKO=7RIGruCZ2DXZs8?w(jHt}3She?OL~j=m^b-8m z0Zvqu)Xh#(SXd0|X9Z|YJsdGAx#O&Fu*Y=HWcRkwsj4sbG03-Y%82>%Hv`l2WgX8S zwX-0Wf!rqbE>>5D{{BE@_KmJ_CCSm^tc3-q;&FM3;EX)H*@6yjd!JA?v$V2GNRQ@x zxy`Ii=g`p~j&7Y@x>3zKk+16+YF2xZ=aFK1|D5Zkk;zH(@pKk32?^eY0H#|kgkH6h zos0V>Cp(^3frwhdOkmonRqULhu8y1_uk!_-qq}i$3qZH9BO1ihTZXo@KYvv^E@;v{ zT*0(9+zwP1{8-ZQ*ERpqIb33}6u9>F0$A2q@}D(xZkksoRIV~I);?V3j%f(<{kPFY za35c49uoUxUk2YscHO1^A~v4u^3A2t`IFO zftG3*uhZh_v3OBG`?F-%a+!VROy4dU{N)CO5~Qv)pNpi^#pO@uv&ZWxr;%QjK{PiOZ3<5(l3Z|s6DXw#$K24jrQ=< zCA8bj``!nwr1S7{a&T+OSOJpBKIVg^_Mq;*avZBNek==tQTc1GwaG&(#X4!7}M0>d1tBC^_ZQ7N1HV-a3hBH{8sImfZx&?_#@;ekv|7b zBobQ6zCvLDtJyIH*B!rYO@|f|S$dH|-87+NhH+l-3AB&^+`|kQvi2g=b35!syp3h^)p`9v&VnTJQnAxI+#Yw2ec}(qo6kgGz+r|nnWvC<{)$K-x zn%am&L~F@ss}E%6${l9S><6?b_1OeXLs*yLs0e;h=en?HPC&tv7{%IV;|d$-#uZ=5 zw^c51|LxY4|3yLx-jWy1MH+f0zF2V^Q_S`j)p-4TZTj$Ls<5#U4P!BbnEURo_FyHU zywPM0o07#KY7%xdpBegvZ|?1ptR{1}BFo;Sj2nQt9u39_DU zPnX}wBR8Zqij~4RNvEp9V-gE}w`jDsIi-gW=gAaiz9mvUujbsoUju4qocZG?2mNO)q1$qDGyXGlqbTtD18AcmerXjSZ{;zW;5pof|8`3@A!x2U{sKuz<9dw9(Llxg&c(spsr{z~^ zlMr1R7*Y?BKP>qr2C}Z8rcgPWf`0pOq7oGK9CQRdh;qc@(WWCE7&FqDcvvya9ZI0S zBm|i$aE9$$$}bC9Y@uFGrbGuX5%*7gM^ymLDOnHr$q}w$>Au0m^}IwvBnq3@Um|p9X5=xC)s%d2$kpE+UFD}3i<7_>6fG1f_ zt0EGA23x!VDTLC9kvEE$sql_zpuTnAw|G0L1t7BmhtjO(}3IfdeUN+%&tqIeRc_JgG(e>pKsP;D;wZ|^m*+jq2;xZp# z=(p>yk)WAdFlbkz6W0B`4cq^{{avt$B|l`Uqf52ph$6|5?bluCkLd!_#1hU9f5gAl z%xC!wXFgmVAjxUgg28Z*Vfn8!Q3o{E_SlDM`@^?830r;GvoZOB8jt{~V4Ri0mdxv> z?zNrMG2h+TsRXb75%0YGDs>W~WJP8>!34H>e~`yA|&qC-By1h2*|8_T`d%U z*ATX^a9?X{z4wAF6#NLY%Yy4tOAi`sM?07m0MG4Ta?$hM5)-knEH|0=FUJ`>6)-+f zqfe8BV^9q0&RiA=KI@Cz_?2Xbea2Bj()N2YB0aYte{{RA(EyNrVx<-6MGjw>Onaqh zBb_6p!+iG-P4s|D<|Xf_UO0SX=|W>pM+@cu%!o~#`5S~6th3eFg^}ErtuGu3jGe|2u#3ighW+!4e~LLH zrVT9d66N@Q2A$N4q~l1&Fs0wX*M3@#9)25-y3bEo+?v93T12}x^{fYYTxPIcIaZ6; zZWyL7u7n?asEzM@G{1sj0SGMDi{B6!MK)@Aq4M)Q;j7YAJkE#aV52LWc8v^{qa|c8gNcVE5Vqz$IiRaN|qhp^!x_IMD36dwl5bF?ukbu z#1Vg-$BX%B3#~s3C5BUWk@6-DC$A#x-bNO&5Rf+&Lw>F>%bO|4EmdydN}{iavMEbJ z!-P-WQ%C1pN-N6ZYr{M^+WlrJ$+5LK0`)WOlL}ty9Nats#omeGHwHwl7dr-3Et)sX zmd?iL8B}%~=*;+=l>q$L4tN%V@&OAgbeBn-k;mVWL8sWg3YS#fsxreeh~Hv)t(+b# zL78j_ef{V23bFF>K9R6}?N8a z4oW?)0f{{U*v`4T_Li3R=4E&6%+xiWWlW#n*&)YFg+nS|CAodj>hGAtJ?uz%1n~o6 zG3FLsQIBA@Kg6K9bTMny;;15i=))O(>Jeiy5S_#-qSkg0!R(w^Y;bJY0L?k;asxkH zll?AB5|PiRO6xv5bCTCy?fAgTaBLVVIUxwjxGP^BxG&a3kgUVg6ImoSkq7;R!7}FF zXj#!Bi|o#pSe~P?U00JTD>qv``?9&2EvslVuv>Yuj{hCPTG1vD#rxGCManSxL!@9& z>Tv?UIL`LvYg@R;l?QL&2|S&3ZKSWbg5pmuL8OWACFs9CurOo*k!XwvoxgKRdIkbJ zzZY5ReR)R`OL&yPY#l;pN3%e_o26W2I$q4kS#oWebo1e}5_iak{M-8GF|^aPtg}Qc zCPXX%5aE_$s2Lz*PBaVrMGrYYN6D(eKw&n8%XtxNGPjPYl~hmIsUNKE`q_rVlk2>( zqREg4UiQ=!`JQy~l`)vK#8Ews%U!)F9%+zMM)2 z-VlGz`h1JJYQE|oNDmLJ#~%uo#hX7w`N{}!?h%cu=;HSTguOEJB^wnjT0H@$9R>?@I;v|+6|e!p?6n{;c- z;m(^oa$I6lf`{75{@zog6-kx zduE+bY@J`IVZLCoi8D<`=Ga8oGDVlQnM;pZVxVr}@B68`yH&jNXBisH3wV;ziW97) z-uF(Z(&>TyxgUeSn|E;Ty_25eaa}*Lh(UY*?5w4##W)QVqx6xd^!G{1DsI>eq4&-n zkyliz`h4^!TlqVl)Z^Kq!Cez%E56!Ev5_%?FxUuwUkqI-MGttF%XJW*j!a$1kw1h9 z$asqc`Q=e(HMUYYX5d70Lr+7a?86-9oS0&WOrK5TA;t0{Kw7suJig4s(w9SDYVAxU z%9qRS>-(WAH`P@JVkv z@p{z|wv=I$*3J$DML^j^;>5Gp3xtb9r0L!~068kQ07XSUC8cvMoy=`3?Fa*;Uj?;+!D zp!2=o4cdQnSl&r;#?QrFy)q`+ebYHb25dEhcm7~xO+-;_eg9$0pJBnFSfZ%3u#m() z6UnQu>K{Z$LZy0c0;TX2~0=uR0nfkQqKZ#ZCqurz&gf)9Q{#Q6ihvLJ(l zzYwxwMw7XASXsI$N-KZnPjir80lB^YM~=z}z%_lYxs|Mts&>up>8z+uJZWk9zN-oH zR0qE-M})kSeaFmtq%p2yRKdv~hxI*=@_?AjK9DJGzU^vvpd%NCjFD0rD%V>Of~^+H z7Z_Yj{f9dw%H1d1b*N=crzop%Vx zz*~Ox1`#9%ODg?g%>3y?$>#NpuZ~UP4ir>|^a z0wIEq29xwFDXtsim#=lRG_HTskc4=C!X+{ve+9|iBW4F~;;^$3QWfS%vRYdVARhsP z%p`H8>9$JpDwa4|;udU-(_IC_`z8G{_*c??Qq9%M`sMf$4dxI1P*UO&MC)L4s}4Rd zlrh`2)XB!~EB;vRt;?W&3Xn1qx2BZbFkXHRFa|k7v**YPw9jG^bV8Fr=Lz3|4}z7e z4F9-TTIyccB^OJxoR+^G zEO|rt^v51B60&l-$~JC8{q?9C<7jtQH{b?OKro;>?bY zDzYkD%l`zV!48asTd5GpJ-5wb@;!Kw_J1djEJ21SP4_VUyiCyj#~30F}kdfZ0*!3V7#^; zt>#P9nY+cFH{_t5&2V*?(jMhrT1)6b@-P5ea$?nYRxQ!@9eLAmaJ2rHCXcv{m%=Cr6T~XsD_G8Z!TJJyBj? z_r6hL09W{&bbamo4H^>MzNeQLi}^Sk1@1L# za=NF`rixSCPG*Z{gE_yCXY-)_j2C)O_t^9*S)!{319R^?d+|btNeY5HGm=DR;BtNh zah5~l8EiFv;RX{u`d$Yq`arSMIjDUGO!%6PYdG+uRNWtMmlP-XKM8%#SW+4FM!|g@ z867@lvredKvz2fg0TDQLC1 zmZ>g&y09J)2zciQ>*Bww2&%|^VBN4bba8Rns~sZT`z1-(W5|5_`1DKdSZ_5EtZnZf@4TQ};0tbe0qVyYn|>O4#8pEIt#8llP^)=kKY$;!e5 zYdGRtD?CX*#O-00!}Zfq?oA((P(%CqLZON`uLEPe;4}5nRPN;r$%CLYKRg`VzQ(NF z=-OJ=&C!%hO$iw2WR5EMW3$Al?|nkCSYx2zi6cGdemoHgzTK+O($PI#^&vUAx!Jk3 zBMQ>P{}c{}cGK|GTg+&ANeaZ}Y9RCpC`YryDK!&B-XmnUoctJdp%)!nY24HUMi;yVKn9I4f)Vz(aSM`(rrTTp%A~^pXaI{iQ$VFYe7R zo=eThXb#ru{QNw4&44!+d&+xl>k2jYJ<1&hX^U>MNDIkiT&e8bL4T-uQJV;V(#%`m z?;O84g)$2X%wtASzeM9g$ThOnqMidp?OE#Wt`P)~F{p29+MDbTN6tQkQ z>&L8(Fe?=}_#^0Tz7;eD1qENC7-A-@U&D1s%Es9&Eqiw-A%yv7?GOIwfUdfP zds&cw6kyeP+S2Avx?DOsQ8FeM8BNJ}`n7;($NehZe)Tt#9&@^9EhqjLIsryAb9V=6 zlIOoloW6CD!%m$6BO3$e^`Il6j|`@+$Dq|!ZEKqvJ#Nu(M6>BUVL$8~u(@SLsZV{| zl2*m1>pk7=VK)$JX!e1CYaQ#0csGF(yxEQL87GL28bBoQT3EWO+pSPqzmPNM*ZNyx(R>L z6p&eqhMEbG-d#ayBi_|lWpNnW3Gv`&DiJIARBHcN{~wSDvEH`4*a?Qt!0l?<+8AX)kT;Im8!`=xVVg-qwUDhE(%kTGe zY)i!I&cq$8A8?uD5lBcVJ_&rcg2q{^IzF^B(nz|TZ?X7{bNBs=7L0Rk$8oR+T{!)6 zD@?Qtbyl4^+6uQT5!yLqzI1wYT)`x~u!=o715db%O45pjZdm-`Dd;FKmo5BupF<3) zc(=sr;ENDTqNh9LgrAa_yjvwF#(!Z(3*E5R0A23^WVDX3M@R`-YwjJ$(mHE)T!~oR z0Tl%Sx2oow-GS%{Z@y2^NQAPgs_50#)f4(eU!~1-v z*h~34u8&VH${Wi?l}_`$+t(Z}mN*6|64jV1`*%GcKb!{_g0&q(qaA%3w{-~g{O4~r zv7StD0~XoP4J4IJ)Ll)niD{zMax#|M>tH^~PZa-tv6p(#fxsD~`~Xv4c(nt>ul{+NE{M&kT+}X?n4eS!&+D)>i84-TucDtiN};sFsi5l9ax5j z|27&_g?m*nQH1J;Nr6_+McCIC`lV(rFY8o6@oFzbQUXP=ktDWJyOMfd`HweaPk^Np z#6XmFP0@V$_rKq9yU%dIT8D{^4(40TTl`FR`}jtR`~Z9>l!~Z_QIT|~Y4h)yt2ZKj zs0nzp88>J9_j)l1cyludrwBpbE%|HTb7jj;=dLAu6dON9PWdEJ`)Y8jxx_^B`xN>m z4&LG|Hx9L(Dr*DAdE~9~XEp+*^QK&%!w9C}57^H>4BR#u{A3AbCfbC=3Ey?oUBiF3 z_D+bSP6147>_G58igtZ*wr3t4kk&W!w&?`&Bg@3vIJWfE(6RHyU6MLw1O){jA0HJ} zROY&m;J_*87MkUzl7u=SeiC49q@FA6ComdPSYXVT zJpmk3H(YK=JrfrmcY63P3WavmC3{+l>9VH^1;w!XiQTN4YQ*^m!J?+gDR135bpu)8 zjahbu{k5~(r{dn?FKHO6qqRX@EC+)qhWs;NQ2)ZA$=Ww zl=%ar03lOD+FBz%n|w=2+?iTD7CuNdIE<=`vLlcIR6fH5xs?<2AQ@&Qg}LlnqSTs^ zIG+h3Ni(F%u9W{M-oYNmxIv=u1qys>jVyK|7%u1wyQn?j2d-75tvi4>HKj>^u{RlR z?*TChXH+X6ZAOHxY>!vy%{YMAz$W|dQ5Z@Sap)^(Z1@LUffgZ8Z~T6IQxfkQ)La%k ztPkWT#5XpT+X*akM zcIis!jaZtLd{-RPqnfrvo7 z-SZWdO9!O?2e5%hHgmUocW)7V%Ga_v_TOY_%|>grGIy)Ty8mdGSl8T=cZ-Xr|cc4ZGm(PXglot1UdXOARe4JZ#V(F(>woM<24@$ z_ZVt~t@{6jo^kRB)TOC-FLmR#sMGaM;3z zho!>f1iq_e2^P*20LP~=s|YX42-e+05HD%2v!wp11x1@+Q-$Ca;I>%sVEuL?foS)D zMj?9sPi6l_Ie!juCJ&GCaG_RS-DVszG#9`6cvaEQ=xN)1z zWbVj{1ch;JBRIO#@r-~9j~+yzn)q6Bt$SK%AVs^X-t2s$e%C&r5!l4X0aK=W>Lrv@ z3r%P*dtAQGz$SV|2`b&MNGSVvqs*-cBKF%;@^OSF6C4U676#tU#TIrve+uP#PCT|? zF*uqhoHdZ^nSSV|^^S3~L1iLxq_UJi5)3V5Pivt1EiH7h{oZK)t)}?uc_;w5_=mS} zRb+DX>u&SC(d-%m?>u39o`xXI&=XtLsb6aK=)s}gFJoeG{8ymRBGiz+pqF@;-7=lr){K?;y(T&3qCrgdTnNEdbj!&2xymH@VZ?3ojgm0LfJUof~ovJF-ca zRw;UCbJ!cBl5Knf-Y4;;+ts7(WKCm8uEaXV=$60Sx1EkZNLEQj&kGbZ|0iueh!w@A z$t?sJuc_ScB2Y;GFy-&0L}TUx+;*zt=P+1~jS)NfV}E+^+~rwG+osx;UNd?EdES%G z9!Vm1R+m2cKV^_lAPsudQ6-gx*IvnyrFOU$B1-7g<*S z`&ZR~t{vskLZ}%3@t7%-0_96MN+e&9cwhJ8#2wui-jFuC=+M) znX*>RXoRKF!JAFP0u9{N+~4M76z3;jNdfX?ONW0!{~YGT2>%w)b1@8;?$!dy4~n$p zClvbiY2W8SXX4OfssicNO<%!EGaFKro4H}NhJw?VE^ zlbPWB`j<}+ob%0pN>qlec$OMFZ9d8VUsLg1*)uwJJ&%VA%YLx>2_loA)G?zq=IR(q zgLjw+*#-lkpK*gCGzDr)IJoh;A=P zzeJ@3b?C|`V;EH}qTOlI=eyGl#yd;-tjdOhT$D>Z>?5QEvU{@)ED9!LC@5JlJw~b5 zp9D{)GX5AEkMR>Y#-WAFrmth_ttqTz4QH1iXb!=kv{S?Rox{32L|RO8GH|X@`HCPEsrwY!C#v-mc{D6(9oeXBwhjP!UxSbVCfq&`pPL9xs z&d|!O&d~I=J5N>g1Q3zL_|y}-e$9`aYFpA1z;cJwvtAH&6lQnZ(rd=G-< zxn?H(HDs^(hjaMJ%523`a5OJRvDtHB$QYg2Y4uO02d2mdm3eQz0wk+(`tY9X7kv#N z%&4w1VUIK-e-AlRO`U}vdlE9vm}DmQNAaOL-&5*Izh47U%dDlpM|eXyk~9B>66kyr zf^R7*=CV(O{Ql=o3vjJ;eVTt(qWsnIr`~_W%VcD1=qN`BIwm9J+LG4A?ii)jCS7Hy zO6`1T;uPhEq2Dx>c8^*W+Cu3%0KmBlTj7@k`g!(ihZNJa;NlJkjrxShd-Q4 z?)Y}dVti>y>KC6tywG?eBtLr=Wv$dRF8%KsPz;Lp2 zB|PljZ&YN1IpX9m&y9N1BDc)a{Nh3dhP6X~Zn{-qtvf7CoQA1CA6nE6SyH-rAA!LM z_lurg{L$jd1u;&>ZM^@@gKzZ*8MbG{mO<0+nJjlX2$0w#Fj3KG_w-7lvCLktToXjB z{O{TE%TwcCkdv&>v;OYGVWLB{=;iV7`HHTypvslB?o=^W4W*b#Z)vFo6k;<=&vbI;J^PB_7- zbMq}5|JX|{d?%EX@r)#i(J^R|4{TAXVRGfg%wZiUWl6+@Z&I2z z756Re3NU4S$%?FGQVqhSNb(JC{Fy>vRryqa*^Tv3`{H#OW->U0T*n_1F%c!IAft3M zC$(xT{xR-;-|5DY9~?3)Ef!LI$Hesuq5$Gkx4HQ}t8Sful%8jNtZe`xx zk~5wl%T2<~6Q0oNqvNYQ#yT_I%B-jzLUCIXdCi?N-J2Y+^(qgloaaDC>9^jK-|fJS ze~_hKH3<7v>kcV?qf9{EDuLKE61Ny{b7^IThN2f_e{CDroE#~So6NQz{k z2P{3O8Mm|Wz5IFYj^cU!Nc~86{k$DC>4%0h3{$Y z*EzYX#w;u|X-K-4TzB2=_|-yi=jQ|8XuC1F!dGt+oGs{InHxW5SMv90(gio;3t&kZ zXKGe_ia~ngyF-oCPZIZQe|^-yZn~Mv8nDNi5l&Hck7t!yh)mNwrQ?QUr%XB17^3Fa zX9e6f89dk~YflDd0U}MbY49urNEE`jWNv+Z{ib=Al-2du%4|-!G3Gv@MNuYO*;Yk8m09+u1(|@`=9uT6;fjEwkjp>1b_lZI1TZi&-0oR4{!ZcyBB>oPFclQ;$ zwq?kkFq>1N@a}|e-2amLscSq1 zdl`(Cy+uHKcsyV-SxrMUx(c%WBOb)01zBx~1YNeqjvz@Oe^^rv)~o^&N&!uVjlrA1 z=XZ$9cFM-YN_Tp5aI(MM8@;dHs*pb3Vh7FWi)>eHgq(U_u?>*mzgP+l6g=btC_hWm zn2Z#tesxWRG`24hxw;Jf7AI+GX@Q_^oTwHaXz+%`kwh=8hB)G6&AX4YXf|#vXP$w{ z1-31*%eIZ-#abVT(J*r)Cq&YQ=4L2D0I?|LEiI7im?Nw*UG|CUz^IE?=r)0TgvE_X z;e0s60Wc)R2nvL0^OFmQfSPbOTeHoH3132mm?mwrpkfs&_TH3?zN z3hFd25#-9;gT(dbz-WWGAd-?Y>%iwU>`Ye#XW7|Vb7?gv+c%^W49+sIO7K}e>WJd# z4UNHEqBvgQ(ZRtL6&)GwlXnP!agdoktmE)zJVkIixK+`#zx1BO(}mn?eS z1WYkui}1EW17f)j{Y-<-rQoA^bmjwU^dnzDrN*;K>!1q%4TfjQcHd68uXgR>RNN5N zdNX1bo)qusqVL<$Pt~?`QBEj!Vx)5ayAqzD<((`_30Gmaf0X5vfzu!36!>KWhU!{w zxg4J5V5uM%!`Uxhz5UX}u3ZROw+*PxJE{-wj*+dW{id`(tN*>KT(}BK;u!QIP8`Va z4j&2rRS}m-$1_+~Mp@-FOVpq2Yl$2p@ zmA{4bQ$`pYJ3xWsss|(MgE3Zi^mWZ;)N0zVhZNgfOo6JZw&C?&ek*X_vKA9NsUuo2 z(YD#2Bad@>w2h%MAF4GKavjeuo)cyD_3cD*GGsRw%_h9rWDhao@Il@SaI)V>4hN8p z^}nFQw+2WVkMNS6WXbk-V7TtRoj0;~B0!1f-z4E>&LZFTuJunWptyPqA$2|R%5bh5 zA{yvq3rx4$fi!gGNrXsxeLQa#Pz7t*@h1t9b)@M{q+c0$KSNUX6pP#w zG1nW+pxs44+T`)t%*4(9Ts&`As2-xG=pMUqQbphfU z(k7cm0Hs6|rPMzdS}bRHuYU`_7AB{q?Hw*U&-yy>k~o8cAjCKo2HDJ z(0bp${R$*BbU0hEI@#n2@hnF_Fg3DXrO*b*9L8~4Fd8~ z-@i|+(RX7-Ei#h4RZJ3!OB&`O;SPvRPGTkzjm2W$uWsKHf5tm{voa4uV?V@i#ru|C zPKkoOe8q5n6OH4knzh{GEj0Rwe7FuA#_-B}nCJY4$HyL;@3Is$$Gm!Jwt&h#*1ePN zlSwq!RC2&Su7m(P^u#*J5!>Acp<*;QT1|4Ck7GIihAn7ad!^hMxg;v^w9*;5?_TJy zTeU>?3Y%FbE|Bb^=aB17jko7CJ&`?g-!WPy{N+?N%H7;RgNb3So<_0paVqwc9i23>hzK^ zreHcz5U;?Fi$z1{%{=jEH^a?_pu(zFbOO#_^^Ab0iui)_>JnjVU(HvCXizOy?V-m> zIvBlWm=HafiEf-n7&$TD3~BUTZ1-IdlKmjS|LJ9MPd7j9kXOMK zw~iH*yBK!Rf)KwLw!-I5GJcg6CediFrC+NP&=%q@mK8CXTgi_4EVe*E5b^x` zUjS>%K2_XC_hTn_I~M4K*x1gbpQ?#X76?*_N*Vi{c8S8AG$Acr%qt1{9?9+=2orIu znQE(@dz@@VBJMFc<)&6>D&cKOv(;nCM~j+$Wuz%DFnK>G_<}N?{N85|d8WK3$L5Zf zrq)id*;utHn6{#3v5c3RD1&k~TytT!=>h^d{cZ<1?be0W5XIgX#RoQ#H*)(U+@Z?? z4xuuIG-@@}5vq}y2|1wLe)Xi}a?SWsi>Y!cJu72ylAgT_L&=r2Me4<(@|^ZH7G*3$ zB3f4rWn97hS?;+f;!zZ`Dk$gxY!6`9Dzw3#JMCB>Q+k#=)_ZvJudti8SXsvGmLVv13UWWL7_-G$c(~j@(W&wul(g#vuj9l$sGiNg z+X_9yw}Tw$^1UASC^$zS2=nYGzM$+I!!!mo=io6B^?ww=3+0(|m-4oR``3gwWuzQm zkRDzbPTd$qJ#g0D{0vTFip>dS`?Mf0x`r~VfA92XQQVN)QOzZ4+5ecz6JD}PJ;E=R zpi$rp=S%5N*K^v??TmcPUL3;kQ|jJo)w#Pd>iwy_c7NQVf@+$+9K8J2PC%xMKq1B| z^$+xK3{6T8Q<74fJAFdgCDuJB6$7i=zfHuHqmLkb1n;+PYKC0O2@_Q-t9iBI`_O&v zl)SvR_`u;yyQS~%py{hokuvq{n&v+iKysv_qEK6>rn+-Wh^_FPminmwqnNAwin4px zA|N@0fJ%3FcL);FEs{z%(j`L*NGe@Jr!>+G9rMyCF(Wl7-HbFd3}@coS!bQU;HM?$F!BFh&8z1tbF141|CAjyQQz>HlTha^-A;qiGQj$^AP*+EAQV^rw{M{5FuJV6PZ6Nf_TqvtxaIdESmu6sm={W59EU!TF9Yuo_kGF^yfeK zr>4Z?ZH|A-?Atr#RZ0TA6!vMFt+5T~oA`2TIexiNMa(Tx1(j|W+@}&e+bJ?MHIjWM z&j8Uk);8*VpVS$<5o%!jUF{s+>9&eEI@!-*bQmpzS*sY*-(80iL3&thz32-e}n7#tjo(KPY=hOaCy z2W>>+eUJf(PK3XFJlof&U~XZ7Vc-9J<}A$d2mV1fd%^n}ud~0B4}GtTI?H>e@DUp9 z^mL>izptOGMA}7m*NOH+d}Bvyo>{MglJ%h~jVV0ZhE#c~E$9)HknyN*q`Asz-Brer z?-?r@{#kkv%3k*`#dX|#mEQS&Rgo@CNNQ!kcd&bTa&qz)1{r2^+rXJrlYH(jTp~gP zT$x3Syn?=S4w(L!6D zi0;QhR~?33Au^3JRJP17{Q7;rG}Q6vvV{Qlh~M%(YiVh5_VB0xgFnvvr6S^dmWV(j zPvPf`6hv3}IyySr2nZu51}bLx{NsMz*o8sri_yA-h7Mnaz1kIIF|yF?Q}l9-lS? z_KolD77HGnt^0xU$gAVci~aeZp||2tC=}9vztTUgCD+bmb<7ID%l?vl#)(_y~39puJU$=E94#2>D$RDH@yt zho~tGH(K{jNcJI;gXwE~Huwu!tuUe_J;nQrD}vWLI+-?l*SThV0ipa$b#;8E4VK(c z3;}?H0XAYQ{IB2yh+KhBq-kB3{QmSCb0~W?cF3>AmNkYY?rPMU)_2Q?h2O+x(q5xk zwBBJ@GYvM32I04_<*MRITx=P!944%*Vli-XoC_I1)4>HLq#fM z2R;c5x~&qWx~;v*GeLyG`3112z@pL5bS|vzQbm80RlFF4ZDUB{_USJL{BTuYbFhnJ zCwky6vCms3dPm5L?+Fnea#h=jQRaQ!|=3*=08ySU(6( zNRx5;>^&Nsl-$$P97cbncc}Dy%0=P z4~RaKRX9)-5>ls{>9_I=%!_>ZvtXfMKJ70hVU7oVbCmitXi+@~JgS(k4U;(CQR=0b zw4c4T5RUQ}_cJqh4i4a=O90tk*VgmFEkeR^3VYul*j%NfCWPB}wZqSYoG99oCAr-i zhZW#(5(HDBEh)3rXhCjlTHU5jjy`9|KaiQ~==AV6Vu#R&=@FCn*tamw~qB*BD&Z!G*%J-_b1JF}Lr=In=2$bi&ZhphmcTeaK zFOoYeIPmX7Bu3w?KR$IOz_f1qsyx-R!Yj3$uYiIj4kz!U%q(tGZKq(w0P-8hK;{;)^a?+;*FQrj%iDnCWvXI#s|Tj!JM z~y~~LL8E?gb`ldozuZ(25IWBt!`)^zk2g)xAT!O3y4Nd zjT!=MV}#fi3r5sVD)GDj{`s{8xtWN+5@?}+s>*hy|GRe**m?{fio+ZYbLqy>I!a{KGhojGJeN_`KTG z&^L=JpOy5y5^$pnZ9!&4-_PSaj;@M$QeSY^*xU2Z^+Y_m+wXTM<{KXqK^2}`+`mvV z&)S|zO=Az3kn^R#m{D05EmqhWxrZrdWARzJTV)(B&ln@4K^O%7Db4B^bJDoyyq z4vS^eKe_7JpRm!${Y0i7SCtW`p72r4Z8uN85rW?5YK)w@z_GYP$jer&Xx@j768rSj zxqk>SNp4VMTol#hKU3yo699(18Rx*>_4z%(d~1EoVyYuarNwDUpS(l`G-7O4(x|s4 zA`?Et=KEHlwur9R!#Nfv{HeF7NDVj%Hgdk$0UPAvYWc-SHV~cXB->8 z!OJD~BrH%$_fyTnI*z$~rpEP0i}?rpbAz38@rSRU>wqH2OMvN#c~@M_UIbl}SJ6# zzpy_}=jP8Zf5Ywkj|Y$w&*-=fNIdzAZ<0?47=6Z68AlaiI=cftnze`3NCWC6G`@~S zBBGVFF#4jxG%K7JH_cc(71ku5HYkbJAhBs~^Kuh6T5eYY+(&OrmG>k3hxR4uH-fQ9 zHmY+><8-Z(p-dJX?UJ_t(zc@#>scKrZCRq#i>k$;D%(RZr|ZW_nY{;Yq}wCz9ERqv z=lT;H-ex{czv}GSIR6op#&&D?biu|Xo?l?eyMq@QDb-B$eh67xgXRSI*HGUn888E< zR0bUxIUl?vR5Pu?jm8Ff*jDPUA3PAGPsG0Ef>+(O6C+3W`DWV?$4BbTZ>P&2edDIJ zXvjRmOaJYdbYi0xKYB_Rd^G1sSortH6)n-sb8t}j-bQ}*eNcjxn2pW{y3HZGbGfmv!f;jTHyfBqu)PoNl=Pcb1!tp3QCGexym1z_ryi%h_~L4DZj6H z?&ZMj$ggy1L#6NQITAQl?|Ja>Eh6E5t;v;W{S7#yK5FL4bKGs9?eL`~w9`)^ssCHd zG~|zcBX5;!I%q33?%)*fX$YY(w7k}euOQNMIm#dirnO%d&6q1G)%@TQGxviG0dV*X zu@n$7x^m<%X-)u;6n97SvEPw-Dkzo1 zV>>Qy;!(Wb0{ri{C&^{Hi3>hC(g_|b^&fHi@urFt1v>v6KboNTf@2Pj6#v85Gku=4 zdH7pnRzF{Pd&~DNKXQAhA?|@pCM>)_i%K>tSj7ciNO{FPy(HXpy%m?7k~h ziToO%Gl)d1w(k<_NYlg{_A9=Ut4;gv;SY=LnUnX-QatA>6n!tV={ZFz`wN}$2`!3M zN-9%*VM3y-dw4k?CN*_w;tB36`OOHjn^<^Wjz|`|D_fC9`U)Bz!?PPT^; zGDns>ks!yj^oD}PVd{x@DRw5^!y-sV)g~Ua&II)Z7XUmUGJeWyv(M}V1S-c@G+co6 z61b&`YvY5YMj!e@v$6og4n9VnwF7^<6FTU@J7kVW z0;dMPFxAgL+|QD{`!d^SsoZB+>V`@C*;O+d41{GYT<-0ol0_$+&j9{i{W3^_!0mqQ zi+M%e#9jLqEzMIoCMut2 z=jrzn=mXn4jHxqMdA<>vT+EQs`_4Is$-+-F{!CFfSF!QR0)e@S58zGRIRYh-%2vt& zrJ{|qs-YVPjO!0>sOsWzF-1h32uUmbZZ9ZUv@p04B>#Fr$mnkPcd_pmm$iTiMy)Sy zY19xS)iPkyThr~Yg$t<+MdpDwooU8tMwCgD9%2lKeQSi@@y77gb{93{GZAWGk^*jQVlIvaVIM;IUgl@WOSJpe*`9^XHye@NmUna zDKM57?$)kM+vSqj$A}@5?q-^@GEy7*+XwGLMS;Ghq8LUD%LPG6^r~vpEMAId$Bg#U zpB3%Hi<{)R{CLg1k+HvR5aoy6=0sHO30FPtrfQwK@JC?FNP5zIDKAB*=Gqs3$;wi= zD^ne3;}q>QWf^FD@o>q$=j6)ODOX7vtfW31;YRc2hS@!AM(Y-W~h6z3#xnvc2O~kJV7+uP0tMHD`t!VSh$EkNG%H4RaUI zI%>wNv3)Du^I3V>iDs;H+g^|!`CRmwmPpd^x^=n8l_?tmEfsnY%=s%z=4UHn0d?s8 zoUQIy;W@p=N|gq+y5|~%hE`+@=}kq4GB3((aSv9Xfa8%5B*_ju|v{#xL9ndy=zbIm|r`*wN{X}i+k}!Phs3% zF@yL%TK@6GQ{G#+PLse&AU#{v)_a;@oApFD&KM01%x#0Ib@L@lcf#fXdy0J6_3$_3 zVkRXWKDm^2BI_XBYm#e|vrj17ny_U)e<*<(M|e5(B})fWsMQat<78hZk0$m8#i|S$ zc#i2R7WSIHJ_OK&MSKCTfk~L!u9&^1e}YK#I9l&ZSDLhFm3M-Goa;v;J!!&MwXaKA zXn>1RvWGMCt5W27ADsu?CqNk~(mIioG|Snm)VjjFQy--Rm=BgDL8qbfun}mdYO1Cs!$dC4w$?7Bs>Vm-)nj2qqMsa7GHexp-dx!v24GKxue9N(g-EMEa zKCykP1$;81+X|QwV0bCplB@o3p~n>*3T9n&wti3?=Yz@H=5piCPly!U?hBoTCjEY4 z|3fkoEz9o^LfUMt-?v#T=C(C#TD3XFPW*!WBL`_ainz^Zrf-$w?|D5}NX!O87+V^t zj59Oxz6OLMuzvOhHs`IqE%R|nWlF!Pj+}_#MVrTfW>WYA8pGd}%E} zeWV!MmUx^Eq5G|_Ln(-)5Gf)^u`y*Hk!R;Gv_)HamL02L&#Q5&ZeEh^N^ytPk;C!o zaRlD{nFevGP&jyz1a!rX)6^Raf!SE9OUbmci`;rt8O%@L^eZ zlSEP6WFM2P4t%>R^T)0Bg6f~IO2v*ns;uTAwq&`O=lHn<<6d_jbv3{bysPo*Fw89? zk!&DC$Eh9Y?Q;!GKLn-^)}RQ#n~2plmE}Y}Q}3os8ax zi8_-%23+E7Iu>|&cGa@``M}w9aLafHPCC47ZLCu4z#Et3ypzxIIw_sm-krAuaIYTi zm;0Z3qHMU%DrTnP$={ES`T2*De!LB=vcE1OQmz}%HM*$TTRRGsig2&bRYe(x^0pnX z&pjv^&-CkhxNWkN|K{UIsxXH*qK-j(GJ5ZSppEfn{5h15d(Qa8VFu2_uL@2!FTu#K zQT{8-h(?FBWctQza$sd{!XMhsqINrUOWfJ)W53lL+r!OaPq1D`^X)&n5*|H~9Yc|C zyL6%b3!84Kb|JQs7Cu6oUo}&x1MM1s0EX~06d(M+O78(xtfkb-kr}Wo7H8tl(_vPVd z!)&g7#G-IyYHjl!hW&%LA`rqWqU8+N#10XlLpfz2*ZEE}mn4({u$JPJ*^ z435QG>6wom81dY!aAM8hEEce|Gu{!b=Oz(ow;0?FvqY_vO|RpF8e!gYin`0hl7M6b zxi+kCP&_X^k>`v;_@{&_lwY9R7uoy{_8J&mPA$=VxFO3`bDaTYJl}^sb!?qIfhPmXCiZrF3ufFR<>huppQ@dT4%*C z(Dpw?`EtfSyIcg(sTc^aF-$s=^;de|Kcn!J>?F1Oun#h(D2p4KE?s@ptyTw(SPSH~gpZY*i!!-lAXNkf)abZrqd@Y8NrGnL&{i z*2z#^E+|eafKps9+@x6s&>M?p5xeYC+O{wMFHf*+Z7%mIheK6-+UJrH*T2T$VC{mH zy(Z^72i#CRnZG2;rN+T^Th~xOn@v+X(PwxgTG6SJ7E>+9*uF>?Vy^YWq5`)I+`izV zR2pusD?8vh3#6!bp2zJY<)1C}Cmh-S3wMR{A}9WZQKKAu((|yTy?46_ghOuTH)mG6 zAkPyEa^1rDcQxtYeM*Of%STVL=UY}M3EY+AUA_)r?BY(|bd5?eUd>;8BZ4|rNHG`+ z1LsG_%U*Vy;2~?BZq&+eD`DJg&KyDZoV1J&|e}6jU*HF}JlWTe^NWPOaTAy`#(1=bdoI>UG z@L!N2O~B~@NKhwD8P)vdKWLn4BvvouyrF`AFCDqZW5V39uj+}c$e2fz)BOM2({2R( zpEoh>ds9UJ)=Dvg`Tvh0jl7d5&1Of|87lwQ-IY<1`92#p-*`wBZkXul>91Sl{v+i7 zqu|(P?gT!T?7KUtZQN<%`_HH{8=Kw#1@fB*P*7-+5~7MwP_Q&mP|$~n@W3bi1d}(wpEvd* zl1hlcKMzF15a9m=4qw$AzFQkRIP2LNL77-tTN*Li8`v2cS=s-zb~u4;7X*I9ZmOi_ z@WswZ&%xB%>VuN0r4jHU6cif^8~aXU4J+$zS_lizZesoiR*v0dKQ`{2kRUb=aA9mX z;oK<{)CVX@QDG&Qw8Is5EoJ5BmovP%$Pgk-fz#Sws6D7X6$&*m3>^=aikp1Moa|U@ z`{9W#hFS&^kQ{YN-W)aY!8gME{gz$OUfw=jqHu3G zH^Fx5Rm z-FUcRiu%7YfD|+|-alL)m0X-v?fy?M%j3rU&s%B`|BpSq`TxC#|9M$+5bSg@QN`rx z6Pk+TZcMl+u?o)*J>R8V;-sfPBO~b6VQFwZq9;wFlXu8JOIUUYXh=rey6#vp04KFK``l&@N$^<~+$suItEQRsaD64>`7WjC1b5db!?0pTPWvJ^rYd)? z>dLU9EMa_g#k;m%H+07&7@hw^#}ZQTscrP1dUH%`Dw5-nW3RU>pITsr(Oe%Eq)YF_ zdW=L2z{RN%TRnyv3mB|7UdGO~4R^k>3Duve_GPG|T6wX!Rw~V|HzaT|zp~hLK8d1% zQhEknkaWyZJc$YK9zPeZ9;KEZ(f^;{v$<`hB3Y?{ggfhC-}qH;GJe`l%2$qwQ`IV5 zaRyncVq0*oByq9QoKK{gQ#PQ$Li3*u)>w_GrN!GD{$PTj|H(5-WmVVQI`bj!py0!p zo>ZTi}z&zLUmW++CN>(MsZ^d*DI?&nxmA zb1{6M6EbYa-OiOdPHK@%v>LkcRv9e!a1Y}x&#;0xyqB2gS-2#5I8_Jk^_@##8oglWK5cX zzm9l;&u-yo>EDr|&;-4xhJ?hJciu6wv{ZRU$*c*QN=AEg86g{%w$*+$tzZ|3E`j(^ z_I5LoNF?sOhNgmBc7!6`?Ll>Qz;UIXMF>fI+(L^7lwZaS`|REM4lTHU4o@vpsWV%P zJwJ@Yvy~|M+FiSKHpTr~QmXwJs7mC-hj>f@)@9?eGhdN95XTfa7K@Q8L z(ImAd#>^El_MR|~))u1VCwF3}Cy%xFD0si6{|)J`G%RdafaLwchOSJ%(a9_Emq8nN6h6=^4hq2|xB$%gC1fg-kdF+%M{CYV zqlBzx^i;+^%nJ&4RQmgkJ?$7iqt@|idXUtJG6qXQkYlUpZSR=jGUZg3O%U=M=_CvP z%D1K!N6e#{Bs(_1)Mva6K(7cY#mZ?LF`C?G6Us)5!_Ra~(FA1}$DgMyz&O@igC?^xxQd5PI7`%k_PB(Pl0drz)8!Ogaco`+Crg`5H z_n&h*H}BHQ4JzxS7mtsG-gKpvE!$nnpiBEbe;altFbZf|WO0dSzbjpb*WJd(` zHw@T9BU>}t*A@gbL0M-`%ZWe!UR#(4Meg^jJuEhhG)j&Zdli2Go;QB`krCfG41B_29I%( zuPEY+$qfUrw*;ROB;Dz)Jp3DDb+C_3y1pkq^u!!{KLp;;AUiGXov&(FWVQ;c_~AsIc$D1T@KNuy|i_=J17d*7ZS7Y!~fULk-#%&f(|#FT4=M1KSvNaTG~KVtk#YVV}mN`COcN z!FADqv08t76#fhweXV64PEtB@gLuC_OTKI?eiGXjjU=eOCG5Kt0c!W1`$v^o2Rk1{ zdmbw1ONkY!x1>cH{V(U^b#v*txj)1O9XPl4X2**{kz?EF$<|gg2IOhymYa-1$0Ueh z+egWYb~WQU-w1eFcIbUsLjYCEa>b>i_aA9)zTMv4jZI4%F8W?5Aur#zus~n})|5?0 z2H~T^r=_Rwk7vVDh)2akC<8EVLX4Y0LqS=#QHNTo^3%O*A&Z8-;)$H7$5X#Cz24q( zued=sZvOmIm?M(o{M+WdCHY6S6pw3NLO_{1tbS?URnXAQebtYKp> z4(NN0Rj+~J@}BiQvvAFkc6EA}MvqSKNI5f<#p z;34jNX#$?z;^lm2hhAi_5k>@aK7QVr+qhaZL4gxpgKiy1_yWOuD9N-QczNg8h-=i$1!g! zbWBkFWow%=}P`(kdAzx|Fe;Ryq7^zo4}C` z12fh2_?2f~MpJiK5`T`|T$N3$T&c@BD<4sKSjheLVjca!EpMhLTKZLy_)Dn!((}^; zG$I<>40mY5_tDYOi1!@GCMG6rx0@)SEuilCNj~yDjl0H3hE&?FZOmwPR+?ylfr7m{ z=}6Ol-UYXX#8gw@Z~fniRjjbE(A5<2%L%rIvEMqgzpjtqa^w?Y;(mzro_YK(8>BuE zQNAeHJh+(G+(0A}Na_pnOq8Jai}E6NDPyO!&IC~J~Pfm6^5EouXocT{@2i|~DUGy#g%`d>BGbmDKptPfotY>V^QP8V;R zKvA%~EFk)BYaZ#JN+jQYfHCjJs$~{!9rIpO!h z$9@jPRWDsE=CK)D(&|1}b<&>@9-a*U)}s;?)!FPHVB0f;bwen)WL(dWhxu*AM19%5 zxG__WR&COl^}wCTQ3(!hee_RlMKhpr*uKiHCwWh=oqlH%L{;vkuRqd6uA&6K+?$9> zcsUxL4_f}Mq&b>Obg%~=mNMXB_DmPwgSbM?^U}SEcG@xc{x(iuxos$*1O3y7KBHM> z&pgqcs^_Uvdi1w@d$YgmGfuka7c;B1xKxn8n>h5^n!o)P%v|+}Kx_FhnRCSVWOf_N z+#V84HeEam@jxK>T5`FQ_=C-ETSDDna*&&kk6phT(dl@Zc1{Io`^drv2M6KT@IIMN zQj$|pKyC_h*x2moKUP+C%Ub&zSnhmtg}b{;7#}@2SQ{D|7-owbV_a30W&8+M?3ocq zn{%^DT;!5$NqFQ>7>2QNsOlNXhW0;b+AWp+MnEvrytGzcU;JY6MH?qRCPo$dn$v}Q z?XEjTLm|q{#BuA2uHWRKg@_Hl0gKcvPFC+=+$sG*e%T(EQKNe}nce8jfj&MpmEK%F z0ArIW=J)U3HqQsOnx7Ml(GUM=Wm9a0AB})Tm#rAgj6!q2kIa?YK(y-3L~I)d)?1mt zZE)f=aOEkD$A4w*XM0!SqY>VpEOYJX`ioN>Q=JdBRYybxnqC~!Z2FeKY43JOd#GA< z{6!$tF`g-T=@y^?azApM%E5VD%jDFQ(KXPAY9#M6%XJI%udkcAad1>^$HqD{}lD6b2ze})Vm^CV&!=<~aQ|1f& zMhDK8;#Ol!dz7L$L4Zu|JQUQj&MlZ z##Y`Cl|SkBY*)ykwm*iuH%d(h5jmAy4|}a5We!PBi>Q>gN)$MYs|b2E21-pT+TA{s ziM%yZofI?iU;9k6`?j`ltJWM|DPf-2)#AP_AeVZ4-{SOQ29tFXx_;;=H9SNsq3_O@ z7-AXR6vrg^3-Fw{QD{wd6E=={E0M zw3UwUGBPYSI>EoXqW#yoJ(|0V>0Hp9@EwA_#Y7lA=c(!TmfjeJSa1-6kotb(OoUKWL0^6x5rR zhEFA#-ZXOBwwr+2UnsDD6e+kJkn0VdpAoJkBQ}SNdgu(US044R#texWz**_Ym7*-g4c#bF~I(@<0gu=Q^MiqXq|W1e8hncNq4=$s1lX^+4aQ zzjQ+~f9aFe7jXzxe>rHx9S0#XkNB3yB)pE%|Qb!9RtBPM_71WiKY&pcJ(X7L#dEb=En$AcuwV0xFj2u;_;&T`D#lB6TuRF5m^s}a4W>tP1qv3O* z&z?1qB2k*bd>in8XzY?MZ#<-$c`-gMV+t6*C2bMi7V@TmCJ2_pu|Ll=8BhWdfTyBpXbn{DFzE$9c71yA(m7VC^$~cH;EWUe_+jcBnTvw^ z@}TrWa{NdhrL)I!k_9gYL9jmTNz{qSX3c&t#4LoW-MF;l(*B%+V{W&LA zDeu=0187e#Ia^M`c7Y?W4dU!Jl`r4mJ2Q*M&mQ^f3{E2skUoOyG}{w_+yHugDURQLmM9B3!wPal4K8K$l1hbU7$?)>~B9z z#a8O2tM9wtg?^WNZZC=A;zTv8mju*q4Q#{h75RF&C zxE8y?EfLft+I-n+4NR|ubx8RkMSTnFt4`O`Svx#PwT?q;eCRE19lo z;XBcm^e+|yq^UFOUd}Z%4kA>h58>SV2Y=I$j*11_0iEY5*HD<9&5S`C)qYZJzW4f% z6LeptfK9cpulX0c{L;REC89_8^I_kG*1=l*7hzudM{9q#L&Lq6tS*L9wM zeb>!NNzK=Sd~bwJeH#zv4($@OgNHuO)Kit7T=}<0JuR_zX2<4r&43%!Q{OsW+WAiA z9B@LUD!XHlH`|*eJd9nhrZP(r!)$1tU(z5tNz=gzBHiIuhZ)BnwJgwo{i33j6F;@* z9jrNqDbGwbIBAhHmb=Y%toqjDHdhNwZ!|3gE?r+Ry4>;VuxBCc2=ld+b~qH>N17mq zj=*L1IjSOKLtRD%Tv`A1X$`$!*@}S(iKla{^L_k>0GG|lICp5WRzwrmnNoQqAPL^! z#W^%#mFpeh+g2u_t-Z6Cm|=aaCy!;;V43fGzSp#KP;n?-$fHuwk!1C0jE_L^Q6_t- z-|ltyuae68R2VUAS5{-7DxF$a_gNrQslL*EE6ep_3e8xsJFUzoI zb`gnLKKJ5y(Vt&?=~QX_*1L11igFo@6uF2MO>XL~FzJZ*XZ#b*W9&{huDnfjsFzhH zYC_^cLJ9_Nyqmq+0_B?C|Dfu@(#*BRbgrt65I>hLld%#0>MSPr2?yd7;kEzS%bVmVBm(tSpLA)ZtHDNL{134GBmuvYoBnKXWq6SanEz1bkJA)Ub=!4b9WWOOTxBmEG{olk_he5xS_tM(68 zPuu>n?st^WYf~{H8BwB8W=@zvBVcv6OL9o`p4$FWKUmOYGm=?Js+qge6WE`s)t6$* zeVGx$V7dY3%FezqBvK(7or2i3?{_T^-)9fxo;2FNa&fS&PaS&B6nx_B7g2#{fKGyt_ z9e&j9mFLneJxjcd+=%ctCSzStez98qSn_0-I3MnS5|H|H8D-wNgaoQ1aQOu1Aw|KIDrRYHAfm7unQI3uzGhbF!=Ixk@@$ z`qfyp$z%LZp4O6~9*nijd->bo{VeK=$7J1I&);(QCf28i3Zx_ls|mp*q+=1aNQQIP z1j&H=Lw~w?dzMa&e`rC@I2Y6=P=-rJf?nTY=}wTWeMoRPJzkd{l4dzD>AiE-(Q7ZN z(th~Iy6X_khcy8rF-JP+8VODC=De_TfG+=vtL55gVB)S5HO^j_oe5R}&e&3spt|lI zi?_PojQOkz>b0}+Pz4q_IkWAy;mlU@N`?&;8*}R1^$w;jW%+>`Jqo|uK?tgC@dZU3 zp?|JCjo@=Qnzcua{B#|;)S-n-vA4L2hPL6Xj>5r(WlNk_eU-s-oaKC5eiB+{5oO{$ z>upCW>G7G8`18Fvr*u0zE94JSDZ}Z(lJ5;EqyFS?b7T3M`?ttw@9e2LeBZ=zQM1oI zF&EKNBm{`6iX|$&JR~b&wed>Kp3K?E;Ylc*emWeb#;T=?J*A*__)$)-pgKf5ELJCj zZhUV-_hoHy_>+*fz|wa~ZGzzjF6^uu(N5!lb$vOSGwW?Fe#50~=R+Mm3%{eTM+6kg zJ_wN#5nCT7Qlv)8JT9iptu{oDyW!b8kDr+F@O&K~oj}fK!ghi)GTc_yg($V!Zh=x} zxA{IYJ#2kF=N4JDGD>B%Ig>i9-y_}K3YESu^Wh0PEgQpPzo+ohS;<_f?!{{RYP7eMs?ODO zF(?J%t#{^)J(FkH4sHuyxH5f{kx0lw#bRy90+AKAcy_|^?Z$YXucky@8%8gI{pNER z*>S0EgTZHyl)?OikqvA2fyE2*fs<6{YnCJGn3MZ&d=K^09jD#PGC|>E+)h$-nt~zy zwpC)`?+G-r-jP5j@F}RK=F|1jQXjw=Te&XR4@lk$?#{K;J96OlOaP62yfMi;jrBjO zr*5B3Gdkb=9Yn4lMb=5T{+X(ePT``2*j(q!qr+Ww zHWsT>0TDZgB;}^A%>A1c*|%V6$mJ)xCAqf&_cfEm-Jm0andWZ&c zC)8&VQGXMk%ISX}YH2li?Q5hq;XS^B9%zbbpK7J^DM=Y~wy(uSxbm-XY1G(U>`Zca zcPck@$slq{3TCFEeXy3Uma*8`0vZr7ZcdoCHhPT{&E87m-mEN*-5EcsKPUENKJ<|? z9%pUYPF36E=aXU)u@}P+Paxdb)5w^{KqShP<>WnZXnhgseQhYESK;K=!yCEzJN6@I z4%~jVxx2X6k%M}w9?9?Se?$8hWGm^OnGB7({$jepM~wr+5Ru(lB9X4>OgjBAW^(4! z>1-a*L)6jG(WD^{o|GtHLi|fx#H*Fx6IX(&@pcrw?4QAqmxA|Wzl?%N+!BlNcoDGX zt;wX@!nQsOlY`Tq2rgMZQa#_+NA9k3HQUO|1wv=P;pMu`{f`t}-6&+Dt+nD{D6RfY ztql%lJdzI^S^LJ;#iP_6SE}Mc3Yi|o)l-@>zM;G2P z29{r^2E6;hn;{-dNrCQCr;isFon@{8btZom+};)ZvO&B@JNV(bl$hZK+wx7WAXd&B z1~$dqfD+L64c+TBMh-N8mufXb0|K7G+6RwimLOSmiA_)YkQA`@)>Q3#De#yd6{t?q=G|UnaQ`Z||C#*l2G^$~st3miS5Nk(ALTLCCLerPpnFoiV1b;N z;eWqjg(lTL@y4ml_3f*B*wzku0`I)3GhTu1GNgQp2%B6Wb_R>lOTSMv>vUNRDQ?(Y z{raOFOt6EUp{4{;4zJ7e?b5lyfOiXuk$Y&!~i>BXK!B{ zMV2x?5Jz)%c{$A+1Z+Tz8W`KjnTgrVyNZL*2Vj8WfZ?7Hm4T_LxXViikU{oB;4){L{YVZy?=f<;gF*|7X1%7_3IY~DEA+O zF{^>_I^wc{HQ?tA z@N%ERLK^F~JL=!Re>XHWnGs7)ckL|10<72b{am}09x#vuO8d7ZOI_ES| ze6-S>SX#=kJDd!w#F#e z$;ru~67woSKBnv~RMS*eR@RtK1^M_uwLKj3fhb;MmLvJA4Jn64M}vXaR(&I_uvlQr za6jgOfrY*EemQwD{U<>K<39;{0kP)mED6cT$ka3jUs|98f`Y1?Pjm$D_j2jw8L)xO zph0)%Z4D^J=4|sTaKzsWWU}qSqZ)mt-$-1yF|Q97zL=WQ`uh433AiaiBwkYq=%2jE z@cz(3LP8!M9yL*u(9{u4a786*DEy z?{PnF1kX1)(wC@!HUU0lmNyEBj<&?FB0JXt))WM|gUFXJwNZ9+du#1N?l;E(^`FRU z&}(xrP5U1`_`Dib^E^O}-(F711MFi*Z?71H+Zo5*-TnD2+MC5Y5#6v#!d17}d+RASt(631V&UjQ5K)}{i;*6C>_YWa*( z;60|JX*{JmttqY-yJy!+)_@f*_e_({v3Q=LH=v)3LHEyhoU7vLOR$=z4R?1$<5t-y z6Ny##euJ7ca53l*K`qk2vy?3gymB=-Sk4rLBW1a$<*s=)uE+g%dhdmvF0lbFdwg8s z@aU*EYRU|am^Z%F{l;#)9}|#3#>uJV0rdS755>3gGBWpRt%9pkuK|Nk_P-gZyHyKK z*~T|sz&$PO^cc?SuJp%A8KD;$U)mkXPN?g4VXE(516c$8J3KrC7W^cBS2pctrx{+k z67a#nAWf!+Ut%I2G&J<#O0z0NVv{N7SY2-0%b8jZtu%!LdhbwP!Uf;JjjrC!oL%9R zh*)gi(EAbyejw2?1rY=zJvD;BZx9BM&!h1N;2pr+L`zExK8vmoaFVpl?T>80CU(7_ z!QLSuA-c1r>HuxcsKYry+G|sG^U2Tc$HjRx1j(D@ZQ`jT14$Vyhwn~yj3FE|b;Qrr z+dka4j}DlZp7`(CQdKi9#MgYjNjZ5?NHUDA88bS5Gj<>{Ai7+# zA)0}Kbefs#0ZqIPX!9q(3GNV3-1T!IP+`1yD7`s7L`>zJH@MgkDs5FP&#Av!# zS69-5H<^|Y^dFPqH{Q5{?Ic|>EV#GJIVU}q|FX)N)8V}Dg2nEBVdgCFpn&Oc600f+ z*W*^SP?g<|lmjowdIXbE<=RRgOST~xVbk>pf;T03M-4r8mMA_#t$5QHlakPL%}#Ym zz!fu2Bb#>;(p&K%346DEfn%lmH}-N`O3SZGZ?$ON5AnYUvKxN&bbv@J9`D{vO0MT3 zxqa@rHGn}f;V&=4N)EcaT5$o%D#}0y@PfX(PeDk zF6joj1SV-&?|QUF!g^O|Xxrs} zc9srza8ZW5li8XI^c7SP4r^Wph$IaHqwctlcxFALk_2T2!&2}FW&+S6Wyr7K9O#;VWehKxh5xSqtprJwfZd)Ea7FQv$! zvu>}uG=0Mt@XCe8OYQUxxI65fb7dC#uiIx<+v_b)`tbGT{7g=3UKewt9!2a(b#Us= zgK>j_eaKCdq|CnmHnI>Jnl=uHg?kv968l+%%xADe04b^I4cm2$d5SrqM1O$!5UTV2 zU4#D}c>xNCh^DG1cqWcU!rD@v(%hKM9;i=ahK<>Qv<1{aldbN~psf&dAY-2eEw#M+ z3i&#klh2)K4nyy(b>ITdOb?fitVOp}D1Gl_by9?a7>d?cajp(ut~7pg9R0FB5s{4F zowUk@6mPU0fuz-Z)1ZeIw7CF#qfs?YRh{G9w_^wsR2!Ps&tkV*6NBBSC^@DgJn^L! zzG5NILi(>uiC^z1@r!NSYos<%u(7o*I*av#iC3WLUihe!R-Tj6p}j*5`DV42;no{6 zQOa_;p|LyD;&vD6Qgg)K|0v|1CB|Q<6F(ES zo62}gkRRj3T)cObsbLn;)WihgPyDjYlS9MaVb+Im2JCgMi<6wPe?BYm?c2B47Dm_~ z-jw+3bdGp5iO1beV$0>EG%5jGKmxt$CWQV*JsiHG&b+0LH(GC|jTCVObL3jUw%gOu zhp_~EzUmsyqtLs%5ar1QkCfh+F1w%os|I7*I;)FVzVLhUKzk6cNWt|TbpJ=JC|jH=spN6KSi zE8D#D>ad9@xn;hnS6ZFTYm~Yvr4{Z%m);Y2Pf&a1qH#${QBp*<>Td9Gm+d_;&%D3B zIp+SddM8rD4OI4dSy?_pPy6z~G*bO*O;l|sw2n-**wuoBFO+S%c_1t?in0xDlN*XVMj5Xu0XCCUN!Skt)3-7b= zYsCnuQ9Cl z-`6fK%de&Jg+6X+w&g+!J(8r|>*$6)&NA=%@MFGJC~AeuHf;*cXxN93R#r)-0IOmu z+rGiyIG_|LUTYY{qlm~@S!0084U`+gn*vl%>kmY1ghszc{Mx#h+Rd?~&jM!p?;z!#&t(e|m%&Q|R{i(B z5!iVp$QjTEW%M#1Wj-)fx=H1>2%^#LHM?&vT;RU&|0#c-X&3C99UT=8R?N`edY>W@ zBJ`J7TiHC26Kd4JW#=k%Z|uF=rH0Itv&zZQ*oRiB!P%dR=5M6dh(@55#b2PG%35}b z@k7joVF+ibZASA+{oP>p&PbI7eb5f%fjNyOst;4`Oy#qejywUXG%VhuwB% z!zp(aczffDC@oU@2r~&Lt_Y>q{cBt0$xeGz@pGj&BC{%o)#^yPf@6l=jrp0qj6{5k zp&dQ>4`nm!=!$}zSt$tzMmb|Me(LJ|z#{yQ9M-Js|`47HK3zU=v23)!rPbEVBU?1Uz;{Cjg8VZ|+m-LlMBPl8l;>)(S z`m_YBdYad+@#~+`(r#TA7PrfvByM|TfL7ouDk|2ky&nkUsAb7NeDIM?reG&SkIwimTHfQo$z#b}yAr1<)wBd;TG*LcbfN5g~#vAv~~3 zSTAkA@bJpP2w)7(XU2D`=AVmzolr$MucBr51u_of?{|Gczgy=r<=Jmdtbke}>lzNxGh^A8aIn?d zyj+OYwG#S0&%f^!zu&mIWy#P^h;l#W^SCeParvQX`tb>gs1)Jd{nK%ZBbDGY>H*Z= zBf)($pJrsc6+PxDDC=9B4g1{+16ot@FPEO9(Ta$+4GB)klu2Iu$JS1hl z4yM)AyWd#Z+1cf>n11!}^jrXbLmd|iG}$q)bC;A85trEHh)pL@6RDq?TE{ek-JPvl z+}GMzd@b|~1iHQNMoLyMHrcS7>#20B&I{yE;G$fzt;PaGV7xv-k|yxjpy zM9Q!0YG)+vl(PJc^?tfJhPv#4%+ENX4GBf)4Y{*wF<3`SJ6m_Elo=cwp7bsdeyx!+ z$x*K!Nicm$b9#c0%IPp10WRUO)2o){IiIY)dGqEc@z+nVaRc2b%q@R=!tw5w)}Di! z-CLcbU%`#U7>-xKqO*_GTc%JhJ&&a^c+Y|N`EJa6^W;SS^JgelR@VOvO?UnS_MCtV zcUyBmys3a8amYsz*lOdE&8M3+FaVeAj&Q9_zd|ML2 zY-r&A2WN~Yz2YmzuSxUq>B)6FM!Y79T;tc>1^8l=?*s!Av*Ubc2+%ozjD2~<2vT|q zGrgpmosRGYJsJSVLHT4h{qYq%QdGq9e%vA*7#f=5jRh2e_D>8u0I+!kaGNS9on^&D zChgn9>M@sfUj*P9=sKjlefIUIA;$mUQpx9Z18FjpOPORJpcp?_;lI(?505i%P|%;&UzcsTrv>U9HO)Y9ct>I&?Orulwm^>XOh2e#~lV}R78B}8r3(=b_zHPspsZXsKA_jKRffzZG z9@h&dAHzET-ESa2wv$d|+5x&>qCaSmnt=(3;{pC8NT)pd$F;x++L3j7BwH=j{pSe ze6QN$ijJv>0Opm~R}vNv>dix#uXS_w-Nt7zm`2 zlvnc*bG*Ma6@0!mD3D3^%jx&|@+m{7)veNGjHDC0KX z`5jk2`f3L90Re^B#Z2N6Z}YNCDaK|7)oXT|c!!ItqYkx}FO3IeCKa=uFdUg=wm<;= z1Y&Yc6or|A_5(V$)2vV9_B|d>bHNxzK!f=|Yx)F0k=EAMz@3nC$9EHhPXPR9I9I0a zaoT|}oXRB+;of9RM{z@7N$2q|+FctKlfzdYZ=TW#w*VaS^?q%LSf%9>Csc1VX}K+y zZMnJy<^X$i=q9Y&9LLix6s-mmfjA;`mB6={9Q?DG-A(`E{4@ z-<5Fy94xmrCJ%+!KIL}M1@ zFsj);@-DUx`|hKC4kt9Q-0$UCs(_y?z+%89VwcCWzS=1AH&8(EH+Z_g;=kLD1EOJt z=Ytc7Vr9x9UEu8a$kpJL3g9ARf0g6ze2AHrmR9dzx(KMwH{k(Vp~Ws$)y#~pyyZM> zHs%#>_kGQ82S=wHU59J!Kb(B<7#HK@1qU(&+_`Nx-*j|zqzSmI{KKQIUI9_j)<TCkO;W_ zBo+_hb>GiVR0FgC2xPcWWd!I5IEQ~{doZlaGG1%0n&GmE1W+d5tSQ7Ibb*D5_+5Sh zMdq*6)RKQFGsmkz{)q!1Og*+_m)&F&AZ&{IuQ;!Hii(R*0bM8niiAW*16~0HxPR8$ z06J-Z$+*3BS%B85c@MBj+cT;^cI3V9u}f6TXL;r5^JCj=N!Vxeb70bB|5i8&u=XjB z*ymem%5V3+sp61>`J2o=Tdpm?ED7?jAt|`s321*m#a34S9}c2EJ|Q8nL-)g{Pw@bw z^SVhfcCSa5*T}4;MKmUGLj+j4hPavX|1Da4`cmzDV*738j6OdguTse$zl|Hk7cNJJF5U5B>k)l8{+HGFuF zh@l}Rz%Fs{Dxz%k+^JFHI8(FlFK(rlk#t_tOxXmaqRGM=lOIbPjMn@tb?GAS{$H~I z8b=@_Gd$t*_~XM{ZC)!hMsp{nv=9l9784#2>GQl_p2fs5O%(uwN+y*vviZ0v{I$&# z>odK6gtH%5G^4tH{wY_6w#Eu0u1L;0_r6u51!?J*C{~}SE-QEFC!(Q#QT^hTVQocy zhj&Q7jtN2}B9W1i|NQy0z7b5y$r~n-3m6Cu149Hr5}h44pRif4@-wyF>gO78e8Jgf zvaJ@fz_QgVv{+4-oiw-$pk}1D{6+Biby&84^RvhM(CyggLjJlFfj7U8QEm8#56>{w z4r~(?&&+V;1)GD2Pu#f`R!AU@8=}#Y)UJ6)F4@}@FO`&4*I(I9zLD2$^_?by`_Kh<1K9$Aq1sm{G=u(fh9`(IX@7xTmRFhxo zV`>SO4R8wmu>1Vo8@G@6dR^yN$Ax+Lyz)k2Yd)W+0S((z$Inul_we_wrg*}K80=+4 zcz5WdWKAoLV-=r>>EuMW8BW?Bn1D!0&cm~?_mMpEpb1iDu+2MPO()-1f}YBzuT=tnGcri2{QZ+Sn_n4-QAQ5 zEv⁣FPPIvGG~FtIub<%&>U$#Ili*{16X&sCGqUPxEdgJ0zci(TDWpm^^IIGL7g- zF++TEopM=_kkz0M`zH6xp+>5tM_TB*zo13EH;&D2*p4J>+F?*CF{MldMGXl3M1`x& zh@F1Xe?~7G_GuhF9EH??@5vjK=vG94<-98rImngw1NqPdk@< z*4mCcm*&E0nckIxC-?4`ua}O@%#kG&8d(mwx&M01F4?SkhI;kmuD`fM3mqz z-=3Ucl03)3{(fB`B8rNMv3Wmx^hOezIOG|3wbzCad$CUl9Mmb4I7f%ZUlAsgI6ZE% z7STx7Q*Jncw~{R=ew`aW6xX`=!B@=l1kZ0d4-%g_;j_fWZff6(i`idO6=y!WR@LfmJ503H z@hJ=~Y`2K(n(aa2Xoakx&UjcD%C`n2nFY@Ei#-S}b)$$3iR%h&F)YlB^`=bWAxw;$ zzq{RizzR*`{dEghJwVhJvp**?P|e=&Q7BM3W@&g-*77%Gfx=|2By1TojySt>j?rhIF@B7>j_kK{H=kJcS*7VG8 zW>fL-@W6@c6psZ2(&+rk)oqqnQE5SvQ~NYGYSy-=>wO2*iundowz%=?WDUviWDm0# z&d?6$Fw8kK4>qKyrvi=QW4<{zGk10NJQ}VFQFhf*(7tx$XKwbZrk^W#yHbuc!z?d2 zl0ZRsv+g4s+K8l!A>){)^hME=t9MDH-aFO=Wk1L{)W5}|o2&BSyqjF-xAGW ztn7Vhw;iWJ(|ui1&S1~3)FO6#XIIPvT6*Kr=})WBi1A{}&gWfkT&nVi@R>ul{@JAW z8!3G$*Rhv(dwX7_w%5E-@|}rzFK@8QgRX-5SF4kbc^RF7;!=Qj>jgvF?%khSkGy1` z$!k0_ReSK4I!?m>x0Qi~$97e$3H-yb5QNS7Sb zTJb1SdbW0S_=KB%&p#I@Lg&MqYTdC-x!PQ6^r170y%@7Pyg@&27ZGot09uBO@TX`M zp{I!=5m^QSwNFOMbTX->G+1LEDLrfVHGe$%Y^7PV?a=|hb;4)l8NahJ~`sQbGCtt=epowg53{HD9in)w zQhHvAMu#RQ-X&rJs8gdK07i5!&W^{O4=0{Cf8cR<@19D@;%&-#yUT<(xR{r6H{ndV zD5N;YyFv`QdNkX7`@J!&J~>QwxcDwLhisM8Jdh?b)}F{6bHL+r!uxI})E2sMl``9b zxJy-Xi9$SYwafg`^*;yKG*E9OjNmG0e5P79*SPL%6d9LkCUmo^>y~1(elM#{LEqt^ ztik5d;CuJ6L;mpHmTeQzN~6~X5*78LaR?c&ZhsSKZvFo2Gq>zY3i}kf)NE(d&y(=5 zY-+|RpHiW~y~t8M6CYjKsT4kv&3YW6h7H@0*jO;mCjNo6y>#^S^xDN^QM@(} z%I!881Oz6QC1m6s^U(vz>kL|GD_xwlqS2{%g13V4CF|uHi`3&|1yP1(Kh9553C~7x z;fZ8gv(_I}{ye%Vlxe>m;kZpny%i(%Zloh#!LwTKRyI>i;CW~qQCP>#GZR#?Cu5ZX zl1tDMUno>%Ds|Vy$eg-M{QW(p#0QT83;Nlb9A2MpAIn6JT^%?L+Ruq{{C0HIkbkgt zc+3)2-9FVNa^&PT;AH%@iX8)Jp8J?==}oODvk%Wk#6Y>zEu2iureKyY!?M$zQFR>w zO5a?mx&nE2&8y1%P!uc3tM5=0v&Yu-E$qI{AfVE&ydPlEVBN*w=o1rK zl`E4cbqq)1{B1&30mI%(Q=zgu>*=Jz1l z?MhfXKHQ!Dq#N|h=5I2GNi;4n^F7P#MqS^#rQIu9MHf4GzC}-`=Inf&7U&5o^E^;! zSx3wQ8JJw~YEO%%JKAXsQ*m~UFl0}~GBLXAUSZ1Y>IBK%-8Oxg(uOz4)T!U5QJ(fd z-NuQ*|2)+6@sE4+7x=CBWXYQT9MeZS@<~MY5>_0~pMM}J-T3|MZY0X}=n-+3ou{)} z+@8*QG(L7-Iy+Qvzl`}jG;k(DNRGU=yhW4W4(u+$L6dfU1_#{EM>bjgUeP~S3YEgqjQ~*(Pr_x{g{h1 zC)xq8`r8v6$E}Hi&>vzf&FT9q4c4pT)l;PwX3oCL!dJ&-elyj^DPtCQ)s{Zl*4t0` zGt^Nd%EjmVP-0!ZUf`3!NQb7n`^VvHoPtZ-lSwSW+piQzcn8HA7xr7!|I!$h61TVf z%+TE1AbvjU>}=@TZXSzzY)_dx^l?>u&H3SxdGci}>X%ky?2?UA@)$4kv0^)qYmqyD zidp0QhthAl>d_jdP;9=Ew7eb1|8+*niDNQq#U+HI&uZ-cg9CiBmhMX2`Gtk;%1!5> zS`Rcb3bEvoDE^N-t<4oLUc5lEBmsf_?AAW|PlrSFDl|RqyfR-kkEu2@>8*Tf?Qr4@ zvv{ZwWP-`6OBPz!>+e%|X|g*1c3VoH)rBvj!a$+*C(6M+wDx$xnhtc?C#Wj%)-UvA zpQB6WYeFUx8S1zfd^~4_<*ICY^XRR>g z$$(G`%s;Jzs7_SZ4#ddx=pC#(42jbZC~Y4J|0MsF@x#k;eQ7u%YWjfTjL)i7Wirl3 zq%OAzrLXgT#fj{TOy*rvbrGMb7qcjVeUycHn9;Izou$ct)5I5LeI89vc7C@l>f6-2 zUdYJa;933K_xFd@i&oYsmZ8FIj;}>aqn$Dq4e=+-Lq7L$n)_K7W-y|_v(i2(RPw#$ zyA^fg$wid{)jli!_Sspb*ku!IDL$d#9m$E5GqYN}a3&OV&-SHW=w^vMQ68wK_7Qn% z@69vaQFMe_!OMze7DY^@pAnZyP9})k-sM|hM)v&i+s#_keTQPKpIu8yQ`ZDDemyQn zA8TP(3WyCb3nJdseqvXklc{}2*D6SqC_`>O?H2PSir|wsxi-8>i8uFlU`*wCcXsGE<7%XuOnp^PfJ9jxyPgH|-Bz3pdNE zbjRK)4GGB7|L{omNpbV|V9@4Na{`;`H5lB`(%!CnvbUn{wB7i;8P{--srt+^oJr%w z^XE;iVq|X|&63~Ei_Q`?gv2P+HC&IXk*Y8e_g4P^NV-L)TSV3 zCR5$epzPsj6YC&-b77~+jZO?_LFq`ov0v?~PgFC8nf^@Q*7_7O?rh5-m+{V-%rFm5 zYQRU8`5Lz_vALyahjZWXkrMgeFw-53osj~Lpp3^K^*VEdOWtEydG&9Nkx$PmzWmZL zK&d`A7nM7TK}2Tjs9bj7O?!Ox;UsEE>#Z%)(Q{N%X~9kIZ{|PBRZu=S%BHYkeC3t> zsG@;7;Bxa;){I}5sCg#i=CBZZm?360%tC=WlsPxK_3G>T{s0d=P2ra_`eXZ5R{IJK5({10RhF%hI=5hy9O*6w zLs3F>+I7#O{h5y(#0H;mPLD$S^p}l~)#{G7rq!lX&WC@}*|PBZU4PLisS!1%i+wGj z`%8iwWn0;k-_A$w8x3?LK9Vo4x}wq>u|)>Q${aW``go)y>_5uf|L`z{mh#16&C1lE zW`!e)dh|hw??PH~)}-7Jdb-NF{q;rsgv3?6-lgMDH3vo%m61ayai@6`{XKWg$K3jD z+C-c@H4WW$m^Fol<<2*F)N4PrsU2J{P&U5|-LyN34QO@`gBA-{9URq=EP5(s*R1p zUF9(JLZqhEE0fmvBqR2meW#u$?4y4a3P|w;|6J;^@j3-cbFRYzW)6GW^B9L&cFh?;ozk(7Nl1j}mBb%-^~3vA@Y3;1IuS zg7RwVK2GLd!0P9;MDL11!iEOdH`|ICHVX6ErSJD$7Z;w|Jn4xGa7|wO8KFsY@1A#L zBuP?|cY%r!pmSBLoOmFA#z<@e$=&LnT+FxB2c;$rE)g1$G?5q28b05$&O*_qV2wi+ zN#Ux?jrLe{7VHoq$}#coxu0AG`%`?W>~K&pJ(c74tv*&@F_HSSC_Z0{yW>IwBuLNs+Ts)ZgVC zu}y5gUGy`2h*?auHb56tuyZ(ga&XZ(nEB@8;e;K>70u+}ka{563 z=i+#{hC58Gyia$vX>{IRC(>eh<4fka=N1(?#TUia(Gi&Xjl^CG$6=iHYqCM5bxcm= zPsYLNU({Cis~-mWNyWbeS$(t|#AF>jSw4<=*YQ{P_q+9mkKg>Ad>iNLj~@ty%~Y24 zYdcMkaB#Y5UeukJBPzsK9{vO_2l3zCXig%?t(9i&|Sh6ERn^ zPm`XCCCBUN=s?sxT{xsU2i1=ysKRpbe)EUM0a?z;|mirCSjf~ckevCRb5%^xA%)2rE{I^h)$>+Y@fmGr~>PmGApmg07{^xDCAyb#*p8_DS(3{m2Y_=Fo}ZSTM*H5Z_oZ~!Q7@Gd=m z{kjJ#Sy$o)?kB)}a2gNSKsK=Raq+m0H92nZ^KBRe6Bd*=st! zceiUb$<@yJ|Bl`e;wrF(K-YGCC_eSc)#13>8YUtAqi=nTCHtGU`TE6FQaGoEYYEpI zoF0A26eDCXw`{9_GRA{}&n>txQ@C_bdP`xw?Pqenhh%-ged+1pD@SCeCBmP5ylbJT zAIW3Ikn}u2r{{+lm<(LQZ|sY7PX}4#zDBb7chJ)}bp5&cGks=eal?vtoJnMX91?!F;Uqt@vzse^y`M9l}h zkv0}E^LE|e#`e|Zd6`;Nls>zv92;3Dc|3OK+0wgjZ??!+9-c*ZD3#&7&^@mA@e2I( z{`ic*;GI10GWsAUn|^O2lv*bp)*fTI5gY21*>1G8Ggo(j6_D*(wAtcc9MV@6^xvvCDM}h)DySckxt2$mJ zgJR-vWjSeAGZT&Fr(fK-hQfo{THQ1CU*KHWczwOEPyg^^nuT7C8OXgeJb2(stZ84n zECEk`2~U2uK3*EaHEHkR>3JP_vH(2;!>nz2Yexr^$SGN1p%O{R3a+h>72~A#Nj`ga zZDXvM3x0P(6L37x+gThubkM44fo1@?e zojrj($0AqtalpUJLmgyAqjRA&{@~%m($l}?kZPpCqNAa4hw~6Tp2vsE2~%5pdq5x^ zP48PMbg(Nx!UUr3S#xfvsL)_#K>hq|f!TFt@QoQg90$a2caUWZFXu7^>;L-k<61;} z<8ZF-aZiwo9!QlT9kK-5@;GSC$OCvv=Q2Ib<3MB))NrBORg{t$FEZrG0gvEmb#>1W z_W<++57f?)1v8NlGSYN*0Eoh^QHT1$gEmO)>3jtM8&dSFtE+>KUV!%1AQU0?grSo9 z$eF@v%gsrPUUw6x{OAd}>qF_tC!c_+kb|7(LkJ>Wad~l?p;fK&5IRGiX=_sh zK!g`2)-eNynHAAkm1#hV8`zZm-hC?#Gv>GN-1&g)NQc*EwPEVwfD8T=1pojvv#|WT z9HHC|pafJs=bFgO*ntx4+Cf4W+(G<1H41u%#N6}v|wZ<49v_pfPaB{9KvLeJ0M|W!A%ZD z*%`}HNX5}u5&>ytTFA^QgbfYTh|~yzZ&+v{t=8FS*bUO%NFzz z5kd{3RgV=;vEVJ&loJ~&Dk^x`#N!st6rtha2rFJk1e1IbEz4JEu0hs)+B0u-gGA3yE{ z-s<&DTM}(}3nf^@hGCL%b|9C&n6PYr46>1DHYNDnpQIMrQ*^B9a1DRLNs+t<#7+gE zW7Mu{ieesmP@TC!?@>I&W&tfN662=Dz}(4%@)p3%J3E%ZGys7qFdFJYl-3pLINq?O zc*nrdPy(24hL9`MAIh63N9QiFvW$o0Ryc8dcARhqErx({kOS7Ga@x8IRb?&&oq))0 zCddLV3g|uHrY2^WZ46*B@BU@qhgmfXmSBHzK!uDH7>4{?1#)05;HNYLz^D^C3K4Qy zY68Rvv6+Cg2?-9?MmS>z;ea32m*<hkCF@%up86u8v$vBOt{g|teCP=8$;+DS6syg{FZpx*sZh;yc91IKpN8fA6#ZNaY zcCoW752A0>_(}MM#m9Gv;0QpoAgxM;eJ=9)C`5HUJ=mO*la8@2C?Okh8->`X)A!d5ayDJ1@Xpc z07j~IbzQeDN8TSDibiSg23T>VJ}oaVkK8X4iCj0G?Rx$YIu4-(Q-jb;Mm|B%dAQ;u z8zCVfNRmG&$YF$D*FoDJ2O`~;V1GEeL`CQMM+=Rbt-1xoL1Y1=4jpZy$b}6+t7B}z zvn>&zBO*42eNBkibk>F5S2)^Dxa`mk5_qnr7LA+%I-G&L9BA~q73*(bzt#k~p6P;5 z;m!UKv~*HV&eyy=*4f!v1aXFFTNyW4vV$dW+_=M9CQOB_U(UZb+V(#z0Ia@K9$E!~ z5J?8z@t}JVWkm**#w60Sz7o8654gLXsobCMZ%I9}*Um|QQns5I7`jk`TA!?pf&NuQ zMPdGk#}B?@GLrWh-j0WdhuFVf9n3rI-e3R`Hwk__0&185Td*K2x&q!oF0?z5W1|TR zui6vfmVO14UyCo{!{yP!hj2C(P}%{N7W_N~WGN7tMG8Wq+vGn3iZl)3P_+!eFzq(r z%b8!EALhTUy@ohew4i_F#hD`fwzkac>g)e8+$_?}2fPKQNLojS1_2TxN&*)SJ4@Fj|`4RRnW~MaH>>pwq|!dZr4JdK#VNoPRWGn@APz179CH7o0D$^dPSbnNRrfc(zISKN>t{E`&$-qXds~>(OB_WX>A|X?V0aOT$h)7U>k3fp5 z5E9JuGnFmV5Is_<0Vp3>%h^U^Eq1W1PG}&{fpFD@IH(m13k&O&-bRF>@!YoOn)9KL z7P$wc$OxgC0Eh`s*NSy70OS7a(87;kz5F_3xD-@XC8eb?shszMfoOD3;lXauF>ZCV zrLCi@i_n*5sum*fwuFm4#v5370O(A|T)FoRx%kQh+2nz-QY)l?J4MNj7+hfn+1Qr6 zckT8&t&AT5)`b`%8&KA2h2R9nslU&Ke-KR_jImraW|{;Y7GR_iHwNjrMf6{nNTW}I z+LY5S7Pt-HMZWX`WC{^J36vuMqqe{njvJX>gh92f4Q8^zQN)UT?YS!IKWkZQEyF(TteW4sR0Dc6`;&IqB+_@56GkJ$4aDw@H1S1%$vi>|0D4oNuVv5B*gZD z@OinOuW2EY!S;(gSjhk!6yPjX@cO(9o>A~xPXi6+Pu8+iT`wcj@RF5Mt z-;fY-20^Gu+4TMYU5xGkG>GCbB0?Mh0DprMB#{o5R;}W2$~6JVY=ml$i_4P=B8CJ( zr4up7*hC|6;daa^S2MJ8T0p*MdfV*@#V*r_$TvCE);Y?q6a}PKf z#S^w<(2NJj;*lAbjIgsfiwbsoW~ z0w)IXy)xb5iNT1iKlnS5ZUI(%CvJG-AOwTs`Sa&sD0Iweg2QECdE7sL{zT3Ka$-zn z5>ytrxW|9vT}}*5*%iGAd3xQ)!T&+LVlh9W z?R2g4Hu&}NH+c6e*p2ha-VDT9rT@+m^%f3JYEI7WgzjeWO}Fj&fjtag0U`Ym73=Qd z0ZvWMf39SUl76ICfF!HH6#~#QLP$Sk+aJ!i*-|5&A6nBKWr4OP8k_k(pb>Kc^NT@E4&;U4Cv$hX>m#hlTMdxUQmWxmO zf(~@Ks$?qtla+^hoH43-dg!>gxL|M~x&#H&Ym7=t@pQhtrM2}t_~-xiUBP(;2qV^i zoY#>`M=k^qfn2@*Ye_UZ6Vz!>iVPX}z#kA=;Z6@f3y9$|TLkZ74n_uOgUf-Ogc7oD zfS7XHZj64epLv3CK#O5k$t)reCEHD8z%6t_LQ}vkonCOhwqUO1m4@VSf*(5(CQv$a5dzDp3wyKvJ3jL7+9m6yI6DO95@S}?%Itb9g~&3f zj$}#XG<^G3<^jEx1ZZ@`dBaT$0lk%)psz|Iz-^ZZ0e>r+9XvfnWeo(6`cE-i)=q%0LqI@~ z1N;II>N*H-bin}-fz2@()q7z%foliD#*qjZ0`WyJGSj<4LJ5H30N(rv#|S5(1JQCX zT_vbK0zyJVL>(A%EOy2;msre!!2uTt>~6ztQ1q=Z1NpL*a2lH4EfFsBW{=jo*oi>A zQY7&B=ckA#_aLusUa>}U4q254YKYDEW-p5|E%N~n;R23?_5Gi_h$jXXm;DaBJGn%i zDXU`V1%xGL|Cp>^-4Z6$>g%&Q9ht+A-Qcny6uSpZ7V_%l%Nk%&W*E<5f?OQTFmrja zc?p#hS_nMAUm*jM)go)qhM6YwOG`!&{d%{Mx@`Mt<$T=L2S>ac5WyqmcG+OS?m&pd zGLAeCC;+7gb&Ezq#5&;`S~8Wdv*zXJufXsK@cAL_)CA0nMT3NY;2?kt4v7TB2czjt zmH~`8#Iz|gG0!C>eJJ<85s3>h>ij~4`(ajz`||Sp{~Q8F@stZ6c+wDb;!#m`!}M#| zmSrt?N%e>?hQvN#eVYE!s@ar(p&Jr^D98!CvnCJTly3B4FBAEKoeL8_fc21J`-nObjV=Ul(*wzztPj^h z<|Qp71H1|(c@g})7_L1z*k}*nntcE7go$PV0z?PXGnh2WZUY(;nEeCT2M6$y10I0$ zN_94khQ!kU1jx`rUP0lw)6AtFR75+BjOji(M6xJfUnKtp`XvDZ5Cd^F5C_kjJyE;f z3n=;&qM*6vpd}#86(mta4HH?wK21$~(iDPB2mHv$@UN)g2Zab{ibPf5n-;(_q6gBI z0d|HA_&_|fNI_>_&}{F(aem&6pB4uC!(7X08x`mUxi*)bkOUHNAw`o1;8Pd|ZK3x& z;ss(L#d2+W+a3vluw)tJ*?=FX!4007nHhK5?flP{Y+!yz14x$D&ZV;;6-4+5rEa9) zrA5ITUb>!+P2Ie8O9%3C|GgZB(}=!$g{!Ejm}+tfjzW~6bD40O=m)UocRG;VK6tp` zCH&Kp66w~Uf7qba1*VmhuIIIv%zu-Ty%>YhXsw-{98cm}M&Q^yhRf}k!J7SFj~86t z`;dV{j0e)B08QKB^YeOT)+_FBEa;Y0Wmg(u`^W8tVs2*p1@y5`Dq?@x?MhyC9Q zx!*!UJSI$2K_z2R$RPyyosppjnIx)Rh7fOegWeH1cMu$S!27*U`Y*X2d zEU_daMn;$5JrqMh+3`;+eW^I$_n3?oZ7(MU?fenJffj+ft~kEqX%8F;DJjI(RGc4- z0a}7+!#!iqjK0^ZG_rNx3ZSAjpZri zbdZ`NG+l61v;`TANT)nvs>N}OIBQhZBeo~IZ?oZKwh&x+FGwe$NAgNF+TrY@JS~ok z3U)7F6Q(?(^7}kaPW6IZX(3DU$;T`Z*nm^J()-izZ&C3TMlUXiKWDb>{R8`w*Z|x6hB@~@QtCl{fHgK?y3pOq$qNHWVJ{M+F;6JrNFExaM>LbI7 zKZV=~;8RXdzMy-V?x`YrRtE_Ec31>>QfixHk?}gera}vPtv`EuzSPiwRyZds%Qw)|0yKi= zH7L68D5yDF2!=~G#`#5AZ*0p5+s;xZh;+*yJnz&9`7_4I(u^s3X<>liIoCxE?<==$N^BAKoq4?2oGw!Hc?h%RV?4_Ra2?fKrXr zpH>$;H!iR`i$9?wHP77a__mp%W7!mCb3M*zi=5RARsL6=`bSp{4xpWRSC#lLMfsM} z(RYn|MKM1lBg6fZzVNu&E&P1ns%CrI-IM&UsGoDazeqp+or1*U<+g_V4C;Ms_jYU& zhdeM;qV>?6Lg)3K*cl3r9a3J&5BqyQ8+o)PO4GIM^Lsd4riq{Um|nAr)y|-XnTnyT ziB`>Cbml91G8C&ki?g~R=jA&K!? zUA+T3YGfcIbaZi8t>swnD^pT@l*1rqb#fm6Kj_@tf`}#pK!F+~P5TKAr)AHP5b?7#(x|+WC9;GK_-! z-hQ4?OW=UIu;NR!8u5$l8?3fI#73`a<~ED)oDw}bq!fIZha2nm{d@#86OTBhwU;ZI zD&l@f#x5s{D54wX&03sZ<&CwGwwikHP-HWwsVMy-Xsaxa81&K$zt_daj47lC_WY|9 zNuT`iW*ItBDNbjkAP?HC`-UQp%e&w~0 z5jmH^XTHDdBrURZPJAr5r0I%w%^fa(d&}^hHDIUB9r-4{k9W{z&JXIJq|o_b)I@&$ zw#1kf_j;{epS&+oW9+*2wpmnb2fb#-;bVijO{i)1_LZ zt!B_|a;(p<=>$%tM{$j_XF@Vtj*x#l{%W~iAbN138ZNATPv)?c$ zZia@etI6q0jM~>TLh7jf&RfOz8`RfyRi=KLWV$~RZElV&O4vvrnl>5p`YMVG>Htj}wRT`K%)N<&U zOUvlzKY`d}bp|HYW?7A$hY7wnqAv&(dEhQ0(p~bkia=rPX|Hp8zZqUWnu&JP=x{mMO|oF=_#zl|Dw%D&9`SLS9k9UiGU}z(6Q_@ED1uMrydYLBxCQZzA^NQ9Qm(BxoZXFN3G zT{R_q%k&%N7{T!NZ@Zb;FzZPRy7a%8%^-B$yC%1t)N1z$FCHYug>Ah##dAFI-%Z&BAa^$)=_6(oXMG;o5ma5p7s$A(!vUcm5 z>QwLbDSpw_QA}1Yx;*<~(gDd|VY2$eRmB8UGpYMoN9~pNLAQ^NzO3r7>c4w6&gsQt z_J|?3y|{TV+g3r5V*0|JCURr4DcP#BtN-FC>E)*aEK#&)A|BesVOJG;y#Nj_V z`PfqKPPe_x5T1T~SQpht<5WcDiiI*;8`Q0gTC3j?ff_A?L=oxFRjD=An2naQBDZGG z*VU~?IQ?e}CeMz%wDnxJHaHcQZsLi1>89LrRmAG%jiT}PDVm;|r916Ewo9*^XHpdr zOZnAOALt>3t)qzc3yL4(W`clbHtKnA3eFcWPdwNU!Tu52K_SJxK}xRI`daeIbXth zT2f@*!LT5Xv&%AH^;DBSX;eq@lY1v7{Bw)t_b+NhTEqE!H=VsRD)ng?WNAjP16GNf z_Qo!n6{(FJ@5eVU0t=-iXsqNOzYEUx#KTdktLGrm1VJN&Pzx(viXEj+IL*SQxxi(P8eaIF}Yx%JyGcj|Ef8jLk)~eh71F4O*l-H-fh8^8RQeGOzec-$5GLBys z^7>m%^pN}q6~E`A$u{6EBW@auVr*W%*ZWj$r~3#3S6u)E@WX)1CF8^Y1L{ehQGE_` zPun);7eh%xYdlLsupA>dDn6sXo{sMipgN3~>@oB>ayC}e@XXGP`>VZQ8DUn}d#n;j zq!@XnApdRoU|?lC&nsF7CdH)1UuufFl8U97+(A%|hytT-5q9tIxpp z)W;PGB%z^?MBh0LLX9D)BCYD`b#CJ8`()zgdP4NsM7c>!Y;QhCF7xruRv6j!H{exA z25hiKl{d&tvYBF27|OjT=JVMl4&iUo+?@@u)DB(xR$7J
0*YUKNMXm*V_5;D9u7@Wn$u?w70YT)$GJm%9H>#C8ih)56kQ$73G+ zCE7G)LVxrW-6%W-Pbp$Ordvd65mz-arz;v?1 znwvQ1vtP>}8n)U(VKOzU)6x)oIVSbKFD0O-2S_*n?0z?`p*fyuLO^8hoX=?wwQXi6 zonV*fmM~S(ST*lp7Bp`RI=#Rqzgs;1Wnb-~V%S?&6e>M7+Xm?!^kx<&Qt|hMlkV!Q zjF`zS`R*J+o>W?7nOQ>`F4#^lMO}`sHa*^bmcXsE8Pud4`^9RTz;@kZqn&(TC0X^3 zpKnOn|Mj@eo}3nU=qaIkcXzwI&e`Qs{K?f%f zlrfFUsAJz4nJ{c}YAo{?^X@M#B}x0I4@gk_&X*xM`9@O^LtplKt|5~ z?J5s9-w*~Vz(^Mq;yEm&kv-U2->wbT(3=>;86xdW7fg3&t_*d(0j-BW2N-S)XBZT) zYL|EU`YdjKV|J;Dq*ORM@lN=5K6d}2`5`&?8L3HN(TwYq6V}rhPGa0C=W82G$De8q zp)wjxymTrXJ#HoOe;Oyn*r0FH#PLANozKg1bl?vq4i)9qDX%EZaZ)FTxervDXF1In z1=+hc#EibNUtjXZS_Bi4lVcvG{l;F;d@(0)AunE=dj8G%bM>wF2J~lxRi5z!Wz0Ro z6gSH;xhRAOkoO}WZjlqJjD%+6KTg`Kr}WA3 z?&q`kZfmh~arLuXBEdDqnth&Td*n8 zwJ};UGJTmr6m+7Y(-JbDELVq)vHPW6ZSki;ZbAE>#P$`>o;w6WZ`DcEgkGjAKAlRN z*mzTHfmM&XeWmu2Gjs%3Utc^j&GanrQc0mLXc8MHW_#W~rqJe|X!FgzyT40r zB0twAJ}@<2u6gwuL)4Q%8;gzi)CYka+v*D{RhF3ge>B+yw+uC14ziEZq*vghuhd>> zjou>!zUg!cal8J`H*`6qBZK^06TRP27Tdkcr-9z@z=+g^-|FohIRbHcg%% z^eiI7pz|u(h-*ZH?;_^lBX7~PV%=jsG9JY{{+pS#$yZ2JD{DJ)wG4LKn6=lkJC`lq z!v8v&Vt*lIg!g)qd?b)2$#W2_03J;`Le8 z?J3K4Q3QB_+NP{%t_tl4lFv%9+Kr-N@~T9og^l>+YWxfUT>?Lk7r&K zt~M%3`%v=YZ4HV0wI+MMP+{uUR$UTS=09IY>O-iXE4ey^4^*eszjBVzuQo3zd&!QY zp@>?)GZAag;aB!s?M~Q}y}388qu(5Pi;&fL;#dvxY!5}X9#uy9V+WO2y-33KMmKDK z^qhI2=2B&}{uRNVR33Mk9$Qz;gH?e){sTX-R`f}dmCv(Y$_F{gec&?aHRG15_o}K; z*yMH2k8DbT8J$gu7`~#!1RNP5gm7N<%P;r3_kJ`bBzXPtxs#B788L*o zSdofXPkzdE4tmGP=x4$$P8!MI8uC%;R`g8)uSxa|lWL<#iKsI4_Y}fuWsZdkd3fjj z($=-F>L0uco`*5`Fbl^1Ug$@uMcgvZh=Pb1)q}iGIj>~N4KP}T78-IMc+7h@Q;F@x zGjZS2Fn@h|sm!7NbLZ45wp3Lb&Tvt*0mly)7734mXEi^Av)9?9%sYH@? z6e(WPy*!bMe~Y?Z|CNc`*T#ac2URSuT8A&fG|Yi7x%pc#KC*d`r(7O2H^7+!x{_n|Fe_s)}ofD3gj=kPo@GfI)g{fq)SK_mmuN$f_+N8E%4O_gtC~0N%9(5RrGO9t;kFt3or?)y!ZY}MF0M}EbyR=tg?^d!>|yMJ zz+d)bZVZfoH-k}U26yGCE7l>oe;o}?;V|Kn?McC<#o>Hm)$Prf@$Y5#WoyvoNw&4krPc-NMQ8Q*ZLaDWt+mx7oS7N+>u5s#vY1pu z*;-4GE#GS^^|;oQ!(_@hLQi&OlkuL%w^&&0m#<&He&P??`Udk$0+C5&u0q<^E|*-- zf;7)rDZO3a3K*W2SYeA+#M?&m``9I3e%g?!Kp8Py4U%nn+I&hkmGpOZe~)eB=q#zq z;~d&FjVda6Q*YCD;E0L!SMMvWb)#-U{XEq5dCz#0@Y# zzE8c{#W_)qwqhRI4n!b-&W8!irz6o@am;Wz(?NP6B8h(Kve5Pg5C7}DUWpYqIZW#9 z8PmR!iSAq8kyCsiOu99%hjiCf*uQf5<@KGp>c}0wUXjpp0F37SeKA!k0&nkN>`ax} zbf@xY)(>jOIL}_|T~ z=G-Or+cecD1KAZ6z92#@Fwavk&dcjYSAx*y#!FG5lMOT1b||JfnG&^ujJzI<-ECWL zO%`tJrsq1uLg79FbY^7=`b_}E`OU^ML(Ol$tg7i#*^ z$YCgvj`1(mFF#`D7w)V`H$#!}NFDU3Y*?vQA!~?*GRG6>p>u&cl4jN~1rv-Z<#!h6&dS-nA2vV>iEzQ`-v(6q2ZlUO+yfTR$SjT-lKAvj4Dj zhEH??xDJ5q#ZCa8LIClCu1R)4C=bC(qnCEbb7lZ5rUNjJ4WpNU1(Sff3XIyy%NcDh zNzVXilO14n_8bIYVpUZ{5@PJ1a~@(%!O*H4czI%>&_2xclhSHK)2MbqP7e73Uaq^&-7=nby&R*uLbC6A!F)#Mah!j- zufQxm$Ok|UcH|Fm%IsHZN>?Hh$%VtENY>a8{9+J1>JXk=i2ggeV`pFoh@<*EImH3< zunOOej;Px~OuuY~c7B&Dr)BUo%b}d9oT>W`abl3)Pw|gwjEZR-H~CE!Y9#R9=)ZPl zIkQ}5e_qj;@!cxJqO`>PNQUT2(Iwg~)m;JbZgm5JbMez*I1d@(I4lX~c;jKLiB z{T5hs)!&vde)$yBXT;;YI+n$0@$28Pp025RgPl;}vB6ig%a(L!t@)7aYB_8g#3+PqFh)0DMY%<8rnYI#xLEw6>uF$Fw)!n>kp%_qXA?T1XfV{w$x&<6E~#>Svea>4Zt&{uSHy5dMbG zan`e%-Hdo!$*+(|4fArzm@jk`uZwe6q0ui{sF*;pysR=#mF z^ACcLXDqM6hQL-AUsm&Nn{QV31oH{Q(KDjAU4gf--J|~u=jG8Mc09E?o9s$+AN~7A z(1#QzdJdEOHv))7P@ei3zI%{nRXB+)ib;aC7%E!#BCqwn#Ya98I4uqJGR3w~i+o<0 zrQaDm;%)sh0#yw6-b$awlYdLZ^sjMaVaI-EIXmz{L+5�qx~ik1hIyx34MrGbm-3 zloL)vDvZ#ino+`dGLELnW?9+(xD*Cxh;fo*-9E?&Zs1~7$$#qCJ16Ndo9uMSc|b6d zqm}*B!kXmdJ$`%dPzd=%IALLE$oVQ~o4%g;(GbfP%L}%=;u#zA%_Wf4nB-|J}G*d_LjaYjpAH9ve~KhdKRl!9MEQa9-n6A?i(x zhX+Q5>}7Y&&-7;Tl=4k8(K8u^qHGojoHUz~!q@Kc;-_Kk#TRY_5ni zww?P(J*xJHqvNm=Z`9#ocGEOkpvQ_{ysw^3*|XX*jp5iCX-6wAv|dac3Y38G)_i=` z^T7}P8qd4c2b2!hJ8I>3uvP^==lDGDxWA@aEqXc4H@$MWa4gz^TRQ)@_$zKPLG}{z zA@tF>Qq>M%j?v5Nyp&MTx>TpUcJ7wo!K9jzZ`g*4?Zr9Hi*nU01<&h|lv<|~Xqbn} zMf6+6-EZij@d z6DJ0;#|v@?D!@pJZQPz$;f>gh}PF;8mHG?KEkc$VEUus zORn)J%EpkQ3Bk1={14;BsK$Dv<@8k@=zb~rP6no$TeI05DU1!~sXnfEfR`FQC_cx0 z&tb!U`nkC3vUn-qsoK}p^g;TCyq{}koGu!xB=0^}!r7c)co}}EnU(6r&hw0huN681 zt=gTxQg4myHaQswc5@%dN*l$-yJ($ZHgsY$o+hHM#r=Fl;qY$h^KBiKGVAovnxcTq z>DphdWhHTy4wa6+L!ix2NEf~L@@ph6`t40>4*5v)T74Y5-YC`&2#*mo4Jo>~2DWW> zA6s{B`u$ws7MEcd{1ekq=aWPqmE_t{H*9O<7;yjVO7^_vxDKPyhmItz$ya_9Qm=SA zMujgJ(@GdaAN%z^5gK@=`jH|H_xnVZshrZ)K#Nv#!CW$hH;lIXzA8!;k%6CUWIHtu z$+=U>Yl?=(Z3As0o4fT7(1;!_+3BbyKDD{Z^F{Gl1bO2B)7x7{#T7N{x-m$Cbx4!o z5L|-0lc2#G4esvlPH+$I?!n#NJy_%JH15t_TpJOlA5xRZgL13EM%!OOIm4;3)?b_Amcx}1cepW<;-u`9tm9SEIeF z&t|d}cvPqllit#iOJRw&8xSdhC%}U713M4=Jr}?EaQ|YiGh~@<;4$a`@LnOn=Y2G@ zU(OJ{q6?A&+>P~JhL746t2Poi{@~UU2n=4Aq|D%9e2lGjV0sxHuZV=e1Z8%%H|9lt z^g<{Z;Iqf25jMllkj~Y&ylmCb)R18feBY*r7z;z7FD*8b6n}w{Hk3%Rm<@7Q7BA)5 z33!c>iR^RBEbEe2e^6b3Q|IUfRvAvo1K$8`7BW|i&2w*1iLgOwvfsfUMGXx{J(#e% z&uSK>Byl{{^9gTphz5{34XdPa^sv>EyY?Id8`I^)(=XK8oEDCdcyZsf7*?&1t!>O*%yYMB00!E-a9v^> z%A-*(K6;Ak^->2uM|=7=7W;0Um|^c~GnAlJCQP*-`y`>l<>f3eT@R)^4TPkXu?p-O zzGdw)Ed2!o`n@t55C!=+#$mivRk71sxiIQcf~(M*jmJ=Ux1#qG3rNv5-h#)Pg29f%ONpU?R~pv zxnSGzVA1E~#sa67$hvIohcEZX;^h=d$s}mL$7wWE9{;)F>G5TnjeO%Sr0Ua*yd4 zi2NGw;ZAnim8ZD-T64xH&=fB2W&$rM^yY=o#qun(l~Qv4kFL{tI2grOvQhL1Ss8&5 z6z&3-@Nyk3P!<{9sfVif=eKZ$kuy?7eEE3Z1d)9^0??=G&vsYJ*6zp0K2x7-irp4C zBHiNGtH@KU4p{6#IBw-kTJLlED2Kz}SSf`q}W z*g#owq@3fqo6$pdwt5^8Y%T-SpJtKr!1krgNNF%E&(%TCJV4 zYC;$_A%iaza4**zXUcfu7Q)X&)XEMs?C^r@xd3QZ>d?f$EZXc;EQvec(3zn7d71Py zGz+cOKw$lm!nC~dfC$}@gYtYI3nfjg>mtAF`$Vj%<9H4B+(Nqau<5+W|8r(zG6bXe`^oE$j=!&lqdxWz>{qnpcl%D{q+>1y%U*8y3ngED zV)BwH6njU|RQzYvI1l;r5zCb9l;uUlrg!&>vFRT&%MU^jSNGxm9F-gp38_QUUcZTo zMI?ir>|MU6OVH7%t6j z_SH#hXz`gX*M%#GJbHSX@PeZy8oKtu>1zJlxU+i?*C3x}w`HL*JF%RaZhSYNe^}5W ziNRbxFDXA%;-ZC-S`CRZ4UZkz_@e=6fG;WzyncRkwAq6no&X8~JhB7q>i}rBncBkh z#8@91)>aP)xEcpF@tF?kM)R_j&3n~-=due3%t7QUcWv>ldWQ}}@A)8#yD40Iva1Kz zIp>6N@8~!eseuGr7VEinM)~@AD)KfF_29uo@yX;RnaQ2}s)$8^fVb~@>tH)t(R*np?Dy|cONQ1j%oCF@a_+1pk&3+^M&nl&X`RB@tPD}Nloj)tY zSm?+IAA$O!>=wJL1rsYu6VYatUzzj?^puo(IhXA`j9Z|yS=7=DQv<9s10gWC4UbW) zY@o9a{@aB+J=?1RxJLHaG%q7t_If4kncuRn5FILyhJT>lpIp&(PgBkIxBR4MQeqT| z|13C}CTSoo&pvk!I1{lib236I1|{$P-UjfA>(lqvkbZQ}`dysFQUn(3COi+!Iyj`0W zPh(HY9`#@QLf7cIG z4PNVLXx#4=mI8{@iL{d!#Uej?tBDVLPbq77tG=|5IenTBbT`foNwpWEpB4J}T$fToZ2e$2t@@3*Kp$;_38R zTAX5jOIvN!=`&mK5s*H(8vT$Y&vaD+GC^~W?7n~yuZTN!^;)uLjSEK9i~2GkZ+fWQ;j zfL^B>v`L!EP-2R}Wgm6{}%iVA*LCVv9)}C z;>y2(lXvtjr$)|guC>FDPY=EF(sjv$pAY23a;)Q^S;;5aDw>0*X3T*^#U9c_n( z{wr`X2cpa4N=K6kH$4x2(FeW|F7N7^?~YsNp=;kUhfnLxe@+`I0yE-00>(t%uF{y~ z@W%PDwhS@5(+{b(_{%pW&ih5*A4$^NqwBr91QRxrMRj`@TBvah8>IaX#LY_Q_Ur=P z#2|k)Z;#&ylkF4c?XaaKn|0;*WTZv*g%!g@Lb0_RmSQj%!f=T8v$)YxZ==o9>ZO>J zNoo7mj#UcyH6Q$fPm{S-RgQUj*K&NyfOkKJ?VUh(t7<(y2H1KgmZ_`yo@&6}0WPBm z{E|07Mg+oB`T@@nfT>27r4c<{VWkq1w(ky18rkoadArZZ-7_$jXS_~Azq3tCefY?~ zSMxgC{LKD~TgHd8B_$dF^a9=#H&)RDlfcnWXf%rQ1rzYD*0yLc?};0m-@=6u=#_CU z@(%&<3iu@vJ&6K<_dc`Y4?Ko+g?Tro*3S`|4Qbb)bHsN#1HM-=%-aB|**lN|-upZH z4mkLbjIqKbq2LmD8{}F^QZit(GBW*hB~vgTVRT|ck=&xRzlpo?jBDt};ow3d9s@v_ z`=xql)n=uLJZ0^B6C zVk`Nc0l0<0N1?vf`@@pMtq}c~&RYvvn=~DVa23qV4-uG#ukUxj&g6L?w2XsPB0BkWd z{S!C#kJ3911HmpEQH(%ykBS(zD6icaSLPsw@uB08m}oV(CBgjx z?s}=q>VS{RZT}e<`KI~vb0cWl@(plQLWIG2tMSwkrHMe`UA)mx3<2*aJ0$Jj4FhT- z=YUfnA_e~(Oi-GPI2C`386_s`xDw!HmL0f$?h@Nk_zy#&JCN;KvKH%Tb$tcDb;L`3xlDw1%yRe!-h1TNXTP zu9Jubm-7BsH(oZt!~*gjC&oxTQOR}FNk3TjRdjKG14)8t4k`H&=y^28CR?Q48^YG?Wt42f z0N0r3rd@yx01PB_njzCyIOho)0@t}|a6$tOz)Qk-QBv7BbNZ9K0DH*r#a~U;gzhkn zq`$XL>~-%Em1>!TH!wouUZZyMont|Vf6iW*zcl8>F$egaOnYJ4qS>GA^H6Poxt-dR zx5Om>pf*_sqtOYuUjzL*mJ2ox`|_*~DIXl+#`p&o|f_lRmc-?rPy%uIN4CKYs3OR^k= zj5U7!aqYw;4Ym`INRk}C#WBT2Z%`c}F|+!ZpkbG+z0u`P9`)%g7tAaze6B$p;nWAY zX<_;pyRB(qWTw;qgOFk{NLi_^M?oKqo5O!~ZyLEovyy=+=CF^}lmx{KHrGa*Sf7}Y z-*206*#1LB=wN}u&i&ZmZ9ThbHGf!|5o%UST&7*xJP5W^T!Ij46}$Mfb;8Dero@<) zlKnouWht_AV^bHyt#QK^xecxvb>7>DjyCixe#0G2XX zNqfx=?^=i~KsXMWh+&!K2V$fqxPT=AF0FGA>ualykFZ&6b=d>6x=B#1V zn`~+FpT`0RikKXiQV_I~`&WsQC6+o=V#4tLTMM9bYPc06+WyCJeAGm#fg#3M8E!iC z@!Itn1i~Tw?;&i+;mK zZL_bgoh-Q<8gxj`;s*N*QiX&bvBZnfi?4c3q$w2H)6Pp(chHF|DMf;xia#QN^dpad zVm5~3eqrYewyz30kV36N?%(OHO`UVf{e3UXqI!7}{eTY6tqE^;=fW4$Bi6^YRN7oq z`Z{eqD1Brk;%bC>rYuL5_6cZ1${8A4+MhVLdUnS6ft53P-}`fsLu>_8c5m>qi47^S z<$prg%IkWx($W}=phK1^z*?kAif>z=6>PjQqy=w(olOEv-&iY7v_@TMrex3GV3b5y z>g(<3*E5%i^BmDo_*V&!qBOnK_7%DI zkN2dK^y#k7s4DfrIjOD|_*w&XNKh+1x!9YNd;q%Ea<=#{RE9wt z?>rwvvs8=OhV~9Wg1>QFAvKDLt!a=sC>P;3XyOj$+E4W3m=QXO^g85`uqY!^hq7TS zuSm%ja5!+XBwT-B&UbQbru zuU?P1uq>%7TcOuR`)-XG(*47@fs@`SN1#+|m=Ag6BO)2hQxR;HK{Fs~R@|Qm0~*o} zcTq`_$V*dvHA*`EX||dDIs|cRjNXiqn92m;V*ka`xbJU_{+mUGH|wVUg%d8f-Xk4Z zpo*nb$LlMcL0PeR{fdXxdTnIk4_3*o+-EYtc$^~|P}>cskNJ!jJ|5*ub#ydx&K`BM z7hGCC4o)_YkB^?g`VQ=xg5LH`!KbCx{k5Ec&ZmSOhppwORgGuf`sWguJXIWCbK-Z# z?hvEQHR*Zxu_V|_PsI7KYDF~~jKz2E+{sT?z+#sEi5|kL>A1s3DZo=Ge51Ol%uF{G zaN{e5ASzn7!=Q7&{n6B+DtcksAdl@)F7>0Z&}=xB1Buz>T#A zA_VPgD+eL&YxJ4cWk`vpqDyozVv%AHmEvf$<{e?&>6)s&o2mY`!CMYF5KQySC3->m z@6>pq_S*Eo0Nv9{XHr_l;XlX_1bMS{Y!JxdZjuJdV~;C>lpClVKIgpuzBJ~mDIVt% zqvgFtO}U*KO0G`f*i}X?6p7ot7mfFYf=UrWxlO1c$~<}fK4DXrAJ#{)1!8V5#;Q7$ zxw@TX|FcQKfZ-0Nn!$D5{y3Ay=|8yeA^;EjD=_9^~{Wyn+)bzmkd)d)ekT8kX;7 zhp#c}ZdS$I)rCVBrdu5gfEd9UukmizmWX!|u3BD2mlT}+bVe6eqxrS|$BYx_BYk0fktgX$z$N%AiGiey z3m%e1LaJ%g`hUTx*Nq+{z~FHJ;Mg)>e@=p52e3u;Zu>Ol7t1lD#q3_tAq60z32+Dt ze}=XC!Lxo4AT2rv3x>N>Sr#TfrZ_!0mdNf3>}LMpT*xpl6AGu$BaqHYKT*HJwLkbJ zh#^#f!>gI0)2%h_tBNpiYmI-;5{3==+oh%cx4u!uVPJrjh6~^8ui+SPmd6HuaW2TL zalJJCn*WTtdg5ZGAvDq$w0_u;Qna_c(0{v~ai3MKt8sZwp3&8fDV59;6b7|(-wX5o zRl4`39SvVdyms5;rZ8G;=LVY&tg0cNO`C}l8h)v15~jQKi!3Q z+u>WIA&uCLWP z-Pygpl&v?t*W(bhQ;uz^{L>jAN`CfP+#3OVb2y@F*brL=lN(tlI4b`sFL6U5|D>={sb}nKpU@5Q3Tz^niDu#W$re+joRTOUl#A z3WKbMcaG!L>z(aHyhOY$%$UeCN>LzvaNS#bNZYWIe_8zrKpf$HO6-Tt;sCq`R8rmZ zt6We?pch*&{@v{wP?;M8oUZp6lJ`vN$7fs(eyH}XJ}0+dJ@9Am0Ri4QSzPE)f(TBU zTRdW8h#WLVHH)`mBlqLC~FRmKx?NLW#2g*Pi<7c#R|0ATHohYvYGW( z1X#BKLnU(FA407J&M=P$B8&+WB2tAC)m5Nw!gRJ`GvZ)G?V3zG7jm^20XD=9iy8wT zHQ0)=bfNJDxaVPrxY=NZb~`B^I#T#ZQQwNdpNETyzo0qNe(cKoF;i;qJYzT8Q9ek+ zmxY{i$$LVD!tEz=OOOCCB%KS4)RR>}GB7~M%xoV;rt2#VFl4z$uA&x;C)$rCBlt1n)+ZLYfi`Y2)Agh z^~9AH*{~#j{hsJDCa3FMTjADUfL42#v0k?|NnkuwKpf0eXC7mP{({g zU9oQTUUT$1J>+c8F0q5qo-H8WeEm4!799F@-S6h%g7B*%M(m$F-Nx~-D~ z8jk**{x5@tGhsC3GP!oo!MgTL!@S%mkO2e!Gn)V<08#?{EF%4dGZ27aNX8)I$(ukH zfOtN=yg+?V4wMNzIsh_>{iAjPTGZs4NI(Rx1z5ZLf)gxYBHQfB@BUUk+sC8!f=ZCP zkvu>CH0b6fpGwMJM)EKUNepw244>jNA0qOjVf*6-J_b;g)t3IrZwwItPLk(Ypn+zM zRMn6Z{@I2De)I4A`D<-bwtysMAkpT)uKgd<5DGesMAM++-KPN~6=#vOpv^~NF!aA~ z8z@McL#IZL1GS;|=l>He3N@67Jf}wAz=vo-1h~9j>NL%v+l9vhk{sUs+!av4#eQStoY(HcR-r;jCKf`MpClB!REpy%ov>jnU3JOEaO{d>E{%~bAZiY4lTo? z-ZlI|LUx>91<0p_{nc`J5CM>$@Gtg$9wgs24uGd9%(5tcI;dQU0(#1D8aCrLAvqvp zwFv+w0ENvtKWbIfWRvmJuzS6oXmm9@T$WOpviu26{PzW1elARUBR+2cU$JI{3y`4d z$hzI(Spme$_PaD58P(x>Jvb78E5I7Gnc43=W#eaHw~{=X1LQ$5vaF#2Amem^G*~Q` z2?GS`n@xs$wg0}`XHl9$rZ5D4d=qV@Tj$6;o|*g+E4q{+*@z;D0=Z%>ViIGrk;UQG zH)RcnXmq}FR$veu%E7Gd-W!?aH{Uzfwjin;muib7!PrTA^TJvHA3LsW>qCwDZOcR) z1x|MpRe&)OCoElL19n1Z#OGRzTO3gEwzT^`tP`*CmbGW+WapBBp=)iop!)2j;%GPL zkVQn5+F%R$!Ln3}tjoj!Gv3$A61cbgf? z{Y-l=(<9m7ULIM9gf&7A?%)JrLG3P7=L~>5aX#up`Wz< zo*{UY{>&TKv76M*Z;URfu~rh%48)_8-q^FQlt?cM;#vqZc)IQ< zUXe+NBYA09)yPjq@@?W zJS(%+nKq)phAB&*(CGXI5@kfBxPB{?<9f1#-M{}Yc@^kz*yz9HRi%*KSAVsY6FByB z(cd4vSBng)@8-LFTxDe-_VbK|K9Mg<6kU2lqr0bewVtG3<3s_=C_pPB`5WxK1h4^e z&}e7QXoB{X_-ygTH&><`_|_jDWe9svSWhQAcZr)SA~N@Co_M1n|4>W?x`=`3YbUklp;ZwFbAB|b41U!D`p~2Z~2~vJI zwxOv`ocsI^gp7UP25{ZCNV{++YQ@3xBKH08FA7#J-lcp5x7p=>5aTD`Lg$c7vi><= z9`j9AWqVlZ|14*+^M^}r-nicQ^jWU}BQiGPHcmO3(>@HpkHqanFY(DSdh(s;yeg+f z=jX_^u#o>FzM@X;+3#v_=MnKR>?$LUnT+d@Qmu|wI;H4S4r{)7W3YUpsXSX8weQ4= z-AfdSMZy!Jhj{+1Avo-h<=7`-X~A5c*$gE8bHHK>c|G#E?dUyE=jWKrYLTLch3+O0 zs8ZkABx?!3lywR?%T5@G#y@Gz{|<3?g%zY2AoTOe9KxESc<%NP{<2;x>)V6?{nV z+*EPqK-O%JAbF@H>&c2Rgyg9VIgcS!@kpKk$d8m_%J;wLnn_0`{=N&D1~O>cM(iWf zQGv`{E#6zs`Nl&WL+b{Ncdrp+&p7F+kJF>3wR>gcP%7w zB1`>OH+e;DOZ4e^aiqoDUA2Xli%0c=nTEdot2uKJ+4;*-7(;MLFHj46i-xBsnXnvE(@ zb4N)0Eyc(0@|ZP7o?3eVN_F+4u2zK75+0Nxo>_!hYdW!Ju>uLA(n4@|VgRC@w7jv& zFsmv$1%(l*z7u76kf@T#yicj|S2A2pRl3rN?VK*+3R4+>uum5qyG;9(Wux7Bepb11 z&lB1tY??z79jx8vtG#3s{kkwSpEDlPF`CEdrv6c7)P%0pAztSQ^X@?Z89+04ns2

8$+XP=l#U|mr)63y?Tn+Jtb=m4PNJN;TY?N?g<2; zo*`zSMMqnX>GfQXlFS?$(kFr6Q!RHw&-5lAltBi?GYLY_g^~9~9*T-_)`c(0xoL<| z1hQUYr7*o>2oyr16byEnmmX3{&S(9pD#|u@k^!QQWYtwqCz#+Q0Cd=_NP`=1ILOF> zAPco|J=X;vyhBR=GQGapTHNA>*Gch!>HnryBX@BCoz(9%+ z5F)F1EUnIOoQ^#6_9rWyUkhE(kx!GfQe^{e9d0{}PzgnlD{uPdbbO9oJw1KubgZK~Y9 zV0Fi0@i+4(Cf>sBsqQ(fp*}!MJIEM95~T6>7BBLjbK@EyfmW~M*f%YUGZB? zj4FB7#{-$r8Ni_xs}+JItO8+hq(XU0_h=4RF5S2Pk}iSlMW#3fi{kTj=9~w;*`Gwo z{jTM<1YhtnIW&I$)~Jc7%4o zQTDx?@zwrmlnU-#5sf&5$)Dr}A8L{_Q?PH&D}HIMav?1)UZlkjKv|I&9=SpVOZ6jd z$~+f9iBl+pkAZWO_Nv_06)|CbA9olo{5l^Pg=tCfp1Sr=^@? zzfz3AR)PNcS5A2{1ihtSMp9Z?P3)0%m}Ui?J4P5fXp@5|${A14TL}Qzu6C%ma1V4 zyOl422S}qW1E)Rcw)OAi5BSJu08Ly)Pe%~tH2bI8{v0D(?U&hltLxQ`%=T=Y3 zP^yS>E7Ufu(2t~}4$9|E8_6uPuG&qr+NXXk%8#iRmv)Z}3XzKBU69z5tGl+sdQUq- zW>g9H)H>HIAGJN5DU3ygsS-8DQLNkYpsCZl)UzXEm-%;=6bXTj24%hLZErv@WBQBR z`rJdX0%%5TARpVTi%TW84asX1KBZjT{23%`Z zqHF^B#b>ahx0kCP5^KBJb=t!;zCXxzV%Gz9xV_!@pF*QP?8mF*$!f!QZuyeC{{!q~ z91Y%CLRa%!kh40+gnUrytyBLO*x_?ycAU;C1S1EfKvigk&vb!U^mzpWk^2Qb{mZ|a?lzwyrUcQVoeRvzfWplv zB#cxiaqU-@PUvT3Kt1l`$km}*95qhkJ|WZGU!x~*xZ$&KsJ-jWH_XD`;}8%T>0kAf zANZ>|U2iN?2lC2#zU>){h(FH?4ThpZJMIBs{nr6eH=x~g0wflF2fk}Gs0%={0Qmei zKH8R!A|@pJ)wun3B_L!@EBrDA1a@T=tSWO9A!*e}XW2Zq$XV#+=LxD6%MygULWH^R zu~cgZ*zEHItV07AcgI)J!q?I@Ykk``-~LFszJ>x%!v}+lhy|dvqUt~lb*W&w4Fv0c zLrkTB@v#PUBY>cVF>k(E?3T})!scyYFhf6kOkY^NTay2>Z5Gme!kl{b6zt<&Y%)2$ zE)KiUjIawi*9FBqk4=VQmALxv?$ufudb>)H{|EDtb(cN|l1iPd{SIo^Hr%iCEOA`O6`?KWsqhkEwpAgX6^Ee-e=C_+m_NK7%lj7g?S;KL`aA%lEU04i-_d7t}QoU+QUlb zaS>O!mmV*+WdSmk{YJQ2p#=d6W4)UAd8q)!1)*ZKq6q+q30PQF2g+J$V-|34m_{Ca zHZHl{(asTNPXf)?6p8wcge-&!;3Ktll`6azlGPMrk2-PI4m^DfN%}=tpEnqwmZvE) zyDrZh&?6B5wYC7k(`y^0007xfP`~S79=2DNl zkDF7Fvx0)nWZPJR=nX6Zr#4^;TS3QmbfqC#Y_3thWBf9rx(zquzp81RX(FOuyZ{r6 z2z;0OKUCIicSS}Bd3jKBeuhS#eW#Ic6wPXloq;PT@*qoqc+&$iiv1=2v03X9DAO7r z!M+mFRt!uDzx2vbExxcK;2yF1T-E0EJHcnb$1h@?&O#ZSH=)2t5%pW@@B=|I!%~O- zfUe4EAg`}*6zz`)kLp4#_Eg{aK}gMajiJp(eDj-=b|m%tb1I$}k)lLiJ38nURBqh; zviPb}lC8A2*8;f@YNSqS1@X%}CKNaXw?NTi_zFbknOu=k{0CS)#OBut{{TLDE-|B6 z*GE1mP^qY^L>HP_8!`S`uaR%Kou?i2?Xxz*%NeR(D{>*|=*~6c3SYBnr+jg*+S%X# zO9ToO)ZjgQ1e6D#ByXLl#T0TYqzYFWr1>5n#Um-P*{w3oB!siPPi3%g-#AqRy(L=DVnM-V$1Ic5s1x=w~R%PXr)c5z^Zek ztG`%&t-wD2nU=6oIrwHu7b^L8H~F)Qep7a@?6xX3M2w4_u)>%z{jNagj|NnADVdf^gZbrrnQs-~&NZuE&-T){j?I`xQ9C zZaQ{pU+oaafF23EZ~(D;Rxtq!@=qg(jPeBlKAo8l_WmhYU#xcf9AV0m1u42Vda5_CDHKg6Li z-lIEkP?-*r-#^VaKF#DG-G!}>hDEiMC&jdn=@!*4bK$6fpCH=r)F&ZZ2ovEiHc9W3gffMN9IBM>qJ>C zNwS`sas8ED+hYdaCV6;KYmL#JoA~kO)@FIx^=K*WX#3(}Eu|IZ=+$c+8U)n`GV1$J|+6eD+M>?;Uf83{eB7aQK6LGMysY%72Gl$8)qnd)H-?uMxZx>D!5 zdBhjpMpYH#-_@&l!BhrkE(>4umdZ=fgECV>nLLucY9Gm|*ZHn~eyt=|E%!e>{DQVc z(qsg!^shTMa~c2DNjIE5-xIU{SclW&d_ZhAx^#Pk@7nCwv#cl6@Pu(EA8ytfZs&x3 zEH}OSbhQ@YkE)6+r7+*#wx%2gSF?i0z0hJ1TpkoWE2|=@)DAfn$|G}Vsq0fQ)y6+u zot&biLOzIOI!=G0N|XV)nQesiFY~BcS4ufujiZ)?xpgE%S&)zl$eK?epBy%t{%OKxGfgj!UQ;4h}0_3b6CC!rKe^e-EvY5rG+B zkJvJg--i}QbMJQ8dcu4mG);6Ty&b(_AFHTcmy7EToDWs&eeJ?)*IUufyz12{Te#g} zRHt#u$MYrvyl`7yO5<()y(K4`$?+&zMN}1AZEY7OffneVTH2&@SJC40Y>`X&e*P6F zcRFl8(isDqEfKNPTHFMaNk*lc7~53TdIO6}+t_BmJ9Ozfr5x#Ny=q(Fq8vy|w-QDd z9z7tonB6%i9z};~A$FonIA8+pKa4aRJQzk4b$kaL<9M4bg&Uu4_D4Z|Y7vdnb+VD^ zUvh`^$G#KtYbK6#4Fs`6Dk^kxF)>{+SIz?O9@i5Ux?+d%M)vnL=W97;^p!V0IV(L* zQi_UkDS{XJkvu;3q*nR}B5FTruUhMU+Ydi+Qqt`;RTUC~*JNbkszD}|50g0J9B%rA zgn9^?Ku18mWfQlJ&-MqB5{>U&*>1!0$aaD1UGp8v2NJ|)sVHA?gCVY|g0a;PIveYw+x^V; zpZ@loLMtpRDCGH8M~J;614Wq^*s%mm_xDK9ZbFK>yRU10{ysV5c%}3cXXdb7Q{RV^ zUv1d-=}MPZM*MVI?l-G6D&1^3N%tWl$CXO zN20FbN8&4dvFi#s*()oOz6pCCYNTXtALu)WGs!*)p_bwsV@|g-jaVidUG0f_O6bK@ zxg%};5~OmP?2e52$)y3#xwzrr5w*5|O}1CiViHCSI^z3UP-8{X$h*~r)1DDQf_=7# z#)Y{(+%D$!9MflVB*pH|aq-;y4I{EN3BXqo3pZX_-PjfcpZ7dU-AGw;4g zeO@3fL3ox?#mWE$)ip1sXK%{(DZ`hj)KLf_%n;uIf=9;XnA}o0TW9ly!}PaECh(ws zMZOoKUtq_{G+IQsZ-u|wLtuI2C-rVM>(#JFn?NN{mg?ynK1%p-I7IB&7v5?Txz@F+ zKNuB-MizxLFW?=2?jUtDEc&V@Y5Zbp!{Y(Vfb+hH9m(pB>{D0t?7&c$?Khx$j6J`5Zh+s;;|a^3<#%NU8lX?5i%xN~&NCg?Tms7^bq|ENq^|5SY1J%? zrO?05^hrT!cH?Ev3!hd*8H-<}k+BM!9PliCO}>Xj(l3iPm@Vin!XD#c#Di~!TwO~S zoE|E(fCD3~^#v*_=<9?=_Hg%I2LjA~pn=cuAekmlCf-C*MMIO@1Pn29$wT&?-?21| z3E64`{4{E$=%HR`9UNS=Md_zx^Z8GWS2Ojd`vd3%Y^s9Wcbq2+`%IEF3kg4@7_=z- zIEnmW`A^J__q~RNc+FYT2U(`u#zD&g*;OMGn1@tzE?$TiQLbYn^zl^l?1Urb%~X<^i)y#t(7YmF=4@=dkiZ0cWxiyY}f_A zS}ebg057`gM%^#IpXi9$aVDN%33FM(43E5&AUhrpUYYQ6MW`EuC6X@xXI&w zRVkAU2S=4S(Rt$il29@xtk5^}&Ev^?7Mu~?!Saboh-KWZdB-ZDr}!4(vG@Xu2I`z8vB`{zhnmRDs~^WNFKep z-_ZKKcl(gOdnb{6vyf?M=Y9{OIWLC^vcC5JN}&$R+x_-+xKzGETaD3;!p=s&@_NiP z0N!wJQDR5br!PnSmCIL($L}D1cqFy(o>o{Q%Au1-JepZa&soeDmlj!wnhK~rn83L) zab~43Z+f*yftf>`V_NutktWk(x-7RL@DRl3GjjD;xzSI;pNK7OY2b|FGwFw|``*_p z14JGT__`Dfq7D#!_C{WD#~IC=EGumo;$qzv-->lSxz5o#UD+c;?i&%7e=}6Nz=zYn z^W05aXM;*xdVhIXux^`Qk`l%hx;k=PfZ|*#KKF52l=e_WVQoYQ8^RP&pPqL7MHj8^ zkX&k5cu_Ho^OF2|TakxP{e+in)||XoO(CjXx7|!T*BRzv^5wQ!jY%QyFB6NCJ05Il zW^g2rwBZNF#!a{-)1c&H(!u_%JDQD`|C$HKx7mn`>!;rl8^=tqM=w2cYMxvsTct-T zScP)g@o6(}+vr1@zs`K-8Wf%uTX(>aXr!3IM=UgC*Ig+s&O7n_co_m=u?fz1gW1(A zxPqbsuc}#4hUWb|($Y@7AIE-LM%K1?HJ3)`KH`-Z=Iz}4?fI#6zQPMt*GEbTs$ANk zb``$AR`q+Wtz(T@uCRdCks?dhZMjW+CN^8;%gMOAs3Ebr$UyeA+1>1Ts<-513P#dK z0fmO7q=5~d^mG@Plb`KAi(l=pisTn+Y6fM9y@xa$Cl70q*FDuX7QFp=^Xo(DnylM| zjj}5C=5WZpUmdwWl5%1A*3T*;YIDSCZ+mcy>dp|CR(OpJoFMZvRnv`oF}AaWSWP8w zOe9)?x146IcW|(Y2yWpChz2`0anyo;ot%~B-)^SmiyE06MfqI$3ril1EbVCAfZ zUK8mw z9uxhLN$Iib?U?}Uu$fj9YpbFu-&hm*`XaQcDn zm&hQQ-i07mEosP z{oG{kOba*PJ#!ZY6-TKFY{-WaYOiFkvLYJRMj->=%ZPcnh zto3@Qz&Kl{lSfqc*5d=oy%sAsI@ri0;=(qlJ1|1{fHo}hB1>paazF3zcc_*!l~R3F z%`i_>WwEzb?os&ahhi7W)k}vSE+k>yTcC+skpalEOPYW9P>8aX9jiadWR+rhxJ5xb zbsTLP3CV#&RSuW!*Nrjmuv+N#{Fl3O!Wulq-r4G;cNqQVo#G$|2yx&See+M$PcNC5 zOY;snU+%ro@ro<9gBg147IPXDf60Bp6~(Po$5>;=)FI_}He%K^Cwik{L0FX$Wn-l-5If`C_1=N!ogW!U zdr2F70Ae&W(B|GqK1S_{@ZO|y+Qs5r;$$($hzE{)<@(|Nbhms4v{!!aDX5h7XjOT?$1bkp&6oQLX0B5O-+gv` z#)luCm1#+JaWwV*7nZB)`_5$u;5y7MTiVnjx|eixHmY@>A*%5U2-@a9Kga^drJ9dx zA|x;{0-LGw&mJ(c``&a6-SrTq>X~U~ySehb^UBE^YZhxsv@YPR(FjMm!hQ3T9Z(6uI=r$ZJR`yH;=mEJ37!mO|4zTP)*!d}_Xk2o zpcmQm$+xH?h(K4q=Zlyc@K>L&h^q9pf1e191AVgoef0m=P3!6g9}s+VwYmTOzHV$| z-r93_AfSPd1SyyW`8h{3`p?7sO{~1n{^V7LSpNnh4e+@Je@4pZ9 wRR-d;f0xnsZr~7f;L3&r+MqsPk)I#&J?Y3JpgvdeFMvx#5F${*r}^vu0SvkRuK)l5 literal 0 HcmV?d00001 From a2755a4926c41618c2fbd4da41324f46cca0b7f8 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 16 Jan 2025 10:01:43 +0900 Subject: [PATCH 55/59] fix(mrm_handler): simplify hazard command choice (#9929) Signed-off-by: Ryuta Kambe --- system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 4022bdaadebef..b5f4bbaeefc46 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -115,12 +115,7 @@ void MrmHandler::publishHazardCmd() HazardLightsCommand msg; msg.stamp = this->now(); - if (is_emergency_holding_) { - // turn hazard on during emergency holding - msg.command = HazardLightsCommand::ENABLE; - } else if (isEmergency() && param_.turning_hazard_on.emergency) { - // turn hazard on if vehicle is in emergency state and - // turning hazard on if emergency flag is true + if (param_.turning_hazard_on.emergency && isEmergency()) { msg.command = HazardLightsCommand::ENABLE; } else { msg.command = HazardLightsCommand::NO_COMMAND; From 347a2e48109452c70447ce219a207b5fd75591f1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Jan 2025 13:34:45 +0900 Subject: [PATCH 56/59] fix(goal_planner): fix geometric pull over (#9932) Signed-off-by: kosuke55 --- .../src/pull_over_planner/geometric_pull_over.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index bf2ce86b49bab..44dca13ccfd66 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -28,6 +28,7 @@ namespace autoware::behavior_path_planner GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward) : PullOverPlannerBase{node, parameters}, + parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_{ lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, is_forward_{is_forward}, From e09193784833044b8597c4d3dd7dda9bf169de74 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 16 Jan 2025 13:51:37 +0900 Subject: [PATCH 57/59] feat(lane_change): ensure path generation doesn't exceed time limit (#9908) * add time limit for lane change candidate path generation Signed-off-by: mohammad alqudah * apply time limit for frenet method as well Signed-off-by: mohammad alqudah * ensure param update value is valid Signed-off-by: mohammad alqudah * fix param update initial value Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix param update initial values Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../README.md | 1 + .../config/lane_change.param.yaml | 1 + .../structs/parameters.hpp | 1 + .../src/manager.cpp | 52 +++++++++++++------ .../src/scene.cpp | 18 +++++-- 5 files changed, 52 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index ee371f8592833..20fd564049133 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -1039,6 +1039,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `time_limit` | [ms] | double | Time limit for lane change candidate path generation | 50.0 | | `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.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 | 3.0 | | `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index df9491576a4ee..15eb23daecf95 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: lane_change: + time_limit: 50.0 # [ms] backward_lane_length: 200.0 backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index f0adcb1d69b42..60386f535fc64 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -162,6 +162,7 @@ struct Parameters FrenetPlannerParameters frenet{}; // lane change parameters + double time_limit{50.0}; double backward_lane_length{200.0}; double backward_length_buffer_for_end_of_lane{0.0}; double backward_length_buffer_for_blocking_object{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 07b05ab0ea131..f26cf79e8b120 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -190,6 +190,7 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s } // lane change parameters + p.time_limit = getOrDeclareParameter(*node, parameter("time_limit")); p.backward_lane_length = getOrDeclareParameter(*node, parameter("backward_lane_length")); p.backward_length_buffer_for_end_of_lane = getOrDeclareParameter(*node, parameter("backward_length_buffer_for_end_of_lane")); @@ -313,6 +314,17 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortime_limit; + updateParam(parameters, ns + "time_limit", time_limit); + if (time_limit >= 10.0) { + p->time_limit = time_limit; + } else { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'time_limit' is not updated because the value (%.3f ms) is not valid, " + "keep current value (%.3f ms)", + time_limit, p->time_limit); + } updateParam(parameters, ns + "backward_lane_length", p->backward_lane_length); updateParam( parameters, ns + "backward_length_buffer_for_end_of_lane", @@ -349,25 +361,27 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.lane_changing_decel_factor); updateParam( parameters, ns + "th_prepare_curvature", p->trajectory.th_prepare_curvature); - int longitudinal_acc_sampling_num = 0; + int longitudinal_acc_sampling_num = p->trajectory.lon_acc_sampling_num; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), - "Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not positive", + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not " + "positive", longitudinal_acc_sampling_num); } - int lateral_acc_sampling_num = 0; + int lateral_acc_sampling_num = p->trajectory.lat_acc_sampling_num; updateParam(parameters, ns + "lat_acc_sampling_num", lateral_acc_sampling_num); if (lateral_acc_sampling_num > 0) { p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), - "Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not positive", + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not " + "positive", lateral_acc_sampling_num); } @@ -409,8 +423,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.lat_acc_map = lat_acc_map; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Mismatched size for lateral acceleration. Expected size: %lu, but velocity: %lu, " "min_values: %lu, max_values: %lu", std::max(2ul, velocity.size()), velocity.size(), min_values.size(), max_values.size()); @@ -515,28 +529,32 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorcancel.enable_on_prepare_phase; updateParam(parameters, ns + "enable_on_prepare_phase", enable_on_prepare_phase); if (!enable_on_prepare_phase) { - RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change cancel function is disabled."); + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Lane Change cancel function is disabled."); p->cancel.enable_on_prepare_phase = enable_on_prepare_phase; } - bool enable_on_lane_changing_phase = true; + bool enable_on_lane_changing_phase = p->cancel.enable_on_lane_changing_phase; updateParam( parameters, ns + "enable_on_lane_changing_phase", enable_on_lane_changing_phase); if (!enable_on_lane_changing_phase) { - RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change abort function is disabled."); + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Lane Change abort function is disabled."); p->cancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase; } - int deceleration_sampling_num = 0; + int deceleration_sampling_num = p->cancel.deceleration_sampling_num; updateParam(parameters, ns + "deceleration_sampling_num", deceleration_sampling_num); if (deceleration_sampling_num > 0) { p->cancel.deceleration_sampling_num = deceleration_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Parameter 'deceleration_sampling_num' is not updated because the value (%d) is not " "positive", deceleration_sampling_num); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 7748795851865..45fcd6fa99086 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1154,18 +1154,22 @@ bool NormalLaneChange::get_path_using_frenet( const std::vector> & sorted_lane_ids, LaneChangePaths & candidate_paths) const { - stop_watch_.tic("frenet_candidates"); + stop_watch_.tic(__func__); constexpr auto found_safe_path = true; const auto frenet_candidates = utils::lane_change::generate_frenet_candidates( common_data_ptr_, prev_module_output_.path, prepare_metrics); RCLCPP_DEBUG( logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(), - stop_watch_.toc("frenet_candidates")); + stop_watch_.toc(__func__)); candidate_paths.reserve(frenet_candidates.size()); lane_change_debug_.frenet_states.clear(); lane_change_debug_.frenet_states.reserve(frenet_candidates.size()); for (const auto & frenet_candidate : frenet_candidates) { + if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) { + break; + } + lane_change_debug_.frenet_states.emplace_back( frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter, frenet_candidate.max_lane_changing_length); @@ -1186,7 +1190,7 @@ bool NormalLaneChange::get_path_using_frenet( if (check_candidate_path_safety(*candidate_path_opt, target_objects)) { RCLCPP_DEBUG( logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]", - frenet_candidates.size(), stop_watch_.toc("frenet_candidates")); + frenet_candidates.size(), stop_watch_.toc("__func__")); utils::lane_change::append_target_ref_to_candidate( *candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing); candidate_paths.push_back(*candidate_path_opt); @@ -1204,7 +1208,7 @@ bool NormalLaneChange::get_path_using_frenet( RCLCPP_DEBUG( logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(), - stop_watch_.toc("frenet_candidates")); + stop_watch_.toc(__func__)); return !found_safe_path; } @@ -1214,6 +1218,7 @@ bool NormalLaneChange::get_path_using_path_shifter( const std::vector> & sorted_lane_ids, LaneChangePaths & candidate_paths) const { + stop_watch_.tic(__func__); const auto & target_lanes = get_target_lanes(); candidate_paths.reserve( prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); @@ -1279,6 +1284,11 @@ bool NormalLaneChange::get_path_using_path_shifter( prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { + if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) { + RCLCPP_DEBUG(logger_, "Time limit reached and no safe path was found."); + return false; + } + debug_metrics.lc_metrics.emplace_back(lc_metric, -1); const auto debug_print_lat = [&](const std::string & s) { From 099591a740cec19de99c4590f7b468ab9e1d5572 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 16 Jan 2025 14:01:58 +0900 Subject: [PATCH 58/59] chore(simple_planning_simulator): add maintainer (#9934) --- .github/CODEOWNERS | 2 +- simulator/simple_planning_simulator/package.xml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 5bbc4d1c6177b..4fea7c85e1926 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -204,7 +204,7 @@ simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail. simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp -simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index fdc782182f9a5..5bd7a2f74eacc 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -10,6 +10,7 @@ Mamoru Sobue Zulfaqar Azmi Temkei Kem + Kotaro Yoshimoto Apache License 2.0 ament_cmake_auto From 01a764782c86e614a27808b973d073c12da2217e Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 16 Jan 2025 14:23:18 +0900 Subject: [PATCH 59/59] feat(autoware_shape_estimation): tier4_debug_msgs chnaged to autoware_internal_debug_msgs in autoware_shape_estimation (#9897) feat: tier4_debug_msgs chnaged to autoware_internal_debug_msgs in files perception/autoware_shape_estimation Signed-off-by: vish0012 --- .../autoware_shape_estimation/src/shape_estimation_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp index c5450dc14adb0..28b2a6e398e91 100644 --- a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp +++ b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp @@ -179,9 +179,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared // Publish pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(pub_, output_msg.header.stamp); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } } // namespace autoware::shape_estimation