From b3a0363b90f27c930d062c1bc316b636af73dfa4 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 9 May 2022 11:59:02 +0900 Subject: [PATCH 01/23] refactor(behavior_velocity_planner): simplify CMakeLists.txt (#855) Signed-off-by: Kenji Miyake --- .../behavior_velocity_planner/CMakeLists.txt | 296 ++---------------- 1 file changed, 27 insertions(+), 269 deletions(-) diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 6acaa54b6481b..47f6f999ecb08 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -11,292 +11,50 @@ find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED COMPONENTS common) find_package(OpenCV REQUIRED) -set(BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES - tier4_api_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - tier4_planning_msgs - tier4_autoware_utils - Boost - Eigen3 - diagnostic_msgs - geometry_msgs - lanelet2_extension - PCL - pcl_conversions - rclcpp - sensor_msgs - interpolation - tf2 - tf2_eigen - tf2_geometry_msgs - tf2_ros - vehicle_info_util - visualization_msgs - nav_msgs - grid_map_ros -) +set(scene_modules + detection_area + blind_spot + stop_line + crosswalk + traffic_light + intersection + no_stopping_area + virtual_traffic_light + occlusion_spot +) + +foreach(scene_module IN LISTS scene_modules) + file(GLOB_RECURSE scene_module_src "src/scene_module/${scene_module}/*") + list(APPEND scene_modules_src ${scene_module_src}) +endforeach() - -# Common -ament_auto_add_library(scene_module_lib SHARED +ament_auto_add_library(behavior_velocity_planner SHARED + src/node.cpp + src/planner_manager.cpp src/utilization/path_utilization.cpp src/utilization/util.cpp + ${scene_modules_src} ) -target_include_directories(scene_module_lib +target_include_directories(behavior_velocity_planner SYSTEM PUBLIC ${BOOST_INCLUDE_DIRS} - ${tf2_geometry_msgs_INCLUDE_DIRS} -) - -target_include_directories(scene_module_lib - PUBLIC - $ - $ -) - -target_include_directories(scene_module_lib - SYSTEM PUBLIC ${PCL_INCLUDE_DIRS} -) - -ament_target_dependencies(scene_module_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -# Scene Module: Stop Line -ament_auto_add_library(scene_module_stop_line SHARED - src/scene_module/stop_line/manager.cpp - src/scene_module/stop_line/scene.cpp - src/scene_module/stop_line/debug.cpp -) - -target_include_directories(scene_module_stop_line - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_stop_line ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_stop_line scene_module_lib) - -# Scene Module: Crosswalk -ament_auto_add_library(scene_module_crosswalk SHARED - src/scene_module/crosswalk/manager.cpp - src/scene_module/crosswalk/scene_crosswalk.cpp - src/scene_module/crosswalk/scene_walkway.cpp - src/scene_module/crosswalk/debug.cpp - src/scene_module/crosswalk/util.cpp -) - -target_include_directories(scene_module_crosswalk - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_crosswalk ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_crosswalk scene_module_lib) - -# Scene Module: Intersection -ament_auto_add_library(scene_module_intersection SHARED - src/scene_module/intersection/manager.cpp - src/scene_module/intersection/scene_intersection.cpp - src/scene_module/intersection/scene_merge_from_private_road.cpp - src/scene_module/intersection/debug.cpp - src/scene_module/intersection/util.cpp -) - -target_include_directories(scene_module_intersection - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_intersection ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_intersection scene_module_lib) - -# Scene Module: Traffic Light -ament_auto_add_library(scene_module_traffic_light SHARED - src/scene_module/traffic_light/manager.cpp - src/scene_module/traffic_light/scene.cpp - src/scene_module/traffic_light/debug.cpp -) - -target_include_directories(scene_module_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_traffic_light scene_module_lib) - -# Scene Module: Blind Spot -ament_auto_add_library(scene_module_blind_spot SHARED - src/scene_module/blind_spot/manager.cpp - src/scene_module/blind_spot/scene.cpp - src/scene_module/blind_spot/debug.cpp -) - -target_include_directories(scene_module_blind_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_blind_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_blind_spot scene_module_lib) - -# Scene Module: Detection Area -ament_auto_add_library(scene_module_detection_area SHARED - src/scene_module/detection_area/manager.cpp - src/scene_module/detection_area/scene.cpp - src/scene_module/detection_area/debug.cpp -) - -target_include_directories(scene_module_detection_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_detection_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_detection_area scene_module_lib) - -# Scene Module: No Stopping Area -ament_auto_add_library(scene_module_no_stopping_area SHARED - src/scene_module/no_stopping_area/manager.cpp - src/scene_module/no_stopping_area/scene_no_stopping_area.cpp - src/scene_module/no_stopping_area/debug.cpp -) - -target_include_directories(scene_module_no_stopping_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_no_stopping_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_no_stopping_area scene_module_lib) - -# Scene Module: Virtual Traffic Light -ament_auto_add_library(scene_module_virtual_traffic_light SHARED - src/scene_module/virtual_traffic_light/manager.cpp - src/scene_module/virtual_traffic_light/scene.cpp - src/scene_module/virtual_traffic_light/debug.cpp -) - -target_include_directories(scene_module_virtual_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_virtual_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_virtual_traffic_light scene_module_lib) - -# SceneModule OcclusionSpot -# Util -ament_auto_add_library(occlusion_spot_lib SHARED - src/scene_module/occlusion_spot/grid_utils.cpp - src/scene_module/occlusion_spot/occlusion_spot_utils.cpp - src/scene_module/occlusion_spot/risk_predictive_braking.cpp -) - -target_include_directories(occlusion_spot_lib - SYSTEM PUBLIC - ${BOOST_INCLUDE_DIRS} ${tf2_geometry_msgs_INCLUDE_DIRS} ) -target_include_directories(occlusion_spot_lib - PUBLIC - $ - $ -) - -ament_target_dependencies(occlusion_spot_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -ament_auto_add_library(scene_module_occlusion_spot SHARED - src/scene_module/occlusion_spot/manager.cpp - src/scene_module/occlusion_spot/debug.cpp - src/scene_module/occlusion_spot/scene_occlusion_spot.cpp -) - -target_include_directories(scene_module_occlusion_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_occlusion_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_occlusion_spot scene_module_lib occlusion_spot_lib) - -# Scene Module Manager -ament_auto_add_library(scene_module_manager SHARED - src/planner_manager.cpp -) - -target_include_directories(scene_module_manager - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_manager ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_manager scene_module_lib) - -# Node -ament_auto_add_library(behavior_velocity_planner SHARED - src/node.cpp -) - -target_include_directories(behavior_velocity_planner - PUBLIC - $ - $ -) - -ament_target_dependencies(behavior_velocity_planner ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(behavior_velocity_planner - scene_module_lib - scene_module_stop_line - scene_module_crosswalk - scene_module_intersection - scene_module_traffic_light - scene_module_blind_spot - scene_module_occlusion_spot - scene_module_detection_area - scene_module_no_stopping_area - scene_module_virtual_traffic_light - scene_module_manager +ament_target_dependencies(behavior_velocity_planner + Boost + Eigen3 + PCL ) -ament_export_dependencies(${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - rclcpp_components_register_node(behavior_velocity_planner PLUGIN "behavior_velocity_planner::BehaviorVelocityPlannerNode" EXECUTABLE behavior_velocity_planner_node ) - if(BUILD_TESTING) - # utils for test - ament_auto_add_library(utilization SHARED - src/utilization/util.cpp - ) - # Gtest for utilization ament_add_gtest(utilization-test test/src/test_state_machine.cpp @@ -305,7 +63,7 @@ if(BUILD_TESTING) ) target_link_libraries(utilization-test gtest_main - utilization + behavior_velocity_planner ) # Gtest for occlusion spot @@ -316,7 +74,7 @@ if(BUILD_TESTING) ) target_link_libraries(occlusion_spot-test gtest_main - scene_module_occlusion_spot + behavior_velocity_planner ) endif() From de8deed8e45177298fe34fbdbf46f7aafead7316 Mon Sep 17 00:00:00 2001 From: Shark <71419791+Sharrrrk@users.noreply.github.com> Date: Mon, 9 May 2022 11:31:50 +0800 Subject: [PATCH 02/23] fix(system_monitor): fix build error on tegra platform (#869) * fix(system_monitor): fix build error on tegra platform Signed-off-by: Shark Liu * ci(pre-commit): autofix * Update system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp Co-authored-by: Shark Liu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp index a9ae72321efd1..8da0d071de582 100644 --- a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp +++ b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp @@ -127,8 +127,10 @@ void GPUMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & stat) } } -void GPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper & stat) +void GPUMonitor::checkThrottling( + [[maybe_unused]] diagnostic_updater::DiagnosticStatusWrapper & stat) { + // Please remove the [[maybe_unused]] tag after implementation, it's a temp build fix // TODO(Fumihito Ito): implement me } From 391ebac4ebf8aeae386c2726929cdb1b334e0b7c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 9 May 2022 14:07:00 +0900 Subject: [PATCH 03/23] feat(ad_service_state_monitor): limit odometry buffer size (#514) * feat(ad_service_state_monitor): limit odometry buffer size 40 Signed-off-by: Takayuki Murooka * Update system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Update ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../ad_service_state_monitor_node.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp index e5a59692983ca..076f8d3a9f399 100644 --- a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp +++ b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp @@ -120,6 +120,11 @@ void AutowareStateMonitorNode::onOdometry(const nav_msgs::msg::Odometry::ConstSh state_input_.odometry_buffer.pop_front(); } + + constexpr size_t odometry_buffer_size = 200; // 40Hz * 5sec + if (state_input_.odometry_buffer.size() > odometry_buffer_size) { + state_input_.odometry_buffer.pop_front(); + } } bool AutowareStateMonitorNode::onShutdownService( From 03baceaf573e2ece3e04f1f4e8b00ecea8558a2f Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Mon, 9 May 2022 17:53:57 +0900 Subject: [PATCH 04/23] docs: fix 404 error caused by typo in url (#871) * docs: fix 404 error caused by typo in url Signed-off-by: Shin-kyoto * docs: fix typo in url for yolov4 Signed-off-by: Shin-kyoto --- perception/tensorrt_yolo/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/tensorrt_yolo/README.md b/perception/tensorrt_yolo/README.md index 5dfae272f143a..5811fa88a6b7a 100644 --- a/perception/tensorrt_yolo/README.md +++ b/perception/tensorrt_yolo/README.md @@ -72,15 +72,15 @@ This package includes multiple licenses. ### YOLOv4 -[YOLOv4](https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). +[YOLOv4](https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). ### YOLOv5 Refer to [this guide](https://github.com/ultralytics/yolov5/issues/251 "guide") -- [YOLOv5s](https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") +- [YOLOv5s](https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") -- [YOLOv5m](https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") +- [YOLOv5m](https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") - [YOLOv5l](https://drive.google.com/uc?id=1xO8S92Cq7qrmx93UHHyA7Cd7-dJsBDP8 "YOLOv5l") From 8b480545a8d9cdcc1f7bd59fc2d3c115011be9c1 Mon Sep 17 00:00:00 2001 From: storrrrrrrrm <103425473+storrrrrrrrm@users.noreply.github.com> Date: Mon, 9 May 2022 17:15:57 +0800 Subject: [PATCH 05/23] fix(image_projection_based_fusion): set imagebuffersize (#820) * fix: set imagebuffersize configured Signed-off-by: suchang * ci(pre-commit): autofix Co-authored-by: suchang Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/image_projection_based_fusion/debugger.hpp | 5 +++-- .../launch/roi_cluster_fusion.launch.xml | 2 ++ .../launch/roi_detected_object_fusion.launch.xml | 2 ++ perception/image_projection_based_fusion/src/debugger.cpp | 7 +++++-- .../image_projection_based_fusion/src/fusion_node.cpp | 4 +++- 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index ff790894658ec..9ecd336818b59 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -38,7 +38,8 @@ using sensor_msgs::msg::RegionOfInterest; class Debugger { public: - explicit Debugger(rclcpp::Node * node_ptr, const std::size_t image_num); + explicit Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size); void publishImage(const std::size_t image_id, const rclcpp::Time & stamp); @@ -57,7 +58,7 @@ class Debugger std::vector image_subs_; std::vector image_pubs_; std::vector> image_buffers_; - std::size_t image_buffer_size{5}; + std::size_t image_buffer_size_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 8fe94963ff8ca..e5824dfcff97f 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index f6466e6512a09..be981478e78a2 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index e1254fc136304..0bcfb019d93df 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -34,9 +34,12 @@ void drawRoiOnImage( namespace image_projection_based_fusion { -Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ptr_(node_ptr) +Debugger::Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size) +: node_ptr_(node_ptr) { image_buffers_.resize(image_num); + image_buffer_size_ = image_buffer_size; for (std::size_t img_i = 0; img_i < image_num; ++img_i) { auto sub = image_transport::create_subscription( node_ptr, "input/image_raw" + std::to_string(img_i), @@ -54,7 +57,7 @@ Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ auto pub = image_transport::create_publisher(node_ptr, "output/image_raw" + std::to_string(img_i)); image_pubs_.push_back(pub); - image_buffers_.at(img_i).set_capacity(image_buffer_size); + image_buffers_.at(img_i).set_capacity(image_buffer_size_); } } diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 57ed245f67bd7..5d33303ca1bf9 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -127,7 +127,9 @@ FusionNode::FusionNode(const std::string & node_name, const rclcpp::NodeOpt // debugger if (declare_parameter("debug_mode", false)) { - debugger_ = std::make_shared(this, rois_number_); + std::size_t image_buffer_size = + static_cast(declare_parameter("image_buffer_size", 15)); + debugger_ = std::make_shared(this, rois_number_, image_buffer_size); } } From c88ae056364cde55edcd0219b215f33d96df1332 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 9 May 2022 19:18:23 +0900 Subject: [PATCH 06/23] chore(avoidance_module): fix spell check (#732) Signed-off-by: Muhammad Zulfaqar Azmi --- .../scene_module/avoidance/debug.hpp | 2 +- .../src/scene_module/avoidance/avoidance_module.cpp | 8 ++++---- .../src/scene_module/avoidance/debug.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp index edfb7d7f84d71..d3f8f80606784 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp @@ -93,7 +93,7 @@ MarkerArray createPoseMarkerArray( MarkerArray makeOverhangToRoadShoulderMarkerArray( const behavior_path_planner::ObjectDataArray & objects); -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index b03282c735ece..876e5fc3112c3 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1939,8 +1939,8 @@ void AvoidanceModule::modifyPathVelocityToPreventAccelerationOnAvoidance(Shifted std::sqrt(v0 * v0 + 2.0 * s * parameters_.max_avoidance_acceleration)); // apply velocity limit - constexpr size_t VLIM_APPLY_IDX_MARGIN = 0; - for (size_t i = ego_idx + VLIM_APPLY_IDX_MARGIN; i < N; ++i) { + constexpr size_t V_LIM_APPLY_IDX_MARGIN = 0; + for (size_t i = ego_idx + V_LIM_APPLY_IDX_MARGIN; i < N; ++i) { path.path.points.at(i).point.longitudinal_velocity_mps = std::min(path.path.points.at(i).point.longitudinal_velocity_mps, static_cast(vmax)); } @@ -2619,7 +2619,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData using marker_utils::createAvoidPointMarkerArray; using marker_utils::createLaneletsAreaMarkerArray; using marker_utils::createObjectsMarkerArray; - using marker_utils::createOvehangFurthestLineStringMarkerArray; + using marker_utils::createOverhangFurthestLineStringMarkerArray; using marker_utils::createPathMarkerArray; using marker_utils::createPoseMarkerArray; using marker_utils::createShiftLengthMarkerArray; @@ -2652,7 +2652,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData add(createLaneletsAreaMarkerArray(*debug.expanded_lanelets, "expanded_lanelet", 0.8, 0.8, 0.0)); add(createAvoidanceObjectsMarkerArray(avoidance_data_.objects, "avoidance_object")); add(makeOverhangToRoadShoulderMarkerArray(avoidance_data_.objects)); - add(createOvehangFurthestLineStringMarkerArray( + add(createOverhangFurthestLineStringMarkerArray( *debug.farthest_linestring_from_overhang, "farthest_linestring_from_overhang", 1.0, 0.0, 1.0)); // parent object info diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp index d7c3b1325f7dc..88c8d102bd00c 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp @@ -512,7 +512,7 @@ MarkerArray makeOverhangToRoadShoulderMarkerArray( return msg; } -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b) { From 13d3b6d0fb464d24e77679a3c1575452713c4c13 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 9 May 2022 21:08:53 +0900 Subject: [PATCH 07/23] feat: isolate gtests in all packages (#693) Signed-off-by: Maxime CLEMENT --- common/autoware_auto_common/CMakeLists.txt | 2 +- common/autoware_auto_common/package.xml | 2 +- common/autoware_auto_geometry/CMakeLists.txt | 2 +- common/autoware_auto_geometry/package.xml | 2 +- common/autoware_auto_tf2/CMakeLists.txt | 2 +- common/autoware_auto_tf2/package.xml | 2 +- common/autoware_point_types/CMakeLists.txt | 2 +- common/autoware_point_types/package.xml | 2 +- common/fake_test_node/CMakeLists.txt | 2 +- common/fake_test_node/package.xml | 2 +- common/had_map_utils/package.xml | 2 +- common/interpolation/CMakeLists.txt | 2 +- common/interpolation/package.xml | 2 +- common/motion_testing/CMakeLists.txt | 2 +- common/motion_testing/package.xml | 2 +- common/osqp_interface/CMakeLists.txt | 2 +- common/osqp_interface/package.xml | 2 +- common/signal_processing/CMakeLists.txt | 2 +- common/signal_processing/package.xml | 2 +- common/tier4_api_utils/CMakeLists.txt | 2 +- common/tier4_api_utils/package.xml | 2 +- common/tier4_autoware_utils/CMakeLists.txt | 4 ++-- common/tier4_autoware_utils/package.xml | 2 +- common/time_utils/package.xml | 2 +- common/vehicle_constants_manager/CMakeLists.txt | 2 +- common/vehicle_constants_manager/package.xml | 2 +- control/trajectory_follower/CMakeLists.txt | 4 ++-- control/trajectory_follower/package.xml | 2 +- control/vehicle_cmd_gate/CMakeLists.txt | 2 +- control/vehicle_cmd_gate/package.xml | 2 +- localization/ekf_localizer/CMakeLists.txt | 4 ++-- localization/ekf_localizer/package.xml | 2 +- localization/stop_filter/package.xml | 2 +- map/lanelet2_extension/CMakeLists.txt | 10 +++++----- map/lanelet2_extension/package.xml | 2 +- .../detected_object_feature_remover/package.xml | 2 +- planning/behavior_velocity_planner/CMakeLists.txt | 4 ++-- planning/behavior_velocity_planner/package.xml | 2 +- planning/costmap_generator/CMakeLists.txt | 2 +- planning/costmap_generator/package.xml | 2 +- .../freespace_planning_algorithms/CMakeLists.txt | 4 ++-- planning/freespace_planning_algorithms/package.xml | 2 +- planning/planning_error_monitor/CMakeLists.txt | 2 +- planning/planning_error_monitor/package.xml | 2 +- planning/planning_evaluator/CMakeLists.txt | 2 +- planning/planning_evaluator/package.xml | 2 +- .../dummy_perception_publisher/CMakeLists.txt | 2 +- simulator/dummy_perception_publisher/package.xml | 1 + simulator/fault_injection/CMakeLists.txt | 2 +- simulator/fault_injection/package.xml | 2 +- simulator/simple_planning_simulator/CMakeLists.txt | 2 +- simulator/simple_planning_simulator/package.xml | 2 +- system/system_monitor/CMakeLists.txt | 14 +++++++------- system/system_monitor/package.xml | 2 +- vehicle/raw_vehicle_cmd_converter/CMakeLists.txt | 2 +- vehicle/raw_vehicle_cmd_converter/package.xml | 2 +- 56 files changed, 71 insertions(+), 70 deletions(-) diff --git a/common/autoware_auto_common/CMakeLists.txt b/common/autoware_auto_common/CMakeLists.txt index 4f7846c89eb72..b0957ad726856 100644 --- a/common/autoware_auto_common/CMakeLists.txt +++ b/common/autoware_auto_common/CMakeLists.txt @@ -9,7 +9,7 @@ include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR}) if(BUILD_TESTING) set(TEST_COMMON test_common_gtest) - ament_add_gtest(${TEST_COMMON} + ament_add_ros_isolated_gtest(${TEST_COMMON} test/gtest_main.cpp test/test_bool_comparisons.cpp test/test_byte_reader.cpp diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index dca22e9b29ea3..17d666e2273e6 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -14,7 +14,7 @@ builtin_interfaces eigen - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common geometry_msgs diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt index 0e964e3b064a2..454e0e7ef044f 100644 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ b/common/autoware_auto_geometry/CMakeLists.txt @@ -23,7 +23,7 @@ if(BUILD_TESTING) test/src/test_common_2d.cpp test/src/test_intersection.cpp ) - ament_add_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) + ament_add_ros_isolated_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) target_compile_options(${GEOMETRY_GTEST} PRIVATE -Wno-conversion -Wno-sign-conversion) target_include_directories(${GEOMETRY_GTEST} PRIVATE "test/include" "include") ament_target_dependencies(${GEOMETRY_GTEST} diff --git a/common/autoware_auto_geometry/package.xml b/common/autoware_auto_geometry/package.xml index 976cf59013370..e19ac4897aab0 100644 --- a/common/autoware_auto_geometry/package.xml +++ b/common/autoware_auto_geometry/package.xml @@ -18,7 +18,7 @@ autoware_auto_vehicle_msgs geometry_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common osrf_testing_tools_cpp diff --git a/common/autoware_auto_tf2/CMakeLists.txt b/common/autoware_auto_tf2/CMakeLists.txt index f4b3223391a7b..a8ae9ec2d962e 100755 --- a/common/autoware_auto_tf2/CMakeLists.txt +++ b/common/autoware_auto_tf2/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(autoware_cmake REQUIRED) autoware_package() if(BUILD_TESTING) - ament_add_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) + ament_add_ros_isolated_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) target_include_directories(test_tf2_autoware_auto_msgs PRIVATE "include") ament_target_dependencies(test_tf2_autoware_auto_msgs "autoware_auto_common" diff --git a/common/autoware_auto_tf2/package.xml b/common/autoware_auto_tf2/package.xml index d6fbd4f4ce3d8..c80ce45a217ac 100644 --- a/common/autoware_auto_tf2/package.xml +++ b/common/autoware_auto_tf2/package.xml @@ -20,7 +20,7 @@ tf2_geometry_msgs tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/autoware_point_types/CMakeLists.txt b/common/autoware_point_types/CMakeLists.txt index e46081c5ea96f..c149f79dab71f 100644 --- a/common/autoware_point_types/CMakeLists.txt +++ b/common/autoware_point_types/CMakeLists.txt @@ -11,7 +11,7 @@ include_directories( ) if(BUILD_TESTING) - ament_add_gtest(test_autoware_point_types + ament_add_ros_isolated_gtest(test_autoware_point_types test/test_point_types.cpp ) target_include_directories(test_autoware_point_types diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml index b7449dbbd13d5..8829bd7538d9b 100644 --- a/common/autoware_point_types/package.xml +++ b/common/autoware_point_types/package.xml @@ -23,7 +23,7 @@ pcl_ros point_cloud_msg_wrapper - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common point_cloud_msg_wrapper diff --git a/common/fake_test_node/CMakeLists.txt b/common/fake_test_node/CMakeLists.txt index cc80077163ab1..8ad71df2777f3 100644 --- a/common/fake_test_node/CMakeLists.txt +++ b/common/fake_test_node/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(fake_test_node SHARED src/fake_test_node.cpp) if(BUILD_TESTING) - ament_add_gtest(test_fake_test_node + ament_add_ros_isolated_gtest(test_fake_test_node test/test_fake_test_node.cpp ) add_dependencies(test_fake_test_node fake_test_node) diff --git a/common/fake_test_node/package.xml b/common/fake_test_node/package.xml index 6d337906ff3b7..8e919d719fc6c 100644 --- a/common/fake_test_node/package.xml +++ b/common/fake_test_node/package.xml @@ -11,7 +11,7 @@ autoware_cmake - ament_cmake_gtest + ament_cmake_ros autoware_auto_common rclcpp rclcpp_components diff --git a/common/had_map_utils/package.xml b/common/had_map_utils/package.xml index 2baa56aa12c73..aa7f7a9e78840 100644 --- a/common/had_map_utils/package.xml +++ b/common/had_map_utils/package.xml @@ -23,7 +23,7 @@ lanelet2_io visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/interpolation/CMakeLists.txt b/common/interpolation/CMakeLists.txt index bca79e0f23d98..7afed6fe57c41 100644 --- a/common/interpolation/CMakeLists.txt +++ b/common/interpolation/CMakeLists.txt @@ -13,7 +13,7 @@ ament_auto_add_library(interpolation SHARED if(BUILD_TESTING) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_interpolation ${test_files}) + ament_add_ros_isolated_gtest(test_interpolation ${test_files}) target_link_libraries(test_interpolation interpolation diff --git a/common/interpolation/package.xml b/common/interpolation/package.xml index 213616b007a19..665e26bab9a0a 100644 --- a/common/interpolation/package.xml +++ b/common/interpolation/package.xml @@ -14,7 +14,7 @@ tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/motion_testing/CMakeLists.txt b/common/motion_testing/CMakeLists.txt index 4e7006978ab22..f8428c0df709c 100644 --- a/common/motion_testing/CMakeLists.txt +++ b/common/motion_testing/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/motion_testing/motion_testing.cpp) if(BUILD_TESTING) - ament_add_gtest(motion_testing_unit_tests + ament_add_ros_isolated_gtest(motion_testing_unit_tests test/gtest_main.cpp test/constant_trajectory.cpp test/trajectory_checks.cpp) diff --git a/common/motion_testing/package.xml b/common/motion_testing/package.xml index 33e7b4798d0e7..f292a7e5bb54b 100644 --- a/common/motion_testing/package.xml +++ b/common/motion_testing/package.xml @@ -19,7 +19,7 @@ autoware_auto_planning_msgs autoware_auto_vehicle_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/osqp_interface/CMakeLists.txt b/common/osqp_interface/CMakeLists.txt index 4180461cc261c..996f8b6153cf0 100644 --- a/common/osqp_interface/CMakeLists.txt +++ b/common/osqp_interface/CMakeLists.txt @@ -49,7 +49,7 @@ if(BUILD_TESTING) test/test_csc_matrix_conv.cpp ) set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) endif() diff --git a/common/osqp_interface/package.xml b/common/osqp_interface/package.xml index f89810ddda953..5260a3f2b07c0 100644 --- a/common/osqp_interface/package.xml +++ b/common/osqp_interface/package.xml @@ -17,7 +17,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/common/signal_processing/CMakeLists.txt b/common/signal_processing/CMakeLists.txt index e93023e703eb7..93cb7aa225a08 100644 --- a/common/signal_processing/CMakeLists.txt +++ b/common/signal_processing/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(lowpass_filter_1d SHARED ) if(BUILD_TESTING) - ament_add_gtest(test_signal_processing + ament_add_ros_isolated_gtest(test_signal_processing test/src/lowpass_filter_1d_test.cpp ) target_link_libraries(test_signal_processing diff --git a/common/signal_processing/package.xml b/common/signal_processing/package.xml index 563715af77248..867f2d05da60e 100644 --- a/common/signal_processing/package.xml +++ b/common/signal_processing/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/tier4_api_utils/CMakeLists.txt b/common/tier4_api_utils/CMakeLists.txt index e65e538fe1df4..4eda0296e520e 100644 --- a/common/tier4_api_utils/CMakeLists.txt +++ b/common/tier4_api_utils/CMakeLists.txt @@ -6,7 +6,7 @@ autoware_package() if(BUILD_TESTING) include_directories(include) - ament_add_gtest(${PROJECT_NAME}_test test/test.cpp) + ament_add_ros_isolated_gtest(${PROJECT_NAME}_test test/test.cpp) ament_target_dependencies(${PROJECT_NAME}_test rclcpp tier4_external_api_msgs) endif() diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 99a03ab92b0ec..a8378b92352ec 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -14,7 +14,7 @@ rclcpp tier4_external_api_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common rclcpp diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index eeca0a2d83630..7ba9c2020a36f 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -12,11 +12,11 @@ ament_auto_add_library(tier4_autoware_utils SHARED ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_tier4_autoware_utils ${test_files}) + ament_add_ros_isolated_gtest(test_tier4_autoware_utils ${test_files}) target_link_libraries(test_tier4_autoware_utils tier4_autoware_utils diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index f1bd523a8eda1..63fd56ae09f86 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -23,7 +23,7 @@ tier4_debug_msgs visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/time_utils/package.xml b/common/time_utils/package.xml index 9b553289e09be..a248e72f125f3 100644 --- a/common/time_utils/package.xml +++ b/common/time_utils/package.xml @@ -12,7 +12,7 @@ autoware_cmake builtin_interfaces - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/vehicle_constants_manager/CMakeLists.txt b/common/vehicle_constants_manager/CMakeLists.txt index eb5f7b27663e3..1e84c5f781d39 100644 --- a/common/vehicle_constants_manager/CMakeLists.txt +++ b/common/vehicle_constants_manager/CMakeLists.txt @@ -18,7 +18,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED # if(BUILD_TESTING) # set(TEST_SOURCES test/test_vehicle_constants_manager.cpp) # set(TEST_VEHICLE_CONSTANTS_MANAGER_EXE test_vehicle_constants_manager) -# ament_add_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) +# ament_add_ros_isolated_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) # target_link_libraries(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${PROJECT_NAME}) # endif() diff --git a/common/vehicle_constants_manager/package.xml b/common/vehicle_constants_manager/package.xml index eecb3e8f2108f..8041ae90a2cb7 100644 --- a/common/vehicle_constants_manager/package.xml +++ b/common/vehicle_constants_manager/package.xml @@ -15,7 +15,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_cmake diff --git a/control/trajectory_follower/CMakeLists.txt b/control/trajectory_follower/CMakeLists.txt index 5c29617296780..67d157df835de 100644 --- a/control/trajectory_follower/CMakeLists.txt +++ b/control/trajectory_follower/CMakeLists.txt @@ -72,7 +72,7 @@ if(BUILD_TESTING) test/test_lowpass_filter.cpp ) set(TEST_LATERAL_CONTROLLER_EXE test_lateral_controller) - ament_add_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) target_link_libraries(${TEST_LATERAL_CONTROLLER_EXE} ${LATERAL_CONTROLLER_LIB}) set(TEST_LON_SOURCES @@ -82,7 +82,7 @@ if(BUILD_TESTING) test/test_longitudinal_controller_utils.cpp ) set(TEST_LONGITUDINAL_CONTROLLER_EXE test_longitudinal_controller) - ament_add_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) target_link_libraries(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${LONGITUDINAL_CONTROLLER_LIB}) endif() diff --git a/control/trajectory_follower/package.xml b/control/trajectory_follower/package.xml index 4bc005335f4a9..840cad74aeb55 100644 --- a/control/trajectory_follower/package.xml +++ b/control/trajectory_follower/package.xml @@ -28,7 +28,7 @@ tf2 tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 886842aa7f634..309a296acc9db 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(vehicle_cmd_gate_node ) if(BUILD_TESTING) - ament_add_gtest(test_vehicle_cmd_gate + ament_add_ros_isolated_gtest(test_vehicle_cmd_gate test/src/test_main.cpp test/src/test_vehicle_cmd_filter.cpp ) diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index cb30c913ad766..7cb8b18244d18 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -26,7 +26,7 @@ tier4_vehicle_msgs vehicle_info_util - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index fa894c8a7b1a5..3a3edd5338a58 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -13,8 +13,8 @@ ament_auto_add_executable(ekf_localizer ament_target_dependencies(ekf_localizer kalman_filter) # if(BUILD_TESTING) -# find_package(ament_cmake_gtest REQUIRED) -# ament_add_gtest(ekf_localizer-test test/test_ekf_localizer.test +# find_package(ament_cmake_ros REQUIRED) +# ament_add_ros_isolated_gtest(ekf_localizer-test test/test_ekf_localizer.test # test/src/test_ekf_localizer.cpp # src/ekf_localizer.cpp # src/kalman_filter/kalman_filter.cpp diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index c67cfaa400a0d..3e9d9735ae3bd 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -24,7 +24,7 @@ tier4_autoware_utils tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index b4b948c236af4..47fcf3282efea 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -17,7 +17,7 @@ tf2 tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/map/lanelet2_extension/CMakeLists.txt b/map/lanelet2_extension/CMakeLists.txt index d256029e4041a..709c7bdaa6858 100644 --- a/map/lanelet2_extension/CMakeLists.txt +++ b/map/lanelet2_extension/CMakeLists.txt @@ -62,15 +62,15 @@ target_link_libraries(autoware_lanelet2_validation ) if(BUILD_TESTING) - ament_add_gtest(message_conversion-test test/src/test_message_conversion.cpp) + ament_add_ros_isolated_gtest(message_conversion-test test/src/test_message_conversion.cpp) target_link_libraries(message_conversion-test lanelet2_extension_lib) - ament_add_gtest(projector-test test/src/test_projector.cpp) + ament_add_ros_isolated_gtest(projector-test test/src/test_projector.cpp) target_link_libraries(projector-test lanelet2_extension_lib) - ament_add_gtest(query-test test/src/test_query.cpp) + ament_add_ros_isolated_gtest(query-test test/src/test_query.cpp) target_link_libraries(query-test lanelet2_extension_lib) - ament_add_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) + ament_add_ros_isolated_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) target_link_libraries(regulatory_elements-test lanelet2_extension_lib) - ament_add_gtest(utilities-test test/src/test_utilities.cpp) + ament_add_ros_isolated_gtest(utilities-test test/src/test_utilities.cpp) target_link_libraries(utilities-test lanelet2_extension_lib) endif() diff --git a/map/lanelet2_extension/package.xml b/map/lanelet2_extension/package.xml index e817b06f1be86..d46d05a7f3064 100644 --- a/map/lanelet2_extension/package.xml +++ b/map/lanelet2_extension/package.xml @@ -27,7 +27,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/perception/detected_object_feature_remover/package.xml b/perception/detected_object_feature_remover/package.xml index 686c01621c546..b609ff0257f1e 100644 --- a/perception/detected_object_feature_remover/package.xml +++ b/perception/detected_object_feature_remover/package.xml @@ -16,7 +16,7 @@ rclcpp_components tier4_perception_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 47f6f999ecb08..6e9671c166518 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -56,7 +56,7 @@ rclcpp_components_register_node(behavior_velocity_planner if(BUILD_TESTING) # Gtest for utilization - ament_add_gtest(utilization-test + ament_add_ros_isolated_gtest(utilization-test test/src/test_state_machine.cpp test/src/test_arc_lane_util.cpp test/src/test_utilization.cpp @@ -67,7 +67,7 @@ if(BUILD_TESTING) ) # Gtest for occlusion spot - ament_add_gtest(occlusion_spot-test + ament_add_ros_isolated_gtest(occlusion_spot-test test/src/test_occlusion_spot_utils.cpp test/src/test_risk_predictive_braking.cpp test/src/test_grid_utils.cpp diff --git a/planning/behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/package.xml index a1f86fdf19419..16998b4f27f19 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/package.xml @@ -42,7 +42,7 @@ vehicle_info_util visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/costmap_generator/CMakeLists.txt b/planning/costmap_generator/CMakeLists.txt index a2c3f70b2f722..648d01ee4c4e4 100644 --- a/planning/costmap_generator/CMakeLists.txt +++ b/planning/costmap_generator/CMakeLists.txt @@ -46,7 +46,7 @@ rclcpp_components_register_node(costmap_generator_node ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) endif() ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/planning/costmap_generator/package.xml b/planning/costmap_generator/package.xml index 289e2be0197cb..070c160d3aa05 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/costmap_generator/package.xml @@ -29,7 +29,7 @@ tf2_ros tier4_planning_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/freespace_planning_algorithms/CMakeLists.txt b/planning/freespace_planning_algorithms/CMakeLists.txt index 093eaffa23bae..a08e89143ef3c 100644 --- a/planning/freespace_planning_algorithms/CMakeLists.txt +++ b/planning/freespace_planning_algorithms/CMakeLists.txt @@ -18,8 +18,8 @@ target_link_libraries(freespace_planning_algorithms ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) - ament_add_gtest(freespace_planning_algorithms-test + find_package(ament_cmake_ros REQUIRED) + ament_add_ros_isolated_gtest(freespace_planning_algorithms-test test/src/test_freespace_planning_algorithms.cpp ) target_link_libraries(freespace_planning_algorithms-test diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml index 72fc9d5a0dc45..db0ea35e9bb03 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/freespace_planning_algorithms/package.xml @@ -21,7 +21,7 @@ tf2_geometry_msgs tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_error_monitor/CMakeLists.txt b/planning/planning_error_monitor/CMakeLists.txt index 8bd30ea1fd005..66932c63e8990 100644 --- a/planning/planning_error_monitor/CMakeLists.txt +++ b/planning/planning_error_monitor/CMakeLists.txt @@ -23,7 +23,7 @@ rclcpp_components_register_node(invalid_trajectory_publisher_node ) if(BUILD_TESTING) - ament_add_gtest(test_planning_error_monitor + ament_add_ros_isolated_gtest(test_planning_error_monitor test/src/test_main.cpp test/src/test_planning_error_monitor_functions.cpp test/src/test_planning_error_monitor_helper.hpp diff --git a/planning/planning_error_monitor/package.xml b/planning/planning_error_monitor/package.xml index b70e2f319cd01..e667c81790875 100644 --- a/planning/planning_error_monitor/package.xml +++ b/planning/planning_error_monitor/package.xml @@ -21,7 +21,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_evaluator/CMakeLists.txt b/planning/planning_evaluator/CMakeLists.txt index 6641d08cc52a5..6865f8eef7005 100644 --- a/planning/planning_evaluator/CMakeLists.txt +++ b/planning/planning_evaluator/CMakeLists.txt @@ -26,7 +26,7 @@ rclcpp_components_register_node(${PROJECT_NAME}_node ) if(BUILD_TESTING) - ament_add_gtest(test_${PROJECT_NAME} + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_planning_evaluator_node.cpp ) target_link_libraries(test_${PROJECT_NAME} diff --git a/planning/planning_evaluator/package.xml b/planning/planning_evaluator/package.xml index f7e1d5c3480dd..8681543485c21 100644 --- a/planning/planning_evaluator/package.xml +++ b/planning/planning_evaluator/package.xml @@ -23,7 +23,7 @@ tf2_ros tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/dummy_perception_publisher/CMakeLists.txt b/simulator/dummy_perception_publisher/CMakeLists.txt index 85347b04b3be6..63d07faf0634c 100644 --- a/simulator/dummy_perception_publisher/CMakeLists.txt +++ b/simulator/dummy_perception_publisher/CMakeLists.txt @@ -74,7 +74,7 @@ ament_auto_add_executable(empty_objects_publisher ) if(BUILD_TESTING) - ament_add_gtest(signed_distance_function-test + ament_add_ros_isolated_gtest(signed_distance_function-test test/src/test_signed_distance_function.cpp ) target_link_libraries(signed_distance_function-test diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index e7ce4dc99c433..1635deda40a4b 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -14,6 +14,7 @@ rosidl_default_runtime + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/fault_injection/CMakeLists.txt b/simulator/fault_injection/CMakeLists.txt index 7cd78e35aadd2..0bc1663412960 100644 --- a/simulator/fault_injection/CMakeLists.txt +++ b/simulator/fault_injection/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(fault_injection_node_component if(BUILD_TESTING) # gtest - ament_add_gtest(test_fault_injection_node_component + ament_add_ros_isolated_gtest(test_fault_injection_node_component test/src/main.cpp test/src/test_diagnostic_storage.cpp ) diff --git a/simulator/fault_injection/package.xml b/simulator/fault_injection/package.xml index 961a0af1e5854..95e50e6448807 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/fault_injection/package.xml @@ -19,7 +19,7 @@ tier4_autoware_utils tier4_simulation_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common launch diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index d62a84e7d7b6f..6034697304059 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -28,7 +28,7 @@ rclcpp_components_register_node(${PROJECT_NAME} ) if(BUILD_TESTING) - ament_add_gtest(test_simple_planning_simulator + ament_add_ros_isolated_gtest(test_simple_planning_simulator test/test_simple_planning_simulator.cpp TIMEOUT 120 ) diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 761aef0e322f2..2c63c861039ed 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -31,7 +31,7 @@ launch_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/system/system_monitor/CMakeLists.txt b/system/system_monitor/CMakeLists.txt index 017e08393baae..65e933d072046 100644 --- a/system/system_monitor/CMakeLists.txt +++ b/system/system_monitor/CMakeLists.txt @@ -180,7 +180,7 @@ rclcpp_components_register_node(gpu_monitor_lib # TODO(yunus.caliskan): Port the tests to ROS2, robustify the tests. if(BUILD_TESTING) - # ament_add_gtest(test_cpu_monitor + # ament_add_ros_isolated_gtest(test_cpu_monitor # test/src/cpu_monitor/test_${CMAKE_CPU_PLATFORM}_cpu_monitor.cpp # ${CPU_MONITOR_SOURCE} # ) @@ -196,7 +196,7 @@ if(BUILD_TESTING) # target_link_libraries(test_cpu_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_hdd_monitor + # ament_add_ros_isolated_gtest(test_hdd_monitor # test/src/hdd_monitor/test_hdd_monitor.cpp # src/hdd_monitor/hdd_monitor.cpp # ) @@ -213,7 +213,7 @@ if(BUILD_TESTING) # target_link_libraries(test_hdd_monitor ${Boost_LIBRARIES} ${LIBRARIES} # ) - # ament_add_gtest(test_mem_monitor + # ament_add_ros_isolated_gtest(test_mem_monitor # test/src/mem_monitor/test_mem_monitor.cpp # src/mem_monitor/mem_monitor.cpp # ) @@ -229,7 +229,7 @@ if(BUILD_TESTING) # target_link_libraries(test_mem_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_net_monitor + # ament_add_ros_isolated_gtest(test_net_monitor # test/src/net_monitor/test_net_monitor.cpp # src/net_monitor/net_monitor.cpp # src/net_monitor/nl80211.cpp @@ -246,7 +246,7 @@ if(BUILD_TESTING) # target_link_libraries(test_net_monitor ${Boost_LIBRARIES} ${NL_LIBS} ${LIBRARIES}) - # ament_add_gtest(test_ntp_monitor + # ament_add_ros_isolated_gtest(test_ntp_monitor # test/src/ntp_monitor/test_ntp_monitor.cpp # src/ntp_monitor/ntp_monitor.cpp # ) @@ -262,7 +262,7 @@ if(BUILD_TESTING) # target_link_libraries(test_ntp_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_process_monitor + # ament_add_ros_isolated_gtest(test_process_monitor # test/src/process_monitor/test_process_monitor.cpp # src/process_monitor/process_monitor.cpp # ) @@ -278,7 +278,7 @@ if(BUILD_TESTING) # target_link_libraries(test_process_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_gpu_monitor + # ament_add_ros_isolated_gtest(test_gpu_monitor # test/src/gpu_monitor/test_${CMAKE_GPU_PLATFORM}_gpu_monitor.cpp # ${GPU_MONITOR_SOURCE} # ) diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index 8cca9d2c71545..559dc9c072592 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -23,7 +23,7 @@ chrony sysstat - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index d85b418d6fcbe..36b96a2a300c5 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -28,7 +28,7 @@ if(BUILD_TESTING) test/test_raw_vehicle_cmd_converter.cpp ) set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_raw_vehicle_cmd_converter) - ament_add_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter raw_vehicle_cmd_converter_node_component) endif() diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index b14b00c9d3963..4f36c95e5d82d 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -26,7 +26,7 @@ rclpy - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common From d52721f6002782aa653a8d8f8a98b779221490b4 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 10 May 2022 00:06:41 +0900 Subject: [PATCH 08/23] docs(virtual traffic light): add documentation (#245) * doc(behavior_velocity): add graph and fix link * doc(behavior_velocity): update virtual traffic light doc Signed-off-by: tanaka3 * doc(behavior_velocity): minor fix Signed-off-by: tanaka3 * doc : mediate to coordinate Signed-off-by: tanaka3 * doc: minor update Signed-off-by: tanaka3 * doc: fix pre-commit * doc: update docs Signed-off-by: tanaka3 * apply suggestion * doc: to intersection-coordination Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- planning/behavior_velocity_planner/README.md | 3 + ...iorVelocityPlanner-Architecture.drawio.svg | 1663 +++++++++++++++++ .../V2X_support_traffic_light.png | Bin 0 -> 91648 bytes .../intersection-coordination.png | Bin 0 -> 161821 bytes .../virtual-traffic-light-design.md | 267 +++ 5 files changed, 1933 insertions(+) create mode 100644 planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/intersection-coordination.png create mode 100644 planning/behavior_velocity_planner/virtual-traffic-light-design.md diff --git a/planning/behavior_velocity_planner/README.md b/planning/behavior_velocity_planner/README.md index a7feea30a3017..20ad38140d330 100644 --- a/planning/behavior_velocity_planner/README.md +++ b/planning/behavior_velocity_planner/README.md @@ -5,12 +5,15 @@ `behavior_velocity_planner` is a planner that adjust velocity based on the traffic rules. It consists of several modules. Please refer to the links listed below for detail on each module. +![Architecture](./docs/BehaviorVelocityPlanner-Architecture.drawio.svg) + - [Blind Spot](blind-spot-design.md) - [Crosswalk](crosswalk-design.md) - [Detection Area](detection-area-design.md) - [Intersection](intersection-design.md) - [MergeFromPrivate](merge-from-private-design.md) - [Stop Line](stop-line-design.md) +- [Virtual Traffic Light](virtual-traffic-light-design.md) - [Traffic Light](traffic-light-design.md) - [Occlusion Spot](occlusion-spot-design.md) - [No Stopping Area](no-stopping-area-design.md) diff --git a/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg new file mode 100644 index 0000000000000..4d2808a5be41a --- /dev/null +++ b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg @@ -0,0 +1,1663 @@ + + + + + + + + +
+
+
+ /perception/occupancy_grid_map/map +
+
+
+
+ + /per... + +
+
+ + + + + + Blind Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Turn RIght +
+
+
+
+ + Turn RIght + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Turn Left +
+
+
+
+ + Turn Left + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + Occlusion Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Private Area +
+
+
+
+ + Private Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Public Area +
+
+
+
+ + Public Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + Stopline + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Stopline 1 +
+
+
+
+ + Stopline 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Stoplin 2 +
+
+
+
+ + Stoplin 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + +
+
+
+ + /planning/behavior_planning/path_with_lane_id + +
+
+
+
+ + /pla... + +
+
+ + + + + + Behavior Velocity Planner + + + + + + +
+
+
+ UpdateModuleInstance +
+
+
+
+ + UpdateModuleInstance + +
+
+ + + + +
+
+
+ PlanVelocity +
+
+
+
+ + PlanVelocity + +
+
+ + + + +
+
+
+ RefinePath +
+
+
+
+ + RefinePath + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ + path_with_lane_id + +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ Updated +
+ + path_with_lane_id + +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + Updated + +
+ path_with_lane_id +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ Data +
+
+
+
+ + Data + +
+
+ + + + + +
+
+
+ /tf +
+
+
+
+ + /tf + +
+
+ + + + + +
+
+
+ /perception/object_recognition/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /perception/prediction/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /vehicle/status/twist +
+
+
+
+ + /veh... + +
+
+ + + + + +
+
+
+ /map/semantic +
+
+
+
+ + /map... + +
+
+ + + + +
+
+
+ Planner Data +
+
+
+
+ + Planner Data + +
+
+ + + + + + SceneManagers + + + + + + + + Crosswalk + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Crosswalk 1 +
+
+
+
+ + Crosswalk 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Crosswalk2 +
+
+
+
+ + Crosswalk2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + + Intersection + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Intersection 1 +
+
+
+
+ + Intersection 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Intersection 2 +
+
+
+
+ + Intersection 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Virtual Traffic Light + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Virtual Traffic Light 1 +
+
+
+
+ + Virtual Traffic Light 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Virtual Traffic Light 2 +
+
+
+
+ + Virtual Traffic Light 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Traffic LIght + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Traffic LIght 1 +
+
+
+
+ + Traffic LIght 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Traffic Ligh 2 +
+
+
+
+ + Traffic Ligh 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + No Stopping Area + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ No Stopping Area1 +
+
+
+
+ + No Stopping Area1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ No Stopping Area2 +
+
+
+
+ + No Stopping Area2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + /planning/behavior_planning/path + +
+
+
+
+ + /pla... + +
+
+ + + + +
+ + + + + Viewer does not support full SVG 1.1 + + + +
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png b/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png new file mode 100644 index 0000000000000000000000000000000000000000..19240ca64224200e0b4b5791465ccf563f3fd50b GIT binary patch literal 91648 zcmeGDS6GwH_XdpOYe7-KMi+P$=~AQgfB(~cwD-Zju5S*KdD=YBnl-c5z1G|lqo=D*O~p(_K|w*S@%)(q z1;y0~3X043u3sacQP({ukpHguDr+9d&w@9^5)HjXc6bO!)dS>iQgMxu4pecJqe+Hor~ z%}F*tqoN#R1Cp12mChH(ztzwaj;8Plk(~)@l-@a2Nx8YS^5M2;sJvtP`kM{QRbMP? z7MjpL%bxe`+c%|4e?Odp;l6QXW#?`I;QuaIKLSzyul`l*J?{Tb z2gT^I{$E|_4)pT>>c2Ua{r~TD>$7s2|J7fo{lAU>f1z9YBI?PyNKd@B)I3_<&*tKt z-|_Q}^-K{VXgsu=qoF#Hp7QFCP09VDD}P^>?)gVwLcyT0-K3B5zBv0>i-Fwvjw=~O z{zu+0gHW~hqTcoK0$%|ztVRox6D4_cglhd!Jf5y<&f+$Lk?FEuwkbBVQ}9*laA9gZ z>Fh0@K{%MRNVVAg^QZk6RgXF;D6|L1;6?0~!=CEZ;GQGjp|5Lm2Yu&h=AclylhOmizfcndu=BxO?Qf5YkZQ!HD-Nxu4o zzW^Yhz{<;N4=u`a7b17l!kXk=A~Mui-9cmia)O;L#`quwy=FWw0|5-npJk{{cLpkqy_uZ9 zFTk@x0||GEsgx8yx6a{#jT#c7a1&pgNvi;ufoG!Vy?wQ68q!u=faJheXjmsAu#0b5 z*Kc3|kf=-AeH#D(_u71)1KOft_nMDlm2ufDV6L=?!3x@% zx_R`|+C4e_c0o!Vp_bOjgNQ(^W4D|=XfhV4rl$|8#&$45+D-gDx-Y?)EaahI8x4}I zhmF^kCSarB5)(*THsDC3ZIa7^5Zhr^>74hJ{_uwWw|7s$hk^0X2j*5l!=iu)=BmP$ zHsIS#q4D)#yZo(tWoO+ZinUmM>@Tb>s;hNS=FsGzPDa}%fN|)Kh4_%M0*@hH_ zgL@duPk9|2D(m6qm7rJ+$Bs*c##1BwCP?+2R!IVlS&@#-GX20qPgc0|c*P*B8oIGT zu=M|aMN<8*t@-M1@oLur7?`G;<25qET&CO9L-on&v$XO?5sQNtGjxY&slVQB?V+1# z9^_NsQ=zG1an;xIJsT@WzE^vY{#*kR+C0}!7XtRjCGTT?c}^5~srLhnzpydEY#vJ^ zcjH2Mr1sawZ3J;^tgsXoT({GK6rmMc;n-DO$q&ac_5O@ZzlNO9Jpbx1H?DJf(gqIu zh-NCTW5|I@grXmFRSidk`_{azB6SV{N6`FuO8bk}i5=_`Y$@cP|IxW>SAV~W(ziF} ztPct%yzgML0gG9}fz;q79Lq5*clPS9kVvk!WiBDRxFlY^jPC)!yL$)r={jE5O15W}!dEHZrvp-nOrA-{xs)3c zqr1M@9_%fHNp5yl3fJVrKV~e#Z3gREpyOf62yenOG}K~QCo1Ka0!TqS*PeZ5FqED* z#3-G{$j_40z%QkpWui;i<@_T$#g36FV*%JIXU~1`X~Bv z3Z*;+NiIZXX!wa_n7$n4%c&25VFbG0NAqM-2K*H-eatf~3MtLQ^P~7@ODe9UcPlw8 z?5z*O5b?vUe*`$Xw!e9{87;C!96zQ0VZD*krT5tjsmA94x;?hi3<0gs<;Q&LduP{93F}x zHmvLhJ!+g6skiYa1P7I!Erv=2Bwt2Q z%J1KY+A{G*+xYksG!Ps01q;mJHFg-(Q&`VU=m&4?2jsZoj2+agGr^SO95xy6NXXH< z&;yw#n8wjZ8_!JMl<8Ppc)>NRjc`3P1!Hq&A{s+M6(>Rv)Y%f|-t};lRY)FDkOg@` zDdZNo8_de=3bAbqf#}NJ=ISfLVI146L(J+W8XlO)sw~os<36aGxA??JSm-2!E@;XR zXd@V%q(;NgU}XT39FIgE%~Nv#ra<;;D{#%C$-PRE~>gSQSUBS zO-iuJZI4&1cp3#Bz@|k1JwD+D>whv`-Nz&ppWcH23Lh{K-IM zKlBw5+GJy(_x|I#cjRQaw^HABBK9B6BzN|l5maK74L8>ud~{q@vg5O;E7i2zq#?H) zmQQXDYDjGbZJZJHJAbZp=~8V}Mhdf?@d}g&E)IP4X~Pxb1J$XjIiDOWJ?rwA^)hyA zn{2oCI_fUpC@9ju2r9HD7PvieKBh9NirIPD&1NKH?zd2=wG8*n=~(#O&yjJNbpIZ6 zjQJqKVgbg*Hiq<-^%{DUkI7KRwCcd@pdTxb)O3F{-^_nb=%+^ zX}$ig4RF*eL|7vug|o-h&Hg)yI<+Bc?W?OdM0dpA^uk9I1#vbC+Xnm8$&)lcCb0Y= zfmxdb556<44-#dw6*(~v>t+iVeDc%Dj>WLp7@r~CsbC|eklbAkAoierJ+FTqVhb_NX#UeRAA^NWgFb`^B z1uz%yXz;aU^}vwcs6?B4o#i@j`E7v8EXrIh4n{{A+desdb~~f7zQ_1!u~o%F!PUrN zyIg?~vh*sTZ+>$$2IsgepI+X^zj`|JUjP#1W&0ktueX4@UXsmPHCP#dSa-)gg0nTu z9e)Zhn>`u5U3?^DK>S$acuCAg$7iDqY16>hu=_T_8deyH z#5v_XTf?6+^m%U;QdwM!VxYY>Hb}`)cH#IuB8}>z1#`NCY_N#dji?gMxd8}`_*Hpr zqpDsDV~*j>Vo1hGG>GwD1d_n(GW;p)1M}{}ixie2AH78iRVHNL(7V??wS zuJq>8$EI^{d2@QHsYnTipc*Wi0YCg^&PK05vR`vFU!6GQimaI~vYSgt^*`9!*&nMN zrm%`gFNFcCHs)@$f21LdHQvE}eVy4X*VX$6rF?6TS|-^Ov%rML#m=i9_3_z;FD+H3 zGq4!AiAXB1L;ZHP4y8$5efz53I;4;O!Kb2j{orkXp5sz(92;nPYRLchSXE7)vGCpj zZf)H)LnTQq+~&!T|8UG}*!2k~Ez|ctcFYbPV)sS-0RDyRG;nJX?_Wz$--PSJ1Kyv( ze&*9K3m9649yti^i=5r6bzVga0FK*z*GQM4l|JRdB9?S{j9p9$a1zF6IVz!{ zu!8v$en_0-G9h0T(+V)(NQ-oF_>eb_=2!1`V1>Dk7L>XzXR%EUO}YkxYKekb-9E-n zY3@l&i)AUxpHWD`NnH0OD%`eVPMt~#gE_(2aPHOfiK)`ObFVK+>}Ddt)n~JwQ((?M zlS#(d_PiG(=&s9jD>CIYCJiW7IKZzaq_K8xaq`<T*+lao^s_U23ZNYZX-8Vhnr@%CkysmGjsyoS|lfS-g!=$N1rz&R#)DMO}R_| zFBzQ~?@X|WYNf#rE*NJGE#OPEmgqwxTv*@+;jx#>nRI6sKJ_sHw?_F#>QBNRx*v_} z#kFB7q{q}hmT{vMH`73-%Latu!U2C9*VU$O$*n9Y*zCCidJyVKcaD~3ZIoE|{-oMr zs-U~Uq_HPO7_Yer7*ROD)IRHFizU32kM1LgNgCdrV00!b5Q zgE*+@o!~qj2p@dWkPr?y=y<1+lEql@^Ve;Gn|t~|VD+E`Vtv@D>(qp784tYc+S#3? z25;_W{tZW8TrW7OyfI#MqW}}OZvJDqY&4SwZ&@4k_Atl~Iw}4rJ6!CWNLzAfKt1jS z{#7-_KC8aD0+?p}MtYhBVPB{jL0A|D$YKFI3fQEFS44$kCbn9f{?%?8g}y^Z$zT2E z*!C%-+}$o{+iTPnrU8TBL7k1QqAuLadrx2F%>u?M;r*rDXIZuR!uYd*xAor{yBw46 z7Ih*dykpvJf|ZWxx+LW+)0qA9B{YR9cOGREZ|JRD<|lMo6`5n-3mKsHoIR|K%DB&m zAD<$vg1Rf(^8B3f@9d0r4$1RG$jJ5jcv0GH0s105=5G8P-RIcP>gcmW^-T; zJ7$ipfy%>Q^E4urf1uy1V2!ipq+8Ms88CSGBiB0FBM=z&j%J+YAHohJYq))eftuw@ za@^XL5*Cp@*<(50lMIKlr4(P9l5Z)lJ2d5v&~&U12KfC34xqiRKM&VzQP5XC6l4w# zzZS(ieYbQI;(<9nHD_hzYY3b`Zyd+o0oxv*;V&;9jTgMr?Hc1cf5>-4)bvPXnNs6_ zDx&SS&3w}SB`|K}TEEPQ*0$bAL#i|3gD>whSehv!T(xK~!bHKZP8a9mHg?0QlIn@! z>65>xZY6n|KPS`f=j3$<=1!{KG~FpK-0bk;cuRbgBIozQ&62U;>mmLJKmx!Y-Z?&0 zEMODc+BYn(m=Vze%IHbyXIwiH8YOxK>6^*X!L6Wc?BN-Wk38-3<&|HLwtG%EcFl!g zWLjO@MC?MfF?)wam;E^u;JVfoX~}W%lCpfH%I;yi2-$Yc<17f+#V_CUg>|iVb+Kxk z^VNm&wqnDgQ(i4x1q}U0E6SK=zJ~9FSgwfu!L66!5_8gR&{gkW?{*=5DCNZ{USD1U zma|*;U?>l%!%k2~aceD=5o{~~e0uE2!IFN^Z6{M3vb|wl6jCq|%kvt4*d+zO(N7p% zQ^fL!DTj2>!Im~w>(onDdox1)<;ftOFw{)FPk)6+2H&F?_G@B0ws68QOXv}gYlZa% zk^Iz7pjKRNg5;U^F#KcbwDaKK`2VX1o~T*AlBpOwDI|L3kx4dSL^ynCVrF%P z_ho&}top+KOF5*aw*f4C*7vq+UA2zx8`C|g$Sce2y}lR*@u@b-DnlY>zlsXKEd2TP zt42VAO?vHiEzg*1`$^ps(^x0bdsL!si^X`oP>9c*fdh*{ZLVY4ES~LxHR*BQ3%HGR z@VwWNLrk7k8+b!Gx&V0k zX!#h5sjEAz zHK*HpQsfP>uUO|3FKKrT3w6$|(i2lm>|uFVdub|5jgv@9^B+C>{;XV;WwG^) z??$X~mG|sxnlxRj+)(Y2{rN_18KDLlVa1Ve=!nMnYee!lg!gvlN{N6u?PDIw3>HREp>4v8)ZGpmD^aO@Af z>$ZGO-HFnf|ClrkvJ5tT|DjjS{Q${TrKi6T7l-2)%ikC5VpYylEKwVJqap9rxOL;d zbaexzGGS_^?)enIHs6{3TFvn+O`FB4{z`caH>-^lwa3j+NUE@$(MLIWJmw^t%ZT~3 z{KD$3kJm%OmP-X1sNkPy=Dl6+z4kT77Sra=r3^}zD4VPJcyX@G9fdJF@C#V`t(#J;-^uPPuuz3k(6sPPEY;eXj@TztI*Mc+0t1Iy*r)s#m}Tz<1>f+{NI@A(RN-tYPHAD6%C7H(Vdf;PT>%=L_?TR3C3!hE&7?_h>c zygq!F)@bXa%XNt502l{qb4OGC8}<)`6#oow3BGx$tW1mY;#Z-jijm8wj(IVb&9MRn zGkkb&x(y`P4+oD2@v+s8IdWE@A=`C{(@^nr6BGH1yU%@>4_K zL!eV+c^*BBS3~eMwJQj@B4{oHrOqTeI7Lw*<5q8JLtrj(F5vOWkCaBz zm1{}n`YK&&m{zc2BQOfxv&s96=J_klk>+mRvagb9@n1OUC(h_EUcUhXF74Q-3`(?3 zNVGN{CtQc;xYq5v0j3W?87d_vQP!tdc=q2sYy0$y-O@k z3Ugfgk^1;fqTA22LGdjwNX{g z`gD708of{R2UX`w*&-JrQ=9eaGHO=#@(t5ESO2q0^vVS3hl+_@?_IY!(GygJbKSP( zHN${~398>X^D;h4>i(X&m%u%KUA*9_GB==_)CqJmG{Hr-c-DkHCns0Ur#!A}kPt+- zKt35+Jva6b!+i<}YUJ4`s6yb{*F9mprHJpmp5Ak^eZOf)3`;r*F~W}XS{O#VQw!#} z;#=egb7{%~E@t7)$Urxz8QB|?A*bWE*GqNI#~RrwWt(T5g7B*{FZcTYjbOj(B6Vwf zov>DlX*dY7&(0G2IkyqD$*8h_48V(D!L4xCfS0$^_#D)>Oa~HJ2Bn8ydse3^$%`Zg zf$htENCBAtWd8XurDfpG%CdeGZvWDhYqrVdwQrs|N1bx5FUrlDyc=Hq0?YX2R~koK zqM?1H6e99jTgrVOH>1UOSaKv?`uU!z;2&65W!#^xq-l3mG8Bu@L}PKS)oYYVV_ea&LVL()FvITT1b1 zlmcbswfG<_d~;#eeB-7BLUIox?suuA!=}l)?X<})DB>jAWpz%VQqd~uEq%N!WmbzL zG-BLxxh!3^=Smwep~{Tq)?bx2$SD(=I_D~99J;BdOs@T9al`1 z5u>j%rOaEzdrAQH=knr#L~GLeR#q84Din!%d9?Rn(@52K?kM&z5_!#}S}yN&#OG1s zAoZT;S8-5iLCoxjw$r~lNl(f7;_M1z_uE)w7j*U-L*BKw;hbZwHrb+WK^luBExC?w ziAKeMmSHI&X>R*#bkWantGpZv)hF31kpg4FeU4tRdNz`2pO+;`<2Y=8setUHGmP!} zv%;kT>haxZU~GIa0V0nK(jS-=P4@Ky13>0p*T>J4Q|QI5(rVSq+Si!x{3`n%2Uz`Q zz?{XSm1(5ZF0EBID#ruhYAG>ZiH!BKZETPM=2=RHRZ*9Bk&NUXiRirTOmSoipBh^j z*Qhq{r2Ro$^*vd+2wcGpSuhv@h9pRtYn%m|t+Tu?iuJJ`vshC`#`H4Dzv+95^p@)r zt4V9m9a!!9$$RM1qN1f>V~sLdI4T`9)C){7U-ta`$EXvaVrk#kH-c zFk_(VPNDcVo6dtZYJAi`2hN3NBWN@hra~7F%{^cwR*cU+&a!Pvf#{pd-4mEl*I8Q2 z<@N~k%*@OC+2cDoRq{~-P;`Khz%}g`(P!?T_7)TPZvn@H00*NsLO?cp8*f~>-BBwo z6|E5}G)Lp{BjpU+E};-X@pVP4Jp=ajCIk*mzu9{j(8TpOhtqIX*awVYkSblY2eqv9|tIxp^1O8S>)8FqfDPlart|ETzf z0^N%0Lx*LRzRYq@N3RmbRl8QB)o|+}p58t)yH`%)8*M@8$u?n_KS>$FY%Apyl7l&2 zl@On~Bz*LLT!6&jaGD?9BL%IsJ^H>(w@`A_w6Q-CYeqFFYSwUkdDX-u^hSc4R~k+D z@8Ot@n@28qE5l=&91e0X9K-eyMlnkLE~I>;!x9SPg6vTW%3_O^?JH9 z6h3u|LyT{*&$)q?^*ryig+|U=FY0`d7N0zNRg$yLra!>1u}3>`vMedXRH9D&xQ{WH zdjNeVREK+E{=U$wUh`Gur`95~mW$D+3u-ERSYwZ-hv{tHtX!$-)vk~E$)oP`YU(FT4NR9h%znQcAm_j|OuH@2 z`*W-e5b5kOE~dK$aQg>&E?7sEm5sJ|BPBSFlfmnH=puL~9^~hrTT2TDZh$8){Fj-Tp}9W6?Ok7r2j>fF4EV!q32HncCo7Q; zc*T^bo>JF}$30;c7m8(;?kkgI#vLr8K2N+J@TYNTpKm<&K7PL*84tTPjfE9OK+(K* zuiXumNtN5{TT1VVo=I00UHjDmm-R6t4I{gD{x4EG)Tk*y9JzTQ6YRFp(>S)B@{ z!shU|zFF6V$(yulaafw(2SpK0Fr8qdE=lf83v=Y@yGd^}1M6nl3cuvk7#BI1x*X=Z z<-hTrDOxu><4Ediq$(~F;Vk5}bJWKy!lT}xPP`e90T*~Lbdyv-I|8stT|eQ05%BtS z80tc0ap!#NRmF}<8Wr~g&3vD+tAzgyQrj844anhI>pCm*j& zb%>W(Yx*VxM;a+qZ%|!W_VJkXmd)Ez@?&TvG6{ZBK6-xBc^QmIp$IR`@D<#IP zXHn`|7i$l|=JtvSQI2@`^v0G(X)a^cxsTbztb#ImKpB!9yV(*7A>;Xj&OP24#e*9o zsb1KMx(h4VJ#?-!(`GVWxyXIda!je(6_>p5#t%qk^fg9sV?hy!0h7V5Wte_l{^vf?B*nl|ei4Je(}4+b$mC zz#-iNh9)IFP^ERm6Q!%(Z)WjA>jwCBOc>|1*E!F&B804_DvIkPHcGQprjUNCu&-Mk`4i+fH;slXBc)3gNtG@1Qp zetL<@smxaxUOZaec{?x(5!kJbg*5j7Gi+>1H$U~IWncW0k`a*hF^Pc}oWx?F^w5@^ zmXhN;F;B0Ia)4z4#3C&`>b{yxe!r4)6kUS4wZD)j)S(D(lT_*mv9B;5I^aDtx4j*@f%zgG8I|Mj9a&F)RwN5x0dvdxL*yG7|J`_$Y+yHlvZO0PIx4KcoKA^iqengy zl4UCp5FY>#RioWKJf*9G{w!SToSQQ-m8vfmA%lZ|3`7%^Y%xinD+y`j1;tiF?ksYn zSnf0@XO<_ih)L#(?K!0BY(UCqF+|4zW@fyqK@hP4>Zi-WZzjWRsP+z%r5`_s6)8iS z9%*i*WqO9s7}7CUFtAaBa5gOdh<1zB>Y(w()v~ou|CXoqaPzM?!x_0<>i3JDZ>9@k~)tm26sUpo0`y;|0t-mVKLoyC-f&KGr zdWoTQZ9ICgqMs;BrXqs(8!8-=SrOZkWb8%ij4t}|pGomTX`kuAgKWwHzc*K%cWMI| z^3VnRD%Ar|`39^@zq^jRtqY_aXFSo78{!gA}i?z9rM%UI!PJk&*(=D?FSFCpCha z{nqLd=9|PrwZUsN|D(To(*0r3?JGIK!oho5tfWfgET9A`+~KW*oG0YGMlEu1-sWoe zGd`Kn9`zf4TK@XB_gM)A#m~zV$N@fl`$-2YfpF5>FrC80UP0(*;1_?QxT4rMfuEd; z3SgB(7aE|y?qrcv5G1c6hn$>(zo7j~{%tZ5Pnh;`mG1CO)(J4K_0&}>&6>PON-`+P z3zyzyA(35Py@5q%uoU%Qan`>^*pi=MKf1yvif7Ato;Zoo+de;*uy}$Y{lH?{WM4#4 z{$>At#lO=e6Z=-EZ8*71jZ(gV60VhL3X!ArSPOrXlZkPed^Q^e)#xiO{`TdQf{DXm zw+}z-V6x)BSH1e7KOL&{Vm&iZ=FW2z@_bka5Cx~C5qb!joCl3l; zNE`T>QBIx29|b&l^&g|NGDRyHP2swk z_}aGJ?0Sb1zU@!GJqlH>UeLFT4HZ9Q6_L2PF*{wTged%eDeTs7dQ@xX&*n zue)Jg)znAZ+ym!m`t~uT*8Su5;R=T*K}y=FR?ddgMF_WJ$Sb0AO2IvBTI`QbjMm`2 z2sJ%5zR!D+Au@2rL>_;yr>XxEQXOAg#778Dp2Ig%+~Z9q>w1k|!jkGDRurUN>~am5 z6E}YJ^%)TO=-83`Te~`_>pAmEkv+WrI#CA3KOL_gnwD-$H37FqX)L0Ma#;`i4`>g# z%u)zvY@BUPDj~XtRb;yA>vh#X`gpx=Vo}`M8&F=XVAV2P3F_jG#N0on3kz7dwhZ^i z<=7=35abOj7o8RmwuU`FO^mWe4-VX-k*hURiCOCD^^2gQ!nR(z2EuwqhtfQ}oEk&m zNTyMUFpaO1qyN+KJm+I@kzvnlj|8GAM(R=}m6JLbXJynqj4>08%eB!~#-CNHt zR|Wm9!*{k~B86yjY)%;KRR`Gv(Fq*8W8}rQPY7vXU&oWtdEaC3N$wQepJ`1`#rG#Q zDoi>P=u*Nz`9Rvb=Fp_&ch=?&a6O#%I~(BR43kuMDMD#81L<8YjG=c6-_bqD$sgZj zfc5O$i4(%L6+3(*{ z9x^VbJ!T~w3jKy)gY3?(w{&R-U-pQp<&KrqYn7v)^OktT&vErVC6#0KHdEtL)-9P1 z(wLpsR=smo&4l}*=hb`*j<_B4~s+(7OI!1SjmjWo?gt%dv>_%1lqrK=JAb|If#;x$>xUl9eQn}2lvZ)|OQ8t2%(UjJ5yC+Ts@LM*VKsOk?;oYrZQxF&~J0rm<|5SCIcOGS0rxM~*huF4QZ0)GiZaJ^e z`!?NwFgTd95jMYgG51c>=3&YCi|CK-ry+EY!N{)CK@XE|Zu*j~2W14U2*^i;sr=gH zkQ9l+IdD;e`w)8fD2z`bv-+rj#N4r9lR{Li^kMr|!rJTOcNSuDXuAlLL2M+0+MH#o z&gfKNjglI?iS|5%7{BF40TlD%;^HJ`}UsaPDZ9y z9O3oFQCmKA9aH%SIxJ!jF1Hx%v8%cUg{B3_i2<%l@_K~45pj+6KN{kYS27#ge0l|k z4$mowqnv@B*e|4V#P?DeJ;Ueo~=nre6f*Q&FM62;#&_0`$`!$94*E zAp@;5UcB-&`o(9j+0R%N%8pEEHR1C=>nrx2vk9-YERC*BA@3i^E>5{03x&47wO)v) zb_F#)S)^M&CCf4qAK@O_VM(MjLoqx3Gm?_>xJjYfz^LPKgVl0gdP+T)!)Bz402RAe zs6Krp%!*nd+5HcY_|3`onml{I{^MZKQ%e0YWb;D;dIk0(@^KScd~c)z!bZABb_QD> zMPH^_-@_ZUAqDf*TF=3cO67EUB^Xi*cy?o1!c`#0gc0>_x0wYm@$!N}xSB;m=NzNc z=kSJubVE;Yx7nR;G|UtnH$T!C43NfpYkth?Og+l7 zPcq!9F8wA;{xr|ae|@28V|zxCPCu2=nPWUv?#DEMmful>rvvK`W~TTI7DWm3HY;i}Q#DPYn$P`KrMB1d{(>T1jVJbgR`HrzkN<*rbp~X~rBa`PGdc|1)NLK*PbF$9N$@;{ih;|5-z?QRx#p zd3h*CR?OJDz*C$@cQ6y|HL3LXFQ$VlTL;*Y%*d-%7%Dt#}4JN9bp%ge!BlWf)0P3ur_a0luM zOG<;|rr*Q?Tn=znC)HNRt0H|7@T^``+_e&(L~4k{q(Z7#J3P{7ZB;#n&o4~NGV>~1 zPJ&lm$4yN*r)ySI_J7bA$<+fx*s}h;k$}k$tG@r^z$aBC{EJO@84P4-QUo3A##}sW zuI;%s?ese0qsXW>^ytgWGuPdx-Fz1%kCw$Y4SG1HK}QxXt~h2R-%@S$a{={rmYYT+ zwx-~HdAtU%$v3-T@K(Bx(JItl!K{)5v@id?*yye7+ko5?vsMMbA54tN7HUoMVfOl*#-KfWZthH@2#&` z+kcD?uC_d76A@EB1R8uB5uuacn%vE^=N0F)G6T{>`CJk;t^3E)#YtN}kTxL)+1$ZD zffhx&g#0^lsgt`-KA_k)b&9FSHt3xAmsp3|Z+%B^H8k*?bJMfdZyWZ^F#UmSE7E^q z6~#>E@Dn=s_=#N`)=86*9;}Qw-^qlG=B&A5{vSu<@)ti+{7&U01$FE_7+PPq^W`x1 z3bjikHmtf0(e~zT(*1co)qjy7KuUs z@VA8r{@XpJeRE9mu>43d>0@5rfP`>7;H+Py@z38u`B0SL0$d$^U=L&Rxj= zziifeav#Zwfn-&^Z+sQm%jwqJH^p{aI8VwUA~=h!T}XF+eqQsJUUB9W+g*wmy8mrQ z6XtG&X(2B99+Yr*^U6w@ejB-=X`NieDwI~yBj-AmER*se4Z3nV8eueU_ zJp{JSAUtBHOIZ_F%YS4P$n~N?=d-qS#WM?l)jOxNe%+iNhGwfzXp2isgLl2n4@JB; z#p?pyp$9XUzk!cTW?5roNxX~#pvzxvDH#e1MmzS%ah^A3-7%oL0p(Pzx)PJ|vMd_3n+uc%($I3h!{ zJO2K`hL%aA=;s>xbuwG)!dBA@@@Br{^bjk{4AcB5 zsxf$N3P|rVcdvr)WXl#p0>7ijq3^$*zWg_sdp))MWO7V_FDcxz^yBK7eVlL77SM3= zaMA_M!GxO5t%9N@emv4RT-x|OV#d7fmsRTFJt_X9>4|E^&EINWpzoeDWs59MA@`HC zUBD;EtG7|QMbf_RT%&X4QEI&F?Zs1UePT~}1)o~)TF?FXV1kjXUOR%3L$uwqn9JMY zEeWj#RVmSR5b9oCOqUKW) z?$S@Uzi#ns=Rv}y@ozV|429W} z@h{OvrjlTdGIt@bvE~%1$mpy5vhqgK)3Nqs^tdB4&jIFdNnGZYa*1{)c^a`!mt-T} z!?tUO~OtqO>dH|pyngsH23n+QpexpjzGCrZrHJqaE?e7o6*i^O(vmak6c8fq- za01`=_x7rPV>+#-^j$ps5{M$=1eYr{j4c~&N!(ttj)nkkwGE*$3AZnM3GuntU&P^m zVhTyy!4X?hKn9oIC_m0;ls4E^jdj$iSq-#j-DpeJs+e`E!X%CMrb*{zY0NH5OOGrP zrgbn=THqhu%^R$fn;TN6HaO?0pY3lyx0%Eq$$u7;RHNV*w|^XEC)y`1AqJkZ#uj8# zR^_V9PlDvmib#AczJbyX7Xv>w!m-3hQ*F&R0+HLzz^`3=mHx0G!<~uT#c#B*FGSp3 z2Ot^O8rIC9x&BF@G2RKJa(JM**w+a=1#IEYwVwBnB+UKtoIyL~vS1WEC(ek{%MOf# z{nRZW%P>M~6S&QKLxZjAeTqM37aFE^`Z;T>-*EOaIn>Auds~vt7ffiZlFhBoHjS6d z)c`*#mQ5|AJ~Uf8SZHCVSmFEYb6!+!Al94I4ImMn#neM-<*iTy$TllT=_Q0Hn_9rS z9h`hHVC!Orx-MWiAMvY)HtwaQ^N`yq!lnBezfV6=JE}I9*JOs4iky7WJFW>siO}(1 z>{{`;vDx80%TRe%W!Y&tsGyZEDEUggzBjUFv(u%O?5s?8GQ*a8zfIT3SrYr$fq$EvtHI1pbH&4YQ7RuqRTo zwdjm4s@q%>f!}4V73v>rN6(JP3^`FFpL_S8Z`1N~w&;n|-okIt#u6527wjV>RMr)w ze7b5rSC!+?!KmZIYb6)HpHc2~d=Yq?lv&I2KY6pIcO>(}UxG&88P>WR$ZC( z>tlJMNyNyLllLO87PS8dnV*VO$y60KbU_ZEMQPi~vL+uqk6MtIuk4&lh?q=gJ7Hiw z_isOsAZ{tt!vS*_XJa1eA+?e@HLIyDM8VC56$|2|8K14q30-|@%SZj{`h<@li)Cny zBA?@@ua{!DK+SNki?v49isaW<#Gk*exT5)~{BCi@!qyCxN#-EhwqYin&d3T+4s1zP zVI2oDyR0GyiYi0rpAkCuWNOBWHBcK*l|}9H*thqOLkD@o@)GCRtEukB{?K%c`9Ll| zYKh(a;r+jEH^`qmo=BQh7Oc*s)+~Q8GXMCMUe86?G1&Z8e_dGKgrsF{)lZ~Kc;2$d z4RiJO%&()|U;d8^us5};(LcRV|MFdtXyS$SFCPge;~k`sXK2837frvj$df~2V5Lyi zY%>Ysp0@0=YatiWdTdri+Ua&v>JO4~iMPyYC(WQoo!wI%%t|ERrtS{6XRNZY*1p`h z)qgtLI~kXH?D$>tywg)Ukcf>V;XXh@8Do)38_#VWfwyE`OvReu3AAO2&HTn&d9tY^ zFB@j26MlY}KEZvUL&(5QS5}^~uuYrz8l%BoRBbYKi7@10lgZmuEK~jL@nYNnd^DOh zwWZq)FC)5Kx$k_)R2A;ty)9ZvZWDpc2ooo^y^KGrYXEoX5C%TcwG4Si&K|v735?jR zc`M+_pPREcg}!VYU3Wq>+0*EsTc~N)wYjh#XAT;5nTi;(%gJKvg52RhzS*_V-bmO@ z*^UZ#Y1nLug7%s_$PTS#N%#C>sJ<$2dXg?K9QMIV&WV7S5;*i_p9@tB%|)DvZ=DLw z<^<27{Rnpa?So%BNurC#M_0>KlgDsDUMtB&)J}WfsxG8#hdt5sVHs(1KOz^=dM$M~ zwpd(*1S*l|Z=L)ShqQ+A%aFiTrtBTR>*H(=Ont2fI=(+~()z`mzOMvW&ywe#S;%F) zH+Rdd<}};5H(GRhtoF&qjBSU5Y$jsREY-h6!JTQtla(b^+%@bB7~Vg-Q2$n_%`VKc zQu6wp&k$A73DsxhlG;M854K)^^h<qj@$Wv!j?$%qHXuqVvtO4yC=P~Kp?N)^e=KD!?7 z{J7pMC9!0UB{50%w!KCvSnmSlJ;KKuLq?but>{>fIk?mhpZ-86Fmfz!ufqS7%lPxI=Ut4 z)VyEh)qJRYbGZIk4oC^D=6U}`(uJ*QQmlk@zV9GA5f!WSIG<}?f<0ydp29W)w4%>o| zYU7^%MSRBi@wxn-_*Tea@{N})^gNho8I8?sHoeH7EG{1{k{&mhm|=XwvU3@*OS8|P zhW1MZ+{I2u27;n)>A<;dvJ823Z%5aC*5?nLBA>~^)prNx%Up*z6SX+W8WoBuqzZ++1Y=LO( zv>G)Rz;A1$pS|+Po!Nok5NepV;>d7)5hOd&Usd_^l~~g*DCEtX%csocakB*yathk@ zo16xVN56~1vJz42GjRW348_>8sry_DKSxhPKhEzVNa)B99rrUchI3I{C5w?XtrL^s z?*H6sd}*C=_SN1#=t>uRrM`8S?g7^KR;yHSSvLDag)NS?>dye1?~yXFgqnS`+O*L3 z^~M?om!r^H8^5Hf7;Fbm+xzl^3pxW^oZ5Mq*&l{9E5Dc~7zm37*Q@SWqCU4si3>{R zQo^pTe09ErKAFrA`btsM{iaK-VqEk}{O!K^J8F9q=f~;A5i9=>XI~i=SI})40zra9 zf;$8W9^4b$NgzRj26uP2;O< zs!pA=_wKqZvzTBX{;(a#G{D&;KqS@p*gjy@5Pf6T&) zf~P~&dMFc=OuH4In~Ex2LB6<-jf53iCw(p zC9&%cEFCogz&*;X3)&dF=7S~sV^B>TbS;Z7PE8FWPr$+Co<5pc%dr-9H_@ezPs>L@ zYuEJt=yTGV3Ly@Nzt}RuVRMO0^lGHu<@=hh1adpK>~RmTb|vk};?9pIlpp=ERv)T) zfVI_+g(4UPll%K);X=!%yR+Vqsmbd5Ibz%#eGQ_q#SZ+ zb85Hp?e9|WwGD-2+)Jjzvo@EpX@AjuIC3zjnbzhd{m78`?b8G&V;#9xV+LYDWmt-9 z30+rj_$yXFu<$HtlvOO~T!)7xh+Zdm8*S~hhpKRLD6`expgedL1GAIV?viwL5`<0F zJSlPHs1`XP(NQGSjTwz2kV?&G;0)O{w7>5qv@PeN*Cy-9kD7gX)oh#cLiY8Kqxt>b z^*7-Vr}ZDmK^`-@gz~m)tuE{kC?A2MmW5mb%a@-wjL~uuVZ10zAe6bsXkYO1J1&D)Of6cYZWVy*Zk~WpSz6tLiS~B(U9swr8MWto{4Q-RdxH(*NL^%ua=5^ix??Pa;U>dBvPJ z8?xo)C%#llHO3Al4ntNClxv9XUh+-7S({21_ccn{NIc&s3-JU(es+H^hw_CD)FM|w ziG9~Z-mk5WhoS4&Omau|hxbD_g5RN{;$+2fROCEO_Htr`*W5RHydDYcUgBs8{MH-sP9Kbdd{a7vdM|1% zrmidC*6r5Nz2mBEveggy?e*a~7>_-wM-L%XXp7dPHhNt>>D)uYza_V(z1h@%!j^n5 z-r+pc?L}II#MftP;+vym@=n;PYeTHu_)HO^k%DtnWMfTYwE zn)#C1-5w~IUI=ZY0@Rb;O&V{jhDk`Gdt7{Xq??~zU>|go99(VN;+KDELo1#A;woXY z%0Vh)%#U{<&o0QD&uU6{pW3N5WMgRncu1M6*%H#0R%ju2H}gWJFFZfmn7yfvTu_I# z7fSdp*}!q}T}zw%BeB=3K1~ywn0bN^>p=Ho(tX-CC*QedvlZRJ7&2$vCH9jcR2!*7 zD8QZyrYgfbNk(=S1@_rmDa7$&ulLuUIZ!IBCqDOU^SV~kyX=7)qOCBRDOb7^5Jbl; z3-<}lZqnV>CQn%`2At4#(EBza3jk2v9B#(2+v4tD)PFWZYl@=TEE*6 zd7v&;t3+JAYJU_;X3ZHywANU!|X|fi==tLaf#dP0J*9I!>)*W8n56m@vKW6 z-enm}DXf(M#e>iEc=m=-h0>YaA#KSSUVg2?&AVP^A!8~Z=CWyKwtKCU`X9L^fG00U zH7rzt1>@f8k~2YjZj6dQsl|U~(41HzXXDCdn@E$(##M;#f-9B1jmAgv6w(C|TAkfj zz(!-_eUs}QZ8?{s*;&bxBm)h&78W~;4=lOqn(V_=HwHp97(2EQV2tY~hSnadM~Dvr z#@IAY~b%3m0V9u4wIld4A zng8$Igr*6Lu5&;V<+Y_itiAscsrMo?ZO_^V_sgq~b7{0K7w)C=DCE0FKbR$11}CS*^P^7mJ16G0&CfJOiV%HFF-LT3BQ)<@|U3o@XUj*F=qjTUoDSS!!`XBot>u z1mnzbf-C|lMqxLUw>om{ra{u#A%fZZP5acRQ) z&Js&F&0zOq#H9k8`-b)reGgEw-%CfUa7(&`{TRU3(Qg~pzu<5ViNsl$k_8u1jJJ8c zn(ZOrjo;|6Z&GGMe1Ipc4t}1n9EQEPN&TxW9WeAkxzEG2p(`W&P(ycaY@Q7a;0sSq@`t?CJK?;lZJ&KnRb6OnRm zNWZfHV$JOq)-lVTMucDMMdc*7xfCMwEKmp)Ri6ugrD_up2M4e$E@Lg-=OO40#NC)Y z9@y1h@A0vV>l?&Q)qLJIZ|CV?-R~SCBm=k zeeRs-l)unpb48-Y!Hy+QJo(lv^x>t49NOVmYn1_sB-S(aSAEt< zVm;IdYL@ou;^Kzi%nJXc`yq?>gVdWtEQ{cTkN8h16DaR*9T2ie`c|Wv+$X4$Py~;I z(3@Iel#o`-1yO!%6B@P`@h)BreT`2XJ@11u>2S5u~Y^S5gL`?&l0|BU^of9cGBBmdiNvC5<}5(SlggKf*woF(_O z!L4^I-q1rFDVqP>4prf)2FL67xm9`$l_K{_c>2wLyxWl@je?n)x%Z6ZocnApeXAhK za6A?N-8q1Oa@B6l)VlCy8Od~sBnLXeB;jDDKlsS+J2WZdZ28dF57^DU3H46e#W7a5 zKAHNgI0@*LTCd@&ZxNK9I?TNvStmuYD9{LDZ(ZF#1Z})LXSMKs zlc^GsLv_OM^=j~wt9};21W#;BnB0@zwf0C#&Hi|@$%Tr=)nE4pPWz@3f`N<+Sn z=gJ!~_>{JkX~_8E)}>*iW#z+J8gjsFcw3spyLRuOKJMkRr6Z5l_$hMZnQ~UZ1Hs60 zz-Cd8sZPJ`FKV`Ve3q{PpD?oM4YCfpoqXu#&1Vhq2=Bfm^a--0rKj7uk!_@^)hzCI zo_xr)u$((W8T06*fw>`lMAG3`GG8eIkFA1JpF{Y|E~%DKOZR89X~ra1P}hTbo$6_f z6;mdI7q?g9$4#W1m3FJA^^-TZY+LR_3=t-Kt?jA1Rc6zkLmJA!1|^b)Cc?h^a>2`~ z4~VQ&pDtVkfgdUZ`q^Rfd!i=DzD1En-|l?C^^Bn8ew@rn_lMk0RjsH2XEZwNZX2Ec zG3bFo?K0#?(|jlVvU79vw#gJHzz8jSf78#ya!zmwEgF6DuxUvK30>(&;+Gx)k_R=_z1nelUaq2rZu=ZCch zEAvu&;7^k6`+0drgO?j`ZnGm}T6f<(EIbnnKzWYH#y#B0EUe$og-kve!zv-tJvh7t$5;CJ>>)K#>9->ONlNFqUc#r1SQ-NI5xWLGIriqm`>T_9? zl`P@v>}=|*4?GWY3=5#FZ?@*YE5_A(QS*O)(C?$PH}ze#jT&B~zf`dkWi_TBnJ47Z z8adVdp*GfDdo!j?iMW{vM+>uai)O}vl`*qp(L^`Lf? zL%&=HY16Pu5%N0(u13U5H7q&i25o`FoA($IUi7?X2Lt#y-j8wrQz{?=;J_YzNK}c1VbNwYr(skIs6+;4V;@xJNph|7mhG;C-nS4Lp*YOQ8!^GMZt+++KLbGR}n z?)9T8E^to@v!gj|ZTu~bWd$l+Hmp$BR!Dz%sXh1c-dE4m)COh~5_ws3l6i<-?Hw+Y zJ6&~Y8NBQ;ympPHE~@F~k>}e`59-cB%MznT6LfLlY?*aCwh8QOZ9C730%mm!gXHcm zUdCQYx|%=}Jhoyf4k1#ErJA=PQcGC7Ek@T44^wq+)mo$P31wl)!tzvql*IBSq|K4C7yn`LiCvWdUw9&*g z-^C+W=SFskyRazdp@~;NYS5x!V}`m8NHE!S_7)O}wkQ$EI{Bt-6R`@)%!nIHo!X>)P!41yzld*JmO<}PHe3y0 zipmU4mzgEbfN>%=w0A_GizED(zB}ALC|FZLJ$9`frtMw@bWCci;Oz56V}pphxEA|X zzYhS3tmu9UNy6E}mQ~mKt+MDllO%jcxn~_C zfw$;aJ-gl$A1(v@22$6(`RIF zsS&;hv`7CIV{fhpMoj+Uj?6vgQ4Y%|qAn>q6==T$QKy|tfUOn953YlK?t9dOfMjD~ z&>^Tf#HN4z>XV&LRZ7w1x%Nw(6(NU1+>JF}Z2|N4FuW$se@S}vbIu0d5}%WpY~Qwy zCZL)t3PHylma*<5azW)N`>zJl*#fv`GM{I&y~v@_MDi7&rN+`b(v>zYMNf+hzWX4! z-bOyC+h}wQ`4x6qEH>v?^Wm=-waY0tUg3C1h_uF}7cg1sEY~zK@P=t#PFPg4lujP4 zGI^%T;T6j$H6Dl3kpujrvCZ_MS(S>x6mX!0D{!agRc8CBa>h*ksBZV}0w2fTXQAEg z{cI5u8ogHpP2MY9bBgar*k8VnCk6&gQ#tC@`dWBdOdGb2uXlV)`;50{_fa^Lx}8Pb zRO|xMrh~anj*5$N-?I-&dUmM!ZS_6R{UmsS#|^pt6`kwKg=@{L49W%aVml^}5NYB~ z#hq=_F-Saf@w1RAo?FVXG5dr$YZ~`?cK3 zq{C;jmsmgfyU`+&h=8)OEh&TTe@db_pbcGj;?%0qn=vZZ3 zauj(@;X^+(hB`e-jm{npgR2MxV+}T=jouolH9pr<{mCg|vU2s0htNf5ssc3?&L@N= z3^RpBj?kEAE;w#vr=^tgBn{HPp8Vd&1>D=MaifvhZop{16gLxEjA&q%{>3Z~y~KKe z;;niruw*F4-(5hhg%4|gCjj2+X900+&u8X-cUy)koL}T#l*dOkRR3yE7f%nbfIdfP zKtQoZ!JS`kD!7x}E5&K-;xL(B(OcEo$vxEweK~dA)A8KwxM|$>ATp{Q1Q6MW1cSc( zcW$NaiCbX@W#uJEb?$xj_F)-)Ofy!=bsWeSB!T7bkqW&Eb6-0HiCNkABMVNQ2#=hU zfi|Av-c0|hFO5CCys0kxZ&z5tY=N`WQ8qsQ52Wypi;7X3{~I+@AglO9jfDJw{OV~f zwCg|~ci2YG`Re0gY2It+rD{%HB~J!a&u>rUe^r^X^B*k$sCidlQex|lZGKY2zQ{e~ zD00KII{BQDlw-)2v%B>IU{RZ?nrp{KrVt~v@CkaM9S^UD8xCqEzV{!s|L^?D1&OhSQ5)WFnmHRB&;cGz zNMvYe2XEF;)QhZ&(~P^h|MSrP$={MW^6e*prCtN;zTl9=XWE+f@G?3XrMiWR_(g%= z2$wYdUZYkt(~Rek(Dg4M-9Or*n80l;B*uQqFVyjBrtw$Pj2$X*ktEm_8)unq znV4A)Btz}Z_FD(Oo2;zTwRS39Cqt#PAawQ2lAFHi4#9V4BD>f0J;hhrVu!Ww=CxUV zYIUmbWEmk|f z6Nk-S!Rvk9*Vd_320Ftr!bwImThA+J*8!RNUDwD>9JGE`IVBucj0O%FOtHzQO^JQYvjd7Y8jakuD>b_h0;gB5pM@FxNyHCHt zbRy>YnMnb70mg45R7+2Ez%9W7p$)J1=9e@J6n>lrbKYm`*qrq2X>Nc?ikDC(rsGDo zaJKA_D!`;r+Xz?9*r_b@6V?7Br7;unP@C+PR!~ruNTe_iQDj@^iA&3sl-T{Vn&<|i z1B*j~EkSCI2X!`vRz9~QzAUR{x?EQgIlJTTVMb(#$2f zqmX;>^!rU0a4!6s%6UTJYHcooydjxzaY=Dg&0+XXNAeHJA!wL=iQ~FYvA5B+3B+f} z0>VvyluvfY3oT{O;&9 zZha;P3?3B2vYshABn*~?k_)WCw*`iwEWn5>C4~%+YuB(*=1rohZ#Tl#YznY||On3TYl#RG8$MQ#>z4-VO@3fq&J&M>oL~WZlDD}hk01eK| zJG1kqao2;3==K+lB1HR0#^g4CnVX>}=0>?Mm?2|?!&6XUJ@nZjWFAEjA#t29>g*$a z8!I27>)U>gN)rNM%^$~RNe}nfqDW!9_UBn#%+~N?h#!J{>EZT^5e!`;O0-F$| zmwg!x+p{FOQ|aX^*4K0oUTb^Lau^0KgACa3XmrBA0muryT+)V%Uc59pGmLVc1RNr7 z2TV%JzZvSZ6<8u4nV_Iz%=m|?3}yLwn4}GVBk#FtLAmj|uJ7F|McCs@{kFm^vO-pH zJ&)W33?DL4J;*?7Wkq9qmqAs1NpkOz7sy>V(aa$2XhYuP#Ev++$ys~f3H(+XrET8o0>J#hQPC}d z>%7Fn1^tK0^qKm(O)sAJvt5(bztL+a<19|&UCU9gQmy@oy%4UH+)#KxE?3{(b{wOY zeF%(fl@PM~B5f?__C(yJvxdhxoa_c~&JQz;qB9&@)2UlPVr!8m$X1RU?riT}eGs#x z528C zoo=kqNC{;i;)&HuoaGfIHv|716&P6eLCe@IYJ=b!)3BfH|zc)w>WP`>;uv(F^8s*M7+XgxGB=Q+H@Bbf#=;l7feV|!KyFD~$= zuDKxVJ{mZZRn0Y!P(nf0i`f@A7H4Y~;W2_3YgZgJe2-SrhcivurQ4j-M*r;Gz^LI7A zg(z@Luw@R?qZKnhot(KKuu}o98i;pu-2~FG`n3P$TH)DBDE&_L$yRmQCTZSIFAf2D zAqY4BS3~z03v(L-Rpca03GmcnUwnHP$Lb4;)C^^hy^X{tAYocv!n+-RGj*}3PPK)7 zY6O!5$^H!QzoY+0UQGC|gFaEUj{=!09g3r;sy_J(?3d0mQ^m6w5;irYFY7M1F*phF zB)xwlceMdzQ@5znGD-R6!|)t8w#9EbAnZ>v&)HE|l{k1w;U_{XEll3K!^w~}U~A~( zzt~Gw-I73rYt|pc3*WB2Pl1=5MJ(5`EURY~rLHMJ4Q&arw(cPifRUO3G|SwfUMUof zmU#SFv5AuZG>GCvday~GvljY&6-U6c5$2ucbU(V=e%LvG&%LOqcAKg=pJ=DpC2+yD zDqUx!^;b|9rBkQax?vQx=9gOu@ogp4#ISy}uRk46Ommc(KfnD)u`s4De-DG@N$t>< zc7y4XQ1WM97t?AHk&(=H;{Rb`s>hykZ4C-ckvq0OBz?LK;2-?|LPIk-gIn1K60d3?Ua#!oc?U&N<_@K ztTSFq_GFHTJQTRU_;5<`sUiH5CmcO%mp}f2F3qkjC3EMYM&qYNjegWS?h>r9B1O=|V@Lsi)wmCBH^Vo(~|g~JsGkI`dN547n~oQH7V9T ztNS<=38fT)GeLkHSx>YG(|WH^Wq5j}>~13r7-$Ta=Y$eYPG^uBu9k%#mv%0Im|p#1 zp?ZYny6`Hp!(i_+@CDy2uDAbC*OS!b(Z+O_1}sVJ8Udf|3u}zN#($X4{^zA^woGDY zQ7rmk6L0V$A@v-msI_a=c1cU<0kSgRI1l(><1QHf)r&uE1e5 zcsdKi>AqmX>z}?R9te-ME7nO$1-ocBuB*$&X%MexD;rDsBITKxm7Z~h(362fQe4ng zcDA$Ch6X>xhSuG3n`@=|@rmmQ8@qP~9QAOFpb}yT-xHKy3D91ykQCRD-TuB%@wW9{ z-^R+R{!F!Ihx?nryqwo~e*(SqnfeW<@Op?GW` z5eDH}VYYU+6llp`C zqadZ?!`D6Yn3K75A?4gj~gK7+{15pIlO#5u+r$YNpgWP5Vee*x%Cd8al-{X(zuc4B)3!!yT5v3e)r(X@^zoQKfN;}2FT zdZgAJEmKZUiez%3a^gre=e62Om@T0~BtNE+u@;xa&gF3+7d`=GtYfp}KOj?B-*zqn zT#wz+!?FnWHiQDRGTu;nxy4lMAlZ@=ecNqHH&R&yw;{A*_@}qX2xI5&;B#G)55>(T z=DN8g<@lT~r&t|%uaQ0ncU*nu**hdxDo$KZX@(9AbDTDju82(2-@ntLFmaA0j#vXM zI};0D^LTWuDDJG$?_juriF zXfDCL;cYbeUUCVSNlXEKMbiZA4rtz=sm8Fkjfv)H&c3Ei)FZ%D)C^zXACGuD!voH} z+=mE}4;2()2<{`Vv~9f1+S$B`&_A*F_13Uq?SItXne-p5b1a_$TOm zx595niNu)EFD479Bqk$URQWDwF~^slFjarFI9K-fC+aKyGw-r(S{j#FhS&MRN=pCe z0UVx$2C#M%A)C})LFUS$aEkw>)Rna?iGmbFVi=9i&Q)%mMMk57GEwCvi{~mRwOuQt zCl`rB>rB4vBmtAi*U6?Wx^gQ5f5Ok%&7n*7RSe@~4D=r(2Z^{kY(r}e#8-s+I>PIe z7igPQ_#*1D{7Mw|{y=WSc^NW!_n%ol_4>7KpIgIAMM5&t?;3~PB=?KUb&_uy!k6{} zhh9tKzkT(`v=+rMWl{h0`9?cx7&+}5j?a3!Bl74L3e%csNDelZis?8DA~AQqAHW*i|$p2 zf+?j&>e*(Ri@9!yWfNFZ6N0IEg@0BJG@@uSrhN4A02XCeC}!li31{v*uIVQX8m$7{ z4n(@{Ks~1By=)`=c&<-s*jRFbKlQq_g$3iEZ5X!k{MiM05(ZicDA|dq9javsV|va_ z1EZkIuqi?F5J%km?mUwXr46T_pk!K272%NELN8mXnS`zukx1wcjSbEL{4Y zm(%vA|2}E1KLQiO@mJB3p@4Dub@jAk|AZ^kjH^)OEFj{ph$f{26Few4u#he?-4lUZ z?8r4qb~=xV6Mlu39L;1vEpyE(ZV5^dJ8Lm5&U0*o@sW>D+8J&?aZy!-FSC*UQ}bsF z_;^MxeI^V{6-W1zFN_L4+To-~Mv|q@5d(=;#g9G@hsw>L{h>>|T!(**vi;+qO~M8T ztf@T00+)$@fY$_6B-%=X`9p*=OjgTjyoyM~oe@ii(Hd~Q*@HG*{f{=jsE%-kqX9B= zc(ZZnxOiQ|LEDPk>4N_0Z!A#@LZf6Hg=W1+m-n^7*ryx^S7C zkKGqBCQ1C4Phpe__dnZ&NtOb(*V{+~m#}Whc>5;7v+SYQ!vi#RH)gEkV;uRcOp=_| zzm*W^Tj%9w$Y`6J+}G!>CE@`0EJ6JK;@;E1<9VvB@E50a%8o(L9kc0~E!Cgoh%<_I zO3?0`QG5p7w``sV6tT=puj(&j7Ww7kJgic(Ts8=7f{=x$hgRucge8Z)5+=;Qf>p33 zGFzHl3rb(O+)!@OB}XGZvyM+}c5=*!(P#X4G|c*aGr+w>L}}H%H-DHZ)KAM=wG;44 zHxkE-OYFfj_P2=!qOMoa>L^oL`i$h6S@MZs6UXWWbla5uX`N$F|IxO@O2qiEN)&4O zwZUn5SXfSN8m**a$6*F&z#h{W!G%!0{rIHO#Sv>Uy`a&cUSk|_Ia!4EQ95k1R7iY< z{v#2Gtraqsdr9=7L+1-t^!3FPj3%fG4aNnQSNZz^PFtZ@G_3++x5*EDatR=q5-)0Z6TzOl}zpAi3$FxXi`*QyM6f|IJOsH|yQ9 zz;AA+KQu>`=hwP_KX^d6v65*f*Vu4+^QkK9mz}7c zf_wTeq<^WasV+FWfyL>SlPQV=4X(~U{hw}MJn8EU{j?fw{l1jadOzdj=C1$WHFJ01 z_6M+XFvXLRpIW&5-%#{)3t0P~wQm1&y`msT>KhU=)n}}s2M?;Vvz)E?c7NQ}?Njrz zv={|c5_*--{R~yzDBw$}dL0pyqNx6G3;;w^OyPS znf>WG)$;X)lIf1OOzBoK75@|yOKH<+m27#`%)n*BxOkuYf_2;Jhe-AY}p; zEv(L*Yvpm1?#}i?K-K5|P3hwuU75#G=jEiaYSW{~!_o=G3imzwY}vGI*&hWj%oEXR zPxTw4??{^TPm${-pKZw7N2Et*yNJij$K?Pgr`M&=pz}Uk%aAoXm@U#%U~lDl+<5HB z_QqRp$*$~6%jk(R`UZF9DblM1eAKP=JY^_-e8v@-ryT#V9lP+DHHNJ`>$P?J#|AN@*YVTT1T^Krbx- zjlJ1wOG7T;2Q|PwIJ@)hi25Jt>C=w?M@@;>4+Bax+T6LG6)2m1h}-8L%H4xP?7Tm% z`tW6T+77FA2gTnlrQOY>3090$ zcT}gO5jQZg0b0VqEv2{x`fu@O2Nht>2HpWhZU`)J?@l0(Jb?Q>U`PFJeWlXh$qieY zPbI%$YPAMly@kl}si#c?6{+gvO6R&+>qbm6T9O{F{H;IDt95hs77a|~V^n%9a=(&&Y|^)K zx+Rw0IAhqNp(^>W^GzvHn8r1BYp}X;rv=h@RZ8Up-Fi_5srdLUw_EOv>pHX!_OjBR zx3s70r784>`WxepqQmzWPV~(L- zqM;zT#jX*go2gTl*+-D`J-NlcA6ivK=sm4u!?(tGh(Ry}VD`|%%`V4J-jNVK_5pGba+qW!sStcJT@0MeBJ448J( z%vtC?#iGo1nk$71T@@@tq1+ygT% zJ5L1v;Op?W=7#&ngC!rw_^Zs_o2xVFAgOLF2Fggz?-=@~NbGCer|2eB3QZh%VpkNb z^F4q8>oJ8<#DXSbd58MBk$E`umSF5nl3qoi%z>d2PG^?m<|0bp=&~)Ai!7sYkm`{Z z5o2b4h?!Xe_pmxMjVew6IVdjcUaXoKbc)%bry^WQ(x48kgq(SK_umSVdjZhJtA&3{ zZO|x6nmOw3@Y_(Lf=NbkJPM;$*&{p7*l~&sYK8XGAd(~HT5<5!sOdWLE8UTWW)~V^ zJ{wAB2J^PQpUpxyvz+L|zBj9J)GQD7zf0Gt_$BWXR% zcrA)45T-~>~U2( zcQ!O)ZH>9HTXG++suvChrO{KBn+W1_V;CQBja*~)m00u#(O1TVu|$#WpaZRSsE<+f z?pD;1!D&D37FPAsvT(7#f-ORXmt+oNFu_jNboE`5zVu$f_p^0meMGFwkt`$&PTae+ z<0LGt#GQ4X08RV*ZFAjo73^Gm&p@T1dF$--dS>1x>ojd)We<10hwkfAlMk6)^8~RC zh{&yE1!iDT(=jLB*)SI|I&>2p&hku1@2e(&TgC=Z{wzkcW{u>^U-8a1VTva$5tkl zi@ojY5EKkaBiE;isCak!I&ZvWH!mPQs=E^%EkQr9^%^oR=xp#iE&{;MJ!WQyAvw!& zTKb`rzCwYkLy+_H@MoUh>c#I^q9NeZ2e^F~$Mreahr7;I{koXp)ZhIzQi< z;0+~#B8~A81E0q4qrp2ZuhqU;#mp{eKqQA_`4*B7zUx#oE>7KH2%0wHq3)9aVrVnF z5He5yqXlqS*JkaUCjL;vZ(EUi-=^Zx5dhT+?2k@2b+f&7tLdY1-1fXal9Nw~qdb+T zW;aRc1}QWSVw78y6R*@i17zwDk)f_B)UU>hu?9ANm%hQL3{?M#2LC2mYG8{UEzE6S zQe!%4T+i9eccQwQInV82Q2l)yQ-jxUXW0Vn2z_bq&7#Ig{SIvjLe1oFKQlC23hhKR61Ab6&Fx$)TO^|1>=Z@bq(+3I-6kcFh;-MyasH&Weu`Kvp z3w(^ZRHhrpB|=w1N~w4rd=^R}+!k+Iuo|9K2(EnYs*S-U$IPpx^BmX%J0f{|bnM|m zUwf^YTBBNOKMXTJnR{$p#9OH5a7Xr{eFIq5TThMH#96iT+|r)!mpT)#R=Vq{fL-WTrw2>8vfqJSw&ax%m9S_l)yk!h9suX3%v!amF~CvQ=aHsW04JzChS z-Ob^aSRuKihaL4({v#SCTeU zstcXOc1Nmn$))BXO*p17e*+Ve`+NAQ&#!S`kqB&TqjCt+U8wr3*vgZNX4O0 zjgmy|EAyb?V%6uw;h>6}()IW0+R-5OdwG&-8LAdy$>>Cbd)h3|suo8bLm4u&!cLVE zfkXA+s}uNcI?_swOS6jb4&@gGgK}WE%sC9rD(Cvj#8_&6Cv+&&l9VW?rB-m4YW;&s zeDpk5Chpcd?0u$}gSS`%54vAdq?GjAhwrxt1& zxmoS)&jKxEB@8;ra-?O@+xXf?*Pu+ky71{QFT+Yxj~-yLq{mC6!Q|Ap^!7V%xssLs z(%^bi-2(1vM<|1NxrvJ70ps$DrCj(`e1`-31P>>MRo+o3qAR25Y=N1vhlprCNaFZ} zs4=OE`9S!&()F+OH$P#q;y?3HR2YVt+$F&hDPc9l+i<_b>eZ&41plot|D2z%rq-24 z4fW?N^?#Lw!8yE6E*=O&NE@(L}X|(?Z3p#DrRk2mIPM>pxfqRL$=`^fv-%OUu_I5@PB1( zG<&f2uPLsfSw>z1N8`-Ry@xiXE|gBT^#%JVJ@4B%>~8juCb8Mlf9G2tlEKBS33Ir_!(*AcM1=5G1CfEFS&aN-Z-EnU+_}6`_T{$2=~gz zxRF##6ng!82L)@|D-e*rYWeQNthY!KZltS)3wG(T{Etcj@q3lbIkK0yhy02j^Y7E) zlh+Rxh-jRZ;F)dS?CwQP0+wX;qqBqXTlN;(^p5H3vm`L(GYJkkravTVttEV0@3kxC?(^OPStbf|rNFp#rYgpc4Ha&9!|- zcPc_A(!Fi%-0~4M`n7X!mGGkI&K{Y&Vl8eho$2z#d+3eXrI7)u5Uh9ba(K(a$nw!T zfaWri{N9;j>4TmeM`+@Qg=N_>hm!a<;)z>L0uw1}FM!^ZTf5f1j-h4Z4qO_NU6C?CM{5s67M)0oK)0zcwxbk!A_z10I zP3W3LI2)d(-T+QS$=jDDC}LkeeZl?tR#q6Pi3AO^>qk_s?gv5=!|^e;@H4k0G|U>N zSKwLUgGemwgr zjfY1ueXA|Ti1j?Kj=xHYiIgoAKA6;<_58WfhZ1@J;a-Hk_Cq3O(zRw_9pSTv$DD5Xw3EDFCr$IeLz>PuH!*w@DHFIcfEA)Y*B9PZk}3=t9jbMZD)}xv!^k8>yPRExB$J)VGgaXB-x0jeK+&cQB_j zk2E@TUemxVzWBDF^xf4;&Ms4JvM6mjEU6|3?rR-7_%szhxfnk?|E4y*elinbHllpx z!Z*4Z9j;a2c_7a@miH>rt=CJ~2aM~U;gzW}&d6{b6&-;r%ppzm+Ue2p^aAx2b=Ivz z9AzH#AtD+|n}!Luuc=WRZH0D4ucpSl8`FCOvIYf|`73`djE(*JvWUOyT^C>2uu(ge zr0bwxjYDf+BpB zdtr-IY;(}V#qK{vPG?_>`G|@>C&R(U&;iLm`Hr`)>9TflKGs^9+FO2fGMfgQQMsF{ zw6J73<{QDLLstqKJnjzy#1gmw+C;w|qPA%l+r6Wff$}>q*uj6;`-9Ud06nQT3%-5Q zX+7=$b1Iuxs69V@Wta=n@xwGA-~Hi&{9=bb5fJ9kyOIb9~rZf-grOJ8ku`Z~MyWSx3g3v~G!U(6Fm})m#x! z_$}2=5xxAY7-V+*8`Hg`?fB>O5`3h>p_kjgGsjVtct|J!Tok0j}ErqUtNd;#!ty69^JC z!JQD?g1fuB2A2eP5AH4@xVyXi;O-3W?rwt(yvaHD-uK>*`7`s)?%vha)zzz3RT;R< zR9C@(NeAmkDS2}9&k@nq*tw`oed<%Xx^dzVG?Ld?iD(cr6U~T-_2`9ZU?M+o*xt8z zuvw>x@0;;V>-bK9jfEDJ=4?{$;lkt*uq-)=S7hvz1v^;py2X1?6+At&w;*Z-mQR1; zi;7zwM<50?j1%|>AZtsfEOFE-INE<@Ah+Z5XrvS58+f&&^@wSP??5BH6aq;{e!u8Ip!OF#t&lTiN(xaM?E?p-CwEdE5bDFk6Vc- zoWzLRJhNH^)wh;A&jOCD!bMowj;(Yz4MN4W)c$e-qua>x1HaWl;VmgDJe4MWK$z_n6MC6Xv1j}ceig@(g7^F z!iRMT)K#fr+eYE2``^VuSuBO-k^<%8Eh_Q5GGN2OAV$EoM1i3K@)R5nXV&%sRG)hGl$U5clgakbdMk!G}&ejr1Gy25aR0IpQ zLoLw(H!GthjC~hqn^#*`Z$L&S>>$=eF&ONelQ}d9HBrFNv97G`N)CRWrdY*PSDEPO zk2z7~Y0Gp3-pdhB)C!h?Ern7Gb-6_*+sp}wh%3W^Y*q>=Z=Y{z?#~(;7tVXW zQ=^oBuQA74ULHBATP~lf0>Uj|tLh6pl6>(Uw+MLUujT4ON&$ZSQ}$9{Rnbn=v=Zb^ zCq^^42$1W(bBdqHP|-P>iyq#ugvbzdRNYZFxq-QHx-b_IrtCl2((xn@7&WVbsX>Wd?k6rykW& z3Qsu|XQC6Z$ye_EA^r$vOIEKm2`dRF{{`KTgTGsEAohy7HswQ z4*H#YVmTM%Mn&7V)Iz^XY>=rIcWY&y`Eq%$BT5_Qx1UF8*2Xpt0z92dQe&&Kz;ir; zNk~@j{Z`qXN~g7_uctI>U|5HB-qFO`|E3s^~2EBk|WMumFEq(C^ALF8`)PNNxZ z9k(V<>H3bcUYRKwoEcM&IY}poReE{&b44BI?)IBHYo^6sC}%rR1@NLw{Wx!o7DzZd-=}85@2bL?fFZlggC(X2%g_Ty?r>Q+wQ<+%9(8ArQqa>u88aS>EBAc=p_x*(xW-VVd>_=h|jZK9e;O~TI!T6ML*YI zMH3?$3e1Zh_R;?e4E)r@G^`4FEtpc?i1utMq#Q*?r1KWHFom}(vLp>|Ca?$U2;r!2 zO;?NII}4`j%4pbGr|!4r94I~Rt^L%gbv~y?>8J!rdP~yHwi3ekQfdQ z+IPrv)97Rd>!SJ=n&Ld`gekJ_T(iGatcW0!Y_D;zG|AQpERltQSXVdFy&8Yo7Gfv1 zRgZHXc!KJJZ-fN8;lLj{*M#>MzrC#BFE$*X9==Opsj0kE?3@WEAG$Zmb};;N!n)z*UO~Wls>LLeJo1x!s6a~p-C%f`TNewZja}CIPG7hE z40duYtowd1YwOzh`1(z_O~bt&d0FrKrT6t}6T@tCwlvt?glzTgXw)e6tB|@tSgh@O z0%s!WxA^0M%KXb91#q=Qn-32%C?w3O$Y4|!rYi80(bjL-zwWFrhFEvkmlz?G=JL{) z(OUACIBV)Gl}*G>UWGY<7mkNJ1|_(v>_g~m{r6ymk*=Tdqe)8Ne4-r+h;I_S$C3mj zj^4^2ZXQjkvLIhRGV2^kv^c=*jr@%7elIJ+eZ2Y3)8RAu=fV3tmDLi|>ziZp+r`AI ztK3o}YFrFeFSTq#-eCZn=+1!NHYFu8x)z1V%ba@a zde$nl^_hz>k50Zqzm!}{dqOH)dVU*veo?aVrUf&Yvi0YrF7m|yUM;0DS)s+If>9qs z%ayy0LnXN3{>Tct){@UHi83rB`8aaO?nM-JJ_>+4NYzaJ&jK8XqgJ9C_f3qu%5=S& zk-o~p#R9ogIF`fcH{`2bozE(O=pLNj71ig<7qkTJnAM65#>0G`10;Zt@Z&63~GBCe1g$#Q&WxTk)+Fn0r8a5w&41NQ> z4NbkNOMJU@4t~=h?u~iDZ3%&ZLlUp?-4d_RA}ep{tI-v^S>Ay!=Yzv?9U8><&z`u16E}b3p>Hl$BOs{fAWx(jpopLq;o{0%m3im})~+2R-N@ zNv;wX@H5FM5T(D6h~PZY(DWH#qEjUD0ie>d8}=Fp&D+u$l4_cEsZh@5eZ*NIK>;^+ z>$+mjW0<$aw9#y3EC-x=uG?v1AqHEW?>*#*_ejw4N)O%rIfr@X1HxGYZG+5sF^nB_ z^ol@vbc?4zlcP4`kDK028PJpzRV0q(8PO*n_t$z3D#2UgP@?dJrYz6zVc&@|)F47U)y8Hq}By5c{J zPF~NTw?(8D&owW->qQ9||5NZ66j}A3viWO+T;6!2C``i7N877^w^) zptR?A=^vGZ8FY=HF&fIOx5*Wz4bTPk%fkhAvMiPO)p##m3Pfw{AM}jPOGZCm!vgr2(#ycfIVJ0Z2B9;>vrNmoDQ*^pbfAd9-2ldJElTx{ zq}`RXdV*0SeS1D0PE;>$jl>1uwKVDLnYU*OV@}b_>|ze611C1X@aqz6?hSMGHrs8< zQqY2R!QGvDD{oYDsWs=qauE`98-Or}{<}nVV|3kfDm(;uD=d;CvLs zcQrK>YFy9@@DNL_#Qr*ac4ah2(5$XIDrH0Ypd5Hk|K2kV7)UHo^H*y0o|KA zsx!~;%n<;cVD{i*HCV$WTBbf}88ealWA@s8Ss!(}x+6N(HGq|WYp`uSOgG?ELTY>P zYd!H%H-J+7up7SM{vpnmBIw5p3!@fP+E3+k*ths+XT+A7bN!hb z z1Qe%^M<}X3_QXMMcSsYIxqS_vat=gTUz{0Q=loVw6gDOO2Qck3$DC$d{ggjd#N4*= zktG&ko0&(IEHyR8a_$s?A6=Fq)frlU2U);ZSb5qpJ@e@W`HI|Z+7Yl)Z?z$|(g z^aWsAXEv(q)&y%Vuul${lOY&oyV&r&J<_SMu_5tZmO1HmNo@+21O+&&Ap@){$Xsj( z`4p@HPyBP27nYRGc`2I%F1MI+1PTqCX*75SE}u^&tIy{cx3Dwwy-XS08=x0p1)_96 z`lr$AhuoNuG%lQy+zO+Yn5JG;EY$Ghk+X?_uc#}E4;p|Ux%I3_uC1VRP(8Yj^9vg@ zFNdk_Kx=&+9$zH8fYKMGU;MuFE7i`Q@4;O>9=WjzAJC51r_02h!Hu8i59|~jol!+K zaJ*f`e-hSV=*OvG`V#m_tn+EE>Y)w70e`d^xX4GnQ>#m@`aK!@c8h-g6k=@kawMRH zGyk|JPMq}Sh<+TtG1#1JIPJp~dDBT~+&@U1$Bc%ep*Rv=OEuCbdmTH~!u)h$--+v+ zd%2WLqg?6i`E*-{1A1c$ntW1}cdB{neCg!me@)h3+u4-x0U!gHpOwZVXsk?Y3kto@ zD_dFjZrLp7H*X$I<^&+-Kd||u!y0RwXa4=I!%G+p&K=g@FOw<%7*YKN4N6n1S8F0Y z0L`gl%YTd>6Jwhjh663W``Z^KcqX)HP86_8QD-SpmyPpFl1YhTLIfV;1hy1jcNLnS&)cdzybuhSkz`?$6&XutN=vcoW-wty)TpVBB^`d% zoVOZcKp&CDI&?82p&Mn3vy*ap{65nbC zDg7P)h7P~zF^BRfm31gj9whS_?cV*E57LYi@{@3Akc>qsB1s>?<4h7DaQFvQIJr}0 z();XE42&V@7SBxK9A6_vB)hb-p|n|}dp9O}ubv(R>4GHcsty~*+G1ucUqS@fU8Qg# zCov(lcl|g~bND7K#f2y95`UjQ#&W{lK8pUq^5hT~cemz^?y46KzM~Y~lO@nr2y^P+ zHSj_E$N8;@*RJ$6s-#IY5~3FG8aF{|czAwbX28rnM3=6Qq^M1TItpjTvSCQ{dEaYA zgA%Wms=*enZ>y}th#Pb@?f!ST)!frrV);$p8R1ddw#zfwxVi9v-e7r`8O|NSqQ8>= z)I|L8@7qGLYfZp>$%4!4GV^ne`zS&Wv&f_vS(76X!8Q|R^bT;kLAs|OS=;6DNI-hG zgdA_g-a3pV&7@7JhFg)Przjf-b@z`>seQK>_)PI6>IT4v1Zp8CnauBO2)apUH?k<1 z+uuqT#2aqto105jki#U+bZyk-Nv6n;rc9iohvmS4%x!^Vj2I)UCN1Ptpqi&UjQu4` zf*PX^7;(bD_>ENW?{xo}^ENxlUv<&+jkkZR@>LRSffUMoyG2d*NfgB;3iSDf3QQO! z#ncfmtBL%uB~d$(aIGXG!xEnq!88CfD6{pj$~a>C8YQ+?#Q5DB=jq)5!=&LMbU!jK zOjrrTOa0Fnjb#6f(S<xma;bjzfGTFD7sbS#?&q z+RJmXJ=vO{|7#^z|XV$cj7`5q?69CqC`?4r7c0Y0jzlUjKiBGRpb$kM!LTifINQ7x=fjsyKZU zv6dIEN09qw#v4k2SHWX=w}W#%(O4jzvvIjmgjS*{KQoW`_Y|DE6#tu1q}Pyfq^0wL zp*^bhtiFe7fm|J2LF#zvuK$f8ylV3Ac{gR|rmZ9hBc{Z34(4;f@02&(qltf=R8mw_ zF;(I}$8TC)WGvXZnWjweq?R!v7Whp~MZps61tXHy*dt9jP~=4=(u;GE?nmohGtj2$ z^ZCC*>a&*2xPXO>mz=63%UR^>r!-`Y0~0Ci*E99S^Paj;h_Ihg{3IWnwhPCY+)#Y9 z6XT>X<^`_6Pmc1#0Hz>YSNdqqy_f&hcdR@`9KuB>r_W*o)R_N!`kB-}e!4GiIF$62 zx-O$MbQl%_2LBtNC)C90}0c&j(MyP z#lqcGv@^L>dGDPW2cRw)@sv2EtI`l*NBN&IZdyRYKVLD8k7|{_<3cNT{peBLZ7Ki1 znkw**rgB~1K z(s7C{zP;0L^$;sX)Bly>7oAA;ZBJFpZA4a1rH?^Ac|YDoxRzd}Zc7_p|9`mv|5L2( z#(#JDl=OS&ymybhNC%q>oj-=*It2-day7JN-_Q_yQ-l16MTL|`VCm>9gp?RD6p^7D z3>33f({gN}eB>mb@;t(cv}s^b2VAZoXX#6ehC|0kL%O6Xio?+n(r+kB8*5-{S}AK*mMmhGC1b#lCW*WSFx=R)N4y4H zID$I$HXV+OFzU&19(idHEFia&A;E(GscAF#Um5~lui!Xx9tv_c66zmHg>^QM1218tI2c zwcB3O)a&Bt!P~9z`QronIp_1FPRldVbr1oU15R%MRRA=V2)8PIkD?q$O~8NU08g?X z!@YqFkqVPZ{;G`H{a4qwL(cuI^xXw$uOB$V;7tP8w;LYKDxLjnW_%I-7Sx?e2H(=e z+{6CgkCK9GIK$$^UUE4Gf&f))udwf1L=hiPa*cwYBukvdl!{w-P!h|vLuyQrEpoc} zhznbGOr^e|dWtXOkfl9xjlKaQeiFCGa2MxAV%R|<7fc`rDU@brcA%S+aSP{jlrEN_9@?XW08jKRH6YOH-Vq@lalV0JLi_$HX=c zC7?Cc&%b7-wYfw&mPGghh1N!o@az4wwXeAtP!_&zgKyUUI8dWlRaYPNYriDxnwbJ; z@PscWTtzB@L(iM#F%qdmA}Hzt>)j0k^CM%`DkFR6)GH?*&j(4(Y;jyD{=XW2a) zVu&|@_Djh^$Wc3%Q{}lw3zR2*h_Zgd#OWWp-}d2|tkrLic-%qSb)dq~ynifORa0cr zF!%JXBJ6$qi7^fpFWny>-bNM9tiE5M%0p;u<))MX5uI-8NJa$4m@(5Y9BTZ$)Z!=q zfKne3gBC7?KLc1A1RmOe!u|(N^xIN+U2f_YdXE@_PO8MS*Pm0b;22VdL6qA9KE8nsmb$1 zT{(gX&YY! z6_lp%KpfY;vm*$*<>IifhC%+IX*JR-+Hq$|M`1G-`k{&alij`Di}?XByAx44^7V4s z%~~kTvHBtYxCrnh^Uc>Ku)&ojuvu)_>z7OZO9aG6BMXNL4}U6{ zqx0Ssa6EW>$a>h$(BG8#mB4_3QL1>TU;ClA1@>l!hbcvMEZjd=m`SFi{6)q-NYGwT zxemegoASdpp-Fj!YN_f^x@>vsOMdoN>O!#y&D(xV99nfoE9RQ=ceK|Cw5o`mAWRM! zs5VA{=8w)&caiTQ&fF&>_wU^IO~03MD44%x^A9|2>g9S^ND}Z0$^xS4{;?7JvH#e~ z=$E6cS8CT)d$>nWBHe`+hrN;ftel*j6rbP_Tw!w4XQ<=r4daxho{ZqI{-ABad<`sy zLIdq+BlZM~6l|H+Vu+Rlf{ea+v3}I`JEjTpNK7uS#KVtw+AT68L((rli8eIQs{L^O z2-PapAK5eG-=kZs%Fq_!50*hPcV$#%G-=RRxs&>}@z*8MyB|C|yo1(Db-ERb#C(fov z{Ajs`JKO~9|6_M4s1?7{$yqmlNts)8>HCsIaj)Ym_YDqWuR<)*6}&0+e)&A9IPtCs zLU5sv5HZA_mM#G|tnb zdb=8ebV2~7LZS)P+%Nu1@5J5Fw#E8&zy585g_7y0-|nQM29W9ehq7s&{V3^h?JcK9 z`j&dHM)|mQG?9aJrr(rJh2Shv`y*x+bM&0vI@`Dvj<1EYOR2p>?@0 zU;UJ`PVyB9zHHL+gq(;tWiXr<{X_ps(`=dv?l&@SXp7z_9hO>9e(IOgT!oX|_f=`r z)Gf${5X;Ul3YXMmp}sd!a)ImZ+mdsQ_1{&E`dOP_rNZ-Klj>f5o%rMFjO~2B-Og_M z4^xX_+!MY~y&XF$qqA}Q@!7(4?}Rxm7eb-4($aTXKjRcUeHp{dF>Rk8;kem>A4iQ6 zP~e_WTMzc;AMhhAFm9S1IF3RNT$dcTBOaT%Yc@`O{%QWSqq|e6f7W=5cvW*_Q4%$m z`3_EAw!DGgS?<;zTn+gPGBRtY*48@no{ir4qnZ$f{PRTXcE_+X_j(L5PKS-b{UDoT zX-6|dbnWwxf}2xeo;0g8Gf26HS|@N!rlmpyQ1{5QGxHgE=(5w#q&xz0mY}Uc9ol82m*n)mlnPT);b+26M5ZEf3J{%Am9>SMX8s>^Cc^5!Us1f z^)l2(Re|P}a=*E7O)sFE?6yXKaPYaA-;GtHs-pt#xX(5RYfBl(zF>K?^ zcb%+81OLjoZOTE`>L-l(*BB3T`A2xjjvu#{7%dEQCD;_~NXpbe6D4lgd2&ey6y;n* z!OnMV=H58rRKaRFKejqe0Hy@V%qg3Bde$-VP&fn=7j20BnyfxRCb)9gmpb}~drto0 zJMpV*`h&jeD|@f=nPp|n0}-*VKuO9zK`r{}F?se$U#9)EBu@$Ui-({sqb-N^-aLs0xTqCYukO#?rEg-iQrH9YgH zPwE6+>6Ayfp3reCJ88ED5+VZUH;`qhoUIICxql1Z(m@1_GrdsmuvWbrj8!`nDPVL+5_)0)136myT7V%pIH}dmxn6*pJUD45z1!Xl` z@C{z)=eQ?%!u0@X)>B)O`%=U*E}7#WftUQm>!9d3w;U^-P+4pR8x*@$JTj;1IQAq= zaGs43L&!(BZPw1Y;q@vxT?Y5Y1+D$XxCd_cD*=28_o*-!CaD8QxerYyHJQJVeU>O{ z1(3Eju)41`lN*hzw#p~|a8Ju0;xepZZxg)Tt1e_=zV$j^s>W;1D}ehl7n~nJplvVqK1(=0&T(AjqTKp(&=w!z*2C7>&dQ$?a=@TM{)WWPE0tkUf)$PU z%Ihb<1R_-4xw#zk2L4g6#F&sOWiRoCm9-Q|_f-%l;?RpH-A&knVP z0|6`kD<~;HB8PIs+XvA^73#N$7ZS@niJQM^Ji89wflh=e|AipIU`LSdt-n$i4$-!Q zPoj8dO#dYXPU0jxZB~n11nFhd6?>CNKR;W)Y7e+K%4Gz1?I%ghi4P~(1bUSk*maKC+v-}G9Dw|vOabc+3a?Oq1*JY z$8pAUWuJU~Yl@f5q{ef3|1$CA!yes}K}cI7Zr!w&*Gq-3^_g~P(&D2}K&eY_2DVh} zi*EKms3G>2>g9Nf74PvH_teYL1%B--J9TI%yr|+RJlen6C+};pr794cUVx3k=Q_`L zY;#`CE=`|2xVgCuH1<>P?;wp(Zmh{nI78|!Xtmh-!M)*Lk8CKvIaUDa_vmf%%zK*; zM~$@x$%r6v)cYsARFLT6YsbL!v+&a%r8(~osY5H>@0t;*2WyVTDi8DZPQo{tpQyjT zImK#vr}xQVLPfRMd@brBlRxk0bDwB4bJRZ6CC)cYix}X5F#DqEj(VIsv7h^$XFD*+ z!G{3UH`B1(#PpEH5bCLb zxSXv!BE1#%d3jKPx2FW&B|pqb;mNDCgZ*;WMYji4zvWL5`avqYr=@|eSLhH+*bLL; zr==yy13r@Nnp$t2oj!=1>sDme&`EfQ**#U(@J)YJi1D*zcTr{;w`v?0aCHPalxyH&84iJ72tj?A0~=G zE3?UV-1T-xUOE1U&PbWAf$G%#3p=ORUKsVM$a~YJB%&}QgA+BHIH|W~;6IGiOHyww z0Q($5<@HPH7qB?3k|XIAM{gv*h~D0hivXhXSG=CdL3qHnMA}yKu>cDCYF6R--3JJt zl&e@i-IDKtqpf&laVU<#3c@+UJ5FRzPmsF3n}4ec&A8GUZ0600aS4CMw5&-pHW zYFS_CBJ?e_c{FtQ zxv`vhlR*^;fW{Fw1hoD2cA)Vxi&96Rj!92v1= zryQRiX5N`_M1@e8!dv{MM~cy~jnhZOYq>nS??lcNbGPn&hKQLqi+=8OdD@* ztZ`x~5-XkM{5l9kjcnnJO+stVw5CQZj;Rq?9a)bu|5`Ps;~=h$PNqX*IjeTk`-?RsmN*Tfx~l;t$%oq8{u&|*nhU1U!8iT9}%Zo|C`C|T^X z{ReM-oT%QBFQ39E=jJIRV#;N#yAq698>9gtT#kvqL`_Vi!3;-J4L|#{TBo&#ObkK_ z4eN>E-_m)3@uCrg_$wM?6TyBp{E&Q$XDR$BIFS6gMES#gP{~EijQ6d(jOX{OixRul z3Vu&~C*_N%jMbF93ek_%O+AZP^A&Qem2#iFER|!Um{OCTD%iIrjM1fqejM@Q4K~vI zDzx2Oa}gt>XFBOEUCp-+0g`fEj}sv|R`MFozo$4TLa-a2@juQNhWXfr{~@)TJJ29s zvLemW(|1I@%@o(A*MU&a*fm|^vH8m1_gozW+oKU$^G z*pA7s&EvUr{Qi=1vy*a;o@S}LC);g-kH_sUP)#rucT2{`yWymfobsK2>K*$m(4Z>M z*_7ub6Lp(92C3p2_)xJ_p5J%c_qd1fKD6PERUUI}mX*~Bwh(bh?*yQ?z~zLzU&_!x z9lZ+XZ`TUU1UYHub+>R{A+mjFRDG@N*mtR`6p%g^xs18(oC|X-t=dn^Xa?w%2w0iT zZEDt48ZqiY3?I;A__#|gX)Hx=-^qWMM&L{(UBIRZ5v&=mio&~(#CK6>@8+2>N|eGz zx8TrR)-h}CHvk@gP!C@6_W90`tUH^OAU>2H9asBoo^^~*tuBDvFy+SmUg4oChlzB> zd0R{WNKmWhJKNI}oOI_2nLPQF1%8p+@57$6Ml|^XgOPR(!}S1_CXA#ZyA~AM63!xjHNkssF2BRY(kSK7E~+PkW-rPQLTRYipL)QR*T=#&sI?vbX?X?~JUqj3DqD8eM4a_#~uLwkF?u&7CWu!s^}ju*CsZ$NuQSw-v==b!5cgl?pwG zq_06dmsW@kH=(97X{5i`mnsE>v?F!1?|J65%Vt3;dKKFp zczbLwd_o^ss42RT;kI9yx+S;ptb_;FA*iZw4(D>ZJvKPv2TBy8o<_F-OqZ8lr3voY z&`X`C>U$z=>rglL-SODl1`;k0!Nu6=cfi@rdAmx7-(F2gbh7#<9`d&{9zvABHQ%!+ zYLnrkYH}Vg##_I4ceI{PgrlEc#A|$5Y@L5=s_CoGSVT9nS$=nCIO067lLNasw>U1N z;cB>g%We5F)-+kO^5Gk-kszKgZ#(NZjmMbw(}9#Hr#yzk9p_k0`)DZTnQu*esip5C zja@gt$nT@|3y|&~zdGfl4bgr!5;!HfQ^L|EHh4Exhr7tTlCWyv=wO=;b{3EmIUGOa z?A%Xo^%<8>mp^Qo8ZAGEN8f<6DO}m)gZnp(lxT>9!AOMz%LRjgU>59e6bS=}+Kxo` z--o3cF-vS=vTs#JSXL>0U-&MZnSG54c1mI)#t#=JP8n$yTc1X8=zv=C=x-`3j*TdF zP}-1%tHJpFpCi-Y$uJ0+x$A1v3h>njla<)dTK=o8OYGCVo=$!kq^(v9J+D{cLxZi| z0N3rzWIEMZ06W}sZbd2Os+z)~a(G_}=US0bVB`7MHb87+Fa3jt&H?N###zkl=ck~w zfwidmbNekFy^)?a4D!t|+0GY&bI95oKPwaa=np~MtV9;;hoWQrI+&F^qRz*7=(Fxm zSEMS)vPj9+oFkw&@pQ_$Z;b*z>1S{(WD5OZS<%3T6&V)(RQ>R3SLMe)C2OZ6@Z6ga z_RtPb(QtW1CdDC~feX4@pVafT{LF?~pH%8Z-pBNq`lwO6j5zD@R2T5zlh#BP!fAt? z=p<__--6tWQ+i(s7L*5GjR1tO_jndJ8mh+H>l#scZ|hGGM+B>L0j74$#eLgRs<$3L zeTooY)ps$VJ=31_Wh(bRC&n2hLl3~- zV|sX7YJ1zHsB)YJ=`X?RQM&v_i<6{g4MpY|!gnXdbSGs?ucHrMk7^%AnkRRyrWpG$ zJ@%m`h1w-~DSMn)bqd#_h~)#hBfLM$Z~_Z@WyT64)^j4^G*`aE1k>OMKS?M>eQuOC zb&ydIr;xAJn!w9SBHa?!V%N>^r%iCpy!*nl$iuIs%sE7i0yyI301{hF^BL&wo7<@@ zwPGB+kxZh{6qd_QR_MGLwfrOEemz!2lmNqrZo`va8LD&JiK!uwUU+tM@>jLb%<7N> z*F-Dw0TZU-=|0A|-8#}lw)tZtWr?mpH)?zsV~zqwq`>e&*=(F~WrfgNF!9^cnj4Ll z`Pr0;V^_MzAPhI_FnrAiu>P-!mJT99YtgnLZhuB^YH4N5^e>;g$r6qfX_>Zbdc2nO zN*E2+esr}C_n$)>rdn8YvY)_bluV|}lPW-p2bzUynjdlcTkAw?I-k#P1RHm(*~sV@ zwuVJ}exsYpB|!-H?y;3x9iQbUB&&p6sudWYJbt5`K}q&)|4{hJEEkTo^Q0AdVp+1W zA!!$b{Ol-yn^mt^2DA2+upOH;70Nm>p1ekeX?9r{CeiWeZ9vXdS*X*=-OFfkx63X& zVLsy9v3dW7VV}L*?wn3@>vdjsnPRB!QRej!XjoVOSA5f|?6?C9o4|V1fiTMivizyX zUHV4Wj-$kMZdvH(lhn;;L|vs^vzlEVPA($SXjtpu$!co8tUp4$D_&+UK@VRlky?*Ww$=0{$u9Rl44;lel~`gZ`?S~Ty~Uea9Lbm(EsKEoU&n55D^7b z;>m)UZ(Zl6uzH8JVDAajQprVbwb^dlEL2;1+mK>36`(tyJBwz#ZVR6e@qt8ti91R( zqe&x^LGX7tjC(AI^Hv2F12x~IM)AEV@Y=DwR%8Tgb~Ih_qwlDBqW6@vHmoVH^$>IV z*%q@#j5{$YBFQuAU4P)Jq~g_iw&2Q$C3g*5#ew_Hd6vT5qu6B5H>eenG}S3SW(+fb z)XyYc%B5^~Q}|)#niBhzfx=1*_fa>+orOfInJ=)l)WlPeFq<;PW7ozn`p%{8%xtV)5pO;P>{vYS)@oKn-eD*SZzY32+*d0D~p@?qQ(y*_W&`Z1l+%ylt{Tdxp% zD8vzc_9cEXb}ug9^1BG=T+8?AgT!`2dB~*>tCKdHv$A*Ui7r2DpJm^F%RKy8KYMQ8 zWj7GDle87-2i#rqvRYXQGdJaHgi^4B7YvI{J%|*I@h~$(F?O5C)K}ED?yY&R<-JAD z%x(~i1iUq|yS<`P*I~f>NN5LKWdk%nc-Y)$%e5U>%%*&KXk~at zy&@%>d^B4;D&P}AnH6P~ZptNMgHlq$IF#CrrS&mGoz)@?Q|Q@wX2vY|rGVZ|Mn;L` zg0-*d*r=)`c~4fDo@rd`l_GawFA!@V6$*SQ%}V|y`bDK?+kINl%m*4EgNtyCu*pNz zvU4O}OQS+XF63J1*|s##rxsF1BfS${h~xzohU&$dMd%%hXGw@7a9?||`!MxmJ0IJp z(E#)zew3u0XZ3;k3_s?xg83Bk1Q$3ST|*7yVnX&z?$hedKozH*^%$XG+Dk`bigz8N z#E3-i`aRP76|yZ?&kr}!D>;KT!=m|10YzN?KkK|!LGKYXG`#E6bQaOPc?X$4Jhr~L z#fVMIvRZimSJju7)YtcV?apxVCmX!j~^=N73qK)*JR@x@!H9WUF2h;_Iehy>&)7H3X9l3r`LBX z(?-DiR(h6sV zcl11K9u>(Js}JjlXs?{I&qwO*JZH(Jct`7}gFg7mok+}9wZ@Tf@Sav(0Q;UJMhQig zx~7lXvvST+Y5PFKuh?Jfvo4jJCWJnLn>U-cFo{FP&N$0T?K=s{9H`}Qg?TCj>WtTB zg1uu~vR zdRqAxqvS4p=S7zfOzk=x$3Y=R^#-Trc}ERjVi7;*{`xRfuC1&2&8>RjJnycTF*au9 zV|z!8wdMS_R0#7f- z7eTgp1oFa>^lDxvV!(oKa%*V=D*+-JU{>GsQWJVkO+J-jJohqqKG5DUem;PInL#vE zM|!tLKH|oi_&yo`q?NlJ8jQz>o&RX+LYLO=k&}%2^TeNgyj^ib&$1BHShd%CcrTWGSpuX{NY8K88#Cm zcmFg}-DwAocTxp0zP{J>(nJV{wW zxUjFR)wE*n#v=Kk^Tx8+mWK!2|MJA>yT;ku=uY0isj04k03^R>w( zc13$4b6<#hH)F#oTHG6>fSA?tKdWpRP0<89+kn>gNnzoV-JBppF-zvMjn;sOHf1MCFItr zAX(O9!s1^O345<$`RU?`jGo6jITFi?!6U5vcFLuh;$YYPohoEzg!xBDH~>O+nxvyC zd}~%nEmJQx$xZ$7yp@hsF`yn|4fLEU9{uc3X-dZVaCa?v!k%TIzhwuEiW)NV;6&cq zy6|BIEWruwmUMKeAxShF+}XZ39*52#C_PNN4t?W?ityhZG-Z1Qybh1Pv_vTvhfHz8 z??4#wP9cig@UnHqn9RK%B~2-2-KuCS<3nOV(@|?$DH_Xpz}+DaUUem_;Tp>}`IhJj z*1X-WY-k~|Gq4pHJ)AvQ4?x*CfaNU`W{pmzQ|x}Idhh>C-xtkYQ^{_)H0vv1((keT zi7jOY>!97GewGON^Qz&O>nC?k++AkKQ5vDfdDW&T$Q?84*n(vxn*Od7cyS|vOL-PN>`#Y-t$dpXg^ z3s7#6N}d8G13!xUR97IiwHu8a9D%$GoqtT<8>S5bozJPW338PCtWu`&*4G(>O#qP4yBZ=wrcBX1G{v;^h0QoB{dQJ zyBOvR{8d**f#=X|SjR@}C`o*l^lLFTRZHUA7*ExoY3mR)GO$^uf5pt2!(csZ?qkudf%0vQN+OD!B=_%gu{nWsFIi4+gR$1| zdW$a!vUvN6Wxsk}6yo1{EyCmBoZf8XyHw(vM zXz+FVc8HNvq-7fJrZi^cirJzqHg5?i5|@f1uguL!@_+bx>#(T1u5B0GYu-vGs>Y0;ETcK`E+b;5jhFUt^?y&s-2*Zp?!*Zro9 zNX@&Uz7=O+A`%a$C5&GZxm414k_m-LU2fSV+(s>%TsYh-H*S;0x7tDwsm3YcZA%4Z zg-DxzpgKdM3QS*Z3((fd$MSzu@S2?CvWgFNkeyIR|Jdz(0c}=3i3X7iC(G=lyyZPy zj}DRh9}+ry5{@}gU!;1W;~SRe)(;CO`T z&3W>PKdq;VQ|AraeADj8mHhSICw+_@WD)%J&2IZ-eqt}S-I%pXO}ayoR@0&vHM}r4 z;MsE44BxBWV0tDm`7I}ifntT4oa4`+lwA=oO_jI<<$GVP`7%ZLUKc%iUx0Cc?EyVJ zFQ|Y_6UTNkL;TYl7ZHZEK^4#2U32@QM{4bbat*5IPkE_*o@%OYu?w>5{tS?z^8B!H z(mTb3y-d2a9md|e0??N1rjh@py$2*k+=cRf%c~}!LEnQwApZIv3ZAi!^>GDio69o5 zS}ny8w5CF@5f^vU0uC0bMYscGU-a)qa6=|n!bq-F9xfr zPl-jsvtN$q?&d`qX*^Sx^h)p0o|8Ho{vqS#k13}~I^OY&h={1g_`gd{bHMdCkANlb z{&+XNk6@d>4Us^9`OUYOGes|EF?i)8qNwl4dF}=;BKt-0cqIfzw@f?-A1=rvdmOpq z8TeWj1F5HBaDQ_%m)bkvWnN-yMO)@hKkF7lSc9%eMoAPnQ6#+rw9 z?F2GxJ!5uoa2p75sB^Tv{8rR4ZJdZcPN%iE?C|F8?t%VOh@`Q%;O;W$Q6F7+5|jA{ z>%^=|FE2iutM|qH^hbZpkG@V7YL(_%W<{U#cO{jWu`PlMqGB z|4+usn(vFhG>qB-LyWtLm zI>lr!aYtZt;YjfD({ze#C-XTByv`?vqiyM>1DtowY@>ugC!kMcdY2*pDYPl1~s z&Go7h5pf`FF+PS=$im-MJn`DiNPVV}i}4ahE3xv`4{nyphtr+=x-s5t$%5py?;+}& z3^o1Ygv24WNDg96d%@$#ku3!*>2v(VYkRnP!VpLm{0|qO!{(nLL1QZ*AI@7Ro6DpZ zTdNO~M1;c*7ErkxohZLz1ThE#dX{Iek_>$is*)L^;1vr2b1 z1ULnj|7Hv=JOtJs;=JWpCO$xotgu^{tNDh3nn7*&Ia~Z7go#g`5_K>8N{qo_&lVLr z%AP@pqCW5MQhzpI6~79-ChW)!(>R0Yy_Ti(*a4@lw=dt~P7OWVZFGJwdh`O4_wg)V zxQn$mFy)Hzvge{L)}S?J31i?rXi?&7V1Pgcpx^%^h+Uw+IrNT+?@Kgt!{m3;c%xFH z*w(hzl|S!OqwwSiz&RTyiO-B79jOP*&%kM!JM%CD_OyY-fy8k{m-~)7QM8tyT;9vY z8JRI{;|ar)r_R(~sTlp+IYRk)+NY0;f=E8ww3{!Cvt%B&b0!HUy7Z+Y#hSwZX9NL% zv)2|}HKcOox5WA=)bjFjxrj2sP97kE2&S|xSVdFgv)j~|iZE58cLHVNd2$j>Nv&r- z_M|MiNTgM3j&X;1Q?JE=$A7n&=HTUDKixY*j+?9a)=Tao#Ol#RK0;YlfX~m0BQ8!% z^?0yO`#&oH+-BHb-U(!bOrC1AboZ}?+}w#>4*mB`050&auJ$n{@80D{{kw<2PwrTE z2IHUqX(;GY=3TAS%GS?(S8YpP7V^VB`st6pTA<>NJL7-<>{G->H=5#n2?y(hik_Za zkv(QYvOr5gHr-o0@WQ*I)<_d*ByarD2P$_roU(C}mk-RoXfVgj8{xL_u^%Ku^w-W! zghLFz$#EZ7&yq4)}L1jt_$t-Hg^*ADoZ&s)$?aFtyEkdvDo}l;c&Kl6(>$9-!LoV(U>y)RSEl> z)!bgJbwRrc{ZD4;d90kn;MvcHOUwkl#bf)tPs6#)T5-l=y|%2>axgD@=sT=ry)+{_POc2NpIF+?mqo3Hjhh^ zn>sCP%BKeWfiwzF_rQ6TR}c9U=*G&QL*oO1tYv=g>b0h4o(+g{&4}qQzE;S2=90nZ z>=#EM4dwL-LWdN-)g1bd-AymKK1ngd*{@deUZhA?VUt%bP{kK+R^>&`Rbq{21>fxUA%Dr@pyk(W<^BVh6X4oktG>u71sRg z*0+q!X~lpf2X6U7COMrC$@{>PXU2?`yt%!JU6an3`4l$<$|> zfAsBcN8Ka3WJJi)xvM_Bd!4sQmQY$Zar7yv+1IF5s8fW}3;{TP&s0KH{4K z&H&>WRXy<5FSAiqJ)_WJllJ3Nw6QFqCC3&~CaF9%RS?U&H62%Q`m&SYkZ{fb=8X@z zjW+J~CbzJD5Tf&#-{TWZaI@sjiDIF_7y$3 zha;>Nx*C0Rtk;$hzO6r^ZsttJVf8k)_b}&{3v=cQCDe^Vr5!q2J7xIryRT_+Y>dNj zsZSg+@&X^tsms3XUHmg7e}%YfVPB-<2bpk)Z@+$^`40u~BX^c}c}(3%rI-tH8;lb^ z1PYXUVdVgPXU?lJ=q0F53*?>e%}8Nmw;52}6HI(@BTZ?e4SmHrrRv@Uc7+k+$Q$8` zzYKQ>0__;=YL$PSxB0qB|Crk5m%WjHc}tv{A$)sqnZml z-u9n-z$Y5gYe{@`WeX1$Fg_bkr++~vy4b~I^AU_<)A7%nR)l@q!%^_r$jRy%M^Ug+ zdT8xg(Q~fxKfU~c887$klg*b6pj~H;!mXV@Zq|dU2H2GjFg+#`tE-GYn>`>9x-qz( z4%4GdW`2pErc6KIwqj{>pB(BxcS~T zF=05Q{4_~fLf5XdaZIeJxB0H4#SAO@VyPcQ4UG*`}`UL)>vLUpsOxa$`pQq>myt7$;F zGAH&|3GQS8v=Z`Xu&~nR-PLR3OGJSym~k=DoMN^x6O@&Qx-p7eUFPyIq{l>=vG!O% zB(?DtWGKrh=CWy9W&NqGbyjf>`MiGY9NQbA1TI~nBPHp_%K;2CoYVF zhtFRu>2YTn^6XXAPBbls-cnZXThaU(lRYZLn%IueaBv}{@+3RipNJvzF?N}twCSwX zX!kn8b1^<(IByNZjD4AxeUbjwba6h?7e;fRa(h?E6Mg37mEs6lkuR;p3lGj2$*f#6 zbobfMtpz6YFviI-*_BK}yC5Lq`pDm$t*on0pmc=C$@d%9a*>jN@}<=qM$3f{z1{~` z4QuO%d~eDeURsx~|K2@KjdB@pTE;!(uM*j&6hH-P`vYUx!ow(gC2v^M-L%_Ev8pl^ z+$8E^&Mk;pY{T!89ecX^0(iCUsmH81oV|na(X_L1$t`H?CYy4Ep0@leYfWua6?Umo zsvGc$BgV3ZWn4!Qifq@4i1Ao97EM=l&eT-Npdjdwh|V@pc7rjkz^5TW%CfX-RfMPu zQl2c~h*i$}HK2n=?_B3Sg>$7_FP+gNB`v5xzW_6%rF&1)qD^Vz;-ey-->hU|5 zY8)Hgr-$w5d!X{N_ERm|+AyrYhBg(*AildH4Ek#86)i9M`=WMy)~@oTS)_5Mxp6$w ztH&+|vFjYk2n;z0tcB;QjA7I=K}uLv<9Z$zw>6}-Ljl`UXv3X#gGIP# z!`!Q0tbVs;N|Ck{LedWcHMNSD>&zFP#G4~_Pu7LqgYkU#B}M<#Z8jfkyO?_c@34o} zPO`Jwif%F=A~hxp7M@gFZ*G z_^Z1b0n^IXkJHahsN6veA=D1}&HO-O#%d0?(54Im2&}P@k1^pefG8$qSE$}w2Cfp~I?Ld^#CPI-b%@K|LZ39q(2_5tPR;X zwL>?iOmEO_1EvQdy7ginrX=nds--<>r}L}tq!5_k$yR)XT@rreNq<0w(PLzNRHW#HG!^!&M^Bxg$Z~u!(cXL5Y8TmMv`Bx~EEZNB2 zWYMhKC5s9%EMT2J{Ru4cghtZu_xrodKtN7EHC{Nfmwi-P5Tz0&*7WTER?Q@LG_y)- zscT9XE35KM&e^^wGwwB=dfyl=0rTEu+lS{QlB(%WW0hGc3GPmtFv`k>ck3nab?5VJ zlQK>Tx{ga9H5?Y#HP4Se_8t=PL?G>?VTw)>!Vr5E*k~kcreqXInHER02@`?GdmU2x zS*^{{CsV1p@t#b+m~jaHj30jcM7ueMe$^}dm$VpvND4DfxEGOoi7$?tqILxE(j!Pa zZsiTRT1y$vni9`d?X=aab7&;QK$&*R%}2Im`sx0S{hhPrzCpKeQs z4?@yF$xqh2g#%12)`P!Xz1h!aaH|Me6BODK`7y|?`ilOMwQ)HqN?cn1t3`A4Z%5SV zrEL1~>fz6|IS!G;x|6uDtEz4Kyw0YHFbn5Ej@vLhoy4ACgWnD}pc@ZDUy8lqHy8n4 z62j%1G&hGI$vx8wILYD7w(AVj;navVW&WeR+QcRK7MvTdXK}W_EjpFS`{uVyp z+a#lE`_Vp5HGpGQb&5-q)Jz4OeFY!Ah(ydH;{<;A{_st>e9MHnli_X#+2}=#T`;=d zG(-`1`#FQo6J_QiWOnwB)>ZCLYVVG+R+}u3NuKUn`i}SlIh6PR1~))2(hhP;PWcwW zdr77gbCcZp@{e#=Z3SY%zK18;(_P}|tslAJ?J-_cH+0~Bl z6)mTFa?bcV3W!E#zt!*ak$QETW8Pc*#?&Cy)HCE!t$?ii$Wb&&DX_gmNc0y|vPTN{ z2OjB9hPyu$JA8m?`g?b zCoj5{W$jTYs76;=@pAI%PdbhXPzq8hww2h`k$!8!RUD##DEq1x<-1UYGYKhY=)_9$ z?I$Cj4ttBWAu)X2T^7ec zLJy-HXYnHHQLn+a>W$2UoqE11CN$X?-So}=6EZhmcY^CRA=c*NG1poZ)E`K$q>?68cAZ>VoQH{4Ps{*m5z$*c`F1hr31r4>I<-^alv_zkoQ|at5RHo6XzWMe zE>I|>5?a+CTH7xTmnPr())?86;=ya_`c1AirrUO>pznQ8h@onZvCzBXxNfhru8?j& z@dEC?-hJqVPTX^Wv#@H1Y{OC+%BU@H#vpnbF6Fy5Z8TOowq8@egpjs+4x=^Ow@dYU zkKH7LyJKAnt}=xBm`yy`G6>ANnqs=<_br$De#$ao!U*ZIep$UY>spgN8`=4psGluU z5j0%>Je+z!gg-X?xfLJle#-BWx zCUG+dneqk^;OiONWtxV4J3_v&6KzyB62Stn!hceE-KOhLX0X!~Mn-xOkj!DGV-g4~ z2Ad~h?Vl=M7?pK@XI66;toWfjsT>ruYjNXOg)VdV1&ITFW2`ie z{3!CRAU8&HRqI|hGLZ@!i#sj>O_IN+UGB|DOw5lFl2fmL|pb?R=MkXD`4D z>nNdr9QQT*f`3R@tvESU7MMAtg!caXveq-op9B8krNutCdmh%C+3|&8I{`D_8E#xELKBbbU{y{+b+m=&5;!*11(3v?lur3=XrQOEG zW=m<~(@w{~fTg6Azf!Hy9S>Phs&7;#*%=#?t_drpJz7u9rmO9djk-!76|2cI@w@T} z=Oe3mK=`Sc#4?Lkn%6V3S7bgICdNCgP9vlowLfv-x8fz@vcr@qSd?k(RnSJ8D^Z{s z48o`HyYQq#`w!pi-N+WD$*;yK$#qj>)JCW9J)cA1){=}l?2!5^-OK+GUc?WlO}tTu z;`W~tiaUgNq2^c5`-=W44boMbZ=z@Cf4;Kg(<>44m%=o+pTvEHJEpa+lbE}SBTA@9 z`20UaFJ6YYxIyAN`Ozh+caU*^8tq>!Q?iA$Ke)HuvI~BBc2tKF`c#KZJFnZQC(NuZ zS-9*=3{bJ^tOzQUEhNuNcMD{hI83>j(Ul+l=BcpS_&^^0O^YS$@Iz;k zSH>1Ox{-a48a~5k&UqsIg8dJSQ100+yQFMRZn8BOi@hVdnd;4s5hsxJyhIl|PkUWes6u3$MubuZyZg5MyuRQ__g>NU3Hra};zm^6egg3}xEv<6+&fm@q`loXC4#seMW(jF@JiORn4RuugY@{bM10?W+d)#oW zZ;J!Es?ibQ@3<=|{g4wSZW~(oq^QNa3MB#?M72Xy;)S&60g!aStev9bc6F4>wKB?V zNlZS<^vJq?p08%n4>BkLiojRol-^KaZtc7mH$_}S(k#0%cr9WG1P~T3c=)PXpLbSI zg<4ew!j4bTQxL1Z`t7sUBYfGOzeBx}edhx0!iaz;6SQ_!8O;Nh5#t^&{oGbv=6Ln5 ztWM(Yh%EtCQ+hi~yIJ-*_>h>58!J&o@08$D{w@smp{{|V*JoBC_rg>aCjf3rvf=Z7 zuAM}i>POu;6&HNZ%6oJ*hc1QTeA61)bU6W0ylcRVRBeo3yfyvsO1grbn~4sUFmM%V zabP&F`d&p(3~{ykQW0BN+J%s9hGW6BFmUwko|7=siQ=s-PJO8ul$wvkS5@r}zs`&m zQ^c8)#e>%ppUK5o22mfD(CF}7v8hf^ts2l)^^Q~+;ko%zhHXA3F*enD6Xdkg6|L2(3;yta4wo0XanN)p`Vys$cG^Sb;_P*+7 zdz)w|s04o?L?AV#G%3MKHTDG=CO+R*x3_frWdg=Li#G!%&4E3q8UW55U@#G3CEQx{ zQ+qq*>jQ=5%tCAaH*y6jzSu6ql_O)8a(4AwoL=-Aa$J1q(fVZI@qvp8hkm8V%$Gxd z-0kMH0NhVXQCWpU4f^_@neGXV=yQ;={y_wd+B=X=@IHXs+UGiUy84X#DC816#tC1T zZd+mWsCl%ROWr&i@Nu07x0ZR50&A>pSr%@+GyG<}el)JYolt1KGu^ry(&z6Ro!$?h zKQiQ6<0o1hZ8C_ad3d^n)_zND7L=x=ol zO;X~Gnha{>{BQgbb2bpXNdkS@K@8msB-FtHZoz}I->e1|M&y>LA+`U zyBs4RNRW#Jh{%qm_mAbdPpYctdEnFfJq z&hS{nr1IXYN}Z=Cz!bUOt4^K2gPlV|k7?K1a$a{FrLDR*f^XKTFZUh5f@g@66DJ;r zrPOMlJFizkqB!l**ZAM%&+XWMS1NLZxp?Z@9GTi3en5o&un)hB#B-4T=dJ)SEy6q) zR~v9|%`gl90zV4z|3)vLt{KHV9zWXS(d*4KksU`iMSZUeBs*2$Qn-u%tS$W|qCa6s zQ>r#;zfa}0Lqp}Ua&K!mO{=UXflg@wUWCED8y2U$T>{Ut3iF)=Ou zDWYKC;S&ueBIoVlk7L22>X( z54X#{_8uk_YQjUL$fh1PRV_uL&;5->Au#XG@%*xiim29B5j5m6HHza9bW-JUyyhRT zt)ZbYda^b6qjN%86zA8BF?a|lMQ6cg*u=&BU~kujTATgWy`S2U;SMf)x|Uv$w`KYG zwn~}|Z^m?yiau-SO_E&$P$hFmC?TbXP=B(ul60>8Y8Vm$x^4 zX8JdyitP;KZpJ7K{&w-%Ke3Cu0EVi`ogL$Nz3Y;!!Nff=lmrhA3)2N2H9g%PNkrat z@i)v7&=7P707vs;7Ai0O{5Ws{Evfj_1UyRgZ%f%?|IiUy@4-KC_5pJCo*@?PRcOb} z<>?Pzhb23!nV}S3SvrD+2FI^10z)mHrye_5L9bX@A*}E`Z*SRNvom^vT!%$*_{!I3 ztU6-R(y^`?m#5nkGcz)((H|E6euh^r%D1k zP0NiS0;Z(e6-JxDzYSVEq6^Z!o}?-9=G6gj_C|c>8#G2;&0yBc(-8oID1y3iZbd*2 zt1QQ|Ur)`r!;OR)O+ygD=)7G-y1$&Es1P8i6Sq|v&Sr#=23v5SRefHHg`fDOAdUsTi|m( zYvJjzjMz*xKvkgP&&2F6`kIbYmcQR1z|{3Oj@*MOZ}VRM&t$q-?g$o=TJ-evr0Q+C zYOet+nQw@kt+u!XgzaR>t@s}N9SYFAXzuN6of&<-d#qNz)j&W&{;!N%xBEX_Pk^7FpIk4aT1{MCTwSBz z(=jaMe}{uEf!VhDcy`#SQG+xpue_R@-b=mANr->_#{E%#$N@|-OWdjHe_H%U({+V! zjyl&9ZZAi``4trvnedxUc5q)48&#C^dQXJ^G-6v6#Sd!&#u>6Cq~5gwn=Z(R)YlTJ z$o$K%`bRQ@1to!Up~0n8K1c1215M4%SVkku$n*MA7$BT_M^_9?Z#6S(*mL?@T&xy; zjyFE6kp8doiZ9%|gZ@8oSqxJEcI>VFCGWD2`cV@@a_O1dB(G}I50^*{F7@c)Hzy#5 z@qdie-wy}x#sXzrU*=?I4@LzoEiL)a#4A~hoPr8qwDC+HpdbCLWTL2&yY2Xo6~X$g zBTFMGUBuG9xwf_j{JE9n&3>taIAP64JvnJndz4#k$}-B=y2!5e_IzGed8t^9NEP`f zc90qDvd{zwwU?Jy{$zqe>lL&ld|9MHfW2=@{#%I*Ui`Etb6Lb_+BN%`wF}kDho1jPWGO+X&&jxyFCk{8<#-2Km@O+Efx(Ybbo&n;C2qC z2?|`g>+0&Z!@O4fFn*RdQ^Jd;prx=-PK99s!)}4ahL2!aD~~DLWr%`no6Omke?p>S z-HAOh;(L?cA6XMX1s3$NMeTCznoT|4F})L-lRdIyXLEjQ7bN-%)#7VeoBh^A_d#H& z;Qa6}Egak%7wX#0TF{yfchl`7|7hvK>Kn$&AJB>Bua9o6nLkO5{01v3x%eLDJA(@p z&XGUL4idJbfE1m136beMbKr6IS z_s9#_uHfdhY#@GEOkJzcwh-(Ic`!dxs^d1fsy`Fx{5kl@iBV<=a=PDAAe*5i76CWD z)v;(IHFNv!eMc|1i2+jSqo<}y)+b_pwgs0-dA&eQ#B2shu8TQQBK=?SL_B(-%)U2{ zp`76?8IdvIiy+5=HEk@>dw0U(c&PRUS>s3MUz5&qle_kh^e6=09g4bl8b+GPu3uMb z;>w~|6AT;?$_^+0hmj0-0&??$7ib*6^bOha4aPQfaKx@CFg|K5-&yH zW~mj8+Twg~`4jLl5uDe-G(SW`JA8J6*PD$eoBQwEP?WzB%NNn@cgoq#PpRN_NvT| z-t+aB>qbBC4H=^~v6~@lIqgH*m~cWLyDsjk-;!`(_I}PJqWgIVy6ULbO#vow4bGvA zxwq{Z|Bs!UEg?j#kTjatORmEjM8;PD{x;`!t*9j&5h7CajZwWXy4*7tFTjc@lgj4x}DgY9$iw8N{@Aao}qjK;%^u6Z}PMDEe_T@ST)P~!MCJ`n@ulZLNq zAj)>hfGx_YBx0*qto0MgA6AU2MqTg;EI?e?>H0$i3L`wDJ~VBN+mbWWwqPV+Z5kkd zO*NDqe2GvYGw)k^jN!rCybp)Ue%Fsh(6{tTJ(K zYa?trLjU|SqX|px`~!Ux@+)l7c<}uqAcXn5YHuT%1X}~XEe_ELjG*(KnLpS@=s32- zz7})FlXE3(yPy0-F%l=X=J2Q4Jdt>Pw|pifcJx@stHY&VXhM({*J8TT^Gri zQ;hvTQEujot2z51QMUD!CfF!peo;Qz$TovP1;)QSbGL!!?KC^!~fa6f!IR3E6E~b|t&uK)72ANj3Gj(z!%6e!;v)~{#kt*4l{k_|+I5zMvoms@Q& zBv<(yA=@orq=nqsmE(YDqlahzMxMVV}7h0C0QS5qua>u}&skQ9kt<_*PUJ9}zf z*8Aq^8_v=_dOf02@lLMiIS@Yn(2JF zGVjMXB$!&WLyid%^ietsb2kStfYv$1PDer3l%Q)-&!z~NOlOU7#_CnWN`b2(d6ssW z1YtN?0(q52SCP+j2&=)@!?=v(ENs6=*vjPZlNCLp>elBnJbxlEM;v6!okbhX!vSv5 zZAgg3J}Vyy-m|KXFOF$M6Ixj3xyiE1`kvD=6SBewl^IuA>{?Jqk&o@UI+c5(k{%N) zaDv|YMX7=NyzRg2!@n|m7g3qV z>?W}di64bae=BScIh3TW+jg!u?Xa;aojtp`OJC6M1Hj_0fIBZce1Mw_XGG`}o1R|% zy6-a_I>n+F2mV~&(voVC?iu*=XAw^K1rpH~B_i=fkbFu4@AwxMyNXcv4K#G92XIbE z>swAc5)EP}fx1pK47B*a!1rwh4J7WtX{?zKDEa+=xHoRZKlU@`t2}sYI=3AB_ImOa zT0qLJq!xfD@`EQDhUF| zEoKz%iqDHncbYp~lxXNdFUN4KDd(!bCG1okTIFUjMSL(!}`UhTKUV9!e?B z8kLvkjwB>#=u+Qbh_Q5yqmhZ3?}{KEl0@%8#v;B-gGJfmyH8Vn)4>lmqR(I$sDjN5 zZ7U}4TNww$_yGgSK+psoBgO^_l<=rTI7s|R{!mgL;vMY4vo2Qn=y4-YrR354WmYAx{Nf8zCf9lI?O+IU9Ad z#fT`pob-j9p=t_G(`U3rZ~TpX*|@s!Hr0#*Qpl)h^Lh@n(%NSAA%~-;X|{iIgcb3j zvkNR>nG(Ij8^6Aup3%=&ZqY;5*a&)OqLQvnHFNcg2$F94?wFAZ7p?>O9pNiw=n-k6 z8}JO}&CtW{&_fH3!>U_SVg1Ey?Y3%TnX7|K;U!?vk+W3X+Y80@Qe{)#XOnf0orw;| zs-xtC@FXC*i#gPm(k2SGB32)TX{zmw2Rksea%bNzHOUhT-EGGh@}ZbQSy@?e zX{iPfZTg)wzdv1W*gQEuUjhUi3hV26bLqoPpQ}BwpZS*yP+VNB1_D8}N_99Y^bFV% z@1j=RJUq~o%>gJ3HZiEMGkn;oRr`}DpRYn=)8Ra&e zw<3`SC7UXg0)34s&RZ%;JE^a=)b1<6H(E(-TY1<`8ZxZzb$=*eDaT#X2po}Yqjqyo zuiYMUaz0XX*z8?f;8Vl~F&=$u z@SFVNVmVDs%^13j5yrOV3X?Y;-onj`>ErM{SJ$62Q?lSAj3<#1eP>>IVq((1t+qr& zF{YBBTOeRCwYbPyM3d)w53Mq;L5^%{!DX9jNpWzox?sb?Qpz!`*|QM}6q%s7WLQ%B+FkmK-k+&bt{GpoSK!Mpw2HTe^JA64*mRE4E-xSPDY znJ8TG$IUeX+EZRC1lk%W2S*m3=#5I0&`Ge9vvbZ8?AT*X(klP6DN4rA1dlhWRy?TgmbO`~p#f=*!scrluIh!Z21jyM=NWvqiT+ zKx*NFB;Qg{+zGO#9~>u?gePj$M{dT9Esf`GyjH{5cV?-%p+32tLhEBQB_i>KS6hdN zYsqANg7n%FEq1(|%7F39li}LDtK%V+QyT{HygP|w^vlcD1!)G zYA@ZP80&eD2_uS7i)ifF0lD8d{>S4PuO_fptxE0;r{D}=y2y(kVZnrg^ilu^p$CxXY8uf=3G2kUfGOV(##FRpG z`(8fU<5^85f9MluN}@lvDQ~rq>7HeXeEf5Yf%b+y0E$My$-|Sse6z*dIRbg87nE1=C`Gu72FV z4m_)-KA7oyo;A5uAzU$3a2|xSa=o-rF{Ac$vdMt$613FNcEFY>f8r_O{e{F~Y%9>H zmI50`{%ugb0U2y)g!W+J(jLUS!4Anl=tk6)Syv`hK)Pf-AqDL!!ATo_^uVbx| z(9=0jn6WyQhb+6uQjvD+b+KNj4`vHB)u>G`@d!gy@ba>yIVPl6TKIaw9*#UCf=q)B z(|jo}n;!_Ib~zBCW*=NFArP?lNq7z|X=!ARL}0hdtq1Ho-MxafsOwcIym&Ln8+bwc z)a!Vls<}w!>U4dsK}!FIRp9v+0t6G?n`v+NSc+R~vgHe@ z+18~Tv})Z}`6U85UMx7<16yGd`hQ|dbVIGM*Ib`4&s{5n#vB%pej43YTSJgR&G7v; z{z6&{{VA_fsfybp-Th0|f?~oQe9FG7ef^6`@u3;ZUi-%M}pj&{S9h&=zE<28x5PgEz^eg1eHPe4m4oR7-!?L zBQUY{Ft5$#ltaDKZ*78^7TySJ1R=W>szSNAx>-5RLjPrFdUE^?S3c1)gy&A}%R<+SDQEI&oG`gL(hj7G~K0-v34Tf-P#k5JyS-mUZ5TcRLYZ+my0mYgNwf@(_khyqGFJfR#l_n@;&vZRt?+>Kc5ieLDB}1K#OrFFpLa%#CYHUvB>^#@zy*A%h8C_kz z138?UJ)WYUkpO2UNMM}pEs)P$PZ?SpEEU3)ef2Te?5A7n@n8-a!4N^+;xTowv&uD( zJM>qEP#)_LtacMtQS7=dQrmJH>b5K>wfOdmItUjwwM;%nz6{pVPbRP3>`QdX%+bAG z5-HWDin17bNU(Xg$4+4>j(0_bB?4?S){gStUK~kCfgj9I7d=>>&4JsH)ozw} zyS@RGiElg`9wyu2!d{ z1RkvW>K>i+Pc0$0c|=N6A*I)vIT5+q3cXoMO~N6oSv z%f!gq+PcPZT^dMlmDOu{ca>)UaCh~->#j6ki`4`}nQpc8Ht?#sg+*>oC~>6KBiGIK zjDGb->5t6dUZ@iqTBY-DLC=-WLYvuhOp zvhBG3YKfmQ<-;4>Lj z7;Xl^JJywVyYP&sPoqi`2i%QVQ5T7G*Lc3bJ>R?5+p&fTV?6t+5tX$(syagUPt&dh zVjXS=3$mH%nLmGW-oX<6u5)E<57EBRm+Ot(tee)}m{bd(ko5aYe+uDIVEt=$9-G7Y zAb7p)7SPMAPR^&5J-B zPEAuYJ~T}Inmv}5mX_@K^Ux*`!Bus39Ud_1n4S3sZ`(0xyck)o0k({t?p zO{b!U2A%l$cqV4%u!}k6W{B7NVr1MjA>ITwwBG@hm?u2NU-%5|?u+GN093XCIC1s# z^~>03nIj@1tUi6}fpR9ah`q>cY;61v!@sdfy5Otwu?-V|cS3yiMJ!zn+`q)p!e%9cYuqEq!D{C*WIVk7P`zY*c zX+TY<= z05p`w=lJpfE^@gMn=A6BA+N1XbPodqMn0gihl!&3r(rZ=_PMqfHa-W=8P!bzal3#^ z*66%VYzw)%^4i=85Mg68ZY>3TyFqUxaJkUb*6!V_T3TEz1F&9c3a~RQ#r^hn7)wx- zhidL%13>#V0k^O#eY^e)fhd7Mgr(tCcY*|{PA*)+Sz^{7p*8a9;lqbsN9`DZ1b$RX z6UfWT8qN6qca~_oQiYMFtH&N2Zq2}N>9?xi3XuZBXIfEk@@uKCt}ZFdtA?0mbq-Q9 zQ)4r8QC^9tudnaLo{F`)B(N*@mVj%zN(Df%SjG=O{%!D!$6t?ib90ks2EfTSPA}E! zq`}~}79)qQV?d1}!owvg+Ugg>XjfEve~z}o>ap?gU{`P$elNtR;?bi=*&3$SZf zF9m4@%~0Vsf4xmWB9Xa0F+}#mp)ubscQGfhtxFGE@_W5VJ_!Fa*1XVjcC_sNfdMRU z;kojY4^s0XRCbW}K{0Y;`oAPooLyYF)^vV$lxZg&PS*Y=-%3Q6$lr^h;M^RIP^rPC**yFF=&O^iA^P7|b%RwXe~SfHeUARn@Ia2fFC*}?leIO|nobRT&PGH~ zfs64w?Zg|R%7=7|j~CnxA5$00=(Er1{A6Hclqla6*n4fvXlTp1$)&(gq*3nA+uAyrq{8##CwZX4kCLd6*YLbdU%_c>smX3MBOC5P+y!>rNO+~7XUz2R2xcaho zoTrGPS-E6CR?j{~E#6L=zNd5{IgFz4!Qak4kczvaseZH3eJT6x+qc)oC545r)^u{= zxD~=a+L^xcvmUeiCbz@qZ;s1J>{xWWySr&-dKf;bwJOos2T5!;^51naEs`aDotr@F z8$bJLlVdB+2Ay@+758uZ-(>;qmLz(N&Ltv3|ThALdoUklf*<4tOSGlY6l_i8@=Bb@J_ z2v0?G3kV99vC)|0;NteLA1}Dt0mK;rSExomE(`1H*Q!9szUvt1)Ke(E`9AVI`8?R~ ziuM2F>pR1m3c7Bw7qBBJN>S+`C{^i-2%!Z-F9DRIfPey_1Su9kMGz^{K_Cev^bUc5 zSm>QV=!*0Nf(ij?awi1e_xtYi+NOCe~&g_}J*Is+gIpxo2%L(9NA6s)DyFY#U zlvU^B;DFWC(vntCNcvdyQdC?VT3TA_1*dQ>Ie3c2MXvG*bsQ9g?wUNyf7$%v%#twoW=%y+;BMzO-27ng0+Y6+`gai*V5gVOT=rV$jTal8LrHsE-uGyr(**(=N z*Cp-7?aVT(rmdxLh^C;uyp5$JS>%Yb0}%}w%&D3xJoT6 zU`r@KYGM@2xNnK`^Hxk>h`>|L&dx?qoceMO4frL$i4ie&1UG+m!MyNZ5a6WV5jo0_ zUXDQlXIj90ayYxJ%m~B@T}OiaW%Dv^`mZWS{q1-Q%b>V+s&U#?^$!fo z6{yht@?u&x+f8iy^q4y^5FPmd>&CBckw!%5(r+PbpJvE2QUEi+%1%jXKygad4 z8W_h?;QJ#e?D*SKGhwx<$h;EuS;MJ z#V#)|7gY7SySXiaWSPIzhEP~|r*=`kHtHvZ{;DLDXO6g4jRjy)3Lchy;qsIBq7p%b zIA!SyYJ13ucj^<5uHCE;Pgw|ET|2+e@LsE9rL(4pa}=(it5#Fl2tqBurmlzyG~>cbLlNAi}D@P<|c7 z{yV zB)C;t2#bo+`AnkcRpa#r+UT#&&l2voxG!;rg<*eZ7~>y$Hcc+@#dZLnN$d3oX9 zP{2cJ9=#G~Y-rd!|9zt(TvukU0m{pUCP0?w~UQrd-;a@dVA4e zp3{?rY@^)BhVeo?Z_B>jyWn^a2)md?=iCHJllQcS1n=tQ;dt;?t5v4nhlK_yjG_4` z2W}LWo{^ynvK?V@aWK3w&CSgQCMH=RN66OFs;aEKzWPK7#BRD7M@B}94m|&@AzY5X z#;_EM6<8{o6_S=Nop?x zX)xJJffx}NvKwNE@A_?bM^b0C;egaMcRBv#b}NBzZUbAedOolze55HHS+ex@E(3sl zOa>l=XO|2lC^+qAPYIrZ)R{~I^*EV+O!S3~%pTp1U^J0KM@NsxJ_VJuL!A=PEtqq6 z*U}df!{hLHe7B5j2cx@1dw@ymfeIv7Y}Z*qW7sQ~CA|)h;E@Yaao--wD-o!Oa}pMfk%z{Z-F8%Cu52TTfkjlFhthnsin0q1Pk&hv-h~ z4uZte&y+n)zP;lUnQq<8I?6*CKxB-B4v}wmH%Xn2OO9-_k9`;Agpg)*@@$Je;G(Vh z%2Aq^f2nL@-sO!aoS_ymfIm~Vv9i^|Fxx3#r_#U;TmZW-M%4W|C~Z;OtC z5ego0i5*Hll3aY^)dlQLpc+(ks=>8cUG=_eUeu&sKAteQBdU`a2gF&EiES*v z=$7rZn+V&m@bIJAS}FyYVlFf{cN+WLk& z@Qx`khi-5i!!!F8b52@&;qCfYUo$SydSLc&;2Q(`1h=!ny>_-oKkGp@jk2>Dop1D> z18qOn1 z^{jF6MgLi4^*7Lsf*6NpjiT7)*qSBqMis4bcN9on7}JC8jjHTmjkSNZV&I%;tw+J=sRFwH5*X(%-k`V8#O_Dz`E+GMRIvQN3v`{GDKuDB))UJ> zsZ61#=~vIVwRDGpkw5;R`6Rql#1S6Bb<9jMd&$z=0sVE(;FyVMou zwe>R;Qyb&0aMh8MM#eU;z+?cp>c5krBw&|y<;`DL%nla+y}HkS^S^VyADi+5xLJUE z#L`HAHvd+5YO=GlX9HB3Rw*DLfB=R4xD`;c#igfTOsn)$N(JfIy-{N$BMd0FzL?@V zcTV5c)wOjUuo#9g*hL84eRp>1-K1DQZmC^m4-ATpjm=C?Pk&)aXFtcr#^P2gM_f*` z@h?jX_Vn~{oIU%>$Lhw7r=V7JGQro;Q4?TnpUa2xztl}lZMC30ayx&1eF`DteO}7EUH|E;xkYus3J@K?s&gI8 zcjk+Ns_qg}mtMWS!}j)i6}+sv`h}&9u8vSj`_j{-q!-ghE-n`C2ROsOP&~orey`54 zmrgG9WQx0bF+SeZz#XcqTaQTnwgB~}VzJnYg(~UtZ&2kK z^e2Y|*`or|EZJIh3ULxr&KwDna|uT^i;Em?2k*wDeYmUN8NFM=R`YkiPK?m9i>2uK z`?}%vBUE4vx$D@!*QoCD=MQx#{_v=m_PVPZ-rOza72kvXv3Huw^V*LDUpF_2v9fK) zANaN5iVjkomyTbM)5%^rfP{+22t7aU2@#BqHhEYoWs#~gH}^F9s!rH)(tF8T10OzG zlgU$LxeC-TQ+2=!o^KIrgsJ8nCtKv594tZ#rY6)Wd##U`R^BkPp`6;yY} zJf1$jZ48w@x(EH!9a{s)9gFN1jaS9@JIKS8?jWSFzU4gt$V^FxsRzR)P8Qb_q+_R6 zGC`phsz{5b<0Sco>Ws9s3)wB(P4Q5U<1S_Q&wFNTH9CsT){mh~ST``>C9-fONp=5$ z9I^X1elmg+)1n&aR-Jc_7*Aq6#-2aKuA`~aL(Q)mn1>|86G2| zs~;rM^KN{VxndWYbz1V$KB#8chigkdKwM{BM{755DJ3FTSem2&A>#xl2dl?}PLD=| zsZ9e$8z1l82F^b>Df0IrB71AxY-hx5#5YtGJ7Wapj`w)^SN}%~ut!4#i4}k2(1W?q zgS`{gAh&bYyBa2qbD5|o*`bZQZS2F>p6j-$UH2V~NF&p>AfD=@yNwutrC0m-BkB ziR5GLt|53K{bK!$!|gig0^#j80_RkL6BmjR;1b1pO3y@gOk^|QSHYQxZYB+^LN>F> zJ*6WR(w~n3MxTC&a?sIny;zeo;)Irl(}#~_2EJr^bPU9*BZiXr zoD0S!q-bmcyVDO-``JxV1tzVEBOE~A5HTAq+ju{j@m1*A*&~6`jgmTGSv;_*JAWij zcW1#csj$o$sNcTYf8?^mFF(%Tyw`KYEU<&&bLfp*ZxAs$x$w>?O4wA0gIsW`{L5Iasd)V&yTjnIVi=k-X$!y%Nxb+vLc9RVVKvGE_2nvwlTWx z%4wGUApD_Uy*jj$hkgG1*(jEAf#d8T6@sLtA~*OiTI6SocJ86zh{F+oEvKKVsQ9i> zdqK#h#pFNXo2PvJ;Z|t?gQbIL3hDmyr-IHl13U_H#n5bqe|h-^+~KFBbT5Ny%n{Y7 zm6B$mM)#S*+?LXs!iP7U&TdywtU9H~Cx3a<>s0`O=z@(r#@jfDv1VS-^QL!+RVB+t zP=IF2%36wIBs=~nK3yAJJE{1~`uVUJSMAufWL?FdANK&xpu5nf0k(GGBg}WdMxPSn zo*Io%a*Z5NrBxIo)BQ5rlZl`XUvKHNLU!3AwJB6fGNZzfohvMmK_n7qfH;lh8n8YT zO*8kpb{+{f0O?DR?)~gDcLkW1ZVBsMa@UwN&ZHrqJn@=?SryxdfgObp?@Gth;|N^^ z12&$~OHK6Sy9|hH8ZT9!aIn8U3po{h0RjptJ$sHR9N+vKf0jn0HBo4wMx%*w5C&-v z*IRXZMMzXs+rh8SS`QS`0YK`Sm_Y4*8knS;slfFXRGYd_+IEzd3U&5meE(U{8h>_R z*kwRi*w*zy#OBmf^a>!f=`4M3cXv8qS))liY@Q&n?V-mU!5+}mM=uhjbegUJvc43Q z?q05dX+7FzEfzQDpZGZ8Ti`k6P;MupG zPYn<6a^82~Dbiv?wpJbN4UPUhcF-4k|9+-!(zP_}D`(tmD5QKko$vVY;Tw)_^?Stw zOJGZprGRcyCjfk{>meZ_h>6A%Kz!x|I#@I`e<=StX%L4E*ffr}vAMc%#G(p=4OnGw zOP0?Z2D-G%%3FEAKxG6FU^-xLn@$CT1q?Ju58V^^;wQx7q5sH(El|co(+S0ulJas2 zC{sP&NA?1xDk2C>+=y78YakmX25dA0Jg~RtPoo#wW(g~!T7Ohpf- zGwEIoNfvL-`wLjb=sZSOBMwSP*oJ{!f*_PiScW@j?)UA@s635hXJZR~0~QwgVeHyv zK+*wj@u0lSl`9cHcV+y_DfgToEUe9{$hle*fCa0%E-nc4Vlv2eF8I*pYD9GxV9=o5!sY|;zkQ&Awy?6uF(E*J# zH8s7o!H%NEMy~zw@br|Ki;Kr}%3YH~lJb*v@0;~8?)T+^ZPUbIK-h7VyjtHT<+pjU zEs<;_S=cApQ<6fBC)tm4!?!#BQI7W%(~o;mw&nPjYSebWG4SYbTLn(}9L}R5Zw@No zh)7IK{7pkOE_~J~x~wG{+~7{izce4saG53t0e5hmor|rjZDfP;zNrZUv;-pvXvJr( zY09WHb)xdp8yObWV~R@=bIYrKQZO?!j>oM=cdq7Fer`84;vY{ruFUD|yxkF|A723@ z^!S3oTk2?>*OMm-6DhByUbF)zccOs`@0fH8ny01UXl@+m(5wsf<@si(-JF+FxG0Pt zGt&t^iz)W6Vt$eECm5D?J6-j`zAZjDL@%oUz$Rww#XBI za^tVnUpGq%B+{uPCBg|LnUIchV#==WPs$8iFafC12sTanfTWq8$biim6p+X;|>qpdxY3AToU$a89x z;7^Irk8L?k+H4Quem_fdT>E_Nl-aZ{)%D4xiSPP7QoREM@k>dOOG`b_4hk)_2>?fs z+0YFVxUc`oVIHx1Mft*C@xJD@!*0L?1%zI{S+HLnW@BUX$>}sJ>r7z-7xTG3^r@H#Y86|xiB9%GV1{f zb6G`2Fc1xzJ33Oma)Hf};K2t(5-AgGum|Tm+`D)4KhYhmBwz(CNEIpx!#^n{?Lh5; zN`uIy;#K}^&mI^L&n0na*>AUja~u=>6?e*TxR;Ab*B;*+E#2uGNb4e=vM_swox-WJ zIcMT|LEvtl_jHbQ^=7y6yP$m-rip3GRtFVD9*=qf z_2LojsoAt6(hj)-=M&p74P3t3;I#rKKTD&of`U_q`deIPW&;_<_&t?QGK%egioEqJ zm>lUbV_UwqUtp>Ky<7|{zT2pWzycm{S+iWa&)iiBNYXL-nYv#Q-Xhz-{dkjJJUg{X z%wSHyM60B(hi6|RSIDJvt{6Hk;)PF7$@iGRrz-q6@gUIkCo^IVn>0W=R|gz6Pu|hf z6x6HjX_#JH`c*-?gzQ`;cNW^OY(((<>&9ec%2)NPr zrv7D7Rc%g=Hof=<_H=u!EzL%64oosAO(s|!oq1Fjer1U z8F-F{KN=MJMEesKOF`uI`@5J5c3b53q8TowO{~ZE)BbPn8I%xCB(%Q;9ul)f_fn{yO;^QK63ogwWUdQQdask z@x1l>_wU;!V1Nrw5UINB;-U+H#h6LlXV~=A6f4XAaby6f9rgmT7%NMAd8i_n1Spz*dMf~lQ0bpR@izd1o54RtmVgZehVSv0!q=ZD!7JU=000IiD&J#UHInz^ z$2}k^!Gc9)7jP7lnTY@dDA>B*OrengL}e8xZ2b{s$s}xrSyOe>;srKBs;9baP;SIhx3b6%j08=9n;n!e>vB-8KhMt_2y>=;{TaVvtf$ z$Qc{E3+n7xQ0F}-^Dv@iQWHriE0Y1s)zQU8Y_5Vti6K#XgP7S%KxNZ;ums}bHFMxN zsICeN3TohY;OT05rW_M09&FYCCBIMMbU&W#HTvpIR>&go`egc^8hTm((PfaI(dDM# zi5daMACxA}M)Go+`tnXlCnqPbwYmCd05~mBI;zg?hXRx277K9!@VbTsurD2Kd9NQ z+P}ttn*{|u9@`D0IDhZ?v4VU$1Uf@u2{pb1%QJ&@BW@oxGE?hu@&s$qttEU)2TZ4^$FLyx2w|{gR z*b-p8)Rhf@59GY47Om^_w3SMw7TDAdueD^=)0tBF*`cf^pgSpz3?L1R0Chch=vhsHi^mUUWoL{0_(P+Rz(yMk zsCj~oBBcI^`+^U-fu>_7EdT{yh?D|C!nCx;v?me(KS}94+v(ULdV81NHk@*EuJNn? z{K_+M=KJ>#+C4-t+QhD|$E5z;J(>%)%!9h{T5rfw5T&=8udWS>o0U}ZU{RyBpsiH_qqz`)Xv0uYjzP!PIE z$pK*3Nhh^L$!>b5d9QUOHdSq|beVm;B`+w&xzMq&5@I2#BRRQ)?!JJ)z~pdJXz56~ zuOi$@&3vJ~PdwmH9k*tr|H|+J&NiLbR$=tIO&DK`J@aORq1-YJSucdR#VF#s6CHo#Mk6%-#ILcBQMYrKKhG z+WVYGl$}(bNd(YADhYdc?*jFb5DRf(Va-)D;3y7-jT~;V`a9WT=IcBUw*jh_wMDCq zO0c#sQjNqfUk(K_rON%>ZM6SnL0k%Z|Oz5S6LOfexy0961tH z1{D$%)B|C?xld3;L|;u!?aSlL9xPzb!6d;|S6f7ulzBOSQQ2Is2A!N*|He{j35Xdm zMPKGivZ#Vd{02M%&08TQB0sjx9>j8n)%Mc6dI!)d{S@FFpaUGhOTF}gy1OsJs~T+f zk;|jQVuO-J-h;{5GU@iU^tLF_f?gnfZ z6lG@SpsyeBu8-#>-rBY$NFSQ_wgPe=@T{b#D3Un{Q`Fk6zZDDlfR9+7ABwWfuc@&F z5#~rG)kAJJli@Q(>6LDWzMh^8u&#nQom^b{z`3WC`oU{)7NCMWvO4<8TdN(DG-N4w zpwbI3q-%e{g@+$GwNzD~bNTAw!33`isZhs67~A*yo?FgOc@l@uUD#?B9wf3wU7 za#3*HwX!K6GPJVF2SFZJP;e!UMg>_m-Kh*wfQ!FXT@KVtAPDK3nm!Qsf&j2<6T4$I z`jCq<0e#AN!&~(cKfkTb6(<1v@c;qcR#%@~S?3#h-~|KHnb)shNAGLCe*HRrp=RCV zo8O9qx3>v5G$1D=gv$u1eCQ)NL>YL9U46XldbJ7y1FJI0mgGYqGvX` zVf>DoS`diuU#=(V3RDrd9d_U(U~jFTf@j4v-OuitE+eT|H(X%>%9(n^p9i>Tu)9-v zWFuA6V?19<7>Lv$kb9xm&L0Iib0+rUwz&iUbm?<4v30&G^CxT$iO@wfU|M}r9ALzQ z?x18c(>)*!>MFW+th*YhhgyAsjs&n(`Z88P>@$48wO-N+fhYw(vRH(_v8g$7PG;C8 zL&7Up?|D?WZ)QlT4gB4(*xGaTakt9o*w}wnVWx7hre11+SkUVGtPYe75!H);ph0`o z0I6AYyR5V{-`DHkK&0h`_^r(y?>=RWu0O0_`t`BSRo8frkC`Jb;2n6D!`v>6Nh`_< z++~3Vk05+bmPnB{(0_nSR<~n92vYktSXEi$~22}qim*xpf}K1LjSqfVedYzqwL ztLvoxeiT@T_eRU_eLW12)Yoc|-pzs+ivdv`SX*G4spgU1_Y*DF2Uhz5sFib@Xq>n5 zRY-|*-)XpwZJnVW0t3K9_fLIsiSc@mT!0XrF(eZ7pkTYJhXuF(r9-+KLHw5kY=6Nx zhY8egcXC@M9(vVu=lDYJHsc7q_Rl*rF&)o5pUup~gi5{JZ-Bp7b)I^UzP*lqG;ZSt zzQaz`;vL0e;2U+ou~Y!--7-t5NxX` zcAERY$KlV`P*pJ(q+NtC-r@7@Wn*p`l^kRn_2c55?#^QCoU`H)PwPGg9|*pBWv((| z;k&Dp?BBgIEaxs+nFO=k-RmS3apjrkyNl@2Dtxw6$K@Z2H7{Sb=D5H#BV*w3ku7eM z99(N-WBFpbc#4uYV`hQ^6@C0I_fr#+6pW;=Utfq~^v!}k%0Ev&s-$lGtaV!GJJ!A~ z$oPi+9|8b>YW>%y){y_&bh}N)*@1ljwP^uruKE}glZj%~Y%}{-%x~(N4>tp@eWxdU zfw52H`||u}tDy{|JsP{SwIixw`WX3NQ<{K8ozXa>1K@X6TpJq!PFvKs9qYXRdKs#@ z>pS0fw`7GHbll4S=zY|Grr!Uno4jDP?i}ywvq^kcl+c2+u=fKhcu?<+cimA>0qV@A=k?dv;LD7%k}P3;Ct~wG;xa-0XZy`{OxIqO_z53fd1Re=;)Npj#ju=z(zUQ z3aOeX`}b!xl;N2k-361&yBW|3(th(!R*9R`&uR6tt|{ZMQmhKU8H2|qLKXkY1}w_D zt+-$7YH+WtSC9xxnx)Z8lswuf~|aB{FbOIX7# z$_G6YBZrfEiQX^MXQ$kS;Cx^nLN?*+%iFo{V&Is5w(>F$7S|}1h~P7Il3(QUH``vw zaudQH9nGH5G=%XvFc^>pHv1Q{{9JEtiX*LnK%nJ`4kc`A!G{dYOk-c zwz2FQ2Wvc)D`u^>_ImgF+jQdEK5^Hc}1Fo*RK)tsoa#$O?=5OZd%cN@zeva#qVTM-4y?P-RfE^^(x(LCv~jv z$Y|L?${QHt=GFA)xoD8DY2oL zt-Ra)bjQ~#?F0Tw#JF-c+?o71o-$^FS6;R8i`Yv0p&lz$gw+&}iHsi9!SMHP&LDC_ zW#5`FR;4Y12O)Yo%(2<0#9nuDsmY(vr*+4D_S zkTqJnyYPO3U{(&&Bk?3Lj7Cq(s1^<<*;#4m$FXgQx9g*>J6fk%H6C>zz_fdXk3-=uN zjIK$KcdkMFvrnSc%cik-lzz_?bpOmejfPlcQmAZOBTaM8Dfw>s6j+8V@(bP87jl5{ z&%c3s_#m^K2p@D)0_Hr{Gk_pK4zoK zxmtO=`hv)!xVC4@>#$hv0F z*#E+E1!fmCFZ3bA3?uJFXlFiiAgjc^YP&ke|i#ySZB*rQ&iH>G-G@FXKJQ}=! zQ(ak>7OK2ifT!~Hj?WdVVG46!{t7y-)L0FRV7+M|kpbOFFSI}?ERd+vzPcc68+4DQ zSyCuij`f%htp)4j0WDTSV2=_Ndv{gu%MNMh^GWdf&`@#w^-wh%roGe8GvBlWZ!x;m z_~N*oY2HtR%^m3}~;|Q<_9p1P}R!)^(Wmx;8D#Wd-W@zqoQJq9c99ko@1BgzJM#H{+Mf-6X42)QoC8fFLY3qiuYG6_nWt-3 z8(*yiU*JiA6xyl*NF{)OMUk0b-<5)}Bjo9#e*!PCK#hT%ukQWV$G$%eGTR>@9 z9Zu#`Ps=+}ocvwM_oi0jzU6FIrWm;9$3|8?Gj$h>3VLMUD{gLX{<_c-nJ~Q?KfDN( zglooIZT|~+6u3DnYH>Zc$djlnGGYH%5;dE`YYe-dEEt2vNg3jV(Zm-&!DE|CLz_f3 zbO_pPl3(M5>??~DQiFzIaOUwyj3K(n4N=s&l%?)-(CyA9Ben-l0@P#@pDsw8WsOYm zM`Sx`VC-Ngo1G?{#kx)i1^Ad%{r5$i-q%qE4Ar|uA3(nR-vJx*>~(KD`zZbC>w zvbZF8N`Vj_u zd+M6f)&}$fHqhB?&50z0os$k_GX#iFsq>culj=3szj+J!A%u^&PZyq$Gtk4`65@enj*IE8Ne8!8DTAiO> zp4PrbTU6SC$U$@!Y-wu()gv|@8+8CqzQ5KTqqWwvGTNPOEOTG~hjUy?wW+>iLT^@; z1-fdPKX2r5H*clIvH>@~DbXy};%W!++>*4(xd&!OYrSm^GCb*^U`&|?9<$$E=o5TEu;9-{OdT$WYI+HLvF)!mt)`wgh4A;Yy z`T_`c$Wc9vom6aAIPfh)^*QEPo& z3gSDCQrG#AGDx(f{m|D}9HHuTj)qs5pNc*fVl&U3BDjz<>n+vWK4ub<@yaa*KQvFF zJjd2_D;mjG44r0ADSx0SIKV(Un!E;Ou#I2KD6xn5h-r_omS%G7iNKL#vVQT)c-1U{HR$ZnMan_$sA;UZP2ak+cPA<>?^zUC;C(W2+_M5`q?}I>oYxXp0 zL`vmpuW)gaXKYauv&5S)Y|3rrcsw=L0C`P2LF)5t9qJ5uVcyEREuq_|7Eday^6hSV zkTcQ{a=1|My&X(=(o#AfN>(Ewjj&e)bQwg@$AvE_aHs4*^YdoORo0U>-h}ZtaCY*F zCU)I=EOCb%XM5+^a>$_16V!a0^l6_sFO&cYGK;*XIhaaJo_5wp4z=EcZF-2EGOO z^?Pf)MLbHJ^%COsO;w8EHxcQXy>%xJA@nby+!W6k z$tCp_Pv5=!n!stlvV7lb_0+-w)h)Ju{1untD5)ZP|7Liw`ugBpVjsyDx#5i}7h73^ zI_Hq2leX;sJX^*lYJ(hBSIIZMLL1xtf?Ze0QA(|hO(x)k3+D@Ays(4m3R00 z^sisGOCZ;WQG~Tfqkm1NActWOsOvuCOLUBSVT^I=Q50UKd50gu(y*rYsXZ4;s+wRFNln{0J77usT5$+HMA zbTrvxBnSKas$r8fhp}dJ@2scvS#Bry+zjJ9tFB~u`QHX1i&N0{$^cIwPNa_hSj1I-{yIroGT*b zUN$;FmH2u*+KYKoO}%IKmgcDuZ(8sgLD%n`Bwz0?@T}ET_&>=XJ3Ad>YEpmm1Rb}v zZ!XGeF?SlYSRjv$n)q}XW|s3iVOr7lgHL2`xad4^DQ*~4QRHjN@z+fVnX}h{ztJ`{ z6h0zgc5VVW-P1l-&wLod`W=7sqTN)8_)*HSO@!Ow8Hazk|jkUh&1%tQ(g;b@QQLC4R3+~f?epC$k9!y^f!)iSr4TXe0i zV1-lHaLuoj)&jQFjw%0HZcqZu88`wbuV8_rwQ!4iwr`(gWqgrn&(xI4NV|;=A$p>X z=%a{E>3(t%-gd7W!-SbNPBqLTxjq(t;)>}_43N-vz@3T8vl=pbbEB9m9wWoAmqtTcwf-l+HH-_nRSfU<(E@RA%FjQ%W#q-tU(hS znJK4t>`wFIl~g$>;!iHfTcv4N7K1R(myqlIPvRYh+Ni&yZP}!_!VKP{b#L2*HJsAn z*N^GZOvyAovvslQ^;4vIzEg#lQ`rn{{0f@Ev;Ld~pv9ZNxrjI~UnQr|9~^#eD=(uu3b!TtEF~B>+2al$hS?Z7h;7vB3Zd`U%F!BJy*~|qdu*$W91N|RK%o2 zFLP(xz#=EGmPe6x>qYxFEll4F@sWNtnfPR8TuDSNgD0a9UX{daq#6t zO~%Y5P)H zarZ|M2wBVPA^$G;kbc4Tgd2+r9boP`T$yoFNWl%w3%1$SNZYC^}Up{1<&IiB~{m6dd6C|PL?ig6)UrVz|Z0L^REZs*3V(+KZ))xqEXyy+QhdfRfiaH~L{YC%x@(${_HzNLI|kDRKGn``(e zLW-tqs9gdJJP+tNOP4Lh%i68YzgnC3M8PZNnKc;}RXV^A=CMIh7H^_qS*w%T;Gtjk zuZJo9zJ($L(I`xhhvP160!agAScwyELy}Yr28`u%xtdPU71&-W-P7FV_f#3 zX?Whs;i$-}?oT)Mi+S`PxIGCtWZ#P}oiFEuY_?eGHR7kAaBSNuFf??HohiG=BQ|s3 zmXD&Lzub2jQ~A=G&X7?hW2o^E)+~0)6g_eHf~a;u)$sHP1tIQB$nv-vSI#5UpA$Z1 zcRaLaE!L7`ok(WXvjRK7ei2|Q5eSSWGEt$IbH<@BfXhHONdOx!k#9AX$rdHHoKk+l zTT_X7crx;t{U#YvLH#`uDezT4REy$nV23s^gn1BtCTgDBoG-`vGY0h!y)c#&ZJw3c zqYsPGHO}?MJzw}f&(VdHAmjzUWBa`1c~cSn)rIE6^i8)&);N3M&R}(!v#YVbbktNG z0kRBZ{n#pE&6uBzu@rJQz5_D z7*|mer-y}cew}7bAq_iI@^W&>;Lx{NNP@1`k&sKLM~*mqiA%TKrjSabrY-sSX0a)V z#Wlc#`LtEbU~&TwwK?eqt8V_uJhoJq@1GlIM~7>$K*xat z2U53!8JF~?(i6=?UZl~ncQq@2#Y?x^4V&O0>J5V=Q-ynnQ#5Eqjo*C z7V}~%t%E%FIV6=r+qvvtFgLHcJ5R5UZz^uiZKgW?Y_8Q4>|1Is6&V~nFZlKbgr23{ zJ{1+9?S;2>f&~kn7A=~`i>#KRo&l&S!8}eD(!Q3jMSu|f;^X1g^Ex^_`+#O_}4S6&$0RwwB5uam~=7@*L;6D zo-u&m?=jbcht&R=>-I=D(BYFkt(GQwJIMO5QOE>;+xr(rF{GY(OK57tnP@xyVxJq@ z>lG!(Q>t1NOO0EX}= zl-ipZMCqQj_ABJLJykqLL&;S`g@n+W^N)N@ye~5v`#H4T#li0iFFu&!=MjC$u*eq5 ztKX)_T^#oym?J9{yKkVBZ_S|X~?me4L=2looUmA#6Ht3RWC0rPWY=q+b9ET zGW~&X_pJ$@B8-;V=X$#hp7+Z(o$%a7N7I;PAZHDoqM2W-;M0?48PN885g#x@INHcw zOQs}HX`;q4+VaP^ofIw`mJVs5G5Lf%G{kl%%QQI&im*m4Q-oQ2TJ1Q1PV&dRN*8BT z@@^h3JTyvid~aV3#~=?YO2Ow+z%w3dGf@-#P@N#{IA}>C`Ny(ohvAgs2%$D}zU3HV zyq-3&NKLpbp(qkSGY;t0p3wTX+V17CzC15kCCeC=lw;d7F0M%*m)Qf?G(X^sEUmMP&QLm|Z{;0HSg|5;TMQ7)SLN7X((n)uboJmeH1ThC0ICYWR4o9(X#=#8v zl9S$)22|t=FJuo{_5Adq!n$UOgNE&-(ROMOJ zpp;jiD|hFH9hr~0vqJqw${5*WH*y5w>y+>&47gU<-xAYPhE63G`A9$B#$7a~Z{F9t-e;ex5ZT)M0`f4y^rxDo3^$vQqHXg;?29 zKjVC7l&LciYtWCML)+}!jq=R=n#$bGoO}mz<2`;!{erBnpL&E(G<3P^3`j?TdvcQu zD$^pY<_$bTj$|qw>!d6g$$rgBc9zW+m>?bS^P8O~NzWjbimgV8V}J8x%EYpVxEn`$ zo0#E;Z3qNU)!0upyPyA?Q1orjF$MfQ3&9^+pB2S96_jC{ymLMiICEE?*ZiK8r8Uz; z$cWH^TgXIbQm;6(D!KS8+L3%$`$pu@58CL9dCYO0O-prG!mrmz!cFD1rV!+kxB8H= zrJGAW8)@#jX(Iz;q8TNTx(K+uvav|H5GT7VFyqIGt z;Rw6Zd!w@B67?&fp<=4BA*NYoP|I3=QPl6g4doUI0&)|FS5sHs__dB-`I%CdKcaU+ zr%uZhmyqWPLf!VU;Szn2PSHn;2pRL~k9fIgA}0s!;DctyDQf#5eMEd5X_pU-;2~AY z41pIPT9Vn)RXWx)v=W(M{rA;TPsyJ8dX@ZIPaPk7O+)Mh%qNRVzWDCqRTW0-kH)S7 ze`cqhmj^8!Q&lWL#F$2#W2~wJ^bHMXnZeYc-GG8wy+10%=WD2~TWs@0@g#~SRn>+W zh^o4`Xkxx6icKb--^KJ;R}NGJd%lqbwp`0 zzv-!>7QQGLPMrkL!)Xe)XxbTKMYWPy8jwG&jmuq>JL`U#P!f$xDhv6FKj?BeeTEVZ zO~1WX`N#YNnPGt(RU#^H?Wx$%t6-z7qO4L{3kQpgw8C{F)ZYi%3k}GA-jrSjb0 zm|&?+a8XxFX}YO*@P!jWiL zw})I;-J=}!10li!Z=+#oYuK9`7vgSa)wZCcyL0~XRf-tqO~4M`xeAtC&~K_894^jk z6J5zlFnAwnaf8A^DJ{v?l6zP9VJEz%Zm$IiNW4YWzCl=vsjJ?wYyo1TGJMt5};(_ND)`h*mGdC6H)t@CP+mPwkA6)&J^R zzhL_^{x8oy{tx(hG5^a!fAcNYdly~&Woo7^>$Yl>{t}v z_J4`Uy`b}6HzoO3)<2fMKjW{B4Bz>0&mif$LJw3FSx#2*e-*X#j!NqK)mwx`FE2Fv z{w^!|`#Q7J&bfQ)e1A{3($Wo2bqu^zw&qKg{mSXPo337dQMzitpd9sV<--ixTgFE>) z)@enqQwu?*!nT*EX5E?=skrOd*Y~-m-l6rC!cEb0JG>_?TGD5K@u854{F9*np(o>4 z#tS!1ni*8x6Z-cjB&CgumpnwoC}#? mMK|y;cf>-(QNssmu>61o<1zM~vPLZ}0x8gyAv{1abdm#je;981nN^y59#fk=(0xb~S9n#+Q({!?S^E7w0!U8!uIaqN)EM2Xv93eJN zZihG>l9+?|!CHE5vaVL8vx#9NV#l%kisf*WaH z_yEX=Fn;09l5gTaMXIo{UScV{lh*Re+*>l#TG-6mx~+QiHAG4VKZI8fH`wn1=y_(b zW>HpH;lz5{Txi>w*haBAx9z#bp1jr|2I7u z552@|5?nCD$~NLZjm#@<=&A_?Bk^=AA$f;sL0%0C|60{rIzv9-h@i_VV z3-a>$>XnlZOtjs3$%nZF^$qGCPNEb6KZ3?W5ClApVZlv|QNX`cO_N?RweQ6|Y-A$f zQ4hD>V$pXA)IK-ni+QZ(lc^^nlc|K6)f)&_p8PzmXvY$$c7#9^{Rza~OA_@#9zA0( zK*4z@*p~}brovZ?gKX%kSNb=m7lUjf7%{zYj{?)@Mk1)PU4V4K(byNPao#UAu`gh6 zje`R+qp`h`m}H$=l^&LCQ=RZUTD`r_|NLl2k`0cf1WehWJ2rmE3UF$d8o~V*u*+thg6ba6& z8v`6J9$g5`wna7f=?nB(KyTUzj@OKT7_R1l5dGKLr8BRL>Vo}kA?Ncmm#etI{S2_( zTk5*!et{GcDYwL2u`6{Dk&DlR*{o}w0Lr_b&I;ilvmRHY|9l@P;^AuJYx*9BxHXcI zH5wA<-L166WV>ywvZbU?=6=RA3lNJe_vg>nP7_ShX)a)U` zb>>aUGHYKQS5AA&CEk*e7nOmYOWru-%urjPlCT|Tt?OC9B4szp+ZToV6R&9OwFQ3v zu&9~H*EG6c%pvn@Og6Z@rmPT1+~O^>yZ{w!9eeEI_j1=ZE`($`sMT_BAqPNzx;%}u zgK#q*%bRnD(xg6tuMx>L9TKgcyf5Q0DHwb1y9`-4{J0JFuczJQS#k^M0-l5@Nysf% zOdX!YKgM|A5yHovpol=%FM}P#t2YKjGjTMZgj%19anbhzQ*PAOJ}{%7JG==CluW;w zL!*DPF-m=kD(}eY%))n@C0S_FYaZqtg^_pYyJb5!b0mfQE?!e`#7kk=i5l=a7emgb zd=ao!4r}9Y(f_nS??fuJkbTxtdg~=pk%d5#w)*;==gf7W4F;NCL#OOKhr5xz>1rpx_zr>}$G5I^0>QotJZj0TzIJfK!hYh-kpdU}$DRt7fe)9*vAR zrPieYozVC+c_#zjaZKH`{Y;FYAPb3M83R?GFa1X_Si~Y8x$}89nx&4#T0Ng1f?`56 z3v;@Y>li3c)LmMBPM@dYAO_d};$F=rWV7xlccEP>!EYz18OQutk2(o>gGjTS>>!D@ zkAdmj%M0S%gcJUe@0)Ea=3*Msy9Ibg=QwD7qx+tR@IdQ1Mh^FX&2DL5WJkmP3v){P zxZmCj36SY4BEjn>Jz($Y${A!TA$5){r=Vb$w{c)!;LkYZl}F<3h55nkmnNBy2A?{c zW3l;+6-0pdJWPw{@I3wv^O1zP>Y+Husk9B)Lw|pbk4Cszw~XuW@%b)*pT4VVLKBpT zUouPAXT3=db*;`Qw2zA2KNT`(S(x|{CBLQp!&=&|(|oR`;F;LI_o1iFv528v{(c+- zaMfSDJC>K9Qt3>`pXr~Ik{eH#tZ0=P?l9lpC@M44D;bet_f7Bu2(L zYFowuUx5TA+q=NX25%rSb@VEhxJB%gh6;CRVSI{~%-1YIPuyH1quusULgw-q8`4;Q z3=tPj{kC7(T!JhgzSY(jsRu-I(&yh2tjMVP{lgIANo^tzW*uCQMNFMk4dUkcw|eR= z@!o_yZBZ8Q^o;_C731^@46?uacWlHGW69U#;K4!CwqS&UZ}vZ!Vqy2@kxJOs89A!i z@yl87;*+4463?ogzM6C$qFq`>~mZ<7;HAiM>RR!M%+lIN0amLTupWK&gRQ-y#B$+&>EC! zc_mX#HZ)WiYJc1~ySE8d8(q%0xG`Jz9EA5;4(Hfv}8sd+P;#@Jyz~>s>9Rki%;V34($`2?ehp{Qi)m(%;)^{m1rAl zonj1wC)_T(n|j7V`F_Cjx{W%^ui=>u8N#jYFT*ChQ-pmdJ6q%@S|lk3VxX!{Pj$`c zodj@giKhMN+?gH;=p>CARjRekLHwcy?-!L8_PS-WDx$JyD5j^wZzbm$lt+2R6a0)* zkDav=k2ZMu&y-Cl8A;tZHv;5kd!!*dh#Yz({5)qhrb;q^=`a}24>6GziZ_6!%_(RZ zQM&$|Q~BrV!KjR}4SYsJ*CHSFThc(WwlO|C(EiI=`!Dazw0v;^Z~q{chDlVs#aKH6**Q(;4JQ4`dQ`8fJwG&$o_WI#vC`BjOt zYRL1MVOJ5G(mDBZF6}m&0z?7Ob(qf3tCSa|8l5F~O1lJ=yC`XAYxaBAivB#@4ezMT zf2EG=VVNPdjeX$f#4!EgtKqqv4TExG1?$!T$96yg0F}))KM^Ep8@Oxesj0sSIxoGn zzpQCHW2Iw3qgv=uv0_0*Guvki7h7V}lb2JVw#-XYM^Q>pEApW!xf*7Vy71SXn|=F$`DS;Yf-9IyGhAibNUgqD1-1{8>__4_iBtx4f;g^p%0z1rYHN zF$qiu8hHYNZ>kzSvHU*+h-#E0a@Pd)4C@r_3a1@(~bW zUHXU4^1AmTv}rwplHqpZQr9VrlMD?m`&I-E@DqN^XQGn(h>Gy8P?a8?_KyDWK?I_Y zQjS~nJHRx1P09$+87qckWQq{y2?PT7&*g1O#eOgFkXyTH^4uRirIe)3gLw2ZkZtZw zr_j@=YM~lj(1#4!C$5(XujW~FvpYli7A0Qf`OfyA0%-u(r?%YM#S<>jHCLE-xo_ry zHsfWlo#mJ8wa1P(>N$7y@yV>`49(uVB%~+rbndw10JJ^i**$_ACHr^yah7;Z$K%X{ zpV+(DDpy<}{;WSmzdnmyKgHWV!Q0+LI~V=#F4A?VBXd~C%6I8T;SX08PoxTI` zh1+qW=or$QZVUt~def+5JV`EGcqE7ZY@XiEJ!$I0m+t~f4nXfMQw{HuPIU+m-6Dp! zpJv@!*3p%%mzWBJJY?Hqhb`YkiSY$50A=N?!UJb@yBFdx6oW=9XnJReGx?gX5+^cj zYl~*JzmmGOJfN29&I}*)HU#3Fxtp^&aplTHSw4<$;aKv+xK`b$vg>qr-Z_L`ErcEl zec>5y12E}Y;7QlS9ZZygxTF#}FU^gd=E2Bkx-GJ$i6xfiOlKJu@pI>>vrytjpzKEYLse%N$Xj+eQs-vWUtiYuP? z1gPE%@scufLEQX~KSM}#@K$uwh@4L`P>bFOlsu|)(Uy5VBX6XzDc--i)jBh{4P`kh z_Hj&aJ-}A=tbFEYx?6jAcD%7P7dtpJaL%w*vfbdjk3Frp_EI?D`VojeL_^#qZg|CC zVIr&kfy{qdA1)x`PkphJ4*>diZm(33hZxEF5pPo7W**S0IK9jYJDSA@-PNa*+dVRv zUd_o|)#%6JCMkq;Mvg>01Yd7qgW5k7WaD4K7U$IDzw;%=c}0*&MC}gR|BA1O)ItFc zSR4b6c3JEmuINUMp{sK`Zp9(-B}ad^Wax6Hy<^tsPMtSWpiR8(T{YGf!$TIZl{L|? zM`XHzr%aplKgj(|5!NOki5k>pTer=~7;`=NF7;YCgKvt{xYgG{ z`$R|wy&mI5d!I{;HvnCJr}D6XvF=_-tm}N=h7|wOtDGOF>)c4i_0qJ4?Tc!8t7M&) z4Jl>#w6YTHwJTLtUQgC{9*QD}vm7epuj}{urn1gjZWhXxb+3d0^|&Mc!oM z=3~%dA+_Jg#~hRL3FfSn*j+BV>BW*46wSu|0=HKRKK`;V#rHP{@JO0O(+^HbHO97KR0%6_?0Zvtd1nuuumR5PUXTXWJ09&(AhEH z_8)QZ%a#vEQghuLH(@=RMwtUg*_}WGOwMvB0s?=@_{Ya-5M6+ZT_ou@uP7yrqH)k*1}A@U83#-1 zGi~e${C$RV7k|G?J$GEjiv9|LxtK|Eo6l4M_k>yg1xEMX9RhkNV#&4fl+f0U;pe}- z9+rUC0#&R@D+DQMbtK3Qjz&VZXtHyckfy|qcwG5;LSVU2rY1_gbh;OgP%B>m{fg{6kF7&V3A6X zyC)*crXnyf6q0&qH<3j1mSLMP|@b(W9}fD`~}V1+~Fm29pA$SGAq3&` zyqQ9Y7DU$eE7~kNbrzd8ogF}xM?C`VFZ-+kok>u7%lmS68XfY&y{R;Pj&m_%Jh|Y- zizALo4kz2cTVQdEqWYgtThxOc1BlNr$QtRr!G=$q<+cyD5t(Oi4=csPXbE)FQzo9i zDe}NfY5i5=yI&^o1;8;!xVq#C!zwE(>W&N2Lz^2u()IES#@3Duo-QNL&xlD}HY|w_ z1@(0C;-*ItGdt$BLrC$?5VW|;(TN%Z*GfE3buFi8n@n2$&1iE|@NfW?eQmG`R z+dK;cdpT8#4H-A$!(W7S{wDMCDntM|=+FPd9xM(2p^U54Bq?*z z%BVSmvN*Q)Iul=A&wG8W|8sXxDz+!#7h><%?p?;^FRyMGqShg*9z7S)jWM9Ea~1 zax8|vmg>go*|3gTj$_5+pUbm&AKu|RM6WnW{&L@Z8F#N0$%rf!kQVHu#tSC!bG*Qt6EB{k+xjI0yRE$!epPV!} zT~$q7xTJ3Gvk*ucT$K1XJ1u{MmBZGKl{3Ujzqu>Yn$Pg}$|Az!y;Qe}CcGt%yo^ME z#=eMRI62*giox~D(PG0_{M`Z$1IW~v(dl>(AbdqW@%&iX$gXapP#OHSpk%nXWY{_n zKs1e~w1q>V}hL4d!bEoGm@sNeJK&WKM`LPKgmnBzC^)aWRTCD@U)foYFMrB)>94{Pz?)qS%qY!hD{mOA_7Ci6z(mBpBC-x2e=NP#@>@v*Z zy}?U~vu`r#aR%ELKyL1nBH^C6OSVct+X?5RmHIkBoO6+Z_XEM%b4tq<({~f?lB)N^ z9dE1S!kfmBYbRw>RzxfKPHei~f2jcX`!w9lMUM zgXc6Bx!+w=M(Llhb5#U-Bo2}fjObYM)SL0tj~XqHY~Sm(^CEo&l=~lxsTgt#Jexlh z&y#g|@B@kGb-r-@4J~3vq!)`zD_E4-T!5eZUYOtO(depIUb?4=05b`N3hvH8G??2R zkevoy4rYlD8 z;_u39BiK{X52-6mgL*rtivoSWY4sa&*tcGTboK@Ssnef(96Mb~L(Wzt*T>ffGFBg^ z-0Nlj)^6kUb+>L9xK*7AT5Ud0Ew>!R7BvnEZR~)2Wkv>28W6eTO1KMgI5l5^ji1oI zcUkryI>qVNIHas`;PZrs$%i)`6}`U5F4){_B!-l|hE)nO4f{s>hd`pFsy&Y$r!bJY zqHWTHvT1QZ9r|!4!(+6=h99jq6Cl&nx!7}C70`HH++<(-NitS0J6@?u8`AL3n|G&% zlG}D5T%dkE*V6Av-+WUxD9cACF6IM$(~#R)UL#1LpQ7@Yc*B`RZhj zJnt6W>w)(&MXuj`xonIDs8U`u+yHHklChQa>O`)+TM&{^FbotS_Vsb7uI&89B+pcF zEi_~8bn0GC#VL?PjG#5K0cjNHrRA)jRp-<3)HvI|pNH+!F%WI=y~? zydtZ5{tsRF{1x($8*-r+a`!gKNAfn*ZeEUJlxT$zHBb&&N5)56C=}> zEj13}q|V7xs^MHTsRzOevfohl4+4aI#;S{4S^6**q@6(Gi2!nMpg~mBRkr1 zZ?0*F*V42{AVhd%Y`6jf9eVBgkhCE!lP+(o%B^kc%-y|=`fv5eFM-}L=iAKsM--K< zCdmR)r^H^_+{iFcNI5h`Y_#|m&ucU36iu_MH~>5Q_PX>r3Jo+W)2O%a+(hPNvw~F8 zynMBfjHL@o#>_W0MEQ|e=P5l3LG@R_GLvV1x*C>Zt`Uvp$#|k`DBk7MAATl@aV;jz zDa3}d2#zU^FNc4WkwVMf>b#$`NJf_%dsn#lWK+~oO-&*EDjRZ z$}^t{iw%OnCK&qnI&rXFa5h$7b-J7%b>{h9=iv%DhA_Nm8MqSe^FJIa9)DZ0{sPH> zM^;9vT(oFJ?Wa4w1-_i_Dr}xz0=Bo7naN-#g7!(*S(P}Te%O_i3%{D(-|-jPf4a`! z*xH}5JGPdl!WoEM3w*^P+s@gF%vEzw_m>b+)ZbwO{{B`+5^0r%F`gzI+9x0jx8)c4 z{8?H8>|9(cKlCwxx;SsG$X|eUNA&*h(EM#?2_{BxH)4yiF==uZstZ9k@!ba|#)Vsg zldv@vL=M~4v-4K3hwB~#eXT%W4zWsO1lT}0@}Q=AN1AjhRiv^-Qg*TIrM_e*p*k3R zxnW*uPv#fSdAeQ8`8-z>wqE*cpeU)!lPM{CnvyF@`zLQEBesc3gp zfn|PY|9B!@0&9~VPCcsTyN#jg&znMY?9(z7!AlEdc*Ay1CEhP^VklMoH0=Ayd<@ax zj!Ndc&rwv{tx2jat*>iGJ%B6SY6?zkk^UCAoTPXVjXgN`_JC@#idI(6@{b5ZJ=+&U z8b%fQp{BOTVD()#Bg^3C>f;ryols=Ki|S;`30qArq%#+%o&;5e?;5M8EhR%4@3tn9 zp5UZG-P^>ilip3L%(yO}p!y<&p!3;#r5)r-vBt2jkINY|t}mK@kv?i%t2PPCJZ3nY zbddkE7KVgZY|~mXutZKSVeLnD2A-2LEK?3N)VVE99V$IBnWQiOAd#R|R8qv8!%=V- ziw8teFT1lnFvR5#^c0^`wk9I#kE$l|q6kRw3K{OA=1yYA9WrM)s@KLTCT zJ4-y9Lz6&Ve47Dm)%A>g-tf3sRORar#T;Bn3-=wf#LBwNj;idx@LmtsY58lZ#4xh` z!tKrg?m3Ot!0c!8uiUtcUDAjUaWekQz9n*`Dr}mGrDbC3s*pq1jOS-pO>~R$yK<*V zib}gP1JfO24d8_p<{RUI<0OCgDGJ*TDuu~B-ez3pBYI=Yo_?Fp#J$QEL)J8&aK)t9 z?XwaW2`P*h*DvN;pAQsb8&3mk%&fe>oGfiq0&Cq&tkuo0ULndB&XwC8C73fp!$xiv z6@M)6&>pQ->2naN5N>{6FIHE@hU4j`1UtN7aFENU$iQtT6%M)SdTY|KtoF}iXL~;X zY^uaLkjoR|*e0pW**EJJ;Y$ysyOqq8wjz^N+2?%$nxT5SE`^=rfqEhhb8j7V(+bTVeD;1`Mb&PMUe`k`uv zR9Swe9l7CUHTg!#h4UMcl>O~nFmZMaQ{5gzA572jL4asU?r>|DohwAgp}T=X(}cL1 zsyBwz=X-2pz85HI42!5pKlZGYO|THf1c9)@&GS?rr9ydob?}m3Wim!Fu(9N91aBL6 zHn{SuFs8q|E$D9k88E1ml@{yTfpA}?%?ggn2w}%5At~{0lusG~`%2EVJWn$6OCHV> zF@S!uX!xu7dsT3k=7dAzU8#$f;kdG9UY|=LzHbglWT|VEY%M)jvv=!61ibhZu2M;2 zp)Lb?bFMl8>qv{NBQPLUA&1rREZancZyop9R4kUN4j&Qq(%F!*d-QzhG?Ia!@Fgq> zNO};Gj%tU7{y6rN{ozqz?d{`V{1=Fiw^IqXjYvL~spUA>Dtl)T-F#2z2cQ6Do4Vy} zT(gQnOFO$lxq=f$m1{cpG8vR-%H!1BCRxc`J8I3~PoiddE)@`%1EN6Xall?(e%{Bkc(#Xo=q6f;4~IkLNi!bA^_s>ziWiR=5@xH?8uAhvZ-@+oEqpWubf( zs?w5iDw9DCx0kcp{7TXr*OtS2mdoJ?$#Fl;-{R;HDjmHhWK)k zgUlHiESWemRr8MK+ZHF?0e*!-hGO3q{Rzie#cws=Z(Z5nk|b|cBi89MitQ{YW=?3A zodve%nJHA+cYUEW^6syu?;=C_M1b)9t|<bWUAxcM%0S079j65?fGU7|uXkKunyNXIWcqsBqM~G>ulMaH;Z2qSE`jGZOAy zlhXC$cRVTK6q?UMx3*j+#t?F#QAG6y zImmn59M0Sn^dd`DP1cH+tN({U;Q$c8P`EVLj|}?Fz5To5w-ZC`&!m_aYrp-h+ttL| z>xs{ejyHGfz}%jyN`!%LWD7p)S)|#o3zLj+ILVYvDAOgH)8JH8F(7{V3*UP}q4e*u z@$qEch(oq$sW#co_-I75jfc_-DE7)Ur<_<@Erc}l9258f^)x5!$r=LhUbjF*_4`uZ z9}4jzRhUM>lWFj>%nDKd9%MlOZs&(%@3&w~JPZ#5u53RRG8uSvfL>#%C04s4v>doY zGolv2tXkRUHg4uQscp{|RC06@+*ViwI@*$E(BsTM*hXXq?_PTIS@mv2*xe?V*W@j~i70-%V925D%hqqT7~Vq#xIZy?|A~(VTq!j1F!3Y+s-CNNgZ>QlY!&Lq@Jz;|9&@ zY8dKFr%SBiwh6btY3i`R(u-myD#8Fjn~zu{6{YufrWNT-N}#Z}Yj=n^3k>{K^r|=a zV|hux|&I!H<+Em z5O4tU#!4A`9I0Q)&#!;rX-L;J*UW^QXRLQ_J!pN%5awaVTzp$(;A1-9N3u9JS8V6S zyby9~V^hlgYe%*4Bw}O~1(31Zmr-cD*Q*Ja#^AGUdzsxOjXJ{YBBXaWfxfrB{)2Fu?xr&US!-UhtD!FpY^BatofhQs+@)Xq^8gM z+taHpYXg?78~a&lEGnruzp+Pc)WwQ%m-dX0JDoCEvzFAzx;zC>kErJG=FFgA%#03@(8djdrJHTcXB*8>;Zje}()JH;_&LkL|} z?-?5*x>PJ3WW7hL-xp6P5J|QT{|)adv<9D91LA!}_<_GN!U|oMkwrdJxw}%g4zlFZFD7a?{?aZu`=Pbh?CtXI*Rg zp+jVD5gPUIV4lzZ;Wn+oa1ChQDbHN~I(C6Y%>Rlodc+x_`Toebpa`k9Z&bN#^rT3l zY*t1yFT7k*?}G@U$EnfcwcL!9naFKS&DY}b)7=DP5y`0jZwv2YcjkaO7=Zqc;*bB{ z{&UpWonCxq17?h``XqVLt{6w*3k#i2VfWtTG0ANyOOHlI>C28i6%G*ob*lou(y-*C z23M!JY#WAeU+hvgot~~2s^GQBsx>W&HLklqa|9mqkX%7xjIK6R@m7L9JZ$8v&K)dr z7$*|0$!nDx+PIL#Nd2bjhk^_?^WLnt4v4soY{`95yO z!8@U4*p(z~3quFeA+ivcQM*D>=mX37h9-`rN~shrYooh4_na1r^F&u1L&1hGS?#IQ z`FS6!Y-}ymiyOWnz`_$q3vDvQk^Mt8xn-~LouP{4e{_Vq=#QukE^)fPwzQdRSwePt z19bh!hbwBSBBfV^7YkFOr%%p z^LKlQl>=Q+@}v+D&?1)sP z$^FtEhA7+&ox^d|GxeJR1>WYxJ*XkZ^F@GW`2l|OMSjvgWLZ?#0i+Fd0K%+4Lzgoo zkTN}&9URTYF|7ALazch=%)?1Zu?;y>ZCws z&H3S>+j_^G!*BO;!O@Fj^8nX(&t690dIy^E$8$caeRbKF1j5yw=gBTuD7Y|6N^V|X z0x)T-gqnz)3PpKF17|9Wct4gH=^v<79tx8|*NK=1oSl0K_m(t3#fJY7!z2};><11G zc4mfN)**eGzN$+QjW3GZCYMi6);NCsrdJjaF02kx#of|a1n}z<&gQ_Rlw+=!zgmRG z;bwTh&~@&Fj5FK6Q}K`WhS~Q9FVf?$(VtAzdO7So0awo2t#F9_94}dUaDK6OtnB3K zLi;;V^~)iFy|(oZ<>1~8A)VR=zOSDfcLR`JLS^bj9ZO45g(;g*xV$%mf3J!M1|`VY z$6+L_gHcvp+eF(sL*jZ$pE4o$PLzT`!;7l3nS#PS&+-$2`ID%?)P9L9@!g9%jPOUL z6$HO;9Yn58%Gl>9QZQjC7j7T7g`=5ArJhzKLY!Nm*IFZK3B#j>zBm1n$Be zS@~S~R6c&a#_5Zv#DYkM7^Qq#em{K<^7iiJb=J21w=xc{UwQb1O$^Y9w4k&hj+Ms# zeI@?Yr+?-8CE8IP&+q;Jsu-W?K6XKzF(g;zoJopmPzVd2V&ryT)RwoohEJx_ZK~Pv zhDlq6)2-9evU80u7ax!kwFsDoReWp|r-F{~0@|W=L_USkWA3a2eb{vSrfq=xW=gm9 zY$THJW<<^YOFP70z?-aB!~)DW=X|%f7+tFs}PvX!NsfS!zJF{yHz?1%fRb13rsE<`Wfwkp5f0 zRJqnyv?>RgRYOQy{+;CIge}^v1F4->IEpH-&?v}Od4SrLM#YueW<_~CrdbdQ@e8?M zZdq5@cAG`Kn!kIS?X$X$K7!&zVSB1#mo$jiDk?$h)t}kKjGk@dpHFOS^)oIuPxPPW zC4qf~`gN>|1GbMW-GEg2j8jj}Y`!*xPn3;R4J$_PE+D$Z#6c!z-ejc#XEyKXoo5Z>+q@vig=og!G~&x~ZK z7=2!a-9z00+0=r9gs9(UqGaJi&IJ9cR6%m&*rY1U)ktfzEkS+Ms&)U;m_X$% z{^2=$Wm~2n?Lbvg&DRXOt7IV*%d2 z>R{dya_QWoBmDcfU*(L&B)fqp9N8(L;v!d)_fo<9ZdV#W_-XIk{irjHQgGw6b&qa( zK098>{5_TjHG+LxLNH0$Y-GweaL=Nm5^N)cgL9SDqBoo8(ql;}D& z=>^#x1N1YE$drYYG@ka{{)UsE%i)|-ogaFCvsO3Yy8J_@s)EhJH9%V@S$Pxi;4q!8 zkLmzh73WvY+!o84@zs~>SGXXb)F7W1?Fp$LF6(atqAc0+crgw%=wRi(r z6^B35Gfy(u2SutyyELOPompav$oqNDxmPyLtQ zkF3*$XMekn3~J;A#H&-MK}R4f=WfE{lygexgvz9BJV(cvDo9%>$Oa=JqP)`e^Kf%= z8g=}x6_c?J@uKXAVa9N2Y||1>=nGckgFhcNTD-=u>?@v-V&GE4f(ebxzJmcj@cZ;Q z%9-~GuYCVud!b8psxU|FEP+-Ch_R_3r*-A9#Mh(3M2qa6w%S5YXDRZD0q&KJnlbo|*&pdouIeI#B8VQk5XYf`?U}iTV}tcNdSH_@cc!Y;XqHyDyH~t6QQt47QJTKI;s$yk69xr5$k0PD{st^8v#^=a|tB=HJ_645_&f?`tVTl zn1#glc*w{H#Rk#=W1>8^)Hyc`uKlxOqQ6W#4hxW}NySeX-TP?WexdM+U5HhgbD&;{ zUk%V?O5%b7?OLjcBP_be^Ao7A7n*WHfR4M^yCdjHR+RG_nZqrz{k8;vaIMyyR$u)U zmP!scZh5|2;Mm}K7(7!#M_D!v+cz6GAKk=K;u3&FZs_t43QOnnj#l!1=jKN2ivmjy znFb8s{GJNj?b5d_s-GWHsHI3?j#~l3!~IPhnX|+M<4A=J8Ucpdy6VHd$86k0OvHR! zi0+PnKl_Y22J8fwNP4isqdT*R>jKI7juTfUeIbIVi!n_&?$pH94z{S+q8syY+QNSE zHl-%UA{k3>Nsr(#XMoIM1oRBApbp9*Xa9pnE zKWk)8=}U1C@VZwKn==P=zw z=U+F`(mc0d+LUK-5qyUA1dkbT9{p0KpQ7C`ixjUFRRp=&d7Bz)s!q#v074ZZuY z`b<OnkdrPf3(qXTQa5IfnRZ8g{#kRNI$ZExmivV1!7hq*>6X#$9BO}4{N0E~RmY{> z<}^oHTj*}#<5!6P;KZxj1j)+4=HV-6ZElR%Y(XF^Cgjb@f_lKk;WBcLZSCcL4$0`_WRXez%lO z{F+ie6q_QYNNr@5P->|*S$WcIZ9feEjwCGk0Vtp&XV+6BQ$9G7g9s0-hd3}j+ZozR zx~8kb5xmTF0)*TLS2g8bI5r-@VD3%@hshT=lsQPEhk^i;8i+%{`-NrUU$FMr9fP+? z$*6;zea)fV6~;Q4o+ZSKaXS%vlsX!=QGKxYB%*DZd5g0ykz@=;6%!-Bbs-C+3)J(n z`To85+VI7Dw5y1=c4yM7z;VLGVp&7|?S_6#T!AE)gC~FPt@MILSn3>>F7Pqu=@Lyl z>a}nqUz)Vl>Yng`^PM&RriCVX?C3U4J|s)UU)h>bur>&pfmi!#5%RGEeoYUG3k$Pl zWNzfy4y!B}&(tygiHSM5y~hENms9;zz-h((IGP>I*RjsaszyJ1h!@nT}I zubl$#VWwy|QW2?K%W7O;xA}Z5DG_yGss#z?5NhiTQj~R=!d@1$>Zv&(s1s=S$viiy z`IuoXAOm{qdbc1C^LA^ac7+Lu#yQstVKn-2nZss(Z|wS;F7tW8orlK{KRly<&=$nd z=8ECU9535oSokU{}xDcYG_D*lzEc+%wvd|+VFTgDf(X#);7d$F!G zglya{Nx1ze+xd2I-s}Ci`mkooxMQBGq%pm(Cgc`;8L*orgi+bD&8H-#V8oV;w-N{| zIb~!{7izU3JVEYSgQA*=E96dz{=w91biEv3sD-WOj$ed~v;(y9S+f6hM*8-{H0p)r z%7rq#y*DhxfA4n@?ya^EY)1_?rJZ?eSvDr2(H+$j7A94+RyF@o;ckn5ZI$89678#J z46AF;;7&OG<5;3mx4*5$K*L3ZVb-QR2g?>-OsVksKLcK(aRe$dTdQ&Hz-+=Dx(YoF zn*pW{PK}RgXiO_}x7iMg(ukAatRxC#fQ>9I`fFLm{C%V}fA>~VT8?zzQX9Ka3wPKl z`Dc|0OzJFn9cl>%78rrah}IXURa*GfbWMiXtd`<6rO;h&6Aktg7py94>I@9rJa!wW z!Ns79zPf*GrNk%P8;=QUk!v|Rcn_lP^y=apSHnBvg#nFW zyc;F{Sodb{n`)2Gxt&A3hp8fBlG468B%69)uYAp|eDw%sr(P2QQDg5!F|GQlEQ z^i5&S1==@CD%8X6k43{C_-zny(L%^ZZK^l6t0|FVW*m7iJ_ft*joM%^z&jDThZ){7 zb9?xEZns0v`L`jZZ^@6Yx?Za;5Y&J_d+}}(%cp=ezH3L0EU)sr3Q$2#1VrM-oG}?a zc%+MGL*run{}QhpxP>5+L=6_p;@>VZ2`ADxjjpoOYO@uV4>JlOoFR5T^oM@-=E3vg zT<+F5amTOIZTSKTi~X$@?S&A2TSX2prBZ-jgrDQY;u^MRU;UIxhw4!dNY4%qgh-d^ zaSV8Geonf^K`grBU3_}|%j_-cdc%fQ5R($Zmb+%Q@h;rw|7ZaobCF*Oh#f>8dz8iu zFY}6q6>lGhx`gM4Ows)ChH0guF+E`DpzGa{yMo^9DvWnAQWVLw9`oq}Jxs!|pcLpWSUDT%lC^iO4@v~e^|f>3zW zf2TJ!5(ToOwOeU)KI7mylptQs#9zx+@zeDu7VMQ%rTaN<0G>5I-7#?_eG&!p zP#pY&$&HaDEA$jn)GO$+9bIEpMKA}+$%45#H-vsv)tQa#U?1}7Z%+i5<$pVGw_Ckx za}jNQwHQy;yl7-EC&3b{Cfuv9`w2OJ4$s_2A0Pb7_6ik!1eej5(6=sz^(k7Sx@#!t z*^0C~Qrk5`1w~2r!d`qZEaV+`eVO7hBNN~|flUybaVfgME2*eN2)L8K z8`CRLb^lgVnD8zBm%~sVf_Lp*0kJUuSTgR~UXvV6Z6J+VQ~~Q(Nz=_pTOAiSl|a(? zm=?ciN@S{yigT@-d(6hs=OVOxv zasCSJZO2b+A+ya?OM$e767lUyx>^HB1mCsszw}$Oxe#rPyiI6)^yp_Sg&M=YG(I%e zd96J%C+F?nNf0LAc-FC2Ix_+CG3uz>J-VtCHLRElS4wznLYcgz4nsNl6ix;Hx74@XN`Q}HqeCJ z46>2I7~xVT%ykX~&%fjxP=#k`Fqu=O-`N~Jd{oG>9=Hr-=n;Q9g`o@v8x z%#6DA3`{D-Cq6H+dg7?UbpsDa3lEi~JYaF)M^;^iC^MWE4WILWf6r{D<#Gw`t%f_P zb;b>QZxH_Ei|BP#QMql%KffmTzit+@SiC?UXaEb=*G$aus~(g_A%B%;*D6*?IYae} z65^&!X;L!0D5~SWpe)F5Nr@u;-AFy5p>fnG)@v1Y`;zs%5?r(Sy^eqRC1M3W!mJA` z&lKV?s!3~U;)-c5PV}~~67uJVPYSQo4n7%uQSt!%oWMrDK7R_@Y)*pHC64T0H;%IN z_797UBD~=(|GI2A#KIwHTXf!R=BVdZ9p$qBUky5Xi=5zd{+syUpZ^ElH}0Pfm%uI) zung$kj&{5lC2gGAt{(c_`$P{c)TT1$TE1x(kx2dv=Bs#MX~+c zMHBebV<6bHwfm(}Yz(&UZ2({;w%J&0KWW(yEcw4-K}`Rd0PFvZ6r{JSQvbUrDVZDi z%IE*w!-}*0`NHV`zWM)t^nbMY|Cda4eL0v?Hj6VN6BD)N*+tyVV4Oj9NlA-{Su4L+ zl$3l82*??mNR>dmgVwS5}n0YXVRj^j2<$y=xDO8?5|@DJdz>c)p2Fe%uPd z?>ELAywE8AODI^QU3ybT-!Pptc;NtFR&EA-$b0VMZV+* zUNMJDnuS<2^$T_iR2W)^ZR_y zO8I$8&b25;+`VU*KGUN-w(o2YhBd-z4X@IGy*#ue$H6>mbr}QV??Q~>LY3}dQN<^I z6Ns@-p4@qrr;k$nCT^ZQ?}%Z9hm>9MoQk#jN9EXM`4jO~OVF}cJ0L>kOgySy^9EqQ zCn9FBU|31E5Dw;SxukfjUR|EC---McU*Q3lt>R~dA(UFTsW`RwjJJS5`TP|ArdG*% zqhZgZ7x&Y|gDVrdKBKN*Nod55epof#CrhUjW>Kg27m-Tid{?E$IIO}<_utuI?1mJ+ zvr9%GrU#!L!$%*F1k{<_U2ZbZ5WEHk{k=SoEc;w*&fH;Rr|c<`T+Gy}ra#%Nsi**p&3xiCWsl!`M5lz&*gBQjUS8ml!Q<6*bB&Uiog&y@kZf7PO76nCCe3F%x z^XyJ39DY7#FPv|1Vqw+!|3Qon3j?uaK$^b&wVYN^Ht$}{5EYB_wav}@K*{Ng8dM1) zZx{G>Z)KHRJXKX3~(NP1vxNcTfFK;aV)mDc#0eHX{@dxu{FYULwN4f-5y7Erha!!2ZNw-q3NX?A4X_e>cclE&vEO6 zheK3S;?GNKF)cO<-p5=r$=KLp(HN1V?y|BU7vc14G9czuXzS@iH>mKNglYeFaqcPg zN51G4ZxceK9}Viiy|m2;k-8UO3^jeb4#wB@JkIOaN! zf(HRNUY74P!1&bERTDGM@1?$r7|3sKoU%#p^I_RhusT5domW5}omgBPcE_IY7PN+O6zblqY3s1a0pGT{k)zxRcd36{0)}%ekpZtu0kHE(F5X7`u-YGL^<} zEAFpj>M$0Kj05gvD?{X($XZ>W_-Cwx+&ORTO?qmYU-dL=nKfxcV&OY7B=-`&BVi}- z0>U%+HGIJhKiAzscKgOBuA9Nc#4$>4nF{f}RF>D7&OH^jbYov+c4uoMN8_o{F_YA8 z^vpcor7K~9o8w#U8SY28v4m#DE^^)v!|ea~l>44F6>%AMLh^s!8Vcc!@L>VqH@EEM zFhWjC@@aS(8x-6(w_XJD0Z*KxN3V=pI3c8BUOU~qz`-wW6nREE? zy*}}*8TT{!%Pk;gZ%+rg6zlJ~PYgtx%627Z5=g25MAo>U7@zYIEas7v!97Xsy zBYhe9JFJ+-mdMd{rFQ%K$zuwEPpQXEX{S$r@a}E}Q?I<=ITvM9E=gY2r%*!r8IPEf>elrrcy9cj; zuuB|ruRbyeVOFX%`MBUVV&3K(V0G3od|HaY*bk|><)4$>SjzyN9PDSECJD<=G?Mp| zFUwAxMmy*a{;?wdI{u(T{`)HDJ=sW-QMLa;o@VFOjH(eRr>!B} z0cDI6pul{~oP)5UrgNC(p^3Pq@2~Mlui(3*bl=e}2Zh5kLrU}HX|)x#O|#)m$?Y{1 z>E8!Qrs@1mzZIOZdqO+^7<2vV>Rr>)i}Cy8=XkG-acIwrU5acopY&^gY~ZdW?}`_T z1!J_lfPKHm^L6F{%>q+2nCYOBH0bO;8TGSe;f(y&^XE!BGRfS&}U$ z$18r>juLo~@8b{zf#&JYRp%g%ppsRJ@Zf$1;wP;$d9E4j$}dsjO@h4}U)I|$>nTR& zL9Rw7b@6V(fU1Xl$37j|0G|pqtnl`huJc7I|(Yvns=B}Y%^;I zXzJ(EZtIF%9F!&9r%ojl_|2FMbEB;lObL=k6k`}&T5`Kx`>JcrO^dN3koO#O82r3! zB$>s;hNebpQcHk`;1J}l zhL?i)X~xf%2=!2`+I-CbE=>vpZXY^=?CdDqv4DA&?TojRWv>lUg?+jQMt2ZrufBV0 zID6h9e6X9j96cNMIr1;=sxm-$fk_^lLDf@yVyz)5xk;P*Y!`0w&Ww+9`WQRfNNy&U z^LGyK^oIeoB{n->FOWIXO&iLY9QokY(r6SjQF*>s+Bta-G9t=B?U`NNZr@Xwm`ID| z!)ZBLbK`eGYpAP{3_UXG;ZO?O*WK%I=WL5xYg%eo8dEz^&>(G^bqX+wX*daz=hIorcDUeauq)PcNlpy&2;Tlj!&US5rJkZ;bO4Ybwh zn8Nx|Dae^TYs(f|OXWckHc?j^6hUJSFxK0r@n;q@3*zNA%mcRWwF@i@Fjt#XocnM6 zu566D$Ropv0c#d-5x+3$5g3u$_kiIB5Wa`oaF@UEx#6~4O<5cs^bQ8y0j}JUpYM!h zW)X#lDX@&F3!$_eP~CgHegaOJvuVx!_>Ia33EqfRFCYCz3-_%7YVt_D$(ahrlr@?K-P# z``#o^Q)Ulju*w)AbO~cmblgR;1ny#N9w|vAE^D~F{0_HS>pW*09e@G~ z9+t`TOFt^_Z5na!`p1mxT^j6$v4v++@2ry9zh=Ch(Dyz3Z6<+u)uV4KpsQ%}(xbXM zUPnuDihpV)sq6H zc+Ug%yoN|8gYSb4)k{mT`n4t2cp`eD^O_cJL%MpG#M-=~+u3H`PdQv44;o~}m2+%- z`DFKU3&v(lNte;Z8riDH{e(Mt;icF*awnIjK!T)IR;8Vmu2P?V`|BQ)9+45HnLUVo z@w`|4(zpGN=978-huU=3-MtS#)(XHC(EZ~eUn7GVuidfY4dRR6ex(FLd5;SOa2_V+VPtfxa-iGJP)$Er2D>OMApcPM`cDHfwR7E){G@O1cdqxy>=N0DF@$ndR zr_DA>n=JEJlSrU@9VS!~?@CGNN+SYNW@Jt)H3F|^xgqvQ5KifCItc++(!iBK$MfdK zksMFvtAoz^=$^0ptD2UKXA;o9or@(Ea6_<$KZh_YKX)ZZ2wQfXJSH2vnLnnxuwXbP z=-|#IZL)_on0g(;R30q4F1}8tyk;3X%1#Ua{foPCIow;~+nGK3BgG%uN=Dg@Ddk|Bl0GopzHyOYP|ZaSB`~5ScC?SXG72R=(Yt;bVEWdzVgY3 z4g{XBS~U49g43RXlQLMT00@77HL%GC82gQ%V;CuK!G_R0U{50YaB+w7BpKWetMKi(m8cjNYmSZT3-zKVaESBZcFJ{#nuUBm0u1 z@?iJ%qc$N}iX{#vBnvsDy>a~>q8RY1;m85lgaJOiZ2FqR)L#mXRjDaS=p1{!M8&lb z8l=H;OkH1s`gGf>Swg2@9zfN+F~m&)Q>}8kSiXWzk6omvRYwQB0@&w1xWpghpa{Zv z)YR9qy;f>H*JrGZ@X*<`;}?xm0Lx?4OLRDu&^a*^MV9cY%gLe)`ekx2!|BP<+7cH- zj2@du-4`n%(t^W=rWmOH*Z9<76r^;2*mNTvGUT+Jqu)I!26c`pnKjtw8)(bGZvEQr zi%(p~+u@AhF9|^_HCGl2&ql$fkg{E@Pi;-}_mKuMZKM{roq7o>C9S3XbbgkaL;n?? zHa^$n7@^1r*B{@%*koFr3Xzt~)pU-J`9kIa*{wUPR_|8YWhmu;F`oG&*(S3>L73{OOXn z$4I5C7{PU)TmgGdt!?~H2P<)Z>`A<3k(l?$R5oE?f#{Z)zloH#Je}b1i_bzonTG> zp{D7cjPVe|P8eQHjT-}bN$jdTnNPKJc#E#*7ADc#nVhvdkxC~_mF-Ivc>_Q^0qXOS`CEKbtu{ zvAHu&P;79xRYBNcA<2fn@8!(R=Uz_b5 z?pnr>G-JMb{mQ4ws45FS14G>M%BP9&w?PNRElbg8+Txd}JSTQ6(LL6FtlA%zWS6e! zmv=g5njSyHIdSG0X@dJaQ8Nb_>>!GFZ(b(@z>nz3a7;0!-}Hvhi_4KHB)(b9*_i=mF#@$`K0xb885HFNA-viW64?$_m^@DAsq5BD3#5 zakdTYNway#_s+HU7&v>Z4bSCq-CwRn(HlD~$>UI$Ul_pKJtu_IgG}L6@C2^V;Dgf^ zRUG8P$~{q$Ox~q=c-t6j$R!fH5R`D%VxR2@-$0_meOrB=iG+9X&$;5ZMuzpGdyj~~ zN?q2(U$7d~ezdmU8C3cNXNBisLHrMXS#*ITb6d@K#~aU={>m*JhmrZu6OtBse_p|@ zU?*85T4~nExS@}%s3~a4w7FGpI-EDCa zJ`ixQa}@C^6r%sta?>J7M#?o^oF!oS&wEfBGdiubpNBk0SRW^q5q3*;!lc6hfLL_|H((LgA?H~kkll=wGd*p|_k+_?C+{AN#6Y;0R zxeI+}o#y*=-KWQrn->AYq|B%-eZgJeuDyoDF=tm3vy3?$xP1RNxc&hUi)v^Son}@k zNsm#;%1zN5-cOx7C?x*IbERghy&wB>c(<>1N|R|#%mhi(FGV`%)}e8(bx1v&?gCK; zG3yCW-AhoZ6wfnElhjSLFOgbb*sS!g$B}Xo9V!%>e>8P23LWQ8T(gm8-cjt<46EWj zLmu$a>!|Q-9xigizdXK9@^p^v^#0&!RlkWMpi)s z_;80SkMk6L4))|Tggk{Sj4``uX|_lHXAO%n|JZ`1ja?Cqt0%p}TIW`b2|P#M<;M_g ztK*W#7C-Qt12yZ;mukhR`!!lCJ6AG+UlvqYx;blb>q{DKi0wA8i-2)n5vSKO1^A(7 z5tU$#iGH7>kCZdndrzHQn0W1}&?g<>H&DA-yMY8j`7hLdQ?K%@Tx&uMFb;AenT0Q6 znQwgnQr7C}T#Br(1SUGUhd}c&94BlFt*<_(82|J%NqF@oFf$rt;*91I!iNOoiw5a9 zZ~kOMCs0Tb8bljTXxUgedcth-9@!aeisWF?s>=TFSJe&uvwQS|Xp(YjcTn-kZ)J}8 z&k=XrAAWPBpbzq*JJf-ajck~?2#YZ%>oJ%4&d6*+)cm+ws#O2@^|aD|g$m%fC2xNI z`;q{?)+YIaQ1@6VGjDU&bg>7+-RV)}LTKBB*iMS-KMdt2R5p0=8h&1KgJ{w$AH!GN zW(dHo@qOPAtkT%|tXJ95BhV0-5b%z+OTnBzfRz}l)i`l#=g+duK>;Q!fpWg6CWsD% zgS=V%$ljZ1ZXa2#%>bF}$AEi`o;nB!mE?afRrKGNI#Nq@P8aU}yNqkaikurB9T?%w z)l$4qcoz*~ULjfTL*O7LvKFWq^&gwapE;slKE8~Zp8>Vm?o*=!wy`g{~OJs|5$FQ z=v}cs=ff3}c)l+*TcnHe{q zz_4&s*78YR;8BHcltS*iX-v}p ziA5*mXFUWrn+H?4sIgJ7!(X@DEkTRznI{Ha^P$4V_xi{?kJm(2xqzpy9FuxhI)Q@S zA74O}*HKw43IC?@^@Z*TD3m7$-`y;n#GG!Inj*t^Le+WKY5tcBfbTuzoVhVRrw)p{ zw!R&Pv=3UIfA}XN6f$sB+hebFHoex|*mAtUYo`i)WyTIxo_mxA=Z3XSmVcLZrRnKNc+*?q3*>XL~-O$H$6jB68e|&)(UUTSVMAJ>#J?WR!^BuFAO0w+`~@7U#{irxwa?sTM*)n+N54P^tY&u` zlEy{Z^|)#~PA8-dR2su9RG?iX(gP1BvDmc!nRu>>mawp>f9QgnI+r32m-Tq&9-Vn= zHsb`>$6+&JFAs_@(YQFB~<9{jwvg5OMm%DHz0veD9 zmd=wslW;0*@I$5|Y;}6^^&0hAl3?JG(EB+Qi zBJzI9PrDJZE;Tqbce1j z&!vT3@85(g5H0juKX!zX^cxLV*YsOE{eLVPEfS9zUjglJFbV#b&3oT;!}A*4haS&C zqguiUD@@)HzED^I-}#5S;PwfGy@nKLWAnDxXoCg;z>VV@LR9=96nunUEB2A}?Z_|4 z{1qj^cNi3A0o&LirrXXoN1AYf7-t(tlvk!it4QoJ>%99M8GU$f-6gL}daMzfdBx+4KSu6UVvDW=p%#?9qXx_trYCr6zjJ$vVAw zPCCql_^2UML0xuTrMhi)UCgP$d-q7veXp!W$~OjsrnotV0ugl;@t)19DS5i^M-W$G zQiH1iDgQRxufsKBV!*ASH%X>wSsuaKJZ`W;{O-t?zgP9H{G{;M$=v+_;gont(q=y_0mkRzt9^ib)L@VDSLZ9R7-0r}$^*&+XTv7amT@}Q@;@ZXjW$-r zmjey?w~=fV5q{eSbOzq-&5mNwk?4xd$aJ`V@+Zx@TI0kY@?LdefiFZaH8zHf&>QM( zQUPW-uEQWbmb&H*u@yIFw$(L+oO7wITU!!_1lp^Azc@t# zNg+wcr42zb0RYQG{`6nxRm56s-Wx8p`9wPWKe)ra+h1$r4|f^xMfM|19v?S?AW$S% zLZo9Bj`2`$6)kQv^uQnJ)WGc5hQXJwn^%&d6Pb3oZpV~%0Af$KU67E%PY_mdUGRaX zszk?Q;r01++D~8LXU%sUQf0S*6ha=D;G1Kj(-@)yXhOsg zcO#(hA@Jgq9$i@rqe&EM7c|0?KzM`H?@^vTDYkWt>(OJgSe}{#+lJ|CkX!UL7w)ow zIi))i+d0TE3}CF5m$^v4=(+{ANtQgI&hKkE!I1udX@N>bMzM2uF^~~oaor6Je6ph& zZ~m~Bdgv-8Nh|j69Nwc*Q6v-e528<4c(L}}b6LB9?qicPGd~+#l^ZG~w0#EsTp6^C ztif>LQh5;d`P&YN5>F%U_-uf2en=D*P%3v*?;QTwn% zjiz@r5dQW!m^YSQ`cJ2#%z0Q(jDoYH|LB6OgeHw=Pyd@H;+zeWs9t2t0qSRRL; z(&fqAK)_+7M5X8Ds5@iZux3(bCKVgVEeDtFeH2>MXaU$4w!<_v7%787x`Lm z8@&*PH`dB=-uh04#EzNa*J22HOyh1(vjYi*2YeR0-Dy1ZHHKo7owD|kqN(pu>4&3u z@2i(WpHjSp)4Z?`gxli~;P6uN?^9EXHg8%iLThYpt(*L1)Ib8gu$rFmX2Q-ofMnN% zYQ3~0m}lqOZzqZRtTxufodR#92IIlMoLScVN9?MQ_T#q?Re-1#;ZN%G%GXEyGJ+eG zqQ-&d#&1>%h<}-*#VPS(!2{!ihC{>N8y<(wYjb$A`xGee9*3wCUyIIvvh@9&YXn&H zUMH0${qU%jd^QpNS_`oUL~&Ian(tSRIMdmCMzXqa2alB#Pm6<8v2TH8%{baHPtF>u$y($37)VWiI z1+Fr4i!8Fj=598Uo_MUzIz3g>v!mN9qAjn1MD)C+$}yjGbZmdrh?PKSK zo^DSK$MnvbLH!oc5;yB!#sq1w7X&0JBju6NS0i{CoTu~4&|;>%F3QxxS}>OJJuU44 ztIHgbc-diAo*p7dWCIfqfBmgRhEDtaQszh@JtCX%?YqR%Y z%G+X^clE#vPxx4^B^Mr;r}x%YtM*48t7`a@Y?6MwRP`0WVr~sYokB&$WIb1_?^d3p zr3kD{SQ}_D8WLzezJUv3)67s8Yn%mqOo%2tOsHxFTLYTXWsrmvKhfvYSEUhu0!&LE z(mbtZz8o=Q+p>S~nZC_m-p{V^-LM4Hbs2}hvx`=3v9rN4fPN`*S(LvXB3uh)><+-( z!jwDbG8NR4`qZe&bFt%;6&n?v*9&&9-3$uS#u6|GoSD#5d;v=^`K61<2W=$7H z1lt7%j3OZVCJo%WD-fIm748l;;s;}F+zUjx8@FjQM3oGiJupg*)!|N0CJ~At)R0GM zU?#dVT<nn@gxCiY*M0{qOPIr^BqxAjGkn^85oI7l}Z^~aqe+mPPVuZlo0?) z$na3uj(nNoMQnWZ)4_hJ)TOa?o8}_ng+G)Rhs5ZozCl~HH7!x|j@ZtiMzcf*eyRW;6*%FpE&M|@=?PRFH<4?T!N zLwt(sLw_iyzvhn5+ih=FDNNRMDuRM8rM+CieZCvoH|<$KWh%v#_nsqnGEYSGtdRCmj$H~o*umu zg7iRg{QAPQ-MQO`o1E+*6mM6MS^nf+aS)Vw>%C=(Dc*V(Apb(Zi!QKbAX_9p%d6G) zU{q3J{xxUr1S=CWJ?4vLPlA+|qV<8fin|i!*l_V>TSz6|J@RSCnp^Lr*W}v?!M$XaVEG&8`pRG7afauN1%c1Fc^{6*=sp3 z)n<;^9)a}d$S`1Layjf zH+I9P>kP>&5sa^BesDY3TI|VBeNRFou{A}^%2X(2vt7U2n4RH{J`FT6ZDwLR8L_8c zhL|m^XNCJD0^vx@z+TWYxf&7eryM!@r!gNeYEVb_s(3?3?Aoc1G+D*n$MoS~JnoqD zWk#0E_~o?sae;0NRb=p!O8E~f3u)Mh5vtvR0AIkf-3~otlQ0JrnWfhv4Yim+=AzYj zD_i%C&h6kkyyKA=^U8;n7q}_3QUVFT3^4RrL%X<ICR-}dm|Lt0h zH+AVV8+9)G#)Zb*TGx;cI-OYweY(gjdoedxaem~WP-?b@Pp^gxcZOLqsOuZzru|(7 zV>}b~kFqh}XHZ(A4qqJReqGvYYuH4paod#}{}F>_bo^d;n0Bu+^eq2P6Ws?-M#OV@ zmzCrW!?~!;Ox$p9D#@$PFuHh;JioInAgvs#*jg9aY*N*P~7Y zGry9g1Q;K8sF|_BkZfF*c?(PXvp}5Nj?-;;+|yDJ6jAl#nu57b{M(|Gwm0#J_tJ*5 z_4(@Q$DTgc+6ZX4LVuqZWr<8!z@*svIqsgvBecz<;4Y#l13FpiocJ$#u7799A*9V(*9nM32|{>y zYE?xz8(|e!Hl#%Y*X${cI76>zLTp-UQXQ2iu^0^_fIn|99^NeD>xNwm(I1S{(N2 zUm9&)K2bdodN{ntGt zr0$RWPV72}fKtuJ=5Sl$n=U$X#6`#t!=D+$!GIx z_FP|f=x(IZt55(e$UQnLliTUJi4?4hG`84F48=EZaT{Fc8+MOVEzIK!1$t882b=xM z*XW+4@tW_e&sCQaF|XD;(4^vhD{uEBYXpgRxQMaT@GOgEFSRV>H7tnXo?J#ydMWWu zvGqFWBw>up-LNaIZO==h0P{|KWS9J8!p8tB?xo&WO*pV-7h>ARyD*#qzS`kWKj-*6 z4f^EtA|%kX!qio;PmpwzIdMR+jHFxT1j02m@X8wrn)U^TT<%^`$`%rcV&N#|(qj;% zThV6L=j^x%t6p-Y^Ike97;N59V#a^4)|Ql{{V*YRZ$i9MAHh+`qux{_{RAU1`&;Um zLh;myp$CgLSogH@A!qLJ|w9UX;pr(>_pXPd6&COR=aVjk{$c}Siev$p$qAc^gwP-mq{3SUs59IdWYvv%QNVB#SSjJKP zCFA_;VjPK8CYN+&K`X`J|a3T%^XcIT4$TY7U1Z1qRW=NigG>93-`DDW+MB&J852q z;#~4;w>RAa)GU1lIE9m%dTw5`kj2-vxgjSsjLny?EF>ER0$ay(17E@j`|VzA|@6Xlr&r{c>^M&1Ub;cx4N5op57wfjj8oT%ICErJ*VA zisSYwFJ9K~a2SQDL7w;P8|)AF?S#-V4>}=8_-I9S$m-XfUB)4%HpTcDW%X=`+*5Ag ziO^EQlgoY}v3Ozpq_g9Dj&2gZOVzL2vFhqzIM=;GgdY_*d3KIoVx(LYq6zA>p{>Gs z#a2DZZYvt=D2&nQHUnXbGRzB4J~k2|W3o&x_u#uPhO6hX2z7xj%j~5(A&&_5dPT|j zX?i2@u!ZJHxvM;)NC_f}@QlKtO3?61r_G}jdf|ZmCqMu1zk#37Q77UX_|)sl0*BN7 za*Hl4NS#T#E$Vy2cHcRSJHRvcl-8Z$fp1rMjQF_iWb|(0jnIHlzHU|O{1S(tvd4sf zW5VpQ9;3GA1ZW)z@(C!gmQ*0yq9(O9{bno{hZ+O!g=8o8dt#}f(&=gnw;eR;sk;Uo z=7`Dx7i@fJq}OeNHmOBrPMqJa3F*n0Y+&dC_NiU}Wb7^o%{IF6c&51ZABp@fK0goU z*r_jwF;xDYZ>%kQbW9lDeh~fW#`UPkA!q!@dZTuz<6MrsFt3<2A$y1z>RGIoEQ87 zi@Yw;Tm_fM?e@slE7R^R&U_k5eY>xOXan*MdfcD+Mg4JC6}d?N)nqeP_PNU=h}Ws; z_u&{JezUCd>;-2q5%h)D+@VTfrH%d?aMw7g_xGHm%0=p zp8dF{CA4yi!h&Oc-8(m`IAwf=rBGBHdbW<504|}0BaNe&i7RoQA51^3b#feGWf<$o zI37zDFG1@`KbX&$iDBDDn#y-P+G+FoKE-kSb*cs0tT_&bBBz064n_rO8=Vj)nj0&0 zyc}}jEqEre>>5x&X+c>&FMs8FHr?JE8(4xrl7&>D{X?~y@uLrgMibfA99}|3-|G^X zonqIGF7~fAUkXDut@6rAnIRn(6=}Wd=tP+JI@Iw)<+RLP0i&HaMV5s;>S>J~O0nVF zygYM61-eH9^G*mG-Oa5PXyCkruW?1`vShtdc&+a29WPs!ahHujQm!Qs(K1Jr5#mI> zRz!8H^-Yz^U`n8Q_-5!_y#*lMAz>(4tyOvvzy}$BYnKK*X~Ctsg>7j!LWX%RJ252x zDAcGm6r;t~L`57GUHr9sA7DbDsh--5z@P7PiJ({g{T-O&v$GV@qoSweM8H0*X6#xL zuelEXOFDPn%R!7@WMLC059E3^$n@ua^!oY|o5@M_u#L$Q;_ILG5wT2^uLyJVp`DRo z2C+>**!a{G54@rxpINv3Yk4{6i(!a}yuSXzA4jDTqh5lmmfCflkd)YQLok2aQ~i#n z95%%{a3>=jbSOL6ax>zxvy|MoqBeOAEvaYI6p3S$(du!S9~q(rMo9jvw0Qx)vvgI5Q+*jt>n;6EDYD zS@;CpjO5yyT|qj$Hs4h+<1;uK4kQ8!2^ib)y0ju4SP4;qK6Q8t{ zdommx`Lz{Vfe@JQh<2GVc|WGc;Lh72`@cJCgYy)Y!=X=PkzL{~w&JwfHr&pfb-7&d z>D_>gZTfb3)%`MVK(eX>`O{f7k3)Ovdk`uOAiUghPGLm#8PoakoVZX&LnweFpG!ey z9n{t8G1ykQz!A9E#a(w!(97XK!|Cqf*e;o)nziLc>T7yKx_yW^S+e(F6 zk6)y*7@s~)36xs2+ELk8WD!2sM|E%b7X)9&OYa-!Q(dbC6<3nMI02e$U2gzh<^*5y z;5(83pCDrG@v+n6P39BPXZfUVW19=RoTcw+m$j|Gd)hcI{d?#Ry?04QkUmQQhIb<>_^A1Ps(bY;Hs4ZX=I?&>V0n5I0k;tP( zfxmMO0b?5U7eGE_@UYD3jl~jsRNKPGsz!l=&mt|MQ`}`&hM&2N&5RVx@p(xZbNS9; zaJGFOo7LI>!m;Q`o6OUoH<+7);nN%NO(>;;QU%$2Deebxt7k78(CD+B?PzY=H|%)Q4U^zv2XQP;6a0}=+eb62xm_v9lHJ9dG`5_PJL*~PQR(qALZ&H0PzQJ zc$Uq7g3WG){}BVk3hZvW?9r!a1g8QZEV|AQ<3%e@ZQVM!0=rq`<{Dx!+xirnS8iLpmVA-6gvEWfmD;S%7H+ z98*5KVdRDGLGItf(eDesZ|Uv6Ik49Z3(KO1SeS5a@JIdnzY9|T^zYnaBjIcEpyKV< z8Q`CrQEWS7y3bIE=J6+VhzHC~qK#r2ykaH##=H6}u4TpfBY-xEJ@mogy2f-gHtwm$ z^c&Avk<;HfH1`ommlt#3+_|Ocm}W)k=Rz7V&Wl4-ra$(@InXZ0N~Kdl_-~Ghmb|`u zPQv;(oEYrH;F$z9uW{Z+mTvzXy`u5nS00oDwJ$=*hw*f8yhFcSqzhPBjnG<`Z8J>{ z88ojiaU%n3%(u^`&T?gk2Tcj_OW}s{d2YDrc4;!4?a-wB{c(+V&9$Crte%c*E*|cn z>`#aKgkO%FD&HK?!>tot-JW58h5~ZWSKn@H<4#bEsQm(?$VNg0_cIxD4yuMGn@RFE z)MxKq(#Ly<^H)?}{g!RSp>1qP0L2&wJwb_myrw?dr{NxzOsduJq40jPmOFX+9cVps zHFocTu6RU7tuD(L%bK&_WvIa>i{)DzbWE@=+z@qt?Hr2IvLri?v{y+6&GwuGsHS4> zab+Cp=*sjliN&)??Fwh)<{|f2ADiuDLpY4RZhe?MN4Uo!uY|sNCF1y%#S{eJ?3gPj zjWr5KxjT!LjVx(EZ9i0Azb&cY6Wgp~9|~0qe$wVU6aG)GK(B(@znqiT9o!rWIH>q& zIK3AMcMsOMPx`OmNhs;`3|TvX2WaxZfXT68GX9rzfl;jGR&K@8%>*}86Bh2|z7*Oz zkUB|J`>#T8oi?6@pY#jLxd)i(PQci@rwe7=r~Jr@Owvw+n+H=x`>1=+Cg<`Nd3-pv z%3B!{6w#TkYCb@#@hgjXZs)hysRTKD`G%E6_P+;?pAb87dJ<5zr%vmfslM2m8H^rXTaS8v{I(HFuxo%ajg_}8+;|(ILtj(B=&2IrLt+W z56tc&*uP!1V6!wMIn^uhUkan={Z~|d8!-J=qB4?ki*qm9mjS*lbH*}o4+%;&rS$^}`7-{b4n^ImNcbRtD$vt->=E_S4a$ctri=A^-H4@%+ z(mMCtgp7s{lX^ceb6#%W@9Vjud7U{Yz1RABM^mM&G3HuzmcKlyvFLlMh~jr< zLOVBe@SmXaVk>N-li3%C*VSM18NWicK^cJ4RUm6biG|KVx^DpEG3JCT>9Z^LJdFQk z0d9sgK%4Kb;Yrx&ADx}qj*gDBXU$1-QRJ}F z54Vg&Z!Dx!E~^Zil;31-=kdc$%{{8aVC)D}wu$_R@9??s&hG4Ex=iK{ImxYfRp}e1 z@4H!ynTa9dFUZ;H1?368yNpmGT zD^8AP?{5*U;2B@aGWn#U?x@;tmsOIAEMI%7=m}c`X99-w>+bHo0VY>A+gv7uA6l(8 z9lQlm5q6WKw-K5JW-Rh!X9@I2`H*{OlRC6MRIf%VIo*C4Zoh(nS5{0Oa}JyJAZZ{iYM z7H(D+et#&AY+y6aF%BIlBt!dqOY$Aj&NSq1)x%p_5j>KYGSB8#)`Sv3PkpxA^@`%oNpHLvH|FAX5 zBhir)Nxf-M?-LpIr77RlrPogqIi@#_V@fVJ+;+wk&SlAqq5gIUaCCLg617#$<^TEt6vrvF z!Mnt{$}`pZg_i@;El%fFvJCd6X6_i^jG6inbXF+9%3?G))uJ2eHp9tINH4h*T0N4N z)(0-Z6v_S!dHP_>O`l9aOs_2;V%>~MAcl;VE5&?$)nriR|3%G2ig#c=()br9+9>#v zF=q$Rb=IJS4}#RiNw}Zak9N0VAU`TvwZ@ox@||wX?KwLax5gb%yE+BUXd-)=M-+2t z+CgjHJq&SQsc*N61r?*3FD%La>IvM?o927?`6HRtx7zyre+K<9hyc%u6ykGy`2f0ulRZ_pM_4@Wo}L$_ftgD%05|jb7E_^(CzLcc5>( zwvK-cws&7*G#b{Ls#=L1?a^`({^ixep0%Yd&ko;I5f+i(iTv=(`bBm^>jv@IL)n^R zc?S1UWW4G*gV7`>&U`R=2#h~yOm-=OG0sp`?F(WhH%kM_ST*8_!N3l3(n48|Stl~I z&Bk{A>Z@&wi|_jTdyR+An5Msx*LPpo?0zrX{XF%-XEl}}f%nOHZaE=7C@3pN1@ASF zpUYlq!!hUS^qmtGc5nQI3`Bb8$alZup+EgF-%!&JT zhUk9fgz_({+)o3Rw#L!cpmwk9-Hs=EB!uo9D>*GtB$H(%hf!l#)yiinc<{CCY=z`8 z1yJ&oX;6i0wYDO*XU&@T>$-)2L}}N|OYNMEqg|8ANqSLR`G5&ayrFO|SzXorXYnP@ zvN65+74{#&PbLr2qzlBh{`27v;Z}OlAH-uFsO<-x%~yyi8wFd!AM&kIjU3*eG|_TX zea0K%8aixhDIGz7dC!LA;uyBNvNF6}Fm_ZeI;Oyd{$uYhs0wTwsnTs_8~By39z z8{x8Pf zGAOQS+ZKl40fM`9f?IIc1b26L*We!9A-H?c1a}Ya?(XjH@HWXg@7}NK{rI|yqM>)M zy>#w1=a_4Z`WU`ns~MHFLZjrq4Bp=oU{<^WY%-pZ#7j*PD9*&@^+zndf_+3Fuv^Vw z1mLjIWzhq@9`-xU)*N|2vO2oojq*`XW#Xd#fY#I(a%Sc zsMb%2+Hc$E?qx4whwl_*MIS)t$%yC)oi%JP}d7=iHzhOLxOl_v&IK*wS>9B zWtC*U7+NsU`1z;VMG}1pQgm8QY(Ec1QY)5Tsj~byCvIVR1N+$vkj1>oYBm4{l~w32k5#yH+{QjVwU9_?H~ zx8hrtzJ5@eOGu*sTv0L5fbyC_kzTnqT(U{PmyhAtMXnLMLl*y3gqNBddFS}s6K&P3 z^GbA3%09hiet{`lGVXwsmLD|aEZ|@7DEb~3SYUO`1Oz;@K{wqx^$U+s4}ZWKOYN0> zx*PCUAI`kTFZanc)vFR-LQltDOO*DUSN&QIDIYc%(UpYgD53no6^eX};KfzN`2t({ z!Fc$#dD_Y}Bf+H%*5v6LR>H2lUpPFMGqavgNE%9S88`MU=Vm z=AI6aLSq(Ekdj_9K6CM>wM(AlIuWUGI=wy~}8z-b_r$hL&*5egd{l+;xF zeUT_n9NPXp<4|Pun!$GaJ%kGLH!M1S8Kl6`SKsxjQHuL5wD3%$a?O1MvsbV%hdqIU z-mFO&nlVSWwx=|{w4*KYZa2)&FSw-6svlf{G1X_Bsd1VZg)v)*(LMFNoC;1W*B97x&A| zP~wi*eb;vTgQNRxOJQOOT5qb!!WEWq3f^R*os%$y`*UHNWDoF4lgzSG3Rulb*wkly z);a6L6#XV0?BqCyQyOxp7SH&ac%*iEUGVel6`O0GOzc#5yhGv6Iy@P5{DM&dMN32| zZ+*)D?GIo{>+=vxNqNCEr(v*V9UjKV`&W&W`{<_3#~i~OBNtXjXG^v7o+^9T+~_Jc z2IAxbq z{KVl~Ff6?mK%c=BG1ZckvR+HXS0y*+F?B;-FS^xu?lRAGS)|LOH1S?Y--{Qe<}=||SYe_IwQrdb@f5E) zM4pn22+f%SRkBPlT(4J6K<|0zhfT){jnmoK_|s3*uW~R~KN8q)m|JRK7%N}>+%?+c zNPMv1^nFgSS4v`ckjpYjl1#Gp$u6VNBcGT*eYU&U$nV+eL4&ad+RohNg z&0LXbZL-OUhdCK+@REAo%l&*Ak(34_8tDo$H|e>V&OAM=;Iu^BZUWh-Sw==!dNc4g zYj;$S&Tlx%)X7X*k5VwzpA1!hZlP3ndc5fM2!TqiN@>h=j%k3JML^bX6$8@-tf19b za*#iWV#`~lZ`5N{r1g?g$ARbdxR3r$mxK6y9%tMEXC5cb7|uhh;4J0WURjDVbooAt z08SVO0kfN2kLcz*-PM@nIAaUA2*AmeouP2k56p${~!9fsI zhpTp+v~Nw_5gASbS>-=^An}0M6f~5Z&3l;`8b_TcU*ZTH2fx19wgzQfE?4t1h*c(P zrX;9itzb3U9b1#VtW%-};T3XYWjC60SrKn)VCh?y73c4##Rk@)rirH$*|GZ<)Zx5B zgQE8%+alpiW4ALqdkBgI#nRi`sR@Iq&e#9}JCgkfd|FC@tNlZa-n;N@y{51aE zaMD0E2~0CBz+`^LyDF@5fUb4wf4=j+_kL^dIp0e=;xd|IVTZmX9pEcDa`gQb>(AhxyxLp!F(gU%Hx!70iy3cP;7ob6Z4brQ*Z(45&rz45BE& zid~-r0u#K8zTT6;txi3FU=vZxYS?QD+z8Gwx)jSabG{a&PUN^Fk+efldg(K-haVeM zf&B=k{b$bN zg7|SY+V|C^BN=>>r`oWu@VMD6l9$Z*KDQ)O77Cn97WJHzPNEdI2m@UWUJ zc+HTn>kvb7|9N`zC}m8KGV19J!tQ|1W>)1yWE;R;3GdZ-!zB`L^H?6}B9b&9$7aeX z=nQG5g-JxX7-oOA_PciT_l11Jpwujpc8}4jBY-S(zo*o;|>$=T;&~=7k zEoOQV+=|=stbB1eEQ2kD?whDB%ecFs52;;GdycG;=1xs#R#eJePtivhoQQ4n8fYUjf^wM`hfa(2{ueA24#)O#a8~fW;wz=%LoqR*TRN;UCUZkCd zSuau7ZFfi%wnXoO_)&{iy|xwEy@S_M0jEh=v$}j<&P$T*6Q`G(V`3eQsV{ z*J!=J=0jR4cYSTcxtZ~fb%@p{Yd%JZH5|kMX>PBA@o)Y-yxoq?6#9AM{}VJ=fcT3si8F9-q{e;kzSiyW+!6j8hWrrb7up1 zV{n@oirl`X3u>Qq)KGKdL*f}aAba%mZab?7W8uaQ-+Z4BbUeytSvWto_?bPxTC!|T zfH)_W?_nNW5oPqUUQH-)Ou|Qq1PS|FZ0t!nT1GC-jBG)#x2*&fV=UD3yN%TM88kRt zHZx|v{SM<_x|^Gb0I{5yF)OqOYgF0z*W;0t^RF5fi0cH>@-}QyVx)%o#wwjjYh1RB z;#)}pYxcyxr^L1ANAL=hi;`Q%N4B69(am`r+z+itr)eqV7UlR+D5p?k!7b={?h?VW z({mkE@lC!iBemmCUN6Z*i&D&+CZ|jzc5G%t8V7KtKpmymdEz3*Js_K#Lbs0C++mMX zRw6RyIZePRF6G;LxnA;TaQPzWrlMd!AjzLAD)Ccw7xnYXy6MHVCMZpmcPdnu9UOdI zH|dSa%N_80){H4NlWfi$0|tNLICM@4h?hg@p4+EgH(pU*&Lv(;2i%l%9ZGRM<7P%D>QLy3 z>u3$EoCiPfd(HJv>(0P_ib>g+k`P~Exqena!s3x&yIhnka9M=MvrsaTFlk>wt6rNwbD&5TOx(jUe6`2xt=7zK`xde|b zne*6zkG%gJ&Y z)g&QEN>ps@VF?98;dyt|{K0U2yX$XW)5Vn!c$!IX!xw|p7<3E)2C!@$QbE1NQFu4s1 zX|c%ms>=-Bm16(J?NZ#VXmc&!-~laS9}*GD5-BGCE!?7eOl777yxAStEd>@W$Ub9e+LT(S9Z*F?q zyR2K5Ou`Zq>X{dD1OsHRTm}#_s+LPDmW_uy8m%9$AS`25b~(+_A17rsL!Yd8*ffm- zLad&uA7o@%3)*)&YSum2c#07_%byUtp*;v zm!FJk)!G=?c6X2FF`rWX97MLDEyRKjJYrF12Jd8!7|DBpL36f-C^X9E3#%)My8l&yYCH1$EX7f{=Uh`c>PL|cN zyfEnfC?9@sqzYGYCVw?Pu&5gf4PY+35i_yEGSF5K8%_~7_o_}j+sAyT@$T+s5!jG# zYgRizVvN>;-5|=PjLx8HCgk%M%hkhHae@{=RQj_qYuRamv@d zgruY)v(JsR$>-ve@Wf@xx1zQ@lV;n;R}B-EV{ROEGN{FTx4O;xn`EyQOrdm5!?;^H zf7|4_ETh=gE6_PAUtfnuE;IurVZPjyva#w9%`ie{sy(a3;K|2xN0gX0nu~t8OXgAs z`?1+WCV0=3q3}{JCQFHA#Ht0U{70w9@Ob1)k$(>J=PL*m^Z=iZv@5UBZLQH=r%{** z__AFUo6pUqxzzW}j1Zj?O*1~Rk=kJD)H>V!D9nP&E|ENhAlc zLrBkdoo~uDC9GfBJja131ySRGYenJYVf=U}{ezr$IXTO{AvV+u(xN1u5Pw&{Ix{Wn zi%r^`ovlj4<@&(1wB|PDMlZQ4#l0kYTY--%CViu=&G)Woc7?LrBKd}PsTmqey#*k$Fw55H#GA&nr3e-z!@bw!DKpbRy7h9XqZOjLjQoC~TnOppBRr}Na3l#EjtJsbPy15uw}@9xNx?0EYcS-v0+``<|6(~RJo5xGr7noKHIttu&E zRIki)vrlPgdC!GIci)dZeuzR6q=G2KmKCD`&he#@#$NBS(M6ffO2;BX%)S?B$M1XF?^Z3UX&A7nl zbfMAgt#yj?cJm?acNzd!DvG>;-?4gVpGAdP3&_}QWaO^Jcxd!UhE!p*t^t|&%ER&? z70MXssK=C_`!#no&9~(2CSl1DyiyBsIGWDJOPE}(B0LUl)2drMh2!_%;`{~I0+LYv zGI`hMQ3j%7CU_z~uD;5g6g`oL8)1se(NlCXP3vvI?Gc+)MR_>wJ+3>PcJ3PsL*Bp$ zW8p|rBT-<7=Xo5LX?Zjqpd`?0NQ;G_peMfv;&A$IL$~vy-0RsV-K?B4`J$f41>5Aj ztS2WO&zi(F#2csk0*ghZRz$9NP(o#eW+ng41(th%ENg^VhV!6Z0pVBFKz$t;LPJ*+0!J z!E{)pR|`fSGE7bvYnbOhRGyIby5%nOO?nZL)Js-*g zMowFX<+6W*ro^ zRNKEm!(r~)a;Q%Vq*u%+c2Jye9XOO5`!d)CPC<=@XC zMR=MPcW^`@b>r`)7xL;Ro2XI=-zZ~wRodghUOYCv_QLgrm z_=CQXv(;z)sz84(b*E1mlnc*8^#C~D86e0MMSjdU^UuYgyh~lG2SRKu@HIAFX3yh$ zPov3EjiPCyYhSw?$oZc=g@|~BVSExG&$XOl=&X8MMx=$}Gtc1g+G`%_; z7Jo;vPSkHRj*Dn2DnbWmWOV0$s5Qxqy~1;JNq0Jm=f(YCV%Nsp$a4VU9s-Km7_32Y zn~U%aNDm!e49T!V6$jtMUjZY2U7BKdtR`t>=42CfdC4Wta>L zLmDfCyt9jzy~vwQXrniN685Or0@cJe-XzF^OLn1<8&OAZFGL>6eRD*ny<{R4p{tD?eY;rKUqVkp%f zg_SeMg|lg{$*C2Oct_(#mZf$Vze^!vQi6-bAGu1DmJ4tvtl68EBRiur111(12g|&l z4-ZQf*y6H2SJ=*LM$W5-PI!~H?Ih%6AqbC(Ku*PHU!4pDYn~B9ToGUVL9*t(viYQ1 z7BxsE^CA7$dz$tyZH=&2`&w6Ys$kH`&$Pg<5{M^66pY79`YdxD#6kk#YwkbXjco}y z3CWN;oHT3<5Xduf#Zy6-(rEMFWNahQFzX3sw?RUOXW=34k&^B~3-Ep{L)YMUJn}7( zH5_@A?ay|-2=$eh_tjSK_%8R!MDdFpJ+64Yp;}LOQ^^&c1o`hbi3s4{cFz-K_vg>d z9K3Xo4aP(^w`;C5&mf@j{z*)=ju?h@Znoa&M9sO-iAuztL_O`EpHL5RL-^jD@UEwS z>LH8%@1P;DTCdqWS~s+nJzRZ+2HhB}>cd{z%08Jqv3e{-ykx$H`3RCfWWI(^B;qx& zfI<9`MfMWpOj*BTdXJ4BSIMZ_gt-lR0qd_-NR-Fb^c_;-HEs6t{EoDD2cve;tzHuP6WMmQGmzy z#Xs9+YV3y#f0i>}GMdV+zP`#k9J1*Jpv{!#+H`+w<$lFcX}e2{@!>_-vTwknfLyM#58{z7Oi{hki=ZCf=yS<^e_B|ap!OpOAVEwVo3zrBLhUMN3s`3T2LM&)H@W&S0F zj{7Yd0_cf)>G71p$OxP7F}(7XQ(!fo_dyPT3w3kpp_(KQO z9%*3qSySW(2u^WYk^XpUiU$0~oUFa~rYd8vmjb03oWozl;GXlSS|kSVCj(z2ULS&n zJsf9eap)5Uj^08we=D)^f$X0zi=ibqhDd5^Bys=z{OV`_0c+cvvy<)R5aQ%z3n8EG zg@0cKOU>n;8q+k9qW?NOG2z?24Z+pQt@Bm_O@DzG8#eYAk%n&=ES{K`-f6mDM|Tn8 z;wI{3^F|eWriF}vavNL#F|E}X4c_O&(=(%cwmr6l9K5)7Zr1;HhJQWrKd|OlL~bk| zRTjZir|N7Umppm;Q1xy)k*4vE1E@zw4xKx_XR?vc4F)vSgG$Lql?vPe$@>6hM*{S* z#|O%aWr?0E#5?iLfgDC){da7WV$voL-Vb=NsbJFOdAIXFL;_#e9iU+VfaXxr)2XSaD<3_AMNco_sXx@y+0!ldZgo0iVMt0zhR-q4v_ z3p@~0JDuWBDgC;{e{189EQGz&1pYsN0`IzxMUDT0rRyWsd9!X^t?raMy&7kG)Z;j{2mP8rJ zvpesBbQh_=1J*?_ux^X)`BK_+5(5}1*iSpEDP&Oqsw>PVE~RRTQ4cE4-8aRxYE4yB zOxY7)Rpwdg7{-qcKdsht`?*a<(0S-U+tKqk31pep`tY11x3(C5lwExdkf< zr;n7Qyjz0ZjQma>56Dm%9-UrSW~pqrw+7_dmKwt^m%-jTVF(Dk_Ihs}*RAecj`D%7 zJ(QHDxobqK7fK%Ff|If4sti_$txr7B6qzexp`CcX>z zxCM{{eC}hiG)~b!>Mq|(Vh4upXE6b29!>NOJN2*kE759lqBwob3Nh|^GpAKjEQ@x( zaUSh^eJ-1{J@5`}XD!LA_t9b4iY_NwH-=oimcmV1Q$KaFjEiO-_B4;Q&pB(~?kgCo zsBG3^F3SRKVu|^eOjJMpOXc$U)I0Ok`}L7=(Jdol_`20{o{@@*YNv?hZR*os?zs8J zFITt5CY|QP+PU|e>Ee4UNKAq$Z5uZ(lLC(uh<_%0JzSVL42#bAe50F2y}Hme`GxCA zKpldu@D&3CgGQq^JSGP93#JYRe{kwZ1G|)rbr%3a_ZxQX*lw;)@)tX|;yDq|Rg|&D z4jcAGdOT>R<-fu3_Y4)k3w1YZ$@ERa6tnX}o*lUGX6MV3B$EAeAN( z%h^F2?IH<(-gO%Z9*g1nI)fRV|l>iqW@l`O_>dUE+@OHzfgW!c{RWgv!Bt_5rCz)(X zVu?AOcIJ*~)0tp1+SBG?ljmn{q*C7d&|II96=_`jdlp!#8ET;W-ir zM36YTY&B@Gvj)ZFF5s-zycc3v=lUJ(YP4C;f=zYfkn^1HqZDwe#V5AS#@z^}977d)waM#QrGEBAyq@iS)H~=lU*g(GGRF%^XYVdDO!JFc6g|3J zTjBWn#}Pf^gxJv~!&G1yH@_h_Oi%;6Y(`R7f}nx{!!XLS_fnR)0APwHJj^*%Wy(fW zBSKP{y!+~Ok(K%X1lvE}$VqVuDM+zIm|?Xi8aSi}qb=(dShOLnh83M(YX{5K<@s!V zD3U`*(FM60wF~VMITQR zp31Q@PdEaJ1tTr&gK0;{N7=g`NFkmh3{3!zV5C2#)BxwHTX3??t_5-$ze$5xxmquc zkmlr#G}#350M?P{TxC^Y%uY{$uZ8;M@=_Gr9gu=r+1$>KLML9VnZA;LNtmN$JK;&6 zt0f>w;O;I$WB9;p{i$Nn@3x>nyW*02R%rCzT6?uv-!muvFP!Tl_VZopAbBtL8Rd=nF~RFV=sD*5vqEDg^AX?og+`b| z+nYdYYot){X&Blo)^4HaoO_dP%Yx*^KL0DspmVkTeFVvIRD|@q(iSYTaz3f+R5~L_rff-K+l{*Q`V;QT&G^F}*MGYxZE21mIJimv#9)uW{^18selg5xb z^)wfkTA-<`dI($b%n~1HaD3F_ZQJH_WU*LOt+ct|`F(C@_FP&q+PtUn+ff*9dXuN1 zJ-E6KcI%1Or?&-FGl~s)`GMLuw&gVdSs(Q;_U&Ka ziI|@q{kGe&L*tm|ub%v>I~u(9_^~SJOG)fj#oe6)ah=}^LcjBewZ(}qvk%DY*;#pk zo)SrY)~9!CSqEKJ?ZOA0DEmaT#{2E^B;~~$OPKj~sqXBvH3@kID&5K?!6nL2W=p5N z97g(<7^fL$!MZv=^L{2Rz}MDsCe=mYhjEbFwc`&QOqjD6)?AtR^8CDcYvD~3%r+~1)P-QdGxKE)BVz4WgiFv$-K^V-)a!GSYg35v z(~+m~Qw6I{5s=^X^^&V@ds-RR&aV&Q4KQQ-Ea1KB!L}ZGzUGItae2SfgabU{-&c~O z{`_stjW$&8z`fj4)T>x(*Lp5Re6PTk4=@D_3rv2|(hj+;Fh+GZw?%lKHqW~VS@U;H z4hPNx_<0~(c_Q*!ut;$cDK;Z#O>h!b*G@>BC8OXaHWaNOv_B)d00dbrHi92l_Of=8 z%{(UlnD$nbx@67iEAQ{Oa9>G2_|aBcc-DvY%qvYX>axlsa8L;k+k)hczX}N)LJ6;A zl`rT}jq@>4oGD2$irUo=768TB(vhgp~}1wpjYkT7QZxNHJSx zz+O_8i_m3UEKiVOTz=9dA6Lok@|qMn*rZ8uN*?^4FdQzeAitA+uFABo^{M#=xmFx0 zgNkltc-rNpE)ou3y~va0!y_)N(tM%LNl#V3pNRrut5oFq{+CjP8xPC`wTfZu8he4k zG0*mJPtC?3D9Q^JvDsV@ngU=i3Aj;2jeOF%>5-eY%u=%a0@U#I&TaF?Vl8N-4^C-< zR8nM%u}F=(%#|sKyK#%7ifqeRq2Bt2KV0u6eW!62oTkUk5m8pzb`+59y7`mqQ}HbRi{`LeqS1T7lk+IV)p?OejUQoFO}m;r1lJj1YUrvJ9yJ3E zMbZHH)v9TUc`bW=o5KB_{@Bgo~J}aFE)oP2o{A;k!zjCDjd_& z{=9WYUXZYe>?%5Tt@NXmJO11tyn$;rj<=D+2Pbux$zgeKMjI$N!WuNrR%c&D8GH8^ zv+tWl$_vht-#$}Si2>fD-SEi|ox{J40z91=J?gqY0oIHhJq3^r3TAd4Tsf*YBzH>D zar6mdIR@qp5Tl(RxRGGyA3b97)#+YDtVkkfnM%o~L+$N9j||sL@y&{QWMZungCBuv z<+-?u<{9X!Izp`7bO*X=chk+gl~<&08)(pKZ!}YwXV%df1MHQlwcXM*%(+A97cGCZ zgf~`-zR%=H@G6N6j0>7U6T;+XN!g_^wQM(@7BwQ{AkROPjQeu}S^5lj5SBO5kZ@@u zY&kcOEuv6SmVgdKgBm`CmH+2ZR+m&y^Gd{~rY}IrUS_gVYOqjZbK{mh=3KB z7XIvowG#`sfkj3^AB)psPjJT4c&1p~71cwgDah<93oYrFc@JP6-D=EMA(K&Z(drcP4qb9wo*PJ{kgT@; z*yI{~ZCSQzszv|MR2XyjW{q03TJ%59Xd_ z<=u;u7=IFHT2_8cuOZQGz`!$W=4_pR<34TfCqK}&F5ti-Upw)36W%yE4YH=O|9#jBC9m!=5AbO zx0!T)0;|h~O6E{43VS6PHwI6+#PzNdK0HN>UBwA4inJGFcEyIo&BLM0#D?3rP_kPv zA>&Z%?535|SIG?5nI)PEwQKl=OnmSWEg&kWsQ7)$JkD0A3WJ7~A)jOnu6ryIK*6Dd zW`|g<*5;GF@f;1B!f*rtovM-D3RBLy!C;(K zKEz9d7Ni}m(E1l$p$n!(&g9UnxICDfG09ySg(`C+`by0;qk1ZA$^~S2BjCPoibOz8 zQ?MYhAoHYkXT8Wfj=b3>|S!IkQ2u zGZ*0TfibS2Gbhc)dS}X4mhGkzH}^;>PafN)ZIR_B5qD$=FCA&y4APTl(YIbE=zN+m>zGYU9^`=Peh9Y6W=WFv z>!5hHF#Qp|%mcnNs zO?g&Abs|u_<^rAp(1k#5;x^qL`W7`}Xbn5g-SjAU^6CrQxRy56NsXSfo0;i;`z3$cTokp)R&TBR zqp$N}c|Z z7T@yFGS!MF$~y^tNLIzQg$Yr8>4};`_Dn1CanwH!+>%m8P)-FwjVcQ4H(g@YkUiVH zb$rv3Pp(MGZ13vRf7x0sNE;L+H`W<2qpO+OJM|a@hR6GB7x#MQfRA!wWq6)jAXU?r ztzU1#rL@ipELwwTg9v7KICDT8upo&s_H-eSSxB>m)BMMKbE-7!gU~!#Tnj6nlHLy+ z`&Oj&^AW#_0|NyL%1=y5&y68ohB0jQX!C7S&$&V5t!*(^zZUJvstn4mP!43_o*2I# zMv)-}lY7ncSF#B#*1or7)rby)8VxJr-%rl;W;&5lB0fhOzME!W7g<(ZI_$VqB@Vgx zSTQnNl$>`B@<(UXqSja>lA|G!Njuv^L0OfeMid>JE%U-#DkcdcEF@87`Q+f=I0W~}B> zlM?8?^CzFrl@gTUI*)R-g#6Dm)r~Ar7yBJDc6Uktf+g=@K~-BrXs#WM<~G!i z|C!5eGUgnZ&~{BRLaG7C8=U<_zwHGu_2S?D`d2`(M*7dJxAQXpc|rs4cD}z=DMDXo z>%X}G|Lfymj(=h2|M{2xhySsC{|ZTh=()H44m6HywB>eX(7E-J0Ic=tLgM9k^~EYf z1Hjz=^KFL5e_O#oYD!AIc3&v4xP*iedyD`3`KO)0|99p7=kEOf|0?t^PW!(K{@cd? zPcdh&RnD)Uq|+Z;dspp8ua+>z>`}{qd=CgwEscIJRXFB9U_@kHnhdbRH`(#Sv((Bm zVbtb#%xJ!rkMrODgyO0g!-bL%E;J#sOor9C!L3jDshf;W)#F}w1WO>A)nQl#qiK@K z;l9deJar#Egp_WVc5~_bG;V0bvwF>K@tJG&dh3zmO(gE^#W?Mf-cj%z*Q-M7{}4}e z-$Xsz3XmMoAd>!9Je;stfgPL3Zj<*0BfLXZA;;f=^6BMJ52IsZyQ+_(|) zV9UkuLA}l$+X@bBQr8OKnjgMVWFM4;^p((n_JF< zSoSxLSa>T31+AJ=+)z7Tv1-{Ku$Jn!qu$kX^CTHW&1zp)9nUqBCt5kVU3;WufQYt6 zx^3&|WbmY>s~k$Mqo2Gs_>R*lFGSY27Rf2;UZF^URt*Zm{bQ_Ad*}GDdV#_%*Irc? z)e)hw)R;kD195Q*4eO=q^7teNjm$v}xn87Po}?i$s-Nc;v7pr0d+EH>k4ZL zzoAyAInHTogSfG}k-<9IXx9qA7zQU!t@>if(ZC7~Yk9fBsLUBdcCsy&Q8@9uuh%^K z#bbocoujrk>dquS{=*x)4dLXZN5;Pn=TnFX14Q|T1x~NOZs38M4||?tGQTtV-pcwO zEqar*dbw`WA6av!ax<-5uX%nJG}J)yIrEC)vL3H90H2?hVi@siq0y7BM0;B0@Ex4* zV(M!sNc7>MCJ?gU9#u%vKvUFqg|0jWs}CWJi1A{QT2HU?SFR+B1jdvbbNG!ut)NuB zM4kej0{#6{=If=mGABL?imN^%G%ZH?F^8n(=8;Ugy8+~45M_dLZDgS5uHMEAE<|D& zHEs}hE=}xF0JN4(kV^H6YiPicl~VdEL~Ot zk5!UGQjS*10nuM+W5b(_0|6Y=vd6i#NjA?e`2RsC1u(6 zIyq13tv+K5Vi0R<^2~{{WYx?78_#`K#MGqr`iAIRf@fP&v+mN~d*eKr1V5yqk;e^1 zEn08iqsASh_oxmcw_&C5Ug^B~Ol!%C#Ur4Qsx7D!p|r<`+P>?gt8w^e8<1J9LcLZd z4O-ywcWR{6Ce)m^fC7f^NuKgQi&myj>S*a>OOwVBUaNE101q4CsQ4(g^;rGvpYp|m zQQKCPEE5&qiwBApENC2VjE?zlAk6JmtKLVqz=Ih`ld|QFnFwxAn+A$ZSX7r^nFm9H z2QCpW&cr`Y+(I%5b?Gxn#340fh&B8U~k~UZHpB#Rh zEEK=zu1O^JXJd(4XrPwN${=@cQ4_8o`9q2}dqVL7BP4zZ<;Dp?(&jvA-(z?eq<2x^ zYx{{mi;L?KyF}w>r`DCSXV)k?cB@_t&zkX_pnqQhe4&mPmxQ5)|B>pCt!|<^syYe} z)NWRE@^WG^vsRKPm-rWJP_~TuUE~(McfHWL{<~Mvz|xWDEvz36rJ77Q%Lg``th#oG z4*q=&a=t;82rs-MOI-Kk`VZ#K{ABnfPEbSz&=d)w=)95opineU)vOsJRvQyAk^Y}| zN$|681a1Rzi2t!1%G-2I=sKa}j|1;vzLASK^?h{Vq(8Q@F#YkkJAlwS&w2b}yJ(}( zC9SyMD7$rZ0<#Dl*}XtpSkJc5NPEtFyx)905z)czSI}e=J(n~+nIH=!XafJu00z;^ z$#oOtUEvziy8dZ7GuL71kwWeRy)~n4p75G3_U-R<>2JcpC!#-^6}t`)q+jzomhtan zg7$immQK?C7*St%0yQF+4 z6?z^zTNG`X9g7!bqg2U$a082#=yd)do~ONF`*FI+f<(|L42X!O~P(E4Yd)qL0 zD)D80y!VT0odBzd?AL1EYHuPAw$b?>Y(zfw`}wmrw{pt*BC_`W;hWYFrV!J=CyU{{ z>S`v5*81 zw|PbApuioQtUX{P72GMZE7nT)-9!fcR5Zf}r)sX`(DmXPY<>Cj&cF$`Hk~3wOgN@n7JPlVQxNFSOd)UWYfy4Ai8J{rtnkQ1G$T5A19>qRl$1i29SN} zd(llLDka+{jqB|6v+S<$Ev~SmUsMoSQuyw%Q8A}T9B`nBO`B`~KPNpcrNVhe&me%M z%vJfn%X%k)XGY^pU{yuD+dSRYxRTB26{p(zMZW3R(iE+- zqO&N@suA8VZxmYq#Sju@C#Z$iMuC4A^wVva0MJAj#*p^h8PVKtIyh+oI62)izWonDgGg0bu z5b1Anzu&Zb#n0nQNZ4(`hkzmc8G{(^R6ei8KKuDAq;mQK57$W~$4;ely`4gVGK@M& z94Iq&F9WO}?Kueq16Kn6o9Lc87cxqCr%;2>OzOvp7Hdx8duFEqa^tPlAtqa{FO~yG z_X|-9O#kc#0-=3lpy&GgUPK z?^W}9viCDKTlw&`bX7jqq)LPwZUTJNA;UET?-bc_cJ5hM^e3=H3PcRr&+0koD>1Ui;ryp23uc;T?c}_fsLkI`2;CcG1 zAOBhoG$_@9t(IxUCKlpATb0(Jt=wdZ0aX`Qac=e%HQg~vMac+@v zS+ox*jo5CetK_myd{@R;7AaP=Lscym8yJBdAAvlVfWmd}K&L~bUq~ja{Bsj-CD(Dt zkDzHb)>1d{XPe4LKx;Cl*C`Pm_m+VZQ#EB5u3?5_O*`U&J!*F4QW{^e-FEZDWr^a5 z{Rq+A0F!3p7B}qR7Ypr?aD_Y#InY^K^FML_vz0U~-pv&pofFj_ zK+Py1yDy$RA>L!7FT*rd3TgW0_+#MVqfg}a`wnSS8`#oq?0SQkHglAvs$eMX#b?3W zdU`rU*=JUfRzea^gPUgeRM6=1yZ=MkSwKbgz5N~q0i{DiN?HZ!lo;t!5D<{=knS89 z5u`)9L68t>knZl5F3BNh7`kTW4*K)A?)$&*eeb$wEf$M4hdKM~v(Mho^Lf6{em*TI z(E`=aO8n>CjtjmS?iydWAg061TS%Ge?2~V%5_N~ld~=jRcDXg*%AS8O!zH*=CIj=X zzXY$7Jx_W^Q>J?BLxLvqfGAsTwtdtcUFVlC+BUL9s58q7zz0_4lzv_Q1G2WFxa4?n$1# z3F1MD`sEyfKo8r7_^7H&gDz)>HAZObUbg2mi8K4SQMm_ZoEkc;wRap>VY7t@t`&D) z_U~nj(r1{3zEeubzM<#O6)h`Cb@}}YB+Y@mnVZF>zfEV!Thm#a$j;7=z>tBV@=9Bf zS9)b&O(>qezB|XDY}9Yb#z^d2#S)h=C4|ALz9q+rGZCf}w&+BTzH}#tZu99?fD&t6OgkcC>ke)fy1@ae!1NTqs%iOE3-q0WBpc2bA5 z;KQ9(U{+~<6*!}7#4Pk@EQZI)=X#y|7itCGlex%FY=1GzAmr6-@JwLZ#g0Lf6!%Am zync{wp14{b&rg-3Qw}vykgsS+gyw;>}X`gYG!LxOVp`XEh1szG! z6g;#$HePz7ru~-YqWd)Ac-TN~nE{res%-E~71cV?c-Cf4`5PbdOtR6EUBR%of>%jp zKTuUrL)fYQaf>!W6FAMD{G>{jL$A{-B`bSem=C&Rojm? zZp>uZUx`?t$_0l%$o$IEjbMJ~>aL!C5{gzG-8j3CH|An)@%~}JuVrkAJ8O1#e3njU>CRo^~S^i4v>qfNnq1WPt``KrBT=36ohUN?)8?t>6;y*Lz^^aGDIXV zWM4h-AfvoCx%$2&bz>7Z#1Zb#NDo{_%MPG?mPz^vXPm6+hALSryw2Tqb?TWtYIZA9 zUH~9q(V${iLew8~32a*5rpUB7Pm=5>^Iu;8#nBK)Nv&K$LP9oatv5*-algYS;5bnurkmS9DR!4nA)Sl7mSWGjK7-zA zMB+$V@EP*C$z4g2PJ+v|ZndomPd(?D}(GFLRz_!yj=p6&r%J49#RLC%2SGY@3{DL%?jDawcb zdlp8*00^vB#A(^(X&Go3Rk0aqlh^s@8U^_hm&dd<4o<6%LbHS;Y8f|OD0^-#5-m+1 zpSl#!_ROOK*?D&g_7Lx#^hW5vKtx45!F5a)wdeH7jEewu=`e-?l-{>Gta`$@wC(|G z?ffi4`*c-g`pw5-4mwuUJXgNOYp|8;;k^i8MfsyOPSIig-YlDzXu1(EZ00oH}+A%v#j`$JZ=$UTo6$&?;Krb z5**{4-4x}itF$Ywto_-McY}POyb)%5G~_uGa9&LqV<(2uajgKUlUczxm09y)u?urL z+e^Tg+~AI!DV%DrGT(Ar`QqIeHb@6d29gt9*1x&`&#>~^n)RS%fs}DO*4IsBhxEnP zNAu(V81?(+zH(Qp--GCqQth7su%T_H@f7$2WRfkJhPQA`b=bTtwUu_ID0dcL=j8BX z^4rY&S1qQruEu*Krc2L10~yq5T}gSt*U5!2 zJ9m?7)H%~HX3P0e;K2F#;J&=vfpW77%y7<~ZE=T5^n3^+;>bM<09 z+jG3$ei5GsEbGtzhe~XW>)!GQm5&p3sKl_?5Kw2ApTX?V8M^ksFhS4+cyb|vdO*$o zZU4;xw+H+zn^r({MmCLA;(f7n2d`=;=y?37_;m?U+)3lY+|5VR91t9}{A5%>`%_{1 zhSP-vd7<`cAuH#r@o@fU8-R#P-@$m(1&`Q{jJXU$&lyy0wrsEc*H;7|DjvY)7%mn` zoEn<+Pk@>^+=;AfRvOVuIX6?1*Vi!v!Q%7t^N#y$MoS7Lo~4mBV7>iT0aOSCTwsdc zGDC8*VsAjS)S&)rqvfe@^K;1~6LZMb&bn8Q&4QH=$IGiI8RM*gni>Jy_LI&}s^Dgb z?5hc^29~RlGb7sxQi!sMwX!{mtt`6pcsxH^;+^^6SdRQIv+3dAfBINpjF%5KJP|WI zD>*kev$0XX>0_LupTzp|#0rp5A>0UBOUAFWD3jpcG{><>c2DG3yWu6UPZmP<6p@OD zRW7ZkMmUIE1Ne0p!^vD)31g;Y|D9Tg--X7B0K5Dg2*owNysPgnv9SzwDE>T8$>e00 ziMui?8PL;=8MGwcjCs?1SFDjZenxJmnXB(tA)zuF`#|eL)cGmy6l!-8gU0R>DzB?$ zXH{_`rbA7@6lJ)@G$)j`{Fo^riKUh^EnVzaK9J$%FC$~`oMMA71-vhhd<4ZTUj>0E zSU}IP$r&&jswU6H4DwnR1=$>U@qh!@7%5CU9&?8z7GWt!Zty*1`Cn$NMW=j0h~ORdsaI!CEd(ru$Kw zAyEzrsli-ys z=+WkAK>!8SI_@;8DTR`T;GZSzyIN-?K#}MQ5gB`{WD{|jz5$|zDJkO~dchV2;*(yk zgQXLF$}P>gTqqvar+_;Rep>b!fer+5aHsh3`NyzG%=Sr;#Yusxb!)T=d&JetqCJRv z5C{b_EBK*%!4ziqMA=9#c0zRK^{=-nI;W#IUR!$vy@zE^#EVqkt~cT0NJ!_q z6xX`&pIN~F;8O`ZX`H)$^bAEYev5yWqN9jHKd^6By%I&fTI!FX;la+tf913A=+OqEo+rRT8Q{IQKw3ef(ZE3}+<4t?X}_3u6X@=_ zJx^wd1p6T_5N0|D2AQ2$n2uSGEDoFH3T4k_Iq#GO{Hnny6qGz^!F*GId=qiUgR{HL zw2l=S>+V6_**c|QW)s_$hmG#TO8f9FU`6Fd_VfN}RUlp9#45|F4`-C&J^A!)7FU*# zJC3}=t15fa9Jns-=K*qfv`u9}*qPCUp5y|YxvjF!X7*>WUVvy=^y}Wf5~}WVZ@PMs zCF*6NOT;iAZ1hpp{7DmW?p_i0vhVSaIeVj8DkBdgqhI9<6@uENH7A>B!61i;1>x#Q z(M8y2QOj5$f7e$@CbB#>jjPhMF2UE&Rn%C09*?vgD-3mTHxY=>Z}%)vc7UF|oLNw~ z*({tHSbN+0>hl%-OT+gc-t}&zrHOiqNO`W{jhRzoSo-Z4WbS8(hvDo%Q*cGx(chV( zVMe*R@AFpiu0M2!-*J`-h#sLA^=!t}P>I-2FpzXmKHE!HI6A#^RHkYV@5CX``rwV_ zlxW&Vq$6g95c!z-rHzWN9-(HeCDKu|C$GjN{oR6 zc3&;Mll0_RTVEsJh^{pJp>T8(-mP9Gvk}~Nk@(bDp^TppdPExbIp?{lva$llIrvE{ z>G~mLPC@QGO~E8B)lH4$z+jDTG-~t^>psQ9XX-3ViPtV~b$;wDrahj2=F}t)X@07f z!Mor{ynQluku7QGom;meDr-9#!M8rlo??T)R*=sGpsOSi&14WwWOUhavTWDtH{@~J ze=V-qqA~~Cmd6EE4OuoOb=|$bhRxomv2(_s3&5z=dF$u-^Ces@m0C3l-Xp@MV6)Q{; zooGRKdg`iA6iObx`M>3JTPv;92Mx|69-B+4ig=5dETNU4(o@vBq& z+vHqmW@C3-dno0P(><918hXj+v8x7USbHiDpRKpqk+^ipSy>*-YXL&lpXL~{74j(N}^CchKts6NWb^PvKzS)klA0y9Oq4WA9~m;jucHxThW~s;wmqvjqlU`373@C z{MXg+BGcA*0Os8&Bcnv9XY|baLeSsgJvtaqh_YAkTpr|h{3Y>dw#^DFZRwNC5(97B zUqq;=<@yH^3J82#s&Z`Ju+pAxe+TwUZYzSn>u#_kcFfhi_o13afLpx!8UG+teYb4o z)HI6oQM5fdRdsC0wBXK8usViK`4#(%EHYhQfADYYlv%%igqJKv;v5bHZ^KC^zyNNREi_^NYzl9Og=(qk1>p)jVMR)3|p+P%BNy->K#W z>$H#)XFj!RC)1_!qrD6XZx3ZaKqCA`_s^~Wb=WfbJy0upgt|9<&#H%7S96+^nEVs{ z@O9zJobl(Bw>YuTEn}b(NQIfIGzGr(8dHj?4;%zZ4=hv&ifJeR4A4%?__CLYaHGOg@skpwOe81E~O z9WMwilj{?JB)C!bkC`wTq5edL^&6qetOzHHU#~TCi#>X#qGkZsQFxC{Fu0+5_>tBj@(UbP8{IgQy!4ii86Y z@D*eR2zd?y6M!x{6@yU*z>zH_UA||hwf1Ne_u26`WJ~V6F9sZQYwB)E;##pDO>U*Q z{1^1Lw%REy<~Zj`>5@-gt|Bp`EV~wswU@BP=WptoKfE(|K&&VD3b8Ah_~FO8&zw~C zTiX_+jk@YX>7$Qxu;w-UB^E~{rOvOJ9fCE=r(B*@-I%5y)=_wAH23jYl*5n0(SRwHe#&tIrwoOqT0u?C_P>H8%en z&U|x=GsPb1I(U#m&ncA!LK~g5%97T^vY6!h#GgIEQq=R~XS_BJQE1xg6LMh5(#T=8@5=kvrP@%q2({xaHW#9Fu zkYeS(oJLe#)RhjK`^qc659T)nWs7g+-$CjVEWpLyirq<{eiHdqVRZKr?&?C<{QiKfO{0+{>&Fj zVN}Lkeo%?5x|^5w@Y%}ieL>HhAe(g_*J-6-1!TTLS}$Xu@>?g4AIm=`gFSo`Zg$x7 z79OIaLvX||g;zV*D4|1je+#norMKbdKCggI!(43Tr*tMOG^`D!ZL5OBCj<$Fi=}TG zQkg07W517ZFm3=FlYS=tS3V2Z{G17;R?*waeb`CWCL$nz#Tz$p@L;O9B&mht6|`Qc z2TcD54rjkm%R92mJZVA8&JVq$oEO7rat|Y)*k~%1;(EVfa`OHrebMY!cV|-*M(=Sx{D0)cy(57z@oWPOlOkMksD*cK9};w1n%0d5t|>rIXa* z?KgPNF(2kK0p`=Q-g12vqBDn{1H6f2nR}zEaV8*J_cgas?J%wNI{Opir5egwlrJ4; zycqm|bo5g}5}FR(*8VBOj$vf%t(?GVePK@OOodi$ChWvrIpxj*gnrtvOB9mlT^js( zCUSv}-l;<3mupNrLDS@Jf)CQ;&hgt1^Ys+%CE|B|h&QYyc(kst8xsr4Zdh3sZcHkN zm+m{Ce>5vSnJ^FbBCoz@bsi_`OK~2F(f(ZgWAE@KNprMmB~-oaZ9gq`#ifiOYHOAU z2Sk<3ac{v9bG7zMps=9HZD z(JR_)1+(nefmK2^K!NX z4>a(8arHOOUf=isSB#!cGQqaNN&0?~SHae8)tTStQeH1>5m*6UF?s&m6IA^_fw(mr zP0#3vA!2Z38zjDp94a;8yg4UA6qcMCiv32Fw=A=O;x?Xe!w``q@A>g<)HDU~I_Vl| zLa?MvGW+7?Oe90EK#40Citax8%e+HEUVS4_FKu-6cyft9c43?xw%SuQRw;@ChP?mM z%Oj-;E`_F+teavPx!>WP4C4-$q%nkcMGHV7S470rNzo3=w_=sG?xeN`E15j3FuOs*B9fSA*|{CxnY@7A{~v9uHBbvWGhhmpDp- zWjGTeZU$zhq8Qd(nRn#SEW}RM1sH^| zL_;9XTaW3GFuJOmafagGHD-VF;%Xbi9W<1SlmzZ3H|zo*-#JWbz4_GM-u^J^R&ntA zoSj09$iKW9wPgJ#asIahZ}IE@CsF_F2mB_t|9_zSf4=Mi8_fsQ7&%&O@l8WsgOE_g z;M<`2?NM3$TWs|Z6^pqs&66VhgXD>{HJ{y<)j}Od5!?g~*J+x=_=2Lp_ z|2iJ<;MdWKQPguGCT+<-0zECbn~8pyiBC3`3($XofO&TR$myuD*Vb_{7krOuT&buT zY?kfEF*7i!2DcRvfGP~AmntklHx>T9U$%~8#A6U*GE29`UO#F*X=BJ#f zaAp$z9C|`>dKCgki2DclZYXu)t~_x(^Q4$LXT9%T8;7t*yiKq%{m>@B$ze)==ea+O zIF#JZHN!zP50gCqAB7&ytH+!Jyxv1>{eN|Q6EQ=F5s@0kS?Ikj9g4xQSu$UJ)a&++ z>ankncBc;6pf`awg9_Y_6TtSj7a7<(${QUWTseW)S~s2!mi>M{$;(>ciulR-S{CEn+T!G3TjsrB&PqOk zZlP;bswDl1zk-t7@HwfgBv1r7fZ_`z|!+PApt$`7Uvg6;gg;?~KerBd6? z7e6+x8Qmp&2}r2>W190n;@v)Cv%i5KFU`p0+;cn2V;p>28yed~IeCNcHy`&dUTk}d z+)b+5fDTv84YSY12G8n>d#1-?jyxW(4G>xYLv}3OJ`M*^u?!eQXgvjznm6`-8n)=% zoEt%?yiR=xwgM(G6XBPydM#|!ppq-E3q`;2i)OMm)Sxi(-CXE9(lcQe>kX{Qw{$fk z_4aMI@;#RG(;{5AFEEW8R*uXxzoLJu5HI`FUF891tZV^p%_42FSC_RPuqc-?RK_x$wEbe` zi&Kk@$?MQ+qASavkWvD3`6h^IfQ>UA_V0MZ9C%nh=pgFA3?lGEB?{bmu`>K7bvMN?+t%us$l0lMd-%kJDWiYO@~?8%*IoZk6R zyRUQ)zj3(MkvSf4p1jjCDYi&;Yo+6KnGn%-E=0AE>vU!J32WI%gZgXF3BLplg@4)j zcrtP{9O6r$gvJ=iuLo+1$`Lr=>o>5DS!~O3<&dl9m31Yl zA~|#iNB~I1N8h|pIdq)#eIaLE0O$VLL||$@v5JbT9}xl6jV^)|&OW5Ak`OUuDbtDU zr7^YBC=AeW|EA~zT$k!Zb&puf*O{1cto~b;%Ukkc^gn3)NUzXcD?<8jpP7Ub z8F!&;8-h6Bs6b_Hh!KtnMgwBQhxHouGO)D`@fw-FMNCKH!5Ip8p{#uw&Gj;MbruSx zbIYA~8g{;m2i4L*_b9*Xl90?S{a4lIb&n_Bu~o>ddB9jGbvIQfsdBI5vOMu(Oq<@z zi_>sbpvdIgX0dddROb@IC?X)^ary9NSrKK;DbLO1ldpNEo->}pnvYODsv6eYJXxzd zRISE2Hc9#TvNJbAJJ?YQzl?S>@3H1CwvO5!!N_O(KjI8G zjK^K@XGICtf0RZcq5;LwXLY3ycYF^dGDrzBlL9XE^)I4WcUHt+p0As0X_YyBSyI}6 zPO#$wf4eLkWVvNnZOSsI^fgdf&QWa>Q5+a_tMeGr7sI&eWQt-9fgYI{cC` z<}^Y~4|b0G^hf*HQml{*4?qhJYtZ@nvPRx4WPH6)*j}xH;1l?@hKC3$L-T~t9p<_B z-6Nc^Fj45%$WZWl^#ea&AKb+pa|KvQg3_Z`B9#KVswJYDkGP&Ka^fkcgXEOeX1x+W zFGVe(O;ddEH_h<%2KXg0`%b;COkY2grG>DbIiqC}J$C#aeUypi%f0Y1>QV>uxUT*~ zOVBR(I&=j)w%IT7Fo0v%G486FytnKwld>zx3zA%~IS|1r1g+mic%U_d=-4yGzl;q7 zKah?koqTD!S#(asmlR3Z2{&3vi;B?|41=DEJ9{(~oUGd7&{dI%TyV&oct%<+=hjXl z4zDYc&}{|oVi24XH^b^oHU4+5-m&msxO&SR^Vj@u2Cw35qD}oWynhHt1*e&oT~!1F zbH$$$UNZz%^h8wzg}RW4j8K9jPwm2HL!arBhovvUjT{&21TXI&9FA2#A3==5Z(#7J z(cV35@e5c_5aKu6+0!hjj!ydqP+W_9(#dMU)Ku_@?X##_n~Qa_|2gf!%+hLm>%AJE z$=tGDR^rhf(V3}N2bk`ScigcsG4UH|eB$nTllztY+yRi9wk;{a_T<1{8`miiCCUuC zaZDUC6tg0|=mVb&u8*nr!Xl;^9s&l5v)q?Z;{DiQ5!zVrtJpH}x>`<&)`9PNlqeP1 z(NFj>0LhCy;zV||-VC;uTMSbplb)kKz_Hj5i38fXKO2Le8RytM*eGRhD(4kV1?B5mu$>34OzX1Z=GJ+976Ns zNgnYj^AmI<+lZK}HW9X%y&c>&+NZoXj+pt~R-GLcBitf8d$@5oObS-3Ha|_87Nwk_ zapDQ@-(2wY!u9Xtw@z%_`0y%Q0Y7&{-rL_T!;^L5Q^0)Wd7ihuL~a$cZy;o93N-c= zGhlGBpjgTN`8DtY{eX6@HPjL54A`Pxhc45wcnXfTo%4!caLD;F$)DSwuh&jNm|?K^ zjq8B*M1JY$u74wv8WzL6{(6cenuAM8q@k<2E-Yq_b?{EII<|Y$%Xxdu*?kn4Jza(*;=2E z`ErR~lQWNS6`~tFOL87o5*6cuFnBUaSv$nxG%!j#nnn&BY&I8gUg*^Sqrj~im7DIB zZ`x^V5*o|tn#^UcKhv@*ChME$%aXNnh&T=%rP{d`mGSiY`~)uICMas zIovF?!l_W{3y9GKe7Rfw;E#L-HL^Br!r2F%o4P6@Im}=$&R$2ay34)r?R|`a3$vaH zO6C@u_(fqCS+SdE^)B}o9lEg}p^<48Nr$6mq4hiV@ONK5AzXf6B_T$HwF`159xSJ< z3S*uEf>}?Sdi?!Aot7_G#f_DsRhPvwacEgE8Q?bg5RmxT5mnJILFPg;x*wIjX)<2j zv*jiMz783RWKclfJ*(z_)%8AB{Bt(nalfow$c2Ms6{x-Z9nQht0?SrN^w`K2!IQrv zKjUl3DN)CQ^+qelYoEpwH-8<=_`U#rfU@o$&{HJUb`jEMUrRxgw%*?s7d7V@)8Q80 z7WMe`s6ZougIt2*CQL2hbdTksWk{)(j;#>^(N5sn>00_V41&9QDK0fC$1+8Ex|mVc zE!5=U?(CHaGalN*yW6OfWO=k7_KWhVT9e4BKDusrMq}+g$LP0p{93+FjY*L6Mwr0f zFZVW-$Q6E>1LDDH(%hX1j~9^)6yTpDJMzSJAf!~PU zBm4f<*(53juUO|V1}T1qIpXI2==@QUAGhW$!tS3u*)#xXt<62I;|yC@OkDh_@O8z! ze+ie+XYzQv`7)L=hy+?nQOJo&iKtM7tv^1U)W=xXkzYDs1^asXU=kMXutDuBXDw@t^FUhWvZUM+8Jfko$P|qN_cDpq z4@F*0QD{49C=e)a;0l=D@)9!p1#ukzHnWupzg7(EfUeITs|vK1`@i%A^p76J%aS<> zXuDaT@7IZJ)wTW(Ow^1~eVF_d{^;}`lN;5_smqa3-~nRT*4?4)^drs;j)b=*;=9Q` zRP@0F<)S$90YEg+t%^r@TR^>XR5w3}o>J3|MOl4H{QsnBnN4vUgcBWLkAW%__XX|S zIz(qw?Bv3%dQBlemO{^m4KQnkuA5fRH4vY<&rpSE(b!0TRGk86T%>wqoVdE$QANmN9Zk8zFgdrT zMts3`MCPZIPVOfb^Nft({w1MT>+biD8x&B&#qDvS5y43_z)nxqm+)?Z^WN|bf6rhVfcfM~kRI?dp1?kDY)1Dy*$K%&B?k2Fdio0`zg!P2>2C}AV zrzRiGnB}*mziqnr3@%9`tNzD~@~BHn0cR~{myZF!^KSY7mZ1qO48=SLe*UXOJOyIbqPZq8pJ+9*R& zclsNf;fUpv@4cG05jM0HUT})*>NJk zi2}>okC?9j2L(TKAwe!$u@^OuwyKX#2xu9dOlR>TWCO-6s$_bpB1Ycf^8MncXfd!A zXY*=$b#;1>eq(`fFVf;MD}8GTD(@LwWmKhJNh2j!dtmZ3R)h22{Zc9xP_=?+xC!AR zRl7TXw6Gka-*1VoD4@4kuxjR<=)u_e(ybsw?0R1)6(~gbYzLUV?&?_hT=v@c~>p&ZqGXZcYa54fZJAqzcG6YS#3pk@F>qyy)0jG zjh3M|$%)v!*v%x}?!qz+3YAr;@JPN{Z?n^YATD~3#SBM{y@djG{~PP0@~^5TJl3;L zLn51(uqdxH`;T2Kr*A|P9{bexgBkBtCOyM>_Q}K+hlB^SpL&4HD)7ETniHYY>~sga z-%x%Pi8w{46SKmaVw}tP_gG}*OSffby5~K+n-s8-XDN*DpH+3({EfJbie0yO3oG2L zTlBvRpO40K6mohM*~3-dV^Nx5%~}qkku@2PRcT_F~d|b zi^#h>oCBU`(ghBH0N)InuLc&Ln&&!i#Z_XP`-^j(iuS(e@nZ@k8rk_L`Gk0A?uh-g zZTbRxorr*L`Ms^0wQ0SqC>?tDJdJr1MK+|lHck~*-x)So)K5!?c z;frl!@P`>?m}KgW$HQl}D_O*Jdk`jz?;ts3=B)!viyXJ630iIE1oFB60*3 zI;z-Snvy|D**AYn**~eAlPp@UWjG-ym(i9hBqp*_-r8$@Q)ZzQgPsrzRt6fXd~QbR z=6UL~Mt!hpcwp4~^n5EOrO`e^uRX>4CcvDNll2*0UU5eoPAOm#SGS(+*2Xq5Dv6v% z8d452$NeZm+ap5b{&}4*-BEMJ(AGo-kHu~ykI#L<@OXR8!j+OYEveb8q>r7d1we$) zdj}NuUnR;vSKx|&>|?j4_svi1F-kzc(bT@msfGa-B~O=*W_3bsZ~zpPT3vW>>YcHB z&N9cSFWt%$0%zeVsX5y!5s%1bFDx>DR?GIYWT*GV7>%dv(o%_0rpiS1*WjZXgOL`& zb%P1}-a1;=I!-upt`Rw#4-s8Kj@nM9te16^`reBzNmJxb^5cwp`Mu<5YBtrCRF3k# z++$-L*+`9Cll-E!_$fm2_ideY5yrX79orMhkeWIx9pMDbZh0B*i7zkaji-0?zf;^N z{hHXA|Ev+lz8Ja?O6DQR3r9$NxG9e#B$gc5qnF{W0DxVV!7f0(Bk`)w*@g;8uyu1E(MapAP|n_kotk^rn!O5_q*& zLzCk#uBR1Y!IevH;Z?P*7s}QoD9uM3C&-2`;raqHQyri92}qxrWX7;^+#wL9W7rlb zx5pt$2TR@A+6n-=3M&;qtaOk&tZlGzZ8&TpX7n9Y00(TwH@VK^C}E4=6{9!#B`ue_Kfe4CX7TUf#v7V5E~`(Ij`rER^1>5DHE!bgX7it z?T%x$_>;Pfy%2mt8ZK-&i^%$M?-kcluvkRXxa`+S zsotdtlA>l;JhN@YGIpr1_@gY;<`sIjREB@G09PR=QEOs}^l;vDQENXG-(maaMz}j1 zE4-0=Xpbch&R7ovzUgogRYL9^8y-$KcSd(Q{#sGZ+qz(Y*!a;NrVkta0>T-c>4GZs z_ZepALwvsmw`KF$D#gNIThY1|Sqf{N`Y9Xq5&N{fG>MMxu{@}&kyDt#l*hFQ;UD#_ zrd$z`-;(^;<{7r_PH<+q&u72<8dXwb_L5z!ME$zFWmaY;ae>Lb&dN1devu7s{0rEe zW$S=F`H8~MgVDVpDXR8Z2;Z#lO!I{%m7PO=s4xzbflcS8RoB$=Yd_P7q07<-Gh=*i z_6;MaBunoeBf`jMSU3?<&7^{|J9P4dFrSJ9x%?4GnY+G*`W}mS6UlWq_A)98T_w87 zTM&9Y1@BZEaM%xHNfH!@H6X4akS(Jqb#IZ?YpW{qzR0@5hqWvu6Pk4J&$m?~3mk$XpS zfGZ-A-o8n<%=vsD4vh~QOirydfeV^AEPA&=IQBa-4f)x9b%NO z=kjC)u}36(>It*wf-My!i9GmoBSc;lsp71tpqZYO6uNSOOMU0RK^(RJ=(gLm3orRR zwfFT>@0@P;wunT+Takij>+9<`s|29r@vUfNeHilk)DW;cMoU#2gltpiU)NZ1u($8A zs1oZ4`P-=yw}~xBpKp_N*gde>MzjolyHP*(#<{O6@)Qt8^+r+TYUclfULi| zTk^YSP~gP#UoHP_>tmSz&EH@TKdR+CuZ~K7Ii%lxKX>r`w$LwsL z>tI_(>V-;DPMu~oVXG4|@91TqY+5*D7Q5j)lu6F>H`fN$5inb<%-0gcGFaJyYG%$- zxEZL)e^O#q8coY3aHynkAzr!K*ju2(==7Q03awTntoUfm*Ddp)7b{fMCg(i`Iq$t=8E%uOEFNAS!Sg5&5CLUCW9nt7PF z{lgaUcN|3*QBgJ+zHdK`xEI$SIJ`>l`6cOQ)*0*U^OmY)&+G={k757!xJLjFRdw|M zbFI{)YI{+YnK#EjBA37g_UhCjBy+naCBuR56C$f2XfYm`DXQ_Cvgu?>IIult=K=-{ zfs*dZfxyiaSsjB=-gn$PhAf~Lisgkw3(rXMH4=B>S}u%I=a~X}XCmOqqgRa28ygf1 zvwm8938+S0W<7*UNIQr#33f_mHEJJmDgv+WG*2Hc6Y~6 z^t%%(9Vy{oVSn%V6o!93S|~T?I6);YI9P!W$K(*vDl$a<4QVd$CZ%D>85MH;;Q5s&*AlVO6aOhkjMR%N!!=j zK`z>A!M@2OpJ03*pEHS+Qeq}0fPj7zpNjAnfBMQo3jcXNniBCSU}dt>_;OGM^%6qB zBugyycdyI+fd^z7nO!6J-q4ZHjrvC0ss5&4@g}>J&XSa!kIa3l@hvo3;vYMIO9IYC zoEIqI3q*bvr)EZ6GnjX_=|LHt*&`b5Rq?m(kZzyVa65Y@mqG!%zTrTshau3&&o+vm zeMh5DA%l3v$_+HhY4h7aUiq_vs7+kw)giwI6$}{UWUXOd!4-ssfNHZPeZ9jql#KUf z1PzzHXgHY_&aaCQlHGRnuQ{(wUv&5Qu|GT02&;Z!W%How`ne!ov%pTHhp0+vP4s?n zT#rXHdhLSp7!8v%d*9eni&DbpfHso&Tb2~Zi;7#SIHr*V%~92OW0m`3Pwp?w|s=yf{u z{c`izi6@xH%x||za3l)Pe&1B8Zdp0j=XsEe$txU(0~X-8(prbYjR!$(yYjviYa*R@ z2(^8$M~5yPIPBB3B{Z#;+E;2nzsY|~G8f8mudle$m&RwZLLU4`BO%CktqDHKKKV+ig<4)?{)ofPRE4pd&xz>FS^Shg zIoUmk8(0L{W%qmZk$|52U%mv;!E2%ehA}_Yx|7i0#0&wu8~q+=BC9KA zAxp1YP-9H9@Wwx6Xf(lqH~?P~i-kED%HwmtTBJW?w0PTQsNsM~iaZV@k}qRez;@Id zdw(zAJAj%ioTFsjfkdA?0q#(t3 ze};fBuR&YnM~rnktjsJ!TjpuPmc^OoXWv6aKTmYCdlg|hBv4L8&8XqFlI#7@ZW`=< z2L&5J2^kG>Cq2I4EkugHs4eZT;eL5CBuWBXmonpsKeUAnzsgr}w7vhUE{561cVL-Y z<8q=>(5rlA=vnPQ@e|SsBC8TV7Smkw6mU!w3*DGggY}zv$KX-xN=yZCIN@#hYS8E zhDtnc5IL}3La!XZg4;9kC02HregJ!1%=2`r5z_NYR_FwI6u$pK5k7@WI z{fjH(@1nX|(4GTq8z&0@lDj&mT~a%7LNo{w?jN2Dvv5uOoKmNlWq0!SbJmC7niDL} z^99ys&=i?!yoH?a9XTB2+i9g|58iioz#|ma&;E8Wh0zESs>lkZOIiv%NH~!W;JG|! z#PFMyOoJ-3(?B;MtOY$T)J|CPz*vTPKk%$*n$Grx(Gl<$&m{rm#L1FQA`16gTWK*a zW4CJge7PpuBOS|b1AvP=EUbFo|9msxJ$c zdE{uR`2jEL)tEhOKBf>GmEIsss1;a-!FIQ+uICRX*2EkZIGbSO#rSw9%cjqv7Mrk zS5a1UW@DW76QuY@4;5<57ZLDFuKxG{d`r$20+qG23oShh6~;n4_{k4t*Xy|rU(y|4 zX6Xig1td2X<{QKYwjHNT1)l3_X6865UhioYIN|~5u-P0jaccY+s8yg~UpwK)u4ti@ zEbT&2j9ibj4(2OGMBqU;O5kf?Sv zR=|FTJz6b~bj_!btlcc4syYut}~FOS^Y0 zEy2O~KG>oh=UBaWI^|}%GkuUHDcRG3=B1ST1i}XAqGG*O8c6Og{5%?`}FTQ z;_Gcl5tYH*(N@J8)@sa9@n$b~-8FUu3}Jl~0ljpL-00)v({^l*mgbh@G~pn~O$q%zz*Qye+KC;wlPcy~H<~eGedO_w;ebvt(;W&k%xcIci=X+Oc!Fy5&Tx z6N>M)#sRV39WYmts9Dl|P044_nAOz%HI3c9sYu3A$gm?N!9X|U_k6zg8Wvw=#yL8k zVccEg9T-DZHDukQ`sKsJh4j#yM*65XT_39_)(V0ig16jXL}%s#48J&BW9y4Zo{S{E zdpdQhTFji*^WEdogFE%cjt#6~t?gsKZsbTny{QHc#HCgU+cn=RMI zlWj@PBOUkj@4zdcTG%2Vym<0S7t`XHM^vnGb{z%e*@FI<&4XP$=1worZS?(@vpfiG z35XXdnd*+QQ*<>1vlcA9WT%B4UwMtUU02ac@>+a|{yg}w55eGA*7SM-H5;8-eprZ5 z{=wt0!=Skm2_=+{uGT846$P0)w=TYRmJ$@xW$7`s4G~oqofI)V=&5=(I<}Piy2MV0 zXSnU#b9F>nsQ8ia+JT*V6zfU*6Im}xMS>8~$Hy!xpHer^AF6naRTg=C;^?r>2a2KU zBm`-f^)&L2gB9hc8x9-rc)$}H*MnJmtcK9;NiJWygavZUs)(N=@6+YmlFD+o{a8DP z(km#T{@5)rTsXO9C~W@moGw04m-^u{yGx^}X$!oAUG~U5fE>C@uLdSV?09d(?zXi} zZsfR%zpl~2M8xr>=qigsyjXs6n)fBp)NNJW-8az<{B6Dc5&XpTN_c(#2Ix3E&S3J6 zV_H#)1wtP$2dC!>B1xqvGwqpBx)nH`@|6Ne`b;oe!Q5a(f?e-?smcv7-SD_nh%S-E0tu~ zqlKtT+s5in5k%j`eI+XY+7Y$a&e81l;%m!;9;J(iSaV;Ah-cWEK#ZuT<2QZJl+Ls1 zJ9UwpPx9mYIdW|21gyWX89Pq4`AT zYX*k!;_7NQi0sRXcN<5W^_hj4Adn#tc2BF!K>r8g!Kb@3rTV%*5aRF?b#dg)vDf)| z_qHMI5?SJxBX#tT}Wypa)p7s2^PNwhKoY(33B{=IJ_3Gt_ zM@uL2f)4q0%?D}Ni5&E>ZmmDR?xh0_Wg$)qybg3VzbX0VmKay29h{SlubU4LsQayH zVbnj{-J4B4Vi}lUU&9VO%ZEqPA*A{h) zl0c9^un^qc-92b<2!Y@P2?Tey;O@aKcnB680yOUK?yikn({MLAC#UXr-~ILKy)L?_ z>fO7S?zQF`bIdW1kGj*2J1a(gRF-8Y?7oZc`ZE*8gRv(0Y-5afv3Y4mY+JbAIZwWI z6`nXAisbF~=v#&{?RdWNT2tM*y{EC)5_N4!lk|5_bRn^n2m$5o0PU$r;O+t#H1pfm zoQG(KsB`(qn2-8em^PPB>gF@I6;VK~hnF9NG= zmb12lwWF4$u+bCp*B(oGiw1;F*oOzDXtoqr!aWB_?)FxWoOLlGjxnDcfOPg4K`fMe z!l`-pvZm8p1V+YJIrHv?MpT#wEWOY|A0wP8X z=yx)RU?~DAvyjOO+6rH(oE`B2=Z*dB9yJLGb;>7jEU`6}%VOJ7m2uc6zqByR+g;Cz zzU5{;-0jkoJ>^GnaaxsbHfu|d(bN1&1$$pNI@CgdJoGzLD?SjL$H>A=_b|4Hc9O?) z7PW=Qh={@B7PVsaq2eV^p`Q=xi5>F!Q7eeHcGeQ}|6hd14t zvn})Z&jU)mbHEUpCP$hIeGop4yP%Tm`9(K8NQmsWK5D!zHDYN?d?j6`fS4g;XWNl_ zJ$B)SE(e1h7@5f@!1tn+*?NxL2kCrw@xj^Bm1(LOY!1;YO&itYu=4nQda+#kTHo;Gqb`a~s2Xh>#Tl*^ zNe)!P)jXbQu=y!4!)HXDZ3QEzM>Xd~vY94|e$D9m- zPzMUEo>wIYI<5<^jeXY3&vadq@K!>jcRi?O4cScbCgozS(5o^! z_$-BK@r-R`Y+g&9STh=Vv&lRNiA+7JeOVR2qN!#O`$4DJ0E&O`oXG$WBB&jZPNwCb zLYaRrAGOw%ixy1>b?i~u3d-$lrggm$T6G<=FWH`EX2$_Si6URmVdk@P+YwnFP&bxC zANWb*XI-fI=0*o%^+(O~HD=4$wKM9HlSK;U%Q-VS}CI6Vh9T$sUxLckG zk*4=3StrZ4UX0S~qTiN_U!&E`JgM@n>FeJr-H-R!`@*xb7c z#Jx2OD%%dV8sLkn4r+jgqf~&CWGpXL1XH(G;lE<;c?pxlQWG}*-u19DpG!JxSejkn znC0R7B`?$N8d89|Ud99vDar1MSw{2@lgwE5S=^G7wJNrb)>axvC?8g!Ob>+4}-SZv6N9-+BZqYK`f{-0O6q30m z`w~oTQUpdr_JZv|UVAOiLrb}*j}LV#jTq1*zEn5xp7miKt*X>x6n;(!-_3WcZAl>i zQa5&`Zs04xIMLV)Ngq^1uZAIlqM}`e(AJgU0u0Gj@nB zbPj1IZ6BQ=?ljAh@R`%Jx{aQlncDNbB?O09%ZL-rR0C~P%QG825!a?NO>zz4e_Q}` zE+@F`i;kcjy<=MX#)O=MBlaWHdCj+bE--}UQYV=q!6G|`tb(L+B;kibc;JJ55ce$0+z*ECoN3VFpRRGcl;cLy)l0D^T zX!Ta1ZK^8IT`XqHHN!0|5Ketlcu@Nb{gVkX;Clu(m86mCXACtzw?FvLV{gzDCMPFHoqtN~eIVfC;+iaZIVu2utMAS#L_nrW z)tLGiXljVU(5y{fGZAF<@wcqK^Ex!6hz^W{uNn&(Z|_2%3E*<@j^g8aJ)fGp$k)9&`W@3mwv-WVSi7r_^tNo9Q&lgRaL=A(H z!E0?ET!+EK8I(;R(Q9=YE1NA-YQF)h%HRdWCbf1CQkm^_^gW}ugF6Bz&1W#k*-_Ck ze5(|W-K{RXGFQN*4YCrPTvu%hW0Oth0TdE6bXOp}83YFbZJ7p>^TSNOhooE|G= zvETA6*dD)AUM9@7u}xk(r$H(oz_7Z+#7kb5Nm-v;a@AKfundnS#3fG)TVtR>vfBI6 zG-4KJ>bx=M8E_wjNHc=Qkv?E+ADywd=2qsWEI%=JNao(B*b|B(o)r9!=(648ncz`q zL;PkwN=i7lpn_UivAwT^$JZMLv@un@AowcEYY*B?#L-HI8n~Jnk_*DG6@B3z*`I^n z{N(}&if^yyAUs9i&no}bYQ{H`wBNy$K)d)fpGAF#Xi>QU#FIPEOB&k{`tV11MYVXI z*&I{bx5z1_K$NV{lZ~`Zj2!2)q7?YA>8m7m2 z^iFUTCWKV{<3V*H1u*9t&3hizF9i^!ECilWh@R;nJ%+0$B`{?u#FZhB&Ipbj(6IRh zOCc7pJ94d9SVAnKdV;bHq}jBB$HL+MEwjXkjL}ovOr390 zE-$Nih(=;~W4kI^EZ(0%g%7T*QMuo|YZ59Ylr4=vA;`w-^XfS2GTQ7Lse7(i>VMVz zkis$e*TGPj@QiI^1t&%NjHo`2)O%U%W;bsWlIPtNYnBjxM62x7qD^iku~k(U#}JG@)FQDB91 zT&VCGE`;Ci_)Qh!BB*e-m{%o|Ns-XMae`1d9F*DCx^UdX9g}Bc-~7#xqzIXN-ld-A zZXgb%+&!_Mzy2c`sK(39^LWD_H5;=Ud+`2v;d7rHEo(1d_M^N)HK=b^TjzQ0>5>d; zj`}Ht#bVsYb#qc$eh-@1`+l$KJslVzZ5`=1=hrZgJB^3?M&zSOx;4($fOvSF@~PPH zGZ;XF16#H(Oe+L9T7zo-Qbw>73~H1ZU+%S@HYHs#q0TS9ZBIL+tQ%snYtlF@zd{$< zAp6bZd)=YD)kQD;GU8LmvT`$tg+Gx)MeFW!L)&}auF+aEB;6`2Zvt(r*rd0sC{m6PZc#D`jT?zNYUqa+c~Gi}Xyp=Q@1JfmyKe2BNpz zpItkZ`T%=Y5dU9BN$G@#l)2sGowT z=dFY4hsZ;aC=LruXEw&8K_d>(k#Ix?-JNv+;*2p1sh zgVp&Z@X#2pjBylY3VeO@xPWJv_A^U5-l@Vof&lF?>4Fz`B|MIAN)HN>Eq$@T2w^if zXfw5`Faas;+4$~!YC@?gkVFLnwl`1zXplbDJ5R7V7<2K;1>>j2#6qjOP44|^hUPSy zw&uOB)oz}t4@oAhfx9*&nGNh7Nkjm}vW8K^R$$U&QLg1r*=f4$QYFj|d2z5GXl3ou z4R0z%8{uEGuJ7|%sx10b?R?^4cSr@_yEH!0eRF98_Zv8F%BGHTvQeOx4&71j!OV2Q2?Eyk45-cSEy6TjaE6=65(JT{HaE*CHMno$#0+Vkm?r81@mB=C;o0V)@6(RU}qu)#}2!E(m`lD1MkHcXrqrlTV=ZtY(esJ}mx_ zU@YtuXGDUJ{S(ban2i~rK{hcXz+094j!xlvfsb&(zaA&`#)ny=zCqN}hvzm$fYgCj zb{rAYyLbLR$UvExL5(iNaCK>|$D2-O)0X8$U6yEv|AjS8{gNbzN2-J;dZ(+k`flIk z-a}ktSSmD~X?U?ohxAf0wVgasx5652gMlhELbY=Tzr{I(&^RlkYF-Us(fDEM%awd|sg)MmW7xs5>Y3Z`%ZpJeENe)k+_RSuJ{bwoWmVBe1S6S4JY=NbfuY z6>-E%@ixS8!DZI(TSiptRY*l*z8g8jNa!Y)c?}2eF3Rpo__e;nDrXT}_l#L3!^pvLJI^_y)Vye)PMn{cRIL0;ESqVTeY1J|~~CXrQITl6@T zCM{bK-)oy#TRq{$F_90>EWTOS?5_Eur|y}H4ZK9cXt54zJE1It<|0cy3$%weja4nh zFT!}vP%?$ZzH^CrJK$6dRpr;wWF$?auJ2F}4(cvQ&d zEYF9Wz9nFSVCIPo$G4^&u+5pIa>iqu<6!z-VAlyP)9wB&DO$nYYEa-^nh;T5t z#KhYq4{Ic|Rip8w`lbHLHi?760u390P;d3bERf=4Oo}%l|Iuj&b9fmz z&zqzsSBb9IaO*@#=^QO>@^ts6gWDm$oILiS=}j?ISDwC|#3Yd;^LAFzab>S!a0k&X zyl>h?r*Rs0=k3!vQE?)V(L?w0)qr*0nU`(9>86h9(;FCzud6_27R!%%q&W9w_B-7riGl$vq*~uxYQzPR9(ZDIlLh&Y=Fp zc|9MpM<64wjQb-%eo)>5y7sWJV6d1jNpWZ#NMdmS@J+sjTTkJ^?S@Cz;Vt{k^C^qS zLQ}@AJ(Yl|-Q50GE(- zm4&(aY_-`$Is~rX{gPha>vF2Z%G|=j?l1It-{W)NQ(^@=&j6n+I=uPFkhkYEeYR8x ze)PUN)C8PC5Y;tLVG@8*dLAZ;Ju;NWbGrogme$wT@48O#EH5c9FJDhC)vSUK?r1}1 zX%aOu+F+NUKEnl&ovzqc0p8BGR|7x5ffRN^ z?Yrtxj}I%40#B|8{;e98mixFB=&{TFu}h25P%2l`Njvh>`}}t(9XW$S=JE$(a3%ta z2t}1E$p3_zMyT+tx&>6Z|04-uoigmLyWS)Xused5{=trl)`86t1r05JWXDtiG&4DQ z^5i@N)LjIDauZwbKX1Qg0_4XY-N274&126N8MGS>1NLkkJFQC)?uq-=YkG+TO1shyZ^#Z6zFQEw|eQ58E~m zK|&r^KfcMn0QTli!-_Dl*>+=Zon~nJ6h_!BmM$bd`TFxI!z1X1n~<`iJhJv<)T%5| zCv-O2F81O9oz4_ZbI2RWwng(V$@m-yLdJjY3&R3*O0)6(65axg&;14opWS*u+{wfT zSrEe>^H~7yfNdVvJNrdn8>P6(mkhC$alC*~Js~ot2aVF>hVU?~Zf6h01t# zd>|4uYhdaX@UZhoU6(&duN&q+M-#yNpZLQU5?;65Idtk-(98Jb=ajXh86W+yqt`#&tge9EQ+-&3prcUe(`qb!T|o$i z4orN`^xkI)|IP9*TStv4uu68m5H2vfiLvf9)7&C=H*0`(vu)6K z{l&-M8^Pp4$&l6kUPApZ?g;RXc=Zm9ctt!Pch1mLCUgV1vECipuFYj-S1-OD{?rBn zP?=n!a{z%Aez&Rl+NzMaMJ2A^@<7lvHGMWBcz4sBCsPd|7Bg#UM3-v{Z-lca0$70P zkv#$+6!r8{qVBNlsaR$^QbQO9Ll8NgR!_my^ZfEk2OHlEI5wb~m|**0GKM%O4;-(B zB!Ms+gvk7m60HAHA4C(KZ!5MRW84iJCkbEyLm2zwPiB^VCi%U$Oo@ z@)5s-{dPj-31C-G0sKq9rin<;hF7cEc|W_mB>y@Zk`JR(9H2*An)!Yq&TbqwUuX61{H zA;@wy5bVL&kqAvN47$n0#?Pvd_k8dpI-Zv5cW8WfmjBzlkpB+YZJP_K7?BEm$$6N4}F4P@)_Z`vmpFcV5`(zF# z_p(b~(+SGV;I0gAa=jWZ#P&*wts?q=0-U5mrT*gp@>%E1)AOGrdRMrM_`OIa2X_PB>oHI$v_@?KW~ z{maXkWJjXH=of6S0#2)?@Cc0_vQGE9!6hVXLV_V)AJO*0J5VwNWL&*`k4qKjmw(!d zf7c=RsE=&brfNcnGiFAO6~^xL1i`K_L|+>Y05Ktd-GaSF1t*F$720p_Sguw}8zDb4 zMjePPx1^r8$YYwlQljh!<(E;(py0Yjdr<4qj(L#wD?9kzdptm7Zs7&k>R=a%4Z)kI zkCr(F_cTbqN9IDe;~dKx7jA}ef1{vf<_c}r_SjB8-@se%2|8(t-Ps(tmYxEYA%OY6 zTu93t4k_*z`ke}%*6C6r+?}o*wEIq&Dcc6TOFwGA9+#NhLaFeQiTKE2ylm@G*WPU8 zPhg|UW2J!cCBw@Vr3%kz(eD|q6ZT-SDKnC`FbRzVt@w7~FdgJq^s6;@0h!~P(2bS_ z@9$X);O$)>vwfQ4d%K9ywdYpg&wLF>#~#jy2TM0vMAck@bI`=JXuUKpF0Cc8ZX-dZ z${CK9(=ua51xFwJo-wjJy=IcS<~CmsifZ1*JrH_9q1(Rjj#m_k^3@RB+6TaM-MAoN zE12bHftmw03Gp5YR{7rv?&X<_a zpn{bn2#*q?+S4SwF|oC>sIci5pNZ@hK;3oZx-7R)K$@xh)-Ww7L`cLemq2Fyqx;Qn z-E~jIC4x*DF|b?*Z`NGRm3v{t@_qT6@@K=uE2hjSBR&r7g6EpH6f?qcAHxwvq76X* zrcvm#mDUC?4!atQx)_de>}ALIK2W*x(WvpNhm&HVo5OKgzjZ`2a?NEqNJ_v4p9rU0FJ`V&XqLl zD9k4u4ZluVM?9Js@axu=NNBDM1JmGN2{#=`_3CE`U%Nf*+`OHu?Fr#hdc4;>R@f+mxw)!j;ypd6&5u+* z5+}%^!n-ZY68aV)8}=cE2YpCS>`2jmhl4|oZm7pKs56u?3aSfq-?e6)i^H!X(eb(Z_;un?HP;b(%*hiM%FJRdU^EO9?YB$=|PRElkSueBMoE8G=j zn4MthJ_hxt*s3zIy6JG=B580qf`KTdbZ)Iz!tElbOW?*~ z@dcAz0mAI-@#+%CQrJhOcGrU)-efI-sK|uZUD#D^yR%0gS3th9zMRI{{&dZ84+~Z2c)3W;9!<0NPE4O#kIt%viJh~me%Uw!!c88F7^^Pu{sMnAaa`K^xlZZFNFMH^ zP|L(Di&Lq3&|U7lX8B{ZY1(g2$Heh);lzr8d_ack%O4|Gf>?U%`JSrX`<+S@FZDc5 z=d=ZwEzJD+ReR|=TEcSby#)>xc6iuaY8UDto)&;zegwC-f)@LjBhlb#s?(pp zKFLnyr1yK6CiEzLy-K>Gq1iRf>xR2-&1;#TY0fMkdW1q4hHh0mrU`Ca*za1{ry1RE zZR+*mOR`S<6q)dt)eMQY+8=)1{K)-kt3IGeC_qy?ez+55sSD$9b&=d)CA69?=eiqX z>XS$*v0=@7HdQM-_@Yip{F808ZdR@C0?gN{MWt`e6F%U7`>u_ZEAWMIk3D)~=^}Ja zj>QB{z@%W$Xylux#lx6YN>9DGDMOO1b3T2a5xaZ7mGfKt9hVwp z@u3({e#Zw6@!M!1PK-T|qm@wB>06ahC5aQJcU`!KPn@IFXIh>_iH|nEw}I?%7ck>l zdCKKozxKpmBr2;g2w^#;eBa%mQE*qLn%EJ0^!9by`tXIYcq3~V#kVaadz4Mhtd(;H zS$Pl3EF#(bC5zz?w(NmC+|&)~0CYoU%4aP9=IRa~8d6-0)Vs?(8@ns z*Be9_z+Y-oaikt37^-67Wp-!_-pEJ&rYo%Fz20?JjRAF~wp|T*HS;ZuOg1uJwC?p| zDdp)hu2-|ly?}PF_0_mHe~8igk1JV@AsY8D!ii*K1QgD6QrFK2gb!~NC3yu)1$$wC zjt+zGuqPQShNb!Pf|rRk@4WZh-Ruz|-YlgyaI7B>dXDo*B_WCe6~TmKumir8LrRD8 z4r{k$^cT3{gK%#=?tgr}onm&s8nR{lh~E=;g`63fTBDA&eh^V8g?s%uxD~c9Esf~TG1~;Yxr!NSKA!(!?)d1FV*XYVW4I~pWKBYT~chHN@U}S z2j8>Kw_(wtT+8)FnBs>i*eB)-3BOzy5)RlgOmD3%$}s&Rh|yBL8zI#j^?eeHmVrZ> zgG59sLX9<#KAC$^kGESRKUmw0oo|~<3T8TmbzIy$#?Qsj*t$UZRbsx~btt;wTnzrn zzlqf=k~iT)u8Ut-SephXNkgyWmUbz;2O^A2K`OQT)$U70=LYRN=ki+`X4#kD37~*h zh4uy*pcaoVuoWmaAn_jtd-B?|x!>&=kaVYH7KvZmrO%c=NB+j1y6WF>B|aa zmC6^`GJ3mYnpQpP91jxts6u!_XP~#Ajb)E+-K?U?KVu@rO`+BVr#2tgSe}4{=}Yr@X5QI{o?X|B0pC+=s?RoauSO^ zvkUIP@@pkQU&XrJ9%^Pe0Dj^G&@DO_T(NJ`U9%zM8swpOIZpO(1GQD|dvbp?Y^lJ4 zDAnL2@^I_p0$;_C4DAP#-GfcPd$&7~NS`#P<&=?yILRvPS<-jK)kRc-iQ)T z;qROj&@Bw*^=)2gT%6Z2$TkxIVQx1PB*#Xo!W(HA?K{-q0Tc@{6;UF+-ii%=LWm$P z0qhM6?-!f&$_xUGdz!deRHskPX$GTH21PQjBZ1h-&*SU+(r?L=CS@qT?UW12&KA=X z$x^q8!ZXHG&#K9Q_Gr%7lCeooMOf(HR2$gOL*!zHMp(X2>TLDOl25q*=U)st+ZqQrrur54{$^H9z^p1Cy3|s^K3H<+Q79#G^wyzO53ka5JVtu9Ndr;Et@eXHz3L3J5j2UXkpT~+TIAEE%RdbtV7+X#b2wU zJUs_`^#kK2HKzFWKytDVRwqObXLyJ79ArDwow;)(F5&~^mCn3v{8^1@wH^dy2u*YonJgPm#9V6tN5I_{R2`@_9*^| zfWp^m$rYN80n4w(tS$}9CXMEKo&4t95U&xQ@y}!Ordpv8p^R1z_{pd=%rCs%eHUWv zCD7vSBz7D75;@b$xgBAt{_?G7qzM+6WMy6aYEiK=2UYv6dGz}$Gil^Zd;yTIhsuKB ztisE=Nf;q;;GTR+g_WQ21KItS>5q>0895N+fC6!D$1n_sNL1EUzBk$BW079cFCWR! zqK2e;_42_w$*o0LQHnT2l9oAn8-@KcC)GH?6TV)f(LPzQay5SZ$)tDcUq9&+t-+7n zv{N_H_;=z9&Fagpt?YEFzY?E;?A|nFo#+cW5>+pw<#h^MdkcwqBhpk5PRD@$E5l1Y9FBX&Y?;_KitanW6JRfS`7CoR9Y&D}d55Y<|UB4ha zAFX~91P^A(Y7iD}5|MF7N*toiMC~ckpQsrTy{|`JnC3t9crKwP(6&t6E@E$}og3G% z0I%lk*UToiFfM`0`@?HKq;I`-hA#jr5wR6E0mNfeJLwWai)#&PkP-)pnm}>0n8|rkYu--+sAF5vB@QN?uG(0{)#i z#*?*vTbIP^8N}5|&v{F0k{O+~mSqivu_%`JQq)HlF3b@sHk{cDg=QHKiWVx8K4nEE zR;hTpm0=Dkd3^gmE_)(|_Ao@(UOrp2VBRw~En`xZmAQ;4Tu79g%B1$idIguXRk?c{V*UK|!(FRar3h zB}R4c9&%1ZB(9&(av}Xfze<)PEJ%ej_m>z)|I1H-@SM51UpRjmI$k`q;BB!*npoZ< z%pU(vsME-9;LvX*>x?@y{WNpD^xjVj@igRpD9E@|0YMzh-%m71PI?4vt%hdtz$^(d z`&nF^q&Bo+%-)wF5Z8+pX!f;-OaJ_4ccx@KLWtP(u)?r_@pnP1&rTb?)PQ^1d|eCl zh~3)jp)c?g@GEjs%#!3qhVH|hkjm)iW@t|zrBkj3qPszX)FWOE;>kRH#+AT2BWYZ- zJ>0x`w~<;7G~&aFQ$vTAW2Wmm(lijF0)V((qobpP$PrOzD}et=P7h4-aGTXo6~U~| zOnu-x7K;&saUvG-nL+%Tfq1=9pdbORPY)5J!KB-vTc=>Q|Lr_rG<2R(A-Mt-7??L7 zBFbDvE#`6=H3z}x>BJ`FrhqjG_Zu;zaAN&xlk`GWGSL^=;9mMSYZG?9 zlWK#JXL6npU|TWj$9=^C_OX&hg?f?fTYO1};5Tu$z$av#vfpBk;o^RPCdyRI{s8 z8pop8NPoI(Aoi)d#2ERshKQ!W9G|?hFPVJTt_xHa{m(NT9{rAg12b)wO<+?7!;Dr9M@60tFS7otIbRn6;C=?zzUR56>B>_CUKjE#A%l`*$<{ zG)?eB>gjuqgw}q0g#RjrSn>6bnY*5?!N%X8`i4Ox()0GeLe|Gf`Oty3A@8$w%ME?u z{P3;_?{9yJ35xx>)3B`s&!;yj^1o&fOUAv%0J;lY9YM96V2?olUk|EC{TXgH8+G*=3Jo{q=7N?g{B3T3IkXyZ4 z?de?o!k#Z>Mjlnsy}@&pK@31CgMt6F6a8qH)+cxDyOCwP+EaA}>u0?w=C`dU?GY+J zy$?9l;=~_{Kr6kZ?XwTolB$48RkJuUk9dE-T3gs7kE?mjOF-dW0bBk;l*)NjaiWNG z8WxOx5cyi@O{36Ek}77>F@q8ah6C@7U0Ah%-!M8m^7l%AJdZJ@S zsR#WIUN?izalzvkO(kguTG-2m;pbY23)9RxP&+Li=0%gqWke!>=jS-EoCMTOw#8{D zDP-w|8*t7`R%jfF@ICD>IKUUlweuD9)YM)%Xhl{}Q=a*$+c(v;wY87Yw}*hl%>4kh z5k$q#6XgE>m3M$230s8%?D#Gwd3RC)4KrHCfQ46 zM=5!N?Q}yNISpr4h1z+srAa#xp0c>XsWEe1I2?*?`Cw=k|F0wg6rk6`{r(IFR_XIm z*m+5lVZ=xZsHl5&eJF{$}~I=bh4+X|E@-C{`6pV z`o*?|1OLNvUQCnqUFXYcHrS81JYMXGoZIl&oQbgL7o3k%xr;m`TV#3nXSLkq$YZ=D z3+T0AmHIN`Y@RiqtD9@uJQet8Y40`-mnCWW=zigm6C;NKO-VZftfNxwTsHxal@L1{ z_hB8LV=jD72CD$;9}?HQJ^OtN;(64iY;r4jBxR)sY-M9PK0l+5$^$|a=;li^opQNq z&7F*%Y#ZOQC3}#5(Eaw|?+_j_XerpU zGJwjy!mo-3tqFT>SMcB01Y>TTQuCURjbAti$=e{hK;17aswbhGb}dB9S+l6!70$fz z$%H$6JX(?P8z9{M9_b=&zWgg6uaHSwtU7N`;;*J1MoyDe8Jwk>(O{kl{NPRxZ=LB1 z*Xp~=NkDYvGV#4va|ri<;|8}`1(cBudP5L3W;p%cgOvLrRdxqiD*|HFRbwU0(_uL? z%qrb3OX0zyXckJKB390+Vu~-Ik2|zrSLYO$KCg1@ooHGa6N<6Sb4s|ey&GsIWZRSy z=UCfNkrKH(6LBeiJ(80L@Soz)#lDIDS?o+Mfhl&KP{l-x&2;or?S=lpQbPw#o%Lz? zO!>LU!=?V-!-@DXwER)>@$pvVe(UNe7&jkSyJdv;+N%bX#t*6Ng@;@7nV$=McZepM zNsC^e%%fmUC*8Cpw{1oR7tz8(*~lUCD1>%v?nX@t^yw19c!sn~{x1H0&`mJzon^=c z!ZPG?(}9jZ?Z7tuovO<(|Jj7%&XsEeB9w{AUrEPB4GTJ{!yk3vthG)u4|56^qOCjw zoX;YuEg^O}Jxh;e5SdYzUQtSJt0K1!I zFO;NuBRRQx8IMeevvX?0`I|!NJ-<+GMq{+&WO&i|Tgc_9kBbMZeB@;&V}(EWA#nSV z8BHQ^yByI?rVNJna1aFgJan_6I;Bl!w?2N*jwL&q#!IwwUMu8-tC@%)4Y(CbzTg~Z zjz%=&(*u65N&?$dweYoaOrgq2Ozz^YLVL;ahx0wSt06UH!mHEw$`40d9C=JIt2uSQ z6*wlFT#R}%4~yF11lJWHf>zrf*S?jwQ_ITvzk2-qnyJtbMF;OYB$;U0$-p8irhjO8 zQVj9*N8BHy_+?xi$3V{{#tFymK`$a~3zX^U4YR_9f7=N5PKxB>vMedm{Ei5$PxATR z-#T5{6i*ObRNYMmwGTBS6((zL_ZFwP+|K%?MXx*s#%gIRvNVpV_=nO;l7kR_coh40 zM#E~*i;nFn+q+|l7ER_Br|MWUU2f|&L7mBymfPIwURlV)3IF=;GaUqe#}TFaI9HL7UpTsBVO{VO{VuwkQ`r;9%7MN|0e2%=+>S z8VI9P-kBpPE5i_e+=SbRbi`56;e1GUx8dzApCH>l5*(w!gzOV;o`=FFX zLgwMkB0WN2*34_*F-HpoVou_Cgk=0$Imj(|Wl|F9EFbACh+s*{pGKoQ81hK&S0^C# zYwf|fZrk+tS`gmj9`1ux)F~(~`}}J#vuex@i%@d62#e~FL5cRO`r5nG45zUg?SA~1 zWD>&c&-H+fPVc?Fi5Z@{8v7h0&$!vc(e{u>w7xC~f*0Nd-ewaI{e$UtskLEkWG=bT> z4KGm81_#SA?TMFkK;dcr^*5|91Zk#`e$Z9lfz7@wezx;jYXYhk8lXoG`$ID*=uLzh z=8mj?(kcc|B0|aMGRqU}x)F!D^6}iZi**A*0vhSueM?s*_!G+%P*o7TfRlOL<`BZ1 zwXkN6jSFk#g!BQ2TU0zwGq1gn1jJNBvd_w-)r~x0!~JWbKBYlD+GBLbiM>EuP_S~f z@I)jKkQyY8aldeE!{Wd#FFmZV8sgiufDCa{ zE*cSeuUTQR@KQIlm{r^^D!=vK96=W{=%%kqA1P1pXi?V8Gw%^6EA*0npOtl?cin=` z(BG+^;JhxwutHg2@$DHkFL#tk5r;v4oojw%fz%1{seuo@=y@Vi-{4D*;h8hAwoKU4 zPQ&30VX}OI8T9?!Zm0H_j4(gH{$9@{+CHk#>*7fwde)ql@wfFN0A}$05LlP8Q$|mT z86n!UX}CG!m!qmbE(V+W(dTxk?y9qH@{rl-PnUW7qoVvMP7>S^u70wff*4B)j(I}N zs`zXc-7|=Tf_t~WzUs7V9)J~;vJi#G$jmGJ#5DXn6wS(n)gua?;**=%?8BSDz^1Ltdzr1jd7vEIJL+@gPu(DUfaq?>63Ady)?*p9tV8^2`+LLGQE7VJS%H*(4Ntz zX~F|#pgU8L0tx-EfH18+gS<^HWU|iOw}19z7*|4#aQW)rG4PMB@eDk|saH+vni(#) zEsw`8&wfmrpHolL{QQ8$jT^~f?W5)kcfYSz%=+{&=on5n*Q79-A z=!Cost0xvbnEbOl*l}^c)hd#)RjTKa**&JDTW3LDA^wgM`A42LDqB*XvrJjw>;m`K zBZ=oqzPE51d;|IQ<;0&Le9E=Ap&4e(o+Ao@#JR@F0qEo`d_pgQgA+h()i_4)6t8}% zA;2#iNU2XU8{(b@@bmCsrhHU6_P9zb@k=XHZORGcN_@`yoF=52l{mG@pn|l58=(wGFu6=Hug@OGyd^Bgz43+qxZ+2jOe7@+?4MctZ1^AIQWzZ+ zzm60QeZaJFMKTd`Ovi6unHDpaM$61u(I@9>8zXt~j!P<}CApjej}8A@h06XW3!ON# zq&a%Tlmlepy(y=dGhBW*XEXfM*;li#NEKK=R#!>={r$I4#RVx}o-o14fJXY30wBFf z`X_s)Ev6F9uOg@x3aM9Tgd3uKZdf8ehu9DPOkltxBI^1vQ&sUhwQ#zOss0d<`Xn(l z1`O`Ae$^n$!`o-;P-U0AD}0beQ53Su*cexk2H zC!LM4XL{l|aNiWJIBa!GFWzj@!w_Wt{M?~h^I4%9C#OWG&u5`BkZ9%cA)?Ra>FDC` zUXd}nwO2GSnSxIAGk3K!cAfc!!+VA2c`;5SzI-q%SMxalFyfzy-H&%Z zr)ZD)v4t(F0~0Hn=@giyKG!byk;i0H*>3#4_DR>ZA01}zc~oDJqzuARUeXWFGV-s3gLWTiWzMv=_3X#* z-2s<{f2j}xkUiTq-&BRgK3_sw_Ub|N4BCnbY%U;`HQnFlQc!6m>4(eX_ zYF5yT8g-aJUH%!Yd@p$vT6pv-zd&v@#<()Jdi%_s^Y zY4bA;iMWc*_6L;@rcciMd2WKPIu;Zb_>)vM_LRYDX>I{x?S%MMZ9UfsUuXjBSoC{i zcvVW~0JFI@(vy_%lRmutx{>~`J0IXa&PRJmBd;MNz4ym^PZFIGZ#fc-cXN>bkr{x} zGQWMt01N_UsuO^XT+ti(qYm$W0*rSzV0vx-dnb)it++(58tG|r%B5g;9p)dz$o^mo z*tvlzGGMi?p77)kdc5uHVrHM|=^xKi`^A{ue$vO2s`1#3f@~=$e=iGjknY_;&pY4l zdUbO$8LaZZ_F#c&8|m(D>FyGw8|m(D9^zZD_c`bN z_5BgAi^W>A=RL<5_n2i`2a=zv)xpqBcr)xR);^=~uJ~Wmr61$=Qi8B;@50vwR-S0l!^?ZZlS##Ho_&p^HI- zyZ(83JJ1-a@#5`k$Lcts?&j-imsGAV%S=|A_9m*RxJOho>+msK^30F?FS6>hvb1o`}}&6VZlHfMw|o>9Br}rU{5Fv1#~7Om0VQ%Y|Dl*w(xp@GZ0Ah4}vS z6!2&=?i(W5N3yA#PJt%2%#>+5l@@L~-NQoa-B?`k!arklx^+5MvtvC6hN}-9gAZ{%R)dNUvgnf3yy!c0stP%6348MW$*xhLfZjTp192e2836GK}8lNFLSQOb)Lu; z78U@u)YjsDW%7=0y?^oo`VFWhuIhYV>ZAj}FY*|Pc%Fco3Gjp+gj~4O#FP~77M-&4 zMC3Cvjb;Zj%lS$=SF9@oGqd9V!!X@MB;O7oi8&N(I2}v?h|fq+ihRR9FVH;v)*E2| zROSB|mHuxXDc`Z$K4xVY-Un#1HF02tYra4RZlz`cqhk4A@H0eI_$?@^j^ORqSh*7) zTG?(TUH!k>F91{?@X1hBUXLNyAEUULG5P-o)?yT(16~3^WZ#_}TG1A&?Hw zi0Tw%s|Cvu|I-&li74-50i^-wUaZ+)1FW}n__ghcVOdRlg1T(6Z3BCbzqxW*ALf7G z87~4g&@U3#{x~r*;J2goTB75Cs2ccxX($ zce;t4-7nylR6u5Hk^@0N-U3Ww}S$^uzKgo_S?7ykjWrT;h-gEEIq z-moR$l)6?`(%o#GM!NRat<{|HVqA~0k(zlJCpdgZKsGx*^mOA43pj9q%F#uby!HyH ztI>uHfV}_m`O~g= z27HAIFzN)FkTM*Ns1@TxO#sGumkc%7Vv--%BxfM0w4L7~(i!jBZ1{68lNXP6ovBq_ zW)$*SqprUD&Kq{(h@L+GCsvDPNcEh+ecq?T~G@5Pw6H9iHOtQ|R~ z`Exf&R|J-%r{`|4=FKK6nQB&R@b7Ym5j@+_2-!qJB zX&7{5IOchm25MCP*$D=ncj9&1m8X5}-NaUizfXbBYYtqnYbK%c*IH?k6-!-}S@EUE z%-f-&JFN}hiKx*w4n4K)an$YhCYE|qioadi&Tu2duy5Wc0@zHnkehF&8)fL+J^|k&-=z6CjTlRV2hVQl(75S% zU?^N`=o52D(PY>THqEUL0Ya8pzwQIlhs?lBf3SVI3fPN9W`*_Y* zQE(uGJ;18_SzpVL#HpgG|LQizVSoW6un)JwDeXBRlVhag9M5Q+HOKp(xL!5p#{q1P zh2OJUjP${iT99Z~X;LK4H!ienk2QTa5`TeYKiqEbT>m*8wUIR1bxMHu82Kf(E!fjcsah>t_GtJl|ILxKl&{T0kr^ za(ESqd&c)-xFyy>y(t(NVF<+5Pz7t)UnY`?@3-k6X5Edh26e<1zo z@X{E7qhzU#g>uObJl8<0H69}pc{#83^W=OrqP!iI+8=MAfIw^Qd&C6IQi-Qjv|3re zS;GeZjHJWj%q`mn7jl;miNs&rA(XYWg0l!hb#FScc8rsjn;E`&p(a;@$OO0z(|RB% zNF6g8$~4C*i|!Z@-CJRAJ1(*rb?Nape3f|_2~x}Jz7>PLNylv$^B2o2I5?@k!Jz*f z1H2G%-c85pS=rgjmrR6KZzxG7;=H3e^sr8o?y<;X@nuS}#g_K_6gO1i3ISe<9C15~ zm3SnwJ4c{*bnv%zTRw|XIk{cz4l7ObW)tOg$SpZ2D|zAo&s85RA*-V%JNc~4 zu{1hx@zR;mZi|*2Vhivf7HOw2$n9MEDXSQBRWsR4pncraUQ>dyBt1{F#Ly2Ew=qha z3|~O{AJ-h6%k_#x%k<<|9QnDcb}ShZwn0A2H}!XxCt5o9W2Bc2g1319wQp_JUXaP~ z2_Ot?DZE&u4cZ8g<|7)nX!IX#c085MFA`?Xq>fGBhuEi`)Jh?oGl!d6u;dJ&sF$(OZyF~Qe;tuZ0HevU__S~}t zy*|xHdcVX(pEhb-7C8gW4^TM896}3f78B*HHFul$AGWSw@SZuPH%BoVY}s>Xam)|! zJ-KeePt54Vi}cI@md47_kOgb{&Iu0TEor)&2C6EYUSU7thyZpLtQv{ z_=KlSGEGgp#e0-{Ip7Kc1Ewa7?%913^BZKhPJHQlA$DvsufFh#JL<`B@bbSKn&0b# z*Q;%;pfsURp4cjI!`7wzC19B%4x`Lah?eP!uI_oSCDbgMTlkG}k# z1@rfI!n>ND`IVn{hoA0xq_P}V)7UL~e4zH>46<5{rWp8r7W8^$H0tq5x0VcUJT;UG z*TwPW78fen?_S9czG2;viJX=YUfUlpF+&W8E** zNcwD1ovWe_uc|FBM}msvgLwcK120>Pf<7cU#>T)m1 zaevWC*k_=ipzQ6`wlO%%_*GnQPy;j%@HVty^L`7iBKF!58%tm+i3+C03-?z_L+NYb z?JSX7-+x3IlE;suI6ar6kB`x|ytvveYe^>VgY%p^dhlAGh#bl8JA8|6*Z%-@!pY2J zAW*%GYhC&>5bbRWNbkT`&1(&(N{mnx|3$l1-xP-25@fcMD$vUw|MLIy8~-c@;R8AT zqEY-UiO(^Q()IPH>T#xy*hlZsL5W)qAG}s#Gd;KopBH?Ygm1B!J@?q|Awc#?KyRnbs_Y>^>C4U_R)ZpXL${PL@VI=N_LYhYMlbf3WZj1{o~% zAg7Ls=ez*(0?@Q>94Be;za)|P4hD4yDeS7D&f0n6!;aJo&J1Jz;_x~Z=oAw|RdWp3 z>4a@od;%yL^a$^}5zGwyw0_}jB^00Eb;A?yAv;EiDs6kHda!B&z)g(&F1>tC#p%#f zRzCd|K)FbHezt?KiF`+~-ulm2kYj6{);=%wlFX7p zl`M+aEtEst|MPNl)f|YWB~x(Xj!!3mRG_}uzw{zM>}RZQ z7?RY!BBv?b06$zk{Bp4cmI(WUHY4~6j#WgWgJ&aGC^GcNESwtd&&D{;*CF0Sq$#TG z>AdXh`GW~n*`@2YzASZmN%5k{sMSo+^G6npaG~L2A_xAEt^NyVZ>+An2EQ{U#Nfu| zGx);DGX-_7fQPTY_RH`&oeixgyqRS@)S)g=??6!{0}-fExq?S252oV&efF29Fm!3l`a@WP~v~ zodd1@JS$t{T*>&GI-$#DOX~&Z17ttyl)LmB#+B*ru-uILhMm=D~j$JA70W@vV2p4%w?9ZUKe|0kUS1 zXabu_2EM!}po}i$F|@jP6gUydXzIOS(quS!P5pG-WOs;2SXkKYuC0!Wx{Gxy((P)V z6wIFw041YCDqKZsFYo7+bw>TE2Fp=Dg#JD-x8GGg9q3u){OB_pQ`0T|ee=(b{TqE~ z2=l4td&vg{rV}`%)x+e>2u0e3qsV|tQbi^PFTLahgu$GyYoFX&!?jYBme`L2xD=42i~HMwdiL9+}vXY=N&eFR`F3+>zo;;2oM?g zui#J{!YmCF8ea2p`M?z>uuhc5(w|?671Rlz@L83R&N6-MAGJX2z!c_OJtJ;i^0(=DR2quUjgEx8nx_@szaouB zr}g~s@n+;1PiffIgI;Xg2^N&IAHXAb%DnE?A8KnFzwkSFcNhhvN(E~Ab#ehFLr!wo zUzYDMa$z9hPMf0;h_pFbjWa=Cz0K1FFl8O4jI?DfXL)8#d@X)eZV?RPY)=$4_ws7z zv->@XpOi?!1#C~fF5abA(sB&~a#P=XGby^^zQ5RWsOzaDN?v*|e_}YXUYV({M>0R| zR#yJrZ0X&{jIkUUc)R*_dW>6BZa{JyPXqH&{j46Vx|@4B@{B^|=jTc>Ev5!S>K#c8Stb3RHZDDZ$((sAIQTV&hde7M3?Q1Kq%4kD zZvAQi48@?=WWua^{MX7*5@B@OR;`p0?x6tmJh};qLJ!vfrgI z(|4w_5J}Z0n_&aZ+XX8Mv&hK^{#&%5GUNhPKl~MNo>AQoZ^4GY{*gZe;%Ucsrq$%y-S(xgMI3E*y# z-D!lbIUq;{hH^_uBET%zA$SN(zFbjBUup;ZS;V?93X^d$qb3{{wpZVgep zH{(+Xw(rCSMOFLkEE{KKIRg2aXpY zlgFpvsKg==H3)=NRVNOmTC?*^B-VyeR!l`&t0tJg;}ZC})0fBmFFo6&Uq98mf_CS3 zSI}QNC3kKB^%KGek6b|PXu*dEC+)X@p zTdq&7hl+2BYO*=s0fpw-ple}hWzuKkFD8KXLEu~WKv5$2J)dyGdfT9DUZWmX;NoZ= z?AwxgRzxopU|pj-q1?-DsOb_b% zU6%&GGDkg*Zz_Nc5BH*rji-#{=JnnSC8%L~LOOv91NVQNYQ2P5oCduK?v(l?3~ZA3 zf#gr~bZ&@lF!;=dr8rrHJ8DoimPW(4P8xdN!S`h+`TP+8yG-I@!tfJ<8&8~AL^ne> zw}6x@ne|ii_WR_bFZ-~o-nzfY(d&hkFyJnWL5=R(sO^XM1AI@5>4Vm1@jN!#E^pcY zaL6eexf+24TkTi#AMOf7WlHQ(_FXnR6G&Ha^Qt()d`&+uj_UrChq9MRF%raY#<>B&B%T0jE+Wd$71U|5A4(LYPA zV`USqc0NBjcz$=Tlv;K#?-j9{e zn~MkC&V7BehM%>MupmJMh=q^P_#9~$bNTz6sJ+()a3Hvp`WX=alO)duiTh#2n$A_C ziMG}Uk;mAHrZ4@}*3z3n}z(q*;}d|4U-O@^BWiyY$QCRiVo);kh+% zowpH?I(9&c*M=vimLa+blEx9>CTQJcUnI<(nd-V&v4Vb;e*dQ+vgwh5+@4CBVch05 zxxDY}frUeymUmySSpaTW!0mE378J~*o;YR}a11Ran>oeFl4_`jvo@fFo5LHUWIXWF zh7G#XMIe+%vT#{nwI=l`aem^Fq@v2xoO1O@K!&iNYD|7M34z*IuRYsZP6Yg%+(-FM zYrm;v#1yE}s-BhsaI&b;%|0bfqQYgnl47Fvr4GJ#gqEJb*x4y>H(`ew7LE?pkZbk2 zn7BB$j^7nGG|{kl<7|*Sqa1M8^gN5H)7+>CJK;RaJD#(+9%!OeGygAxXtI)gGP zq;>_fGnQ*@tgq^}zMQCa)-{GzIN7b=c~Ol++VOKiTL&dn#)d2}d?rfmOtDvlJ5E4m zkriMTq5I)xOOE*2xk)dTOTQ9dZpynb?fx9@^NxxNdVGRtA0uJbcqIR3;|QnAt~5kR zMDb@09*^$FB&l46sLF0GzGiqv-hwBghUhU4?t{N_dNaSLqZ|2Uj}3C0WcSkCFePsK zCDpZxD^i8M$ZkMNiK@Tnmj37-ldH)zxGLjg82{*adHTGU;lzokQx8KHm*QiSDk+NJ z0EpwFWA+R+6$(9QcGDDd=fgDI_#c)2lg)NoJp4yyFPd2@0}+)!YmZm=|H+pdSEV$g z(cf2l(an}C`KCAJ`uORyv#O*)66|t|BZ=SADM@O5Zh`n2nq|lw-?CppI%Gl z+S@a$f*GfYlFYM17Zt=G8+$F5>5sZYXSp!sC+4_nBTubPZ8pSw{WY}9J*=~<#rYG-A`MKevf+5azSU=B zWeU;=nyG8NI~2||3jHMMI4OU99ppSiN68j$P$417B4th^N^+KKwERCU1F!hGGwE-0 zbxYwqnBA`V3}=_2cO-qM?BQcSO(~q7d3pJ4fR*&bOmPpY-)ex@D`9(-7^6cx*s&Ap z*} zml?YHgSCSqPezRLwA9|VfuTOeedYd2Z(*l~rsqh0Uqfn)6mv>X(@@*?%gZ-|`Og7J zh=0#~UqL_?^6Pbo=uJNWBr(U=tkl+_gBSUI|))_5LacL zomr)&)IRsUgo!+8KsL_z9#3Y8@=5>a0<;%zIjdPlr}pTmED+4=tnhp{Xa`5h^mfW& zQfA$WCXr0j!H{|<*NE_#fb| zX<2{d5O39|KHe^rlufe4HcORXQNG-v@vc+`v%8nrBw^0yoZPRmuOGOKb*xZRY`8u* zrKT0P9(RLkAeKx}KS9=Hk%nYMBk{BR*ib-wZTL2)sy|>diR{54(l{I5tQ2j&g-3qN z(sX{xA7+{Ld99+isY2|YR`SU!;G7Fxx;?Z{AyraY3+M2+O3^+)cFw^s_zZ(SZRO3i z`YUu_@LN7zE7PZ@RHEN&Kbw`voXN!QN}%oI(92LrJUQ<44*J$Gx_u_1Kx#h{bueVO zv05g@?_dOS%H#fo*J6fc3k5q2g?mTit`R^b;y~VbM4S^5#z-;nL7nQUP*MFC&jQpD z<_ri$5TIC z{o2ddMQrR=vw#fgo2E1+DCg=gScQ@r_+WP!iTEXY5-nVorcqnKr##0UnT6fw?)x}9PGfLz42KFp?#=YV5Fih z5sCkE0Zo;GZLFl$TzBU5_Xzo^9U=Wy!1Io9SJRh}xCKVx z5mzgktUQK0LG3ZN3*DKFac=rHOn>F7^&3L<8wArbB=Nb0t-19=4l?|D;mSvKF6$4- zEQ{7m6oZ0>kI5J6CMapai~36-12iO`wiXh{ntdf+kY6Q82cy!r-JM0~4))Xcyh!my z$K9{J*v;-;$up~_2ceH|w$_sTeSQ1QK5!?@t5SoK|G8<)lo~oCPa^nS8gTxB>Vh{QiOc7X*0apJp*x@69*&?uUCFlbKeoQ0C8uCJ zS!{Cw$Mr67o3;xv;3kly-H-qz^+44fR(uzwR!ffAv@)2CPoBE`tE00YvsS|_moeAQ zi%vd9e{CFKi~9kEeiy~vaCWD}b3q>-emU@^Os}%=F;Kk3vkjN-?@!B$=&;={JGkj_ zC^^kq7R6lJQLo)zE?Tf9{Ak-Lt)^5nF>bn5IVQGb9o88lv_C!U;;t%8EK0N~S(3b0Xi=xs*FPIIe9yPFMIPjpvPeN4*q)A>G zH}^&M^De0f|1QqT^9&5xki+qdmZXQaWIr~3?VV%9FY5gzA=>IQA!28YUoTKrc>I8r zf&81nabraa+kC6f!FVJE2;Qj75`cDQ?R02#)gOF7;ItUX&(k@l?et6w#}*qNoja#n+)%Y~PJ(T{VOMGwe^aF69K!=;M(7rqYZ7C;gW+UZc6*~?HFv0@k)*ky8N$^l+a1WxGpQHngkkLk-!zEsPJy4CuJKuJi`f zVMOqf{dkt<<{L95$_Ie*fGdx3*!a$647|paBAsittY2Q%w8Zgsv_ntttDcqMa5OHv zjF+Lt0aL6wFSjq<_;F7;>0*e|h$rClhz>}DUU@y9-#kF=n`4VbTBEENYXXmt%QpT{ z0-_3Sh?YZ*v(mw(xiJ>k0-ofuE=7TdG$9r5nZCKd$rGy3F>MV+>dGjUncXnc*Ksvp znf91jSd?ErRG8xcmV`;#HXA*G$ucE3_5@g1UvS!;lq~7zGZGR4V-4yZ_4Ei^D)k(i zFAP_fmT2N$bRf$~Jv#Lu$7d5H+VrAWS`uvGXcQ05=y$thqE-N+3UD}-Y&=_OO#)Kd zQwyY%#@tp|9<(LYn6n7Oa(^WNgr6LP-OJO1G(Ab^yQF2r5;8%h+_`pd7D+2BHW!v? zclp5Nwk=2LWo|af3plBU)2uVRY%<)Rx-!gyoeQ0HzVc`JzC4g6X*Js5b1d5lOC7z8 z+WN$)c%oO$r#XB8MBQ5gZ^j1n&C6>~qierXQc|W`5b-#_%8wUN+*8rh6Y$wjEH6hC zjy|#~8zj=PM!2tmygQEAXua~Z4hGYm`v08#j~3ump^xpj19TcLe;@Cs_k5_H&gE#L z#0*+)c07KoWTppf+>nU9J(G!}Mb+9f=uVG0#hN{BvCdps>Il-z!otAL?mYKzaVdA6 zbLYhXZj#LDxKaDN)J0v6erH@wsk0=k1xmBHsqf=}P{?0oqTkcNWM)G|7T5k+=CyzVxioW&?hu9~*{Zi7ke$~CVqv6?VJ21xHB{?H~I^znR@D_wi zvRb4o-O%0^|$3%iaD^506Jx${r)@>))05)-h={emP{h$WF(ef@fI>tp5D@lgjgXY@h`M z0>vHP@N^K`>gi=&|LFW+!VOaf*_85-_T%*?m=GmOr0MLmb*NtN;c5gkEx>t#@uDC` zGK)!1{OodwwESvZhTl;vYGuPN+4mvIH^rs-^3tJA*H-FC?iNcRj{jt+TuTuRgI+uN zvc=QWlc8BgO${TB-8xnmkes|pop(37ds&(RturOvqOM|a`M;!2V-nV+AJ%gBiQ%La;b z8=c+r)5mgbuz8?G{m)0VY4Ra~4Ke?x5HGj@VdS;U6YoUU$5Z}V6A+_hGq|LVn9fpz)u^zI#zZ{SRyxf6iY}))(d0r%=XR!EAtL3I7cn)Z z@Vq+lC60RbpQeH)s`Po+QPLQJU!7&+K5e7cs3e?i?-cN$1^pU!wLg(6{NS@#WBlfg z+KV0{_TOUmB@pugiQAj7DYmm`oq$LUjJHg!fD2_Jlw$4135vK6-Qh1?quuNCU9Iuo z#L1=UuOWHh|BBl1pcX+DkW9f3I<9>Sx2hRmQO-G*PH0tT-6uT?gWVw8k_B=n zi}9dL7IQ_zfeL45Xa88T?exCBee;ywdwRG6!{hUaU$SYX(;)&MAI7

A=aQo0vS9dKH z1dJU6>Pf~5hEI09)#$FN9c;mO^QhX&a+10p4R2;jA&W$GW&uF$6{hjKcxT0V!5RAM zZ2*Vm=~Z!m9?~eE=ZCul)K~!zG|}!)Ah~(dj#I3Pkk5lPauS*e#O>RWiD!urO^|#=r+8GK zLpdCXSr&;mXu*4@uH>1GN*Bmx5nQTq^2hWpy`7Gyq;su1EEpGNe3rcOM^_wz6(T!1 zUjx3t#k!p;%6`V;Ew`R_^k{op)cy#8@6b)Brr?fv0qZf{pgURFTJH^->E2ef{Iq|2 zaq2GqZxE>UKw>BGEj2yFUG%NEOoOyRKiO6UNr53I=L(%S1`f;=;Fkto=ueY*;-UQp z<`H5c-)2Z{-nvwgi2fyR$tn~VwKeGrzaxjlu+ilL>o-U=# z%+ap$MyYAQU9iA;d)C0pRb`T09A?+avHW`d+ui^Zp)avp3-)WJT*HeM<--l;Gf zZ(MtD7^d*STl#tc5)0|um^6qoroPGpd2*r<-49WCx!=;>Rca>8X#}AKItIneVFe`1 z!@|NYbovT_0g}kY4NRaUwZYMEf!Q$fGHcBR-- zi6TFgch7-mI37e=Q&u+YzB9@N!_pmfmxX&iwnM&~vpmYiYAxrArhIho&i1ojH2`*3 z@D?A8!kA~c*t)E)DPfiG-6zLOrwhF3%f=Sy3I2eYiFt)NqyO2M301g@#{fsZ2G#Qs*bhlGxa#*PMWw^p~Nw z`nfrovfYAwv!2dXAYjeP7(b0Bae8Wty|KhwutK0lj9hbqHJruGy*N<1%-~w6akOg+ zFY&65Ja?iCrlt471#ZuE+eLhy1PeMabhnFggDE_I7@k7zWE0y zs4soIZ2aJecH4hqSVf8ZcBaghR3+o4$WHMH<9vyXB(~%lt z6>$2yqT)xfEYrJD!rY^udJAdCt01=VM?kx$LIuP9+;>0!vHZD2|)Z&vR~{ePFkg?0B_^xztQu`EtT<)x(qKIe!%q4yLn)?3Z_1{ zI-hnaA@!<@8>o1=&pac4J^1v25TE2;3_VcC84Z(9$`K{yXrdd8&+>DTm(AC$h0g`? zrzhR56`6^RxW#r9r&7k{xkQIjZSiNpQ>JOq4Up#Em2jXOSTFeo<`pZxQ({CeYj8i7 z^d_~pxpokD+V%_B;-_caCtkhtZz4M{=?f~N2TkgimK_{*j-Eh@^*;lv-2|2rTE zH;E;4x9h#YwyVCT_A?9eru@Kl>5lM5cEytg)i2VJDh`PY)zLnN zj>@;$;r|9c{c~v*ny#!>Nh*-R{D zzFcSF++zNPelat!eYLl|f5=n8yHN7I zPpH<@+2$(oS&|*|CMb2W?!TMr|3?&P{`wnLT<~RPT#;4eN}TK?f~s<|^Tw7EcG-EE z>b=0Qsk|2Ij(e!;@=i~CxAY4MffO50M@d8HK%{h8!82z(noK>A#|Er=?^zAx-x{p2 zY1Au$K)!Yt2(^IYS)G+9J*X4+Q}z$P52Tfhm5nXAKlJTdd%I=BF=7e|JF%nCtabQK z+wXMC)ht_jlhK3p&re&=3V9;((a_K$$kzox$1E>TdjgI??2*q!O{9c$l6@P>JwpLu zCI9Na#?-FQjWDO&o|k%CKl`y!JJ~?>tg^3@EXCp(x`JVLx;ZCt4ysVY#~6}LelG4+ z3Ex_v7+X5l^kJc63uWkzw23`w!>2N;uy+i3SRVv|$+M$B*tj@&YaRJ9 z^J)_}N#t~SUgW$|={CZtlt*_w^BIA9X#iz7FEK&+MuDz_BQ?Z|ig1O(*%)$GzL|oo zNk>#SecWY&0Q@f2TnN+@^T>|5BQ8b$df9ba;8m8^;t$U4yPf*@QMfL$CF$SL+8kr^ zPE5aOKcaMrdwERPm9E$Hvm@m{$zs&>v?5$#9#!wZ!u#bDNNQP6Q*7?Tvt~>CFO-vYi>5>ClfGX z`R&aFH-3V^&Ne#RYkSxWBO`9uE6~qwn$B&O{MKX-SS+qvg{kGy8_Hi5+DZo4m!BkVr7M&F%G;Zu=vuH_i?_@R#0wl zd;35o_v9mj`1x^qhiIgwGF7Fi7IbDnPmISWpwL!MTi;ZL4m1UvL4GRHYSos&s$0-% z$5Zf^{>2V7z#P_?FzqGL+i1S6M@58_#$zY2&?VvResA|HikHxNI$gxRRmTh@9FQB4 zVPsd4+0w&D1BDJ>ftgGWPRNBq8h_NyBl{eD6lxO1moKNc;>-Irn%4(51Ge z@#lo(xvZx_aq#KyFz*%@Zw!ht9`d!MDGgB`XrFwg`##pQXj&ew>A+x!L6k@Z&JUR8 zzewLgrU&u&kV(88Nj_}+2h-y#tm4SEp>bFI&=$Ta zFbRyC{VeA<@ma@}c#cOZ8N;8IM^NyreEhLeYKnBxhGpO|i{ z9>Q|NdK;Y=)Ff98<;p8g%3zxrG3IN8P@6bGzzGkUOf{oNF7JOSUF?d85(V$i&r3${ zU}wJPEpn#YJy>9Pe$U50{l}}H1O5EZ9jeZtI zje{_=zGNlNvn*rT*UOR?D>+>1#t!<;xA4_6KcK>8->o)utOr)=YJd&{@}|}2LzPVi z|E%RuHnJxZ|tPvSLHtb_DW$A`FOh4Qcmu9XbeMA z*C{yK(;gJI(tMac5mcwh*xpPjBi>n78V)NhUYM6Ma)jyjmc2%sRZ88yopCmfr@ff0 z6X=xefE+Sx?FEkkpJ^l2y3!^ejK$+zk>wm7X=r3k!s8Zn-W*9YM{{vF zMsD$BQ!*z`p3*Sp`dzjX(5k%j32YLYul<){R)^%fZPzY^atj17;Vf0D*9ar~3f6u* zjMSz7+WgL0Sj}x3(rIsU*_H8mp~(Qek&bz?$UI>Dc6w!6zNsksG!tA-^wY!UF_K<- z_>?pMK*<&NN;~(4u79Ra#%edEe=n1PNA5|)&_@iKUW|mRUD}uY@3VNo3(SWqD9{^~^{%_r1b&PM?p$^Im(7_mq!>{Hv-!JgNueS{$@gZQmNtZ~tH zpi7i9ULN4aQ^xXu@O@}ds~ClILdqyrR0z0ZVWtbK-6!OeX+lmHn>6S1=LOLv^|8sVz?(4#oc zLAnj3tNR7LdC@~xowRl;*=kW|YZ*^LZ~?1Y>E~!I61OJ9Lr~to>sOO7mudWlEp3nQQf`pO_GU$YCne}qt0`kut4d=mQZ?pfd|D@FWXPA)zne6(D{%H&&ON}w8x zTCMrD0n?!LY#tMYHKkY;#?EmUlIdgceT)3oxG9Khc6u;t?Aqb-+FdS_UtV5Mpv;!> z;+gF;;M%~P_Ih+Hqef3ao~!ZTzqu|y3=e0h&+ajK4e_{BB^Git%y+lU^5_bHz9%Oq zZ--0LVwZGxxpbPMmhEiKFBJ3Wotd6&jT67OJlpUFUo4)W3MIO;iU(i4pvSj%4CCU) zew3C@;HESTws;#-@w0t>ZqU?ZB`m;ImL6^)r0sQYLVo=`dTmA9%VF;@(@Il9d6;ja zMVCXx+!J$m2teN}R3X?+mNYwoM2DHynO+7YIJp~p@J@T&MOgu=H%b@D;p?@kGg;}I zFO_PCcY*YZNb6lYHPa811&L{23aTBHTKc8$j@VdTWVMy@P6|ByrmdeuLKK|XDw~fh z-}ebFqBjUMnWRLuizZ!|%*x17cRbtG4$GP|h~F)$BZr7TQshB){>xxTsGosJHJv{$ zhDmH(fkUrQ0@*ie=~`8rF*SQy-LA&t&&@YMw3jv`CjC?W%RW~IHl5~7jVsBcbhm-q z^h)1aCWa$Ru?K}v*S^jCebs-UyMu$oih@7KmJX$Ca6^AGj_S3NognYKF#-^c?VX)S z-6U!^d)cs$3pz?NvsxQY;;|?!LFzt? z)}@@y)=hj(o?6A;OkeliLdHUc<9G6`;xZbZ!Rz1)?v?1mI?4iSR0VO?aI)Qo4J&M` zk@sf|g^ylbo|*J*`#9S2v$aLP{fBdJRN8T}w~Ug{LjlTDO;KA#Zfi)oU{>{VekTtf z21Tj_(aXXx0i*ywd-??(_wPb`Rpi745`J)MiFcoLe=vgfbb1ynA5eyr*#%(YEuLP+y+a@yS!cj>B*!ym0xM zQp)d2UllifX()d+>0r-y@pYsF=CZ$&(N)S)lJyI>%Jh9^xw1iRF>uI zk*sJ3U7Av3duBOTbg6xjd+JHP{;qzy1Qk}5X1gQ>pYDZyJGoV8_BF6XM?XtcN>9}G zDyhrD-pSn-L_DlfYOqNr-)b!nP)C3&X|D?2Es`E`@=xk!*DKw1d&|2mbIi}eFWBN-*TNA4b0<>p1J8=nX+__j%O)*t!C@qHCZ=B< z?@ou&{LL~v|7Gikx=abCTa|&~&D_mVFy}PZ)XdwMv)gsgny6o8sdMwgg(a8KNSsK0 z)j3#=Bb$JIxsbLqT5obBLZ^^SRY5_Za*f0&D)+Xb8f}_NKT5Sq^WlwY{)f?>U>iF7k5k)a8j&cOnV)LDpTvD}g zL5vrTBqmuMrLmvFYSx)A^A|@7iX`YhWkJRm`skdi;~2j%3355P{?`)i-b3XJ_BS|# zRDJv>uH**s(}MKK#RKdPA5c2|8!eWv;>S_;b~v$VJ!z=3_GQoDb`Eo0^X6F5&o3`3 z3if?0^2KS_Ra0}3#ZO}ZYCvaXYFY%C4DMFlm1(qd3CZrGdwn}V*wsYNxe&x;E7LSz z+mUl+H0-%St19VrEY2`Jm2zbS0)haEgmeKQjqo5&o?p@xTAfWAcF0v!apKQ%em12TF&AMcfu8G=#}jj69pN{6AN<@f^brn} zT2X8QEU{_$$D#E$10X2)$Rg7v4N56XDl~V%lc-Hk$2)B~qUV3PH~g|1wCf=S92n@u z@=iw8>LS_P$R7B^kK=j2iQNc0*V%ZI-OTYj=5OtA{|hfIPI@=Mv{!ut&kbTLE9qNW z$VcJGlzv@ztAa!L`;=eDb^k(^kJ3UzB}XAU4Bh66P-%;P_1xz7*PzY(L1-?Scl4KN*-H>;6u`Uw-)c`AvR& zqR8^{6b^dcAsE21tD zTY5N}*Q$==Y5%6r`p3{mlUk|{{^};@b z6sdRNRYK~dKQ0I9)SfdQeTd=51xb{(t=m8GD5nT zCNK2r9ujR@qGlEAhTjfS$Y+BqV*sWJv66Xy3#5sP3h6dP7JERd4igjp+uTsZ>T zez9DQ<}E;;-${ZI(jM<&wZ7V1+@|=YC31R-IVP>l88|q!0H7Zie|R zk^0%uV{|+nAAFtyDnc>Xq`Xot=&Zy%`l4mdEx^K%tNb`}k!Il^b9>XH5%lXts#8am zQhD3_qE>cRnNIeAm};arHvi-gYPHzP#QOXVR&6yp z^YGWng0zLG;gKq>xL5-k32o-rfB2d8Es4KX4cg-C3EFm#V}!T7q^Rf(1{o;3T*PcS|4)!CeyEHAsSMAh>Sa zo!~yWyZZoxyZZzif}KV7zyIf)i*v&j&#Yd(x~sdY-umipLp(T43v7nvd^;!iV=C~! zL`pfu-^=~y1e;4>tM(Xi1Y#nBSxJ>P9!a6!=-PBzVsxRKXz*x4uFVLV1>eaK&3-X6 zljP{*$Z}@ow_;N#W+onihU~&*o5Nh@7C2sAMQrUj$(NKllFCR`kTKR zsaC@-6*OQlV>x(^+3O#@_cHfTM`;~Q*Y|+TIXX585xr zWSiF;VOX7&Gz#ng#}n<&9^Lqje?tun4gQIy>xpy&jwHZRKYetn&;Py6?sr6F31|oj zdg!1yw^>&I#mCj_9?p=F29EMAFPjaucUrt{eN~6B1Wvhm)fE%Y2yLkx1W)0gVokc_ z?8$OTWf~(1(|_9O^_kiHKLtYeO@JI!F7y{V5HP)oC@MX$iL7Leq%S+W*IAu@DU*#h~WcQR@N=LtP~+j9rDndj6f`x1Y`ZZ-;} zi&PHuy&GfXJ4izwKXbk|s59#+866D?y_}rod|l_ofhiL0NNFj7r&t`NRvmRmuJ7zw z;Y!PaR^rfUESK*Z=tJ|ig4Fn{HHa>jhuEN2E2jKM)LXntJ&dO##D-V+5hSSusr##|1&Y~K!9NgW?XiJ$nRsX7styW zdvfO+QzZV-#Ps5Jpg2XxvqKk)35Pl%g6ADSNZx)D7a8kd2UIq^OXVY?gPGezL5t%( zr;Ya2P>kDwpYx?XcxTclvC~_6LjN1>=_=J~a%3#gDBFMorFTys;_t(QOMcWm>HmCA z_<}(~9?OH*YeSx{#FHN--)2Q*d~9Y=I^?zGEy>YGJ7q|-PoeKzO0p8SM`|ZiQ%5Ye zeemhBIj09o48dYC!y^PU>LFD0Ft5>H)+XC#s?7Pk{b==+v4C$z?eFhP8~?Yi-@f}d zBQ+e8QOd2nU!GK!6dzs3m34^XPSq(og>AOQ>Af)>eGD`hbGq*`@iM{-xy3ys9UY1i z5!HK3S>Zu>qsERof%Tr_6?tUL-E_4Ikjv9)+RgBI*Wmr+ze)Zl{7gms?~2Qp+glVR z@BU$^+iy~9lq3%e(Ih|?Q4X*Te`lW6Z?soMR5i!mEkPpjMNH!7JtmH2Pax0596J$* zT&S-!vE^H1nwUFSJAvd|j)Ftv-lIT{1!d6;*Zz()Eka%TZX2p@D@kciw9KUyjJIY+ zoqou%bjE;C)!$Xm;UkUn*J>4|&FdI|t2*+HRYnYGaL<|m`((_M%#KMee<($|N6jl7 zJX4zWg@A>wBiL|{Bd3Z;qPsgpmfIo3*QhHdI)q1pmRhwpC0ZH;q9ab`<>ch#NFL2~ zAOd+dOLW6fI5oo1XeTN3pt-QNbFiR{cyRL5jDYY?=@m1!!r0mj0M7sj?)}e_>rwj~ zwgIywBeehrBdgiTh_>&39qG+LO_KMUZlfF@rGom3%!hTo@V#dO7-cN&jA3a37@sY` zF{Z;k36``FD^p)9$u;g`%@bjPD{^MA%nHz+$%d78KM{e$8SGWRR zDV>Jt;d1e%rM+{6CdPGIA^U<7O_B2^RNY2>_&nKJ{}^(_8rIUaKK}VsLi)BRZD4%d z9N>s9E-w*aOs-F{&c7SG=Z@yDzhx>DgJyxOBxm*pv6~$MT_e^{I%;we&uoSj@W0Rv*X{uHAWyBy!%SwObm^rO5IeBn*8sGNyB zy{(A4u+zlH46Y9%{ye;Qg&FAd^Sm3yocrer15v0SBZp;)Gy-^D&J2X|`7=f%3`MAZ z<4C4rW@lXEi;@&yKi^&}L${OBrPxEN?z~)@`DIIq-x%fm8e1L$E zc=pS8iOi$Q|2wu%bcO`LUUx1+EHV6H`y-#(lf3r#OjZb3f}^HTL5`0-briGTsK-dq zAe4R;FL57g&W_I&jJcmS>xg1xJop;}vV#(eD<*AFr=^ut`!Z;g?zgRz!T8X}+8;AE zq1U;59Yz|J`C1e2Vk^-(u1{Ld6>NdtrIUx8#3lb8HsT|Sz-IMNnxcF-3jzp&nI@CA zFTNkTd(40GKFET1pA#bh!_7skl^@f zhvGDby^q<~N8d?+iFq;U%!5t@tK$jHG0*_fc}Ezkysy>Tgkl978EE8X-d+~h*K0;1 zp6h)0fWXSi`d%2}(FG8cgJcxq0ij;{o|D=ec$C%amD1w5#Kr-(3+1-5&@z`r2;K^< zMNsho;OpA>2#w?C38fr%$CG_`^R5s9GNs?@wkM_eUWrQhC{6JRBbYRjJDOL-4rpU6Sc zw}x%qR#Mm@7>C;_#|})BhM*FMXiGhi0L{FQ=0$Uw{05D74!+(f61^(%l^)$# zv|^jjx5&X7izlIvR%pLnKAj@>Yw(AmxynQM-7gpb6)gFuvniScilc4e=Ba~GX5nvd zF60Y6EM&0B+kSmIaW=6;6ZbCYz<&KRYB}wGH9#!pvX9=;>4I0iXH z3@qzNKz1CZ9K2#F&H!}e7cojQUAhq0EyEYb$kRC|GTwmH*Ly5=Ry`==xeVxEMm|EJ z=EM_$?3l(i?z(($NPtav;0g5T;>^R7r&%NjR%}AgojC|m6AD4$Hr_t(n6Qt_7;r;D z$Txf# zZr(r9eNQHKBCh+_MI_^w(4tS59DhOYX9=`t;A%-9zWXKcV9i9Q*5XMS0U@*S?NPX3e$TMQ~_Sn zx?ju#?d>s5*IoOOM?*^K{D~hF8$70T7eX|g#i}!AhQC*u?p7MmOrbF zDx>#t!{$xJ3L2J}j|7Rgs zvs<|_`0S%#;i`sA8yAeM^z(QwTVxMq_9iesj7?+P@1=d`XSUDrgp3r3&a2)dPK)RX zH=U$ymwbLavrSQygIRrYp5L#FCrT{7J^#F3X*ldG_o(AIQzg16af}vBRu&~@R)nRk z;K@Q7rFdgS{=G1UKm)lK&~UaRRR`2Wm9<)PH~o5R@XDq|6Xptz(%|P!;Ao|o-LmJ3 zV?Q)OeZBrNtvry(Ot9=#QeD2l^Y5{*%`)x)8W( znhT#P%8VO(4K@CLns40Yp)52xbW#>lHQ-RWpxt+ZXjt_<|sF$bn(Tp>f(=t0uYH2D$ej`^q15NG-q+ z>Nl!AJP<5*O+t;EbJK5Hs?T+D<7vWIrrJa9`VCnisz$sfb~ZDvYK7`h zT!WX7q1E%2Er`1xQnj6@pN8v+xnEe2Y$(u?3f)@*k9ufyDBpz$iJhrN%We~hz@Yee+}kCl)!u)G)g=o53&xot=LuRZy0 z6!~7l_lP?AiW!cIa~t-QQ`o+(P`jw2W!Q6J1r^BD`CBf$?tr}~4oH~3etQ8n5{^Qx z{92ZMIZy?!#u0jPaE1w*TF;&s}-3?cHC5}h->`}E59Wc#n!pXzJ4YQVsnLB63Rb54x?%a5 zL)b1KJdo1P4$<^brbtM%+q8f}Qqa4J;`-jnvAk>}{%1eGb6&Ctj?muRcJH}8b$Tpr z4$1N@Gt9f4_|n&k1iKc`ro69!N2#qSW;RU3?a<2Nu_-8{&fMO-(Jj9$D5JvT#R(bd z(!g7>l`c*aZng*LPqM=oQ!T?m$M2Cda%8^53Tr~Yw`5ey&p0+Q&7Eufb0r}!41Onm z->oO3pYczNJZvtnb+^B{Q&CFK&2vQjm|IL69Tfm}=Hyd(!KQ3+vTon`MD$%CmA#Q( zvWUz2*AwTGh}!*%{KUs^E4yXqOJ21Ik-Q+YEC5KKBUEOX$m~GgI*?U@YcbByFRQgo ze3S)KMhP|>iJ>CAzVm-1p}AYuU6|wBqhNO4ABOFC&vIaCCKqI#Oa{lt`4d zP?1|D{^RXy53bQ(_%C-d>5SR=_w#*B&m+T*%yCaC|Nm^#?TsUId}{HYmIi3lnzcsw zFia6Ub*hTC*Fk!RYeYr-{2MaG9v=8r%N#b4*_6CN#0 zUzfv>NH7%5#)@vW$&@i$QSlW--3UY{^>8aI*gS49uF`4r0YU%-VCIcFZ8#09k_JaA zjjED3Qst6H=&2ldNa zOS{=tPz_Hux8!fw%|LdTS8aXu^+)EE%8@~oltrC5kzEBZ${d7)47>hwonXy2F<$Jk zc#pGk{~22EgG|h7uWecsF!QIaedm>%PA$PcfNxq+XS!))DyIBhWiCM#lRFc4e3V}* z@Lqm$;G;JTx?(l+(?uK0RI1n^$^P4E*83p7pK;F1stCsJ5_L97rr(A z%qW+jsIeTY70a>?f$BE(cj(af7VQwo#Hfn_~ML7KZ_lOHd z)$Q*h@3#2g`fw#x9cQM6+nKo2gFJZcn+jp}YBq(m5_H&Cd*zmLKPex*0U^b3SvN_E z>3gcoKnYgk3PzoVWv2AmB?@uwl?YPp_@YRPf(PUqoXmp_^+VhYlE& zep7Ae{MkMr%T+ENW#!Qra%>mnv)W`&z}=1Z`k@u!ZZ-YkQsi(m@xXxwx%2g5kwsgN zx8A|MMACmSn?Rk|Sc^G>PO2<`_Nd>=ST1n#VlQM9qFgyo{GJFHx02~ki0h-h8E2od zm5SKOdTynGeN~jvj^SVA)8d!^%lmoR_!>os$1gmW=%}u*6rt^>1(n8kw`5ee*Aq?P z_>PA0cTn8`evie$M@d9-#gQX{R*Fx^0Q8?1;g|8LgV_wv42%Z;Y&eJ&_Brbd`vt>n zc)-W9u$zsvkX5fq#eVZwq7O&hlwMQv{rx^0?cUeKr}t0??1vqf8ZzN7HXNiIeY^JI z)OODx07}2NTX8+tJhJ}7^SHW*@X)%g`vv%;;;f?##iY2o&JKejdprj;D=7Xkdd z@`wMFq&o|KJX9P$v&D#cw87dQ?mNLaE&1iknQ@ctp+Ys-W+_Ba;>X<*UpROFFHR;T zLr33vq&HOGw9iiz{P z?ETBJ$(&?#idwvKcULD_kDyg}XC}=^u$rlZQADU-sEm+M9rYp7POF0%^V^4L&bEz5F0@A;t4$nx7LN|0fmr0q#Lv!jLVp+c`8oFyr6wA1B1q@b=R|{P%)f2$)gwKgdwY&0vj|BL@~Mx>F@q8K1Kp?ZVuzj$D))t$#mMmZlX4eS6U|>Db8@4&VkbyX3nE z#fQ0=jfTA6#0kYwhebk3620JYIT*1~e=|5GW(DQoN>>ZHqMW7RPtjneZaEd(SUL7W z#ZSuJ(YPl^i%J)l)yRk;#L5X7JlNBPoXpZ{_zJ`#dSjK}^v_YRtd^(oJ3f}yfM0y8 zGAH%F2ksMMwG);*>up9343xRT{wU-%^g zxd$E6G*afmIew=)Y4r~gR;t%#Z9|SnL;Ysph-QYlg!245c?N6Dsoy_g>KP=R5+A0i zRxL<_F&gcgkNt5!XAMNZ$=1PHu`KS^RpkDDR9g*Kyof@5;kdoI$nVrz{KVy56J^Ij zPQ$#6iF<1%Joo%iIJtRU*1YYlbM$y>z1|EXMs5c$}n!uW7|fJDP2Nf1x}5 z5h`e^ZuD-&=^YiN6OF=0BukOf^?7zlqgNdnQ9>256L31{6XKU&Qm3Y@TVAyI#-wCR zE3F~l)B9VcxkTRXM#Z;l5M?>eVd0(hk1;fQ(QoaVV^^%kAvtOZ=`;%pYxYRvbgMN4 zqvi6y8k+o&6eF7_H+pK#ilycTt4b~|uyq_C^AlakzcM6Ky`m^6KVR3K`cTOl5}qVD znqlt7pi}bdz=E=svDR4iU7I{blm4~prG|xgGY!FY!f~9>xadz)a|>zFlNLtX`YnTc z>x&Bo*Vg%TetHovu<(_tz>0ztH>KVB^mteb&m})U6c{r>86#z7G7TBgDY0J;T`KFak3M&%{3ZEP zm@KVwaz<6N!F)R_CtKICJn%5}jvbH@pBl(ZdWPrjNEB-XQpN`|hyqtO3SMr65>dS+ zlkzYYxCP~P&&Lw#M%bhV*XHl-CJOyolh90S9(+8)5?>x;6EE~83S*1POyuHZJFi1J z7BdVY6u>;=8PG+CzZM^{zFzu{(|&(!hp=~YveOfSSE}PyE( za?9np{6KidD&C`#aI$9>a2P_DLP44-x|hFx8fNJjFCV>inBOc*y`&*CMhYoqFYfGn zK{7#p;;Vz&2=O``9qJW`d4G8FzXapPUxINkfQ3z)Z=PWhfZ9~0g*$&caLMo7gr{ zis#R;gj+?}ozVA(m8H9JGwU`-ng>L8 z1srhmg)m2Mr0fBt0BiS}43f!R$?qVT-CB~GET-v9*68d`MP1SFj~^*NMxSC)t5)Tu zEgDI$3xnE4N5!DF7@xKiv!se@8XUEsSvU$SWY}5cr%Z3DavV=);KOQz>B> zA*&3)jOPH78UNB1BSlXY`%A8y5uWFxeD8q^DUbov*;e3HsjKp<+upW$ytQIlDsc$+ zoD|jaJ>0JW@mWuk(U+@lmMrPQUDPK$+cQ)8z0_8{)_;?%{rP~$8l`yRBh17cO(eU$ zXp67pHBC1E)2^xiv(1)H&4NxZcs}U36Xgpvtxc^&f2zDAp@vclU$@t@fp1lpH-vSf zr1_glKRVW*jV=nSt^Yds<(`o|J@kfWq2UoX;4!oH7RRO zL8BEm10UU>vkCvB6X!qFJP`0RTDB^hW)ODEd-y#zJ~RlBC$qq*f`*UVxjrHy)qjDV zV7_vI4gIsQHfBuAx9Xrd-PE2qhpR0`v%_-Rywg(!S>fo$bKlNsK zs{g|zLV&m5q_z*jf&oe)G3&DGOBZv>zPDxQ+Kg-X=OJ zi{D)7oE< zR$EITYId7IjkO}{AZQUS!=|^rQ}I#(mEKw1v&a-d>Fb=V$Nq8S`*#+K;Y7SkiNCn2 z$(!YQs$G+t$WV)jswgVi?l~jo@h=?MCD_3i)+RBYkXodNkuiq%0v zdQ#5hiA_T5(hleK!BLJK-vXmFXkY#r1_y>WLYh>mvk(o6aw4F}Z8mn;I?-sFaL!q> zY6v!I@5N@j#+Bue5A=#zfwXFUeGShKN+Ku%tielxn4(Gr537q|Ip5I&lnR6SF1Wu~B?*W5IZ3}lM;9bP zH_#YKLWnJw24dxe!KdEW&AHd(86v}^b}iA}lP})3#Z5a<^~XSFQx!0E$S+q5%yZ48 z$j5S{&f(c;tY?K<$8-)2_s>U_`n5D0$14U!6z<-WTi4f+)Q+E?tucxy+-3{Zf=P{w zI_d`%;O|MRpkFMaJkGunJ-!>WrHrwwg~8a)c`$$d$TvN+OCc8PeBxUIiZqdQ#}=N^=ZJ=aQGOl~ z+Rx7tgOQ%@k*Iw`0}NUF;o+EE_E#99H#D8eihpj7z+g-qtlR<~&RR$^x zwF#aS^(LZER)VcVpMhddUW@yKCl7?I&NM$-uFQBpR2MO@D%MU|e<$)apOHBJsX*0C z@*+LMNLVD@A6pLQE!SB)AGB$~?7Mt?QE|PV9@iZLUP(PD+<4Y&F~G%K>g>V95y z`dVQwQ||VmWv#QH&ZBXQPhlp0EE>fWFx7AD@4GwCyB}zbYs4VZN9Z?qy?WS6w>@ef zU^K0#^jSTiL9zsqOoG#H?<3ToNZ9hP1ceBw&P?#HySqj#f#%!DB7Mh6cJLs zecs$O_NYVG?B=N*{BY?6H&cp!=av_c0NE9z@X8P2ZBeruK#4JTv#q|Ef_-G|L{#-m zP-*RP?{v;}x*FC4P-Yrb+;jKnZ&%+>J8HXRuGiUjbvI=FExm20+)MR5NwbbAQ|NgS zMoZiGlh0a?SAQk9Gw%s=j>5XrouU+iQnsonELm(}B*7RgZoA&LW?&7Dp{aXzuV45mKQ6DfEx;OrCG0U|TwZ0;OEr z3ldk!Z|xrL_c**sZ`dB-VyDq$Bot6JbqQ!~NQ9OXbym4$U;BKi3+U%bzQgC!p}lr@ zI*6WZf${_~1qoF$nUSlj|N8nX5J<(Mh&zAeTs%0y(39})u%cao(=EXK6WZJS^}HQJ zwtK~!!j(xGcm%_8MS$gfkl?Jw^sDbpRkXL#;TQ}(S7Pr?bFohRZLWRrA!H2Wm%L`2U>qsWgVd|PT;ZNIi zr#Hy5W?&p^k{7n&cuQK+Yd0fF?m3RFOa6AoKk!NpVXHhpIX;)AxpqlhDr%#(6Ht2# z%0SN%nD}_2=cYdyENeyP{%L)~Ds<#HO*HIcns6#QEtd|J@6Ij)yRwOqwvi){1>Lz) z*yNwrGQeEZ=12|2qtrJ%^m-p-59IQ%Y!cGHIO{D~Ey2BK6`<0_dR@1OYUL%l9!}J^ z6e&R|fHsbftZ~gL_M{W1%!T6)MEQ&4CZzT(4mwu=jTm>i&Ne%kbwkT2%6Gd)KG2R@ zt)J2pPi2Z2zb_(!sp{4|mZl7m)1Muot8lr$vP{^`&tZBlv_$4J!o_P2Bbr>T`wic* zO2Jj1UOr5_uYRpmS4?*KDR?d0Hitg9XLmD=|FBULCaM!u!u;cO{pC7ePLF~!p7*+g zr!~b|gVQ%gQf76b)U&?lY8uEEB1T8D&`w}HH!n7m>Pxp|d3-cS+)SD_QAr!>b>b*=nR)(2v3uA#U#o zh;z6-{rbj{AN*M1GF8(nap@iZr{Je+dD2clM&@737X-rRvcys;;=a%H1|2!#6g=#T ztazPDh~9I5V2THEFeZ(no5fnzWB{-q<9S2$x~*`=*ABr2TPK~ylo9IW{s^BSl-RUC zo0gGxx2N!WpGWeF`|{N5l~ZI9ycRxbxNdNO$@Wlu?zNL{A`5V^vG?Dz`e&Aji{NK9 z<&a(Xq0T{msnm*z_rDX1FUe{*x4D4}^@os!O?k{9t@-})_KV_waf&`6a02u^m8V`e zW`$3)cX}+vE$c<@u7Ie1)jB#K=URF8I5cL~<$i@vEBK`j0Ri2}-SwAM@gJz9NMPYn zk=ki+ZEAm)hF}rxAn107va){pf*y#le}hg5u>K)b`+MT)+xe2DzH$lE~>R6sut3oA2Kj0-QN{ZYLWH59p}>i+3Eo&8FLGF%X6M_ zkVT`g6KZ1pZ>gw zsv7I`7r$h~<-X2-_t|w`&_`S2pZ|Dyz-gYu!?uNo)Xm27+%9~z>l5r9O5`0jLpj*Zt|a{ zCs>K=8v5y1ch)C;n!GIfa)suw@95}w)`?2Fp!CONf# z(NeZLz(6S!@BI~}VsO^mN0Dv4_CoXKjRPUxPkdGlW&8lZ9E%={g*CxZ%A42eM$9(r zEAvhDznV0VE>f19V&k1E&gGXYT1*KF$8Bw{TnGEulZd1bl@g$%zXm(*a}L>l8DWA1 zE#+lODqj#o{T`EKAsqMMn)ruk>+8e^R%DT+_$9CQTcEA!IDH(~=K%oTM)W>UT?K}m zIQk@%^lhUD?OB=vz1RaR>br1GVcF7JDV|2<=oGJg-LL)yt>iiynG}aqW zeHWZQ)MoZayCiS+{CV`8eu!6MtbGk^Dp43$d;~*44Y=9_;rCi3eaZR)KhSI&s;*cZ z93S6YYNWBtgi~kYF#U)@D`w8x%VM7Y=qyJ^i}!<)QU^NegghZNJZ6z1`qnkG>^dXS ze7%IvC!jY>U4@!4Fi?t!WVTXkgyBbs4Yz*z40@GPsZQfJ?q`${p#8(cTtH5QssfMz z0eA?_Hk$tC+_f`3j@6H^#C6jCc1k2uQkqcyl*$5%RVV-bo23x>hJ{IukwuL|dnC8$ zs80+;2$VoG;%Nm{eL2fL9OE_~T>KsuCCsZmi{zV$0*7ipQaKK(hoGOOH)&22A-Ld~)9Yc?lwZ?&~d_ z`fdsQ{)K~S^fMqXz7-tlmruI>HCBMs=1I;ZHT*W#cy-ff+UZjPPmLUskC7zDW?TM# z@=j^2btmbt)^9m{0)py1R}Lrvn;9%eoP`jBE|wTvZVc)=6=&fFC~`cjPD&wXmLMRH z{4^I}Q+;KSQ9bH)LcUxqRPKEH(&?iHl4Xnj)Bn@_4j=&hz=zxRM~{_R)-w9Oy&vV4 z3>NrWBU&T*a#=bbptWeVOHSmD@_f&)@~h;oZ3dG=J~(^nbkA1xhjVfh-CUz@eID7` z)n+$OEikIfeyML1N%}zj`Igw@xfp^gpj0E^^@kg% z${0S*`gfYb3thezkxv8dF8IC1Nu_J)Vx?;Oom|Jv;3*?b~~E?@Q}o~5691_4ExXE(c+9 zrodt?Go(_r_P&VuVZw}2HSvj<gCI_>MA1FA$ z%JW%Ud%J$y%zy3p1m4hE^t5OLps{S?yU|Pba_QFA)<%jho^?Q|;Z3^2_#Y?1fBLv* z8FisdHBF(ey!)%7)(A2Q_ING6T=5U?{Ei;?=?R=x4QstwHvpN)q)v3@6i zPprFA$W@WGMNG>6tJadFAylUskU&#b=K)OQK~b@cw6t`25C{EJ$&QS+HmT3uCM5zt zusnc51D{AKKp*JuGKLbOb%eQH10RSUD$!szxTH_fez(oGi~mFM5S>vj4@_%@kF2XX z!MSZz-RVqD9vj0dpR4$yM-e)}d7H*rZtubSQcN^=#fUfBoFmGIwkgLL5Mar^ zniEqXR_6a21s_qL?ae$Ktiz0)T-MWl&en1XEtiH`pK!klp!f1h1()I{3d!G zzbGzH8mfeU!}GRByw2@>XYzJ;EPeA=qTYXY0}z#2ppGVZ>py@j`2m$1f2s+@nVeT~ zstTBH>Zg0s%Hx}{4j@l?*lo@=3$aXBV~WVPOp-IP>NQWTVcHxTVPH?;u$%S{s@ld( zmUD^aOi|91`4zF&oMSKrVTb|1Yd@fgsCR5TJglAQ{-*b}{>cBBtiO+@1r&H+J*`fYp%F2q~ zk+aADHQ6YCcb{qgpChk%f_<(^ z_^X$c!>;2fvzL>gqRrHDk`j`V*A<8spuyDjbwkmcJ!;WE{E@}QS}bND&=e+}Q^U&M zKru6}=WC;EK&_{_sH}|q??i0%i#<4COFb2eJ{eFb_P+y(`qbVV4>>uP`$@_UlFf>r(SgxKzUxDs@N?OPo63RMLZfL>1g&I1R>#1nP+v9_ zVmQ@kUOq!dL>BX%Uhirw0ccqkO9-y`cmG6!HJgkGRe~O%4F= z3;d%{AZ;nwWMt;*nxtlh6r1x;rd@XB8_L=@nRhM1BXp|yX_)V?B9(VVJcbie2WQ>+ z!e`tw$r_-J6WkFk!WjCG3!`z(LvXPA>bjz)cdA&U7qOKg!X60_tx^*-ZF&EqD(mY? z3()IF@Xt9gA#qQ^seg};T8Zap0QicSlFz}(=@`q>DTx zqSRT0)P~RW`H5h%q!eSQ-@MIIAJmsJlhH1&iX)q_nB_}N@Ww{3Rt2+Bbg>a{@(0=6 z2u$Mn--#|(fO?I|`OawWwZ12;mn`z*|2(&x9QUa(hHS!df`BW(<$0VOyY8S#rFAkc zr#r7!Iq@S2mKHcdgG*lBiO70r$fC~UsW31s3oUWASOS-5=9kR@MO#Jpr=675Bi4>X82Z?u}XRN!UNLBoA?hMq^d{%s&LZ zA?tk+8HLhOJ0ee6cAn8{3SRJa*tWcw9J#jn>S|Dv7cp-`CAR7ZoHv}q1w7=jgP2W` z`PLw`v|&*J0Ht1oxx)MS+Bp7zK*HKWOiO0{V`l;SZZfA1I(UC~{ z*C%TdnS7cE2QGzq5E=;`w;B1cKV=xynq-r6wI6kjOIyWJjt(z0Ckvq{4#X7CJG5#+ z5?XFprA33N7hEy`XK`hepzeuh1@4huDb6vC6a&Jt83%d$(N;?eLbL%u$9Pv}(~=TP zS0=e5tJRx;{0j2SZiQ{tDxD}3_aa*g7lP`m*P3TU?fzQ`lmYeAuM|chDDEkrwRIHM zBHX?_;>SplFn|-!;fINKshZ5mvTw_E{(h=qxp9+*f+@kKdB5^QP^gwuvh4*C%StRI%Ls=MQX?N?86vIi+<42+OlT9+Q zCGkx!1tX6VMt#Wp2D=Sw+*@YGmR8^L8}#>PznUx>TK^fk4{=+Wc&=hn;8}|bt&Y)& zLQ>#ef9DKwNq9Wq8!0n(rrS4e~g*INLI2o5=3EMd`;h;sf_@*>Y6i zV24rx!NEg8Iynml(55PKpcE+BXS%=NTvQ_WS+B`pT<%*)lKNnrujVsWh($aa!nF;r zFhg=jGt7UGTSIomriz_A?`)7h)9`U9Vv8|fPJk2(JRfevk)37Co62@R0*DJi>f7(X zJ{*ldgsXrh~j2?_w0snrQMfC`GPZJgs%k#I}uREvDmq}2L|k8 zqSxPo0#Uf?fxkhYA~0iRuwqGw-=-^=r_>&3vA89jqlfsUt!;8;W?7P0%;WN+yIUdY z%0`=4W##U=5Ba}LoPe{ypEO@R|Lhk$?Zu50r_$K7A3+OJbSSG*1nMv6c77&G)LhE{ ztGLwD_2y~gG>qVP*zm^c*C46ti3*bJ#z@@3E>P2iFA;V@a$5u}MhrK|McGKSl9d;9 z1dCX1aroBw+c?qVyL%GmL?nCLNA#z^_oWKp@Sm%Y+Z8nTRj*X|E&ZMs+fdMH##XnB z&p7I7M&9m)w7bG%MwG{@G4Ojg$N}LNZfSSj9%(ml)j(Corx>3l7Hhn?VgY+{-d*@h z&D7CUK1KNF6rdP3;1CT`W6Ek;AE%@RsE!fLAYp%e?fn%_9M`6#=?1fNRN;R%nVA4^ z!nE3g(iv7==>=I^^KNTra7~(!wwE3CO_&}IZv%RrZOaPt4So1xF;r=A;0%tyX8dTm z{6+ePl@^~+6CyehS)uh|@H@njNqRQ{7hf`a0@CAOya8h$#nDtbVaTqm{3k|xNXuh& zvnDg8QwRbXS%|6S&QzFaZTCG;uUAn?``rI?)KT88({KmKfx$){=hc#$w9#SYL>|I! z9a7m~-*UB>J>O?D1e;ge>o1p8vEO}wsyeAP9raa5ek-mI+*9bWc<>$!IIO2E+ME?e z?wx-Reg7Iu0U)Xw7H7R4!Y}Q}Tr z84i}kJ!bjN#;W?X#TE#3_Us62!DA2{el_(q066Btni_Quj z;}a4Zxs-4FW(M_(o)-~QRM6}Vky&4Dh|AbAnjim^_or_SfMmP|x%9x(qR4~#1RB?q z%ZsAAKgP|Hi{|!AR&jW*jtdr?*hPm=K0vCxSZhf84R`k(hzf3Q0|5Ga`vEEBJ|1AD zRdnPJJ1)K_6NpXOv}9g6>_!#!Ed!Hp#3x_y2KHw}3{gB7BNi7Z{&OHU9qwdlzAFfC!<_hH^s~O5gpD(f$byeFNcG!$LCTXxo0sA7NyPf8%Y`_Z zMeF6jA!T71;V3xziK+L@J~VsX5Ct`eACmaSdxy)h?1j@LE=t=T{hwRNl1;lW5Dm#q zh$uHyezO`AByH7!;h=s4XvE5xn$nV!lmAc-+&O(XIsGQg1bD71cHQk9p!FRT@hJYP zDOnc}E?-uPrrRz@;jNL&7rW(MVFd$H=O^zxoAU?#>eXL)mJc;NS|mLLWjzL14LJ*0 z3X$}b`F)Ag<^Qm&fzy^Kdv-b}v1^4otLC>CZRQu{cGlPJ|G2{AAXKFHg|d_`rZ~sj zMI+v&ix<| z@_I!Q<*3wrM|GQdK-)4ZYtbQbJVxk;%^YGu@8OJcRvI?xkoRhQ55>IE4otlIYcA2m zZ(vMDyxmEqxh$aLSR=-+4$@GDZKwZsnQg{^R6D8sD@BXqhs#JaL8w3#okvIw-}>sy zJ`VfnwUq-CYLL} z_*r>KX2V1IGj+wZth-JiEN&CW&)KiR1S&LRb?PUZKADp+s72&?Mg3a^FY2*Fau?5V zf#RFO{Y`qbz=%|F<{2-}aYf>|K^y%yy$gQMK729wvy552mMCP)`R(^25c$RN1DM?> z1CctM(}sP8JKi5I#=%`4KaT_&aHN#|_Oi{MM>Xsppg~}T*4XDaM@3m;PW39E*n5fJRSYsl+aGb1We!rcCA|LgBZw`RAVwQzZE+<^;QabRCk3JjzbmdELMuclfy`VVBy22)X zxYF|+q)CtBFZz|dXUkSB*(Y$x8~@(r4XU&lJ{w7@qc@bV2@~OypWsh*x)wZ*xG?*Rmx3S zY^*H8QFK~-2A-v?C=@+~P36&wXFZ}_R#=3q_MVlg^NS$I6uw7x2%#+NdZM423196< z=T$RPrTZ|N=zPed894qRgOWK}Dn&k8izr}yH{b(GK(ih5B^#~p@X`^qR zb3pnhbZY7#fBRE^Lq`o>qAcys1)kts@b$`w7HSvLiCwfZHH)6(;GNsk?xsTDp`L#}uj;IP%t*K4Mo*HXBV<)+yeF+cOScnXKivJ4L295J9e*cDyY)IjNzIeI zj#P%>aVJwrMTdnL;FSVS+HP&toLC0VHp19;?778*_X`iL&^%A?CJHtm+&v}J0o=G9 zkm5I5Y>3+I|8iE8K3!2|+`cS-IZO8?s>e*%h~CmkwHayR+lT*H0HNT=vGd*Gx;_av zAm?|HM<3cUZFfG_)M-sMiK8J@H<((@59Cunb(7roY8pAHoPV0RNgk?W^22Ekrm!Gp zHRfFON*#s28*OVS^y(60{7E>Cj$_Ls!!3BFauAHtV=p+LqM=~2I#iSJ2IKv%=(cV5-!(0T1(y*S--HNzpU=rYzwGo7~6 zy^&)WcrL=H(X!}=2kt^Br4TNO`M659`2Oxa9xHtAA@&@+R7QGGq)U;#y^Rrv-}LN~ zSFDq=%WFspX6(wowE+Z9#rBWf3p>_XPXVO?(N&}boc4gd*25HL}H8^XLR*@2u!3A|) zJz?SPGceb!q6UpK6tG#wL z>@vdWzzd6m*>ZYwE zoU(b$i*FU~Y~Nb2Zp9gc<2h-3Oyitga(k8DK{W%}EZQe9#kc*x>o)A8+Ajv!8x3Ix z*O3Eb2J=PBax$AH{wFwB%yyuRv-fZ84_M-4++8EE8wEXXe`!1 zw&cPy@znouwYHgeKvC;w6!6cqs zk($wnjF`6V6h&`fb19^ktjWeTmi6!7KYwJJdh-(ndC)*2WZMT)^$G)vEC6o2mihfX zR;gqtC1rmXGp-FA{1ByE!6?`7kxZfzn9Q2tASb-T$M1h>(6a`m=}*XFO?i%~q45 zz9vrIWjxve(WU&2(C2a%LT>XGMXReHRaa;&c&uDbo!yT*G-j+}Z^wSuU7H+Cv5L(4 z2w9vujhBnf6=^s{ucyA-jvF<>SBOMYdCx9O-^wGtsW}tZ!Z7lsn6z|k!}SlFh&7{> zj_~KHd|cAlkJLtSnpU~H`wT}W#Ff1=&p+5Q90|D({}gHMrO6EfcKK-_R(F|9ddf21 zAUadP2jsOGr;~c3uT!O`&Ki3zU7O6_>Zy!BM0duMY4{Ppdp`my5sXJE7j$d5Nh9RLN#SufQqWqW0&~|B4GkHM zv9xTty36v_rk7ig;MiX`MzJA>Wj)Js)&6%Bzf4jB2M`1DDu0j04Mf8N^)T4abR;FQ zf6@sWs%uZ!MzUr-86_@vB_K~5idNJlr&uW>Ck3|}L0BG`*^-<>|GzX!+%#?S#Uwwt z`+WO(01H@a-5OFOP{Z4vr^^~y+1F+5>gSNIdlW@P2GQF@m-c5ghxt?SUr)MNAg}K4 zF8mN1n8Ycs=ocS}C73=6o$@4=0%)2yWmdRn)I7)8$SVNWwbpXn0Nj<$Lg z*}FauuL{p{7g}2b4cg}KG7kVXN8d?DsZc@Rm`%>nbJQNh)Jw{`)&BMcuT_snW+D%l zKy@onG@ccuE>On1xEx9PJ0cffWmK}@Ee$A1C|r3mYm^&TuZaHL==*Y7?2rN^u|ap6 z_=Rg>m#Z+IMPZT*>ciXn-)Sabstg40L#O{K!;~|?ZJt9br#ku?we{^U%gfH=Y_8E(23VSTKSZnHd>f)0iZX z|3vj>t5F2*R96&A`1P9ETWu2}aNpzzu%F1gN{d-F4$T32X113K$p(SeAGSx^7E=wH zn#JSapM*4b+1oxm8RR=z2!W4({bb8a>R><4Z@s!9EzoxT$G=3l4*MiXgYp9kutqv2 zlB}{=*_0n39k}m6(Q#m?&#g7$&`Nc1Z%^v!E!7$u@Z$i;`!pnR>cmXK;ZcSCYBV<`2KFV(Bo_aXVvrd`-{y1 zkJc&gK%405w)g65T#uxcf$fB2k^>+VrjX<9i(^@n{ZAyrj+jGQ%kqLfT3-(I=jbAG zFQzJndqo_~pM-EDFGUtHyct#yLAHMqs-vmk=;ec}L(EZ+xIiA%9>iYg< z(uxyVnr)GtAShB_^BAX0sa#EITFCFE_=Y4t%ezyN{%t!Xdd%2Dx{lFPlXeFc`wj^R zx%2x>GjDj(8n@MtnR(E6pJwNjxtDOy3OXI|nf@O#Ba`a6CEcK8u78xwl;WczY-XYF zXfktp`tXm)LP0W*BKt*q%PTpUiG0H4q1{Ta&)wnTAAn=5q4$ULFMf#!fke=#-QO4; zxd9SW#@s@MJn7#m4g@{IbI~$|pKxU^v`!(uS4H6vO5_wOBn|&I{uZ5?DC#A^`~KdQ zGIYW~>05Fyi;fZ_nK^Np0CoO1X70|j;7Bs<{GvN@cx>8U14iF+1^&@N}CHA(Soj&Txw0f8C_31LK+OSl;N#YuLaOD=eU; zrA4w1^z`&(inoGAPuHs_A?sp6en|mT!49IiTY?JM{>*#rb*~v#JxkY+wld33sh$lM zZnmyPJ;O*d;};pM6#xq@a5sR0YEE{&1)o;(2OcUUgiKAYYVnA)sVStOg}v`p+lpG` zFp|7e9CNPJFPZue{D7|)xp8E#)<+cfgZ4{}nLOi|D^R8n8Xg(8x+k@Sx;gf>v$E8% zj;zDvl>^(TdrEQTu;rQ&6G*a}{_pzYQP=gQ5h35U@!CU(dN`3q!SyzxeMgugy!bd@ z?&6Alo?DUUxbQvtJ2kdCIi_MM@uwY#C?eZ+zD)v8jyU8Rotcpxs`8Vh7-S zmI1jJi^(B3PB=%7Gs~1F(^G%iw2<)@7QyN-oi|+MJUFLh8Ppx|JgO(9xlYndNb0FY zZuu`Qj4~l>fnddw;-9AP!(d*qU@}%B94yW9a!j6L#G5j#3hcW@ZJw-(sRwYbA*wb# z=c7D5f46_8cPIDkW&aG?IcTAw6{6p8k}sReb4^7OnhWyB9g#F)q^HF8 zMe3E&4G5j@2`gR;5U9*}GT)vtNEiwsHEgJ#wohm$OqKvwtq?%*RA9Itwm`Mc?S`8jCQ1NEa-EfL4>XX~DS;S+DeQZ_Sfkl@6F z`^BbPa;AyYmmt~jQ3l0}m4BTd&i7X>I$d{M8MUY{U{7V#WIPw=box#xVWJ#nt26*hHK&Rw0E zx9Cs0+nT~JkRpT_f9@V=F2NBY$)}r9R1QRJVZj(45)nHL3ZL2d^BfwX!PY68Q~(<07KzKSjHSDO zq^M>r<8MpFVk7CcciVyXj~vBWHaj1Vy=uv^n+_oMcHN@IJs<(iN6=%7Xp!trRt) zoKQ@!60@Nx%dSRUMY~u-)0V|*c@X^azDXoi_R91C2IQP1f~+hd3G>-*4&Jr=C6b6~KYrUM@c(A64chk5~O@U7qnR_j&nEyO#a z&Cb`7d`fsghOr6E+R^XRrWy$9(aUaW@enz5e>|?g2NFqi4N_iSyw0nxdvRlBF9ka- zh=5|_rCTeFCa0{a{2P}fiH~Qb)G_ePfq<_quBVn}M)=p%cL#NPf?Mqei<|eNyTJU$ za$LJ~Ng&pedDkWmI5x0$pr?mM4V^eJZ zTH;995+*s2-fI3MGiW%SZ#nes6~+zwkzN9Oqk{C0^@7PS`i?Bh0fd>4abZ0k(axds z*gL0Mqe`I3C^>aG(a*Md*d!w>>vz{jluZdA#uAbG&VhtpOEgGtT-hs@uUI3()ZkN3 zo?PX;;096;WluhMR}cfBOTO_og70Hsr);#pp0qv|rJMxRP@iR+wuQf z3%Gwp`>)Y4#Za-WeD7m(vcQ~4!2FqEa8gapc?_JSk>3q@mI>mm)F{TWh4Tg(6qnb zSe*Yu2eECWDchO(TiZw|{PCyl3Q^w9i%vO=UBK^q;9g78^Z5T8oA*C|aLND1S$SKC z|9$J`{y+ZNzn_0Y{#P9M?-zhy9fo?_7T~)7B)EW5&_p@RdCVzRs9m4x?X|5hfRa|d zqwMpxH6CSi#Y)54oW%7p@;C>>t>u48f~rY0jfDRu19f}YFQaeHXqGQqwA2L3sbJ3L zEL;4i_$qWF_6Fkt{wnw1gg=dhe*b%s!T7)5O7j4~Uvf(+_FxcS&n9)xfI~k$E##|6 zTU>EJTZ=|YqX0j+(q5N+gAYTHPjovQW6tKCi5$bsE^m&8NAM@2D)e+@D$k9m$&?!R zF35~Qitu-Gt2C^?QDgGeJQj*=&kEfF5xaYV1v~Hl_tvW_|Mz;zT?b5pd+Vu9ti0n@ zq6jITycJW35KzasiM&^3Efa$ha#6LA+9dkW>Auhhh>x0@!*OPsWuI+ealY&*ed${~ z15NOsiS6#kj@&u*7P&nrX+0;ZxL%(TQb$g2dUM!{-~1C)e!KG>lK&xGX8@_Wi`yM59i&2VM|6q8H6G#*w1NG*Nj=@@w^}Q}95~=$ zWzlYcGY=tH@^1@;m&ajdTvqs&bINtL%z93Cka+j?Pq$He4dbUHNyt_Q=RUAUNz6%R zggY;bSoQR`zHs;dY^w3C%M;kF;IJwTt%8R`@&2!cH;o_7615VL{lnF_b7GUxVLhYfE{-<}7MO0-F|G zfJogtui5FQ8mQ|6_G?t>L0NALNLMoNt2PVLV&9jK4{ft1ae3^~wr*w&be^5MQDpKhi}(LQZ3aKhUNS};NT7Rl%NVwVyd;{@DbU9ZQ7#B~1)8ZHT{9Dy^cuc*q~eb` z(5m^bBoK@3QE z&&;P|aTEWs@Jf=*YPTAW?J$urRbqr>=|l2?YzzgD?E&9KrM&A<0#65aXO0;hpK%l@Np$@|ls0R`I81^N4jWpM$L3fe+J# zsr!S>N(w4>MJvoVFjM%-nk>sO08?P4uv(dNifIbjCmEUC>cVp zy_4W!UWPe_(YK#Z`riiwY!!cA0To}IL<}^1MN5v-+dk3p{|+_$a$PXJQv}rgZp_I zP=pvW97(Y#Z7)q0&-bbMUK=bbJ?f?YW(!Hl-PWltI`%A}%z(yC?=8ae+zTSmaKJrj z*{u@#L9+n~AWd(@qnkpgA^DGt1Q2VQ&MnQ!IDa4dYI<#mTICx^Qsn8q^10s~bM*A(36`6l3UX7_hfpp zE>7M>h;`eXB8}#eR>dT#9STpHk#^y7>z7`Y7g-&O#l=t%y0y|9nd;r}oRi$Ur*7k^ z!RH~+I{JgNRh|7j{wNajbfv%n>qpFej-?F&Dvf@vVLwN(ZVbJgVIOG4%_fO8mdBIl zdSWBG-B`*)EVV)PYKsD$dlxf%R`BGB8@v}lf!_EQ=UoDKn!Is(VV7{0&0W6L+O2I* zb22c+hgfZ@ZMNZ^zg%I5?Jp8l7y>RtZYJ-Bguv)uU-ZQv=nI37mB4)9-e)5#lW)Jm=8efD0(hTFNbyCz1@?_X zIv-!EJT7*)c?iFblDsd4*~}}~Ao1k%u_TsI@MH=Zs9Lh~&ET;TWTUx@x|vLb)gvNo zjCcPF_qd8to53(JG}n+IJyAO))zszdxyFp`ZagIe@r;YAg1+&@yu`hBjBBl*^pZ*@ zk?cg{h_%Q>Cc!3|$3>oznZPKZ;qLYggz_Z=Owy$Jo;l|6cz%g7$=Nx2SZix>hg6d* zA`h9}CK6fAI#Ql8zQJkUx27(h2s`iq=l(0{Go_`-;qyWAeNiE$*$|usOO9w(~9BjxZh0QyN1B;`k0f+*hMoK>-EZ=vy$@iS7pxh0}}M99xAS4*|&WZtd251-CqoA z(!%g5>kGBB zK);LI1ECWM^v1gZ^c8I4=5Hboapp7-jgzwV(!#6rLWk;FlNHiTzWe%OTyw&Jl*<9j z5SSygX*Q5?KI+;f?P%yT&4=FxIK>u1ka?UW7Z)KgFHcJ&cl2Drng_islZ{_71y9u( zyyj%qvtahBY&)iXq4#$@^P)H?v|4Bjg9-Qhyx2u=%d60(4VADXl`4BNN$cpP&Eq*h zMrIT~UY{lYkg#mAj+r<2GKuw9Lsz51!R6AB$c~Oh%Is=nluJ@QmGs45=>Bep3u({i zU7U;HsVF_^RZ|gMAtJy3fuG2&9Hj+AtgAs6RbcsEXJP!IcZcx;ac%CQhj@g76cYQv z#M>)R>%E~R5vx7=EL1uv970>2Z`*WLO2bIT>j z{vIq9A0{bFr4tEo%}MQXFqL8V&J>ct9YtoHf=L_=EPQ;cC37uy}t-Icv)1dU*AJ}{6X`e5VrYc@1jjL`FBmU0*(AR1KIHI`G<0yzPfd1E3epk zca?;)i(l2?YIUmt(=;azDIN!OUP>i@Tcvp<9vOo$|T< z793J?5l1*bV%W~k=J*_YYyYcw_OfR6U>U-N_h1$M8kc1kXE$4SNKz}rHo4KMzhlx< ztn{ntBhYK`>#M2wKf|7qiM67f9a=MFDH6+K7uSUL`nHy)e$AohvTL?N{;=Q^*T$afZ>B_IjF|aZc;VTPg}gmI^%C(>|IMV&5WYanhSHO>@!Z zkLn<=TB4#^*C3XiTIAfXR7FQF!l1T{lDBZRGM|QxH!evFJ@ukt#g_1NGg5Kj(lRpNgFD@>IdiS1+6k24~42pu4hTugW3W7Oqli}u~VMk>JYg*!ebs%;m=2n)3**rsuscB2Cug!%O(~8)1se1M>$!{9c zXaB-HIVt%&?lvBDu7Q0nzV>Uk?6cr?>>Pt`g~~+vHf1=sBag@&2NNw!pWkV&@*V6E zLk#E2Be?Je9a_Le3~LS6h14PlfPaCoR$-AJ=B@QR&-K#g6E^6P7eXpP2x|}0Ma^AT zAd8NguQF*60(<1l;(m-p>N(xoxOgmIcnex#?jHy`Jcz+=T!f0e2D zEM~Jr&iu0L3)c#DDWW_d*N4$9iHGO_)l+oKo@eB$|=x;kFw^&+nxANf#MpM^z;IeGa|%w7fyfUm4>Z2fu8F@$mMK?CCiL4r;%SdlnQho#7Z>p zO5&-+#lXv2U<|Sy{QV)$**a>Hhr=`>`of7qyf~grUMAOI{FAQgihx~ z`OFLPGC4}C`eDMte2F9~AC|s^GXg$n**ffMoKk-QlN@CJV3;O4$xgvdk$rNI;t2P3g|s`QeXeivLpEpYBDr3P#mfK9xU^jE*F zO^D!Sph_<`5?b=C8aE&t)^OmU#ET+6PH)sS@84Fd-URlNYiVzMKJ!37N1Q+CQ#xzG zJKWG>G(=$i9t}dMZHO9}nm+6c@;|uPz=tC*las#&<|$(Pj72vX^u~TdAS`P3yCaXV zORWP6kJJMeet)T|Q;@?D2PIptl+|RaH}MGsD7NPJiS4M7B0kbQ>Z?lWSNxnC>PFzy z5sJRdV{*kug8z~J>x>Ucb2`hc6+OsO;*jS~L<9m?vGglE2J`w9Y2#k&_YP;D9htN` z%2-A+giew&IU3&qZYPW6(oz2(v@1Pdz6`)09KfWB6#g#EDum@#m#iH8(p0XKsubyo zp0Py*hD9l5n`-Ke%UI&)OmWP%lr?Ex9{N_eAQmZWGiS$1jCUFp4PNN1V&-^ouj4YNVPnv+#jt)z!( z-8=gS1V62x_8kJ?c7|}thClW3QK;K+^G$=2>nkRmkd{!sh=i-EGi?aS9Xvxj{WRir z)TaBz>Oj(@sPg4pBzW4`=iSvIhYM=E|DI~nb_gZyDOLlm`uWM_mIm1fNUQ6PkZ?|x z3~B#xrtk>eUsxcmc!kf9-wqA59Pn3-56|pddC|q9fg^PWiKoj)%mFQ_=%%+)IU32{{C$En-y9-{Yo(tWlpD?CQ==6 znV2D6xo?gW7Lu4gvC0B@s@42L+#xziQ4lY$^S;)T0vrI@+ABc|eJbXlM9O+-2^}C&i zQIjyY<-pxJj(Qh<9&~BLZELVO`EqBIDf@)ar0$%;uzyDw_(~_I=L&z`;C}P>Z6sZH(f|! z{TPtLtkGs4O##QDc$foB(0E(J&Sh~Vt?<201Cgyd&PL>FlO!8v@Kpw3Dm;VtH)${S z#4^v+fUAk_`Mkm&=!qe$<*mP?5vn_#^5Fm*w}XZIr~0*VQcd82Iflk?EN(UsN91wE!A7 zoN>1^PLgdAJID$-c|_d&i=)G`16PUzQQIFR!X{Kd5>HKM1q58yx38V1eVO<1;NcJJBhk{gShbE`d8Az+S zWv~I0>9*V4^g362)~F{3Bp%H?E!uP9Wc(1laY##L$S86Fl|G><*N18lA|G|W}++O`_`-4+X1X|XncaOidI{Ntz zV@%$9B}eoJ1Y&pCRt(aH5hO>n2jU|7KpP4E88>5`&S-pSuIfAIrjP-&>9UT}<=6dl zXkCG_>-E0@A@~yO?tLt_9@ZS9Psi*5NLt@qOw`a~pdZ%rFh0jXy%J&`W9G(nhD2z3LrX@NM;q0Oj{n3K3Fk5&YMi50 z4}>QS#C+wV*rlM~+uslVJxNA`zytRcZ4|q8x=B#zhRZ~o%eJKEQa%S@Wz@#eGTich z1vU=9pn*lE$QImsfgd^Eyec~c2jfXUdKQwVzjlEA>uz=Wyp4!36}bR%N||r9OUo~) zCGX=RIjGGoVYKd3elO+f{(~Opq1xG;DBMxhx?3Bj_k+7A=OdV*C2FU4$LA>C)|(~e z&b@U?tK$++&(Q{KoIG5QjnAK?RH?YdF`h)b@^C%bop#|)9Cfwd<;ya5d!vv(5b?Sp zhp(8$@-0XWy^kN~DpSRpxF+|kWG$PZC2&;!e-q4y7C!f=EVx*S(qI8(2~`D4|5 zXXu1BXk3T*&5G5X-|yt`AANu39E7z*z!sv zq=?iDUMHkbM#m^84IzL>om%d8FBn+kB|!)2e`Ac$!bfuTv*b-1OA%-m*|mrpui_ph zWXo_(qz7^qF6wbqCNb`*z_?t!()5Vm)&AfV%d_W)hNXgXr^%;XC=gGDMEc@AaXNMZ z&I}7mej^D}3AGW8xnd;P_tCK=?d?g%Ey5d$N+7+T6YEMJ;F^1#%_^QG6Wy)Ovn}HF z5vhB>*|3Lh*ANpcb%xiC{(3V$#=lNY9%R^4#U}D{kFp=8i@&w$)Fb;Ku01NRYOs)C zXU%#Zejzo(XYZLb+#)I?$ z6QS5MYB#}RBWYNcmS0=3n`{toHmz&)%bZc!U6H0%wI&N8UGV1G%ZlG^yHjkjr+sl8 z7kP1Ex-kx_V{?)3ywyrsO%}=PI(j_Xl6eZcWJeaYk;aWEKRWnQ!z-;*pvY{$zZ7Px zH|J<)-R#vSmjlqmImURA2>Qes%-DP-@v?{ECFa9*pY z)7NxhP&QrV|({A6<#b` zcHS?0-lLQGlA=U-FWa*GDQ;%BZ<>)AjCu9GO)fP}ydP8nbv8L3QiJNw zmp*_vXUm?zqI@aiyoFN(p_pH(OR1Kz-6At0Q9OnD=hhdLbG-K&5{2GHMRQMJbIPNw zV2ZZ$(E#ZK$i9b0O9;>L;7hqrYX`#2G^+mqEU=P&og@w^%+3!%@?Z8I2Q=Y`Es@3- z*-v6l_+v(Y!NJG)^HSv==e);`YFKNa#_r(S#o=1cJm={=|=-7 zRbM#~vD&dnTO@_KCZx<|3Y4Mxd>JxkAUFqrk?M7H+(Yj!gl?|Z*=Hj!bmPX|UHQMq zrqvMHAw^79$Q61NB=c*sX-3F#uZe>-;0Cg?XE;pxz$xraZAoA3*u~!wSdNG9>2O8b zrj|z~J;trkLo#} zGZa_Bqfr};?GgvuB$X?C9>#X-r@JHNc*7}Yl{+DzaVfiO&=&7W-hTVhkM5ClnHwPl zt3HbKnj$@WL|LIP+1#|z6T|?tJc&i?kPS?jV3A{K*XhxDBz=0I`u5j-IWS1K?%9b% zV(N1MXlt~wjN-qWK11Qjc<0hkNIUgSZw)UcMg`npf%pn#gV6s`)dP3zh1Oi3PS-xM@^uEv)-048%vc z*ZzfK+^lvKPK4|$yQ6Nl(k`oMuTHP ziV^F=f$N&d7B-1GZjhyGPPtJ|;Vby%gKF)$az{Oe0(?%p9p9 zo@o^KB13Y?Knm2_P}G}g|1GH-cz6jdw)}}ojKV!9xd1y*%iNWO#m#=Lo0%6knN9ud z#G?1mcB+O+Py{dKwy=>_=H!R}ZmT@wL*DhEa7+c;){V=#+j7HgZ~w=S*sj^{Zx4Bd zZdtZg_6zo#wQ`8Y4xAw0>JI;~q5Dlzqz~JMsr}@_gkYA8AW*`1&d$DK!s41FBoYwx zC*RA(sroF&fY)AMi2b)T7f;iF_K%eNpSsZiMwIRvSC=%k^w{w*4oG*k-_mGqKRetj z)dIHqWgt_z;7$;T=X{MSrxrg)!N1IFnXj9AdPDOW|CLB zpNtQ8R?;I~Rv=;;vx9PmZ^b?;QIoBbA1=Udp>eaKr(DNk;Jlm0{fB;W@cp^@?teKy z7{mhD20;VXz^akmIRy^c3q4xTQ-|D7{9MO9?u=1em;q1fUO7L4@7$@;fGnbxAhtW) zTojURBHrRY;qa6qkTj2h8y|@Hszrpq8mMs4QYS!-EvETr85Cj_`%=j5d%03G`)-cJ z!px$>wjlA&9PK;DHB@)~?Plzc|8MGaXA8DN@}u6Vd*I~0$EWV|muai1vG=e@5BofZ z0+6AnP3P%0led2|ty*)2g*jX!)vkKD)UGdZC(PtJx5VO}Y<!_gQ7__(A!N1pXi7<|jGvOiObK8Xk+i^UW+D2Y$C!p4YtOg-jWr49=e(X-0Wypjam-@l-+{eU1`wlB;(G# zVY}2^_X+Pc2Ec^8GG>s1+l=ylN!12Ky`DG2vLQen3|Re{R}CkbugPRF%=yCuhC^-l zNZK!b-r<^`k{o<>@`ekoR`Uw#oJ?AqnjR;E{3?Hw4)|Ipa;6PR>y7+Hx7?l&ib z!6C~T+c%L#Ji`I|sxV_cU5sdy=FUyo)mF1@JV$I8<|8xaN&@N@duEJGcgo@USyazc zY1yxAxwZ}AL93hyv(zu@9{*lx#+HZAu8O~-NsWR9!VMJU@%>Tmj6f$Ixqh3>aVYB9 z1J}^~P?a-%FV!ZguwXEnH87YhNo49MnMT>AuzmWcM=#Z$mbi=Ufgv2~TVG|G-)-aKmkrqu`RXER zoF-(y+jzr3v1At%zq;v=_qrw?sAw|xJB55>I>KEA&*67>a08-iIMEk1xa_(9$Cm)_ zSi!LEKpt_~+WCb02#XuVIg!qDUK*&9DHU#dkcFeKiy)7<3x0~tUdYcX9t{3zyUycP zu`~Q5-m-z{vTA6^kY=f?tJsTt5J#Z7xC@bGZ|wq=T24E$1(&fLoMz2^gy2t0;^ zoM;&Rk8y)xz2N5mwQpGDg)I)a5+Gs3ZLtPQ2Z4&IP)`$tP_R(%z)=_ zVW?>lu6w3|2`bC05-P@kVnYnRDF*ep4Te^k8;{T@u{klcm~y40SkWFOpsIJGnrVjJ zMJla@|K)4K|9yeU!3n@7BR<}bd5_+LZh1iWBi7aWeIG%u&!?Aw`rc*6P?@WsNIQv0 zJ3Vd^4nA-(iJBxGA6OsqeH9CNzBjsod&R1)5tg5Aq`F` zgjF72qp!^gP06EID-NZ&!6dWbbg!|^jihsRB3Hnvmz@x+5Zn+=; zu2k4|0TM_5o*x_8C5`U4Co4fK!R~govAYPsu$Yzc2hs3@u#Cf=eG-p3;*&_#TO)E%HRxgWQ;`=BNbX!%sV*EIqr7w;JJJudj~ zfo@w*&!11dGuvJc+sd0(fe7U*=;>l;qA&3E(wn@6?)tjw==9Y~7w-}FLHbJv_Umz* z{AGl-&25QxS%Xw#=L$p{Aa#GA=zX6!(dYft=Z)Cj_L?23{!ndth>wq-c5@AoTR=Cp z6(iGEKY@YapMK{p2>oAYv8ghY9XVfoU-kF_#|8W5hJWbYOca|INuWoKu z6RW?zKPY*Bx`%$I-CvFPMX8Tu|8k5k^I|#5>x#tdDwpWI9uT4Qczs+m?u#Vg1_C$q zg!_NeY_HAECud7iMxBR}p~4x^fq-OU{_9SgT)hzzOYPsx?K42;|JuLr_2u;SW4m?R zonHsnt&{FC5LhyOnAywGprbc&&Gde8?RoyV&gSgZ6_Y|i>KXl?sRB1sfMtkL=>nws zOp&(i;1=Z8>s+@3FrvG};lU=qjJRPu!KWf(TBEV%Oj~^54mwW=!tN zF5oRfZj+O+P8R}R#mLwyqXft*0Df|S6Q7I5TY|Hcr_3<}(EXs8Lcb}PYbr043MJjq(>2mBR z5PE})#s<8dPnMINguq*yL-cJzbB+$ryi!fhM4u1?gPcC=lsnS4261oyT{-o-h|N5U z&3y8I8_A*znAyAq>uk9u0{;lM_L(+C#Tm48=R=A1bLg7Usic$Xf4~v&0RF`7IeZ6TA)4y!e-;D+$JzWz$Pjs{L>^}AdH%lhS zQDWTv%s#73{qldC0T6qNsd~I~;m;X_b}3o*|JX?0nv&|8jI5w=m{efAOLQ}eYAUJ6 zf!6yON`<6GBdIAa67_Kv<=C8}tl53nk%(eSTIR0ktv7^lUf3_7!KHG3Pb*^-$o1TJ z5xuk%0SOxzwbKYZwg%g+52vlSgs-RCPw$slE!Mq@y0Eu1enW8USwa1u8vuu;U1JdN z{yrANRS|>#wUmK*a9O8E%ZkjaE5Mp8Yi|H4NnS;+!sS8sakCS7o)hdIZk3^m-QkKa*@+A*jGORyk{~p-}Z12(S>(0 z_1a(6JMWiEK6xW8$BE`(&04*x zyL#`cy`S1v?-O21IU~CuII@nD^ow!-b`|>l%ZBQ~_v$kO{+W`dh$Gs}g1EKTi#lXh zpOh(Ngg2OUHQubv8R#yPymK&@If_&ERU@`CBDfPjapw_=f2>JaaB!YX){N9Qz@FP8 z?C!sos1rm!LHgu9`vT0@^vi%?afjq$j&2&mS4H`sqQ{$NT9CPR%f8TOZ37=?`n#b4 zl6s7MbCvc;{WNacS!YS$smls=QvGzepI{0-T9h|J((Hy0LQsA;2%?ce+^y8;wGzRSCx zO?$urOmbHDr$m+C!C^ORh^Bp;<>~jV5k{2<#y^_{%RD7cJQ*BhHJ|z!>&!k_)8cL} z|418jf>7QbVln6Ngxu0zE%81~zKoktX#TKn&#h9f+X-#{N5u1b!A04F`~tOlqKINX zlq!_7IwRQMl=IaIe1-Xh4S1F^Ow1TT>*9i!Yw5(it8jJ~_Asx~q@$EwU{+{UZ?H-G@zu4)`KY~Qq9wXLhQ-yLh)NY<**XASGm ztY^O4jF%k{u6*YIi5OLv@txwk{u~d%eL_dQEn3-*a{m?2swnWgHfCvxZu5EE1ESmB zr|2{Y6Ih`cyJb&&m2X-Wa=xyKErn`qjqW)oyOZ*2s#IvV(oCPhWWl4yXlxe5ro7xE z-TZSSn`b#-7)IT=>maoCO4Bw^z4Ep8&UTW@xnOA9l%@n<^p+gnK%_IRAYEkUlgmpa zobv*<8C<@qgL9pRZVsC2VX3c7g1daO)i^7JzY8Ee>TiT+v%AXZ_l6Jkj*8;v+(qur zG&l{1#X~q|KuNPg21* zQ=Q-Qf_kt3sm&%8@D zzY|5h7w9=7jxwWg!ecs;k@>F4TsXtQ{Uu)3O_K+YoPCG5%DX(O)R0jgy(5JeVI94iXR(%DkSh4n&fw#R`I&2n$exRF zz<1&lfOy`W!bz7D=*Al2RF(Yxq*ygk#+N>P*jb&uj0cbKzug|E4ZbNFF#AZ|h}^#6KAI z)KInXr@#Sa1(!6W9T%fEKP zDv)YE2;(eAG{nCY8AI2k0%F@J^L@pdmxH+(K$#_=m6^59^679_(YLPbp@%jIFBE4* zeJN*(VOH0E+Y48{4l(mOpH_>}q2wYHb*oxl#x{c;lV|#HhOzV+{k|Ok?V(_?Fu! zPr(!S(9lZ20Q@m|#t+^`%Ll-$Ku}r~ZPU$GQk2+RLdoiDCW~JP*9?@mPP%qr+6}p~ zSI{S1nee(B$4aLzaT|VIF&=#4wsAGZ^f42UhAvw+{eF)8V%sMX>1%#uv#qd}zliB{ z0bt41s{Qlv(Zl0zJnih-^Xd8-yH=`R=jUOrX8hxn6kXO1PX#<6!I5(YA_H+0s!M%e z)O{&aC#i43eXZSab2kTZY!hWOBDrunnrx5^_2{d$JmK~c>4h1?hs)*3?iN)|O-+rt z^D|P+GjntO6Adg~M1}(Rk##jdK|3uY?F)F0re>yP%?Y9c`<=>Pg`}nFr78XUic>KK zN$r?_xIVD_il5YVo9oNvLzRz}2S3M)vm-UtR99oCX}0I4q>%A9MSR+4rkZ!>4B_iw zkog*sO5#Wpp;r@u)77hFXuGnw*`ohjUX;trNd<{b@=%z6Qv8Tr{_9tvVp8TyUajG1 z=f!@CNhu2pdP4{FL95)~&fL5|Nto+ookYc!uxkc7F;i7kg~D)&S$@4wpZfCkYkMN- z;9{QDgD61~QaHjNit60j$D&o5Gj;Q33JdB&y>vp0yKekbBi^*OrlRB_Gt2PI0*s6y z?UmP+TX0#Q_WELl5wo=FFBPE<&U{jYN3yNZ0GBR0(Raiiv8Ft*YhW zQla7PaBWA_>+C_1HO`T=$Qj?mG_=?yOUKb<@QY6BF7CDZ)>z-tHy< zVFp>Xur;-b`*IBwxl2v;mo0V1D-BJ}2CLNZUAUg6C`{>7zA{#saJg_d&U|C(G7w6m zJjN40!(hKpy~>fzlRV8HuPnwq2T#m=g_dKduSCDKuU#_X$78vY=K9<}UhO9aqGw6o>Xb&H1?r|(&%u{>aC37j}?7J z+PM#=L-U;T1|dv|re?ptvx_+bSqIGa>c!vLIjbJd4+~#!_*3B5L|u4ro>xR9e#T~# zKP5`tM)8`(KA>cZe{oNVfM)lQa`Uq%?EM^`f63=fMv5J*m(HKCf%M?g=0|SK{sp6* zxJ}VZu>PtI$b7aUVDT9fta{LF2iD`?40%DmFz!kvZs;(ceHIvU7k`b?;ErhG7jg2Q zXBxSBfSZzIlegSL5g(p~s-Zzl6D;y{Yk6OIF05HLa&aZLGU&@Fmu_GA(XAo0kxypT zFlfxkhWFc9ZDA=H^#a|d-Wj5;ujAH4u}*WK;*`C0=6Fs_7|ZkFgj;v!s1I5yeW_`nU5B`gxx<%Ggij1x zb>og_SnlLmPydZn_8)bZxINbk5zN_(a@)d;3L!=7Do70?Mz9OK+ z?g7Xw*qJjVs~eUX-{7LKyjUrALLWb+Et9BW2^+?Z#CgE%Ii&5%@XRdg1< zEHPHW_0iEU{v@CO4w)-pd}3!~$+WG4-hT-@lfy2|46FXMv=7bP`fV-eMC)E5HIQ&| zzxEs2BsL8!2z)%g#^pNgXr1Fk7$gNP{DJ9iDPld%l7oT5B)B(IC3R>}hK1BnEhXLcj#lNG)%kYjYwk%xJ%*~V9V+3*X(A!7NaN~Od?@)yH$Y1iGCIC>)aE3s~o^t z_g?xFSmh(_R>pg&X=GRcjS@=8M}2G{U)_1Nt^zv;FDH1s`4UOmcFd#4&$cOgi?k+^ zisUKc3GZAM{lZ8eiqaGTY>byg08Y-zqnD_s^U8g1g@DR>jp|mD_GtSvrfrLrsuTTx%o+kaZEm1vhwfu5u}1veC>#&d9l?cD?rEy&XISjO zQ8(d?{lN9eUl#wwQGR-xD%=_U(p#y>-oWLw7~jLTI5?-(%b|v#hGE_97m~VmUkQVt zQ4!45XB+YdDwgE@ttC?m>t4a>98I@E5y?;POP|JF7_SyJ1@|Ecd?@lMp$hO7FvNPQ z{Ov0U;v#V^R4?I3f#eAmq?(@Q#n7h;pP3v>byAzV*w-1?^w`a2l-46Y=QAT*ijVfb zwXL#yO(V+T7qPDo@yvTvw^NSqCm>o2!=D)4T*RDk8j%>elqQNH9SAm)h^!1gC zi;S1eclk7@CC4S&*e!FfyFBCJ9o$J0spQ@<6>$vfN!%C11BP!A9-gclc&^kx7WBpR2-ObL_aG>nyQU zv3&MjBaoF%s(FW^x-|-}JG{2L3k6(4N5S$90-u*_-9LY?!-Gha9ld!wf2Ma|=nu)y zik%34yW25?54Wd^7%qb7bw^=e#L^UEU7cpG(#gm5dHlnJE>X>L?^uoA*yn}_L1&)V z&gj%_m!!vj-c~6oY*7T=j~|wRoSgP<;ytpDxZH5kkD;-4WF@s?8gF!xY~*)H_#o~V zG&*C)w;~axeSMDR`_i@3@CeB^;|&^ytyej9fWjcG8M>eSCA~Z_Ey_f)jp04ZS-cKb za@#*pCg-^l($KH*-@;KC`kOB_Q9C>>A+X4f@m&wS*y_7@GyA*q{>K*4o!oe^qz0!* zy-SXFeQS8dcz7wjKg50c3s>c0=^ML+E-pISUgjuu#0iq&^IC2milY5@-tm>jzgavu z1SBw5U)|XBeYfRAAV3~>pz*yGM44sY7$Vb_#aboRuqU$l+5F3=_5X+gK+yp8@0+~> zk4x`(dZ2hFA?}M1t)2p5(~j`Q1R+k7^2Uwu$t@% zjx+a_IS%{vV1|)3OlT$n;Eyowz$-KImX!C=5y1yGFN&PW4Wq`HA?)58dUu`5M%90h zm#{rH1dYg(sX*1;N4#zOop-l?&E@RI4hZVEnoyN_)taeU_oW4%CYz}4&7R7s8|FAW zsv8!}>SIBEeyjEe?GM<1Z3D1Wgg;vWd3Db&Qe|`&2=NiY5zMQm=K}oEYT@!H1V}o= za3)+#?Nk%C!87HodtN8CD-i7QsaJ=1=N;jc+dt*k2xC};BQEt8iEyzvaSgwmHm_}6 z%@WGDhmBUD^%zP;FAMp2H;_uDFYy+dUWUAknaj9%`}GlgM9%bmz5mT+Hyjao(q!#e z5&P4PN%G8R*kemPv~(p2gt9r&<4x98xRe`0TElZ(_QN-CxuP>_e-JPfp8<9d=FJ6# zVyE;s`nyB~6Zu)dv4MOm$+)4Bbe!yoy&Cz+!5gj7HlS}avik7hm)v!nHV@^_~JS00J5(oOXI%u2{uYI+sn?Rz{+UCv^84G%8%cg z`m=~sK+Y6`_>708Qj1C(gT*&Wc|mCe{JF;BYuhb#&29K_6+SDEvl=&J{JnC@8R-ft z%Bs_X){qU&330+Oxfy&iWr6Rqv1NzX>$Q=@kE3+BA11WbA<&htz|hlr_9-mmwj&&u zYg@00ya+_(^IQXtgH_VqO@^{nJlT(uo<^v2ir(_Zl^r0XE?J~`79E(Pl!peF7PoCn zI}OvZeyoKL))g7nO0u5r z(k-inK7nHag^`lB4N^IfOZ=GA&a$QxyO8p4Y!!!u(5OpCf>TKrFv(^x$&yDu5pg$C z?OU)6t2UJ&u;FE%3r7tgv7{>TeYIrl*XpY@?60LQQN!O!c+8lh?wk1raq-i2Tq~xH zqo=8}<4PA>Hb}@t0#*)%Q(cI*+D~mYeuE;$u_X#Wn0jitnx*8C`oshz^B* zZFL7<7L^8SJIP1@SDVrD<5kTp$O3O3WU>BSV~o(z?hnKq%`_6%iY&7zijqy2>AKNY zyU;E=8=ur6UmO)Y=wj{H82(A4YR#b-0+nDqXa2b%CiR=ltg9p6XVaG8%JMUn9R2b# z!;?AV4`X9H!VjDh{dm-8(PQ3;;PosA$izq8PTMrA97Z5;DyLZr#wbUy?*+{gAF^#; zu8e-XJEh3bRyzlCMU6VSIlbBm!O`ZN5$xD;m2R|c$2HfNceG1H*_ei@P!7_Yk+}{c zWcC-MU>2SE&F*TDZRsSgKWIJjRSVv`2_xD=N@fw2OjgdgGf~yUw&s30F2(oHc`$^B zM(9I>j<1j55RwO_B^b$cW|xAGc`9*eY2?%lw!gB^$-&vGH?XB$4O%p(JydY-hL~i# zP+kQeDwZqj+t#hF98P*v7|@2(D1F$hpY=mWtdStbD~xDVjLG*pvQ69|Cvf%2I{U3L z8*E^Zs%{yF{)qD~#%j>=-s)67@j!xdXfjr-Mp@xP*0vp8hj9YTDr$FQzQD1sQ7cVN z;+myTp(U-p+wl~P?vR>wSlw@8OTiQV8Y}GOL_E4W&n7`Ii$`L{Q(UmSUaZ)rKk=^l zyZDZ$;iZRec8BfTX3w$Qly)gqnflef*^CBf(BxX+(3&~z!NT_6 z@JBH7%mZr0pb0_kzrs5>i~WOkkyjK=V-;{?h%q{gFei;OBwT7Rjux4j#?Oiya22oU zX1k=uZRc!yA4mmW-F`wtqa#cjw=JNVs=kOVArwzy0-k+|Z|l zZjq&VpE|*n+?YbQE}}~aGvRu@>Y(_2b-kB0YD^K*+d1X~D1HtXEYf%NzXdi(ASUpq zdM`~~Xo4O$?jqN|-g$wG(6+q{(Xgb@u9a44e~^8yt?`@TJ1Ecf%BP{I6v$eEJ0$wu zmJmK>(<(Bi8D!<5i9zz*?1Vr`Mc=%$^p}wAh~gg-M7+BfU}{898`-)Rw07T_NR%-W zG!V_p^B7XFv3RBfH6@EVTLUoB@UwypW^Itj(1?&xT?+&6QrKdSv;ys_;fGBbG4_E9 zZ&GV!9cIilscA_PU_}yOfA8 z3_@#zAG|a$YSHE9k_stN=UHoKK3#l?nc*=Kf8-A_&{%z~ZNO4yNCBN7qY~AfDIC#d zBAeTz-vEi4;|eMI);6MMe`TZ=hyn9^Sx%(a5k8g8efry`3(8ecXcS>Yu`k-1e*MZE zmgCx~^j>|M^*rlt2xdY!P4E&v=}|JQS*7w18*1qqIlOqXS6~IJ%u-&^sdneeSpF zthBuq8pH+u&$M9`PH_QrytHq2-0No%_L}+h-j;nzD|6p;7u|h2F5+@Y(rZDR88S3Mp`}9GF$d%=Z8O zPR?{WEQnl!=fk^uL*cY2TU89pnQDS_UO9ccN@-76lsu)cvwXcJo;vzCx)~cV6i#4P z5uKZNZr!xi0#sXbD|(>dUyTm`aMYT{^&K2%snazkAy}M}?YS(o&O#_L#^k+!5W`PM z>}d0vV7X)X+z;Kv9({UJKb*;GTaU(H7MWjkpkHe@xlr1hXD<)~SD6nJI0TrA^_7J< z+Kg&|2}_x+qv=(6lsS6}XM^{|;{wTr-f=ZE0|UoFeoo13M_EOg3&$f=%Wl`q9;sO1 zh(EEH@XxtJ?Wj(ge2SZ@S&qKPadyFmxiS}KeJsc;0dCvrt4o=&?urSNP-jn8u@9&% zHPwD-<83qrWL0ir0}o*W2(anf1^{q_XgpfY^280x=u9_jyNll&<#`-hV-M4V5 zgZu}yS*-4=VV)+zxzlSi9G#~ND^Ze7IK;m$-p=w!G+lb7Dk*%eCK0Y8MKJ58%3@6^ znv7cf@;4TMGs8kI*s=QjDnjHjOp8@iKrp}E0Vax2b&1E@>86*Vc67%K8j_{y7U6Qr zM?_)Qh-~G6;ULMwW$QCmwceKv5!u9)WdrwWTyt2?b0jv+GnWZ`@ani+Lklh<+ok*9 zCwKDM5Y^r(dXVX~NHrrYO0e*FHwE6%aZju=8>T|(LtMB#?zX?>nd;thx4O&(UMDgy z9=@ z@(sLY-scS|sHw0sj-F!qVeSZgf#A2!{n8IZhMAH9#p+va8u%oRB%dFCd+He&^Vne8 z89eN;b>z+4qNJ|9DyEdbNyA}8`1RhSHmJxg{^f^r*A1Zx`WLtyXzf&Y1g&b zuN^!Dw|za~W!kK*l`!-zMAxV)a9oaI9@epP4wWrt9Bh{cdY}$Bm>-MV_}KPKrDYY1 zp-pGsx^Zu#h8AW}xZ}X&C292h3%+(RygrYy2fg3JuBm$a-24>mX=!N1u|Cw4%u3e~ z_9f&i!C`iMEj2wj=!U{!Q8u^O%Pc49z)Nv0Zrh(D;)SxN|G07HIv?UP6~cxbB>|yd zT}OCi?@u@iw~+kwH`fxs1qdk{%54)v1{Qv~=OA{MV3(i2PwwwF;U$=s&k#q&sTZX; zva-oBs@kk%bl??y!}#dX4vxU$&R(*PW2%Fp+F+w=rpYfWk>li;OA|o$=@;S7DEpIbkj>KaSgFCUaDuIKU*c z=eE#8HazJ(hBa>8>~vtuU-SFBinj;_sbqKQ-bs_D;NV?C6Cy41ID-_sbph^8m zDF`DRv+^||JPoY*+}%obc+LlH#hL%~?Pt{bB}_O<;fAI2iIu|`Sb($d)@z`g7$P%! zYH_K_@p}5ho1)Z%i{-`-yf-!6#-28U&L-j+J?n)Pjs zKUpZ^Sk>V*Iybk(Y_58u0=31W$CR}84YxCc&->lJ3ndTl7nD6O2yyKB+;3U zNjLV=r8%i|z&+>oPS$r4^h=;3vZ}Z< zu(%V@&6C=ElMipEr^=3v;d{@;(ehMHW)51PJ|TqbG&kgF7UpEudv)+i4B(+mqd&+Y zhd-RFgaMaG0^sIU556eFQ?JUMqV<_^-TCRq1p}}FbUCuO;Xz@t5yaacFqRjVd;)}TmykF(C zb(2rmXBR&1^N7o1eI=9qoUaDhQAT8)yQ`CEqJypErys}!NIPSFwJ!A<*E-J?po@>M zx*sfQk&+gjOC<-AoUcVr9{I&S8~oh*>b{J~9WMI&ToIMlTFPAiPM+h4TzqahX~9A7 zUL!D+d@i7J_YgeSYaEPSlK{eV|U2ySr;1o{=mbQgd)LZyK3HmI;$(kN>fD zOo9E|;Y4l{O0;YSL$Q>Q@%u`e1w4}EhsNezdv!@z8Mk@fY|WC4txfEpbLuFf4ion} z%;7Fhx)hf)le?iows3l#dy$wvN+@B-u-ulQ_YAFrvr~tSc`4r6MueA>8o^LFG247* zhk#fVcN+2I7QdZ9z|AK`Zd2tWPdNu&+5s%Cf@rCH&cS_7(=j3hOF zz_Ht-v$NtxM%(5A&v=#@3WTE%#q@GsT zQ&}XxU-aUh)t~$AFd=2W(*6ne;f%&Nn5BU=ertE$uB?Wjv>^FdGxFNjum=yG95b^Z zO=~pnS()`j95?1!U{&w5IHwydY@>qPXahdk@#j2yC z%mJM|a|?pe2m)Uj5W1%OVX{njwZ3O=(2WO5f|7e}%5s*uH2o@abbS^R)Hu_f9ry6y z4_$zMHn@b+=!>g47p-UqGK^kZmb{FeK@S}c50~Y-9K}|!}1QEd|FKoAwWgs>~VLeSi~O=<8zROGt`rLgeo%|&~wEkvNHs0+k)tMrPzklVrML%c8=S` zEv`=@U^xqj%>o70QPh5e-JkSP6XXbZB=ZM+#lZZP=TuSwT#6NhJ)H>V{cm{{__k$0 zfdi@Id9u(Wv$MT9lJPML$iJdc`z!EmzRTP3E? zGbrhy-(BUtkKi9~h{&}ATamGUZMIr|5lN_+ni7HxUjvgo0t(uW@H5=2y6hp{pN5!?`SS%gVf zr}cz<97|z+#W$fI@U`bdJY05Lp(2;T3oR|l2rs^U`{tr6{M__wHyeVEey8j1^Y^Jj z&g4m$ALOlW@+B3}_;ypGvzB$jDOQRVFd>qnCs;lXMRE1$m?aK}!n%&$@b|wyUKtZ) zplh}{imBwVvIUey<~S(9A7QoEzF8T6RSnN`a^MhFBZ->OuBxgEr{#G*$U!4S${e1- zQOwQ5*p7-n+5-7FvUR>b~1CzqI1yt%Xq5 zeK@MoA*--vkb!&;p>3FhC@N#t-fc0}2&}ci{WPO|w504>B6c5tFsPGXY4HvkUZ5qh z>l+zkdC}C=M5kQ#17PvjZ{OG?<$Ak`JO?P#+@LPpr8lOSfBu+8Cw-npH9_PaOOFcz z^Kt{9C`yQGF1LRP>(5~*j$s!jA5!I-%TTO{#`;86zZ6vSpN!_>C|ZR6=Brtx(5A7$ z&SX!<*y0U~2p3QLQot2_yM+h*l4g;GM40S{VECAxpAR%`fN7T(~Lz`&E`4=SDD%fjw`b z$qgkWB@y6!ri%*;3UG^_N|;$mrr&tdYyh3G?Na_3ZD6P@f-`DDyi6KDpXr%<%SW`w zfdm#7{Dhujlbd9OToXV@kQ_A}^QV`x4z_F*{X={bW+sW2kRD(lV>wLG$It}@1=gJS z5;Vcq53jDZKlA|A-UrhjX4A@DF85l=8dI^KmnqN^@X1#`>ucUU#~mY71H+QnFheCy zI7kZS#eO5Ns>)s4SWpl=S*TR$e7e@k{@=@BD+zuC1}=CUHJ-~nA2#@+M6;<+Nz0wB zA9ZmFZc7R~)s5)G2ctGXuGHD@Mp>!`{quEFKhaKrsj^P!cJisOukS^z+by$&g+(R) z=;7hT?zkSsGW;8|)z}|c{|=8cHXZn{ZjkS4Mvp@ZjDjuJ7V^)NdODtw1&M7^(m>!< z5ZT`6f5@F3@%)1S+V^yT^#3(6!asff-i?9>X!hUDzzwheXI;O1n130#@TJ5jy)sI% zGA62Fr&-scmL2w$xvlPyt#iA>0ZrCpD#e`V!LP$F|IQOYV#QIvWUK*0akQ?}E1>Al zyGF4dU#v>|1~zRZD5LSmYcKb`y+RkdODG6IrAe(Y4xQFJ*4miEpj5OjT*Q1^cX@y0 z)V!V*!4H*QQ{x1b3jeqDqQs_0*5!?Sx@@H|Wq^6rq&MiuI!(*U6gG=2xG^<7Ki>~< zxX$IW;6DN|TLD9{iy>GZN7fxYoW?X*V>K^HzdyC@X@6f37u?;Se-iig(HRLMqyIt-EHBx)^~y*f zR30LX;g$8!?|GEFX1%3~axC)OH8a`P3U)Kqw!jf|)j7ckZVIi>A`o^`kXxnieh|aK zXwX&P*ZGx7HcId<#`R9mqtV|zucR6jKJ^8Zm9PV{?MpV8ARG+$OkTgB{>x+%4pDMr z{UK(2gI@vB`X}0z+^_gCGIlyCmON%)=%Pv|R_0AeJ- zG~clk;{B8yZLEXyv#Lz8O(uF3LJotz{)Gl2`&q5qea@YP^kdlwJ1cyIn zi3F78|Etgs6n}vILW9Y4dTQJyGpKJ3teCGSCtu2LbCqrZ)omj6TlOzIQ4@H>e#F=H ze^547QGZ#{jk~Lilli#nbx`l67eeGD%5o}KIHBBu!mi`VKNBAVM^*N;V+I|4Vq*EcAYi1!tKlFv;Xjt`SU zQF-(|G27hB^(A!D`g{SoC8Fr-Rx%?-b+d0(xv49AUOu?noRl+p|1Bh`RFRhc1p|XR z-CuMtQ9&^IUtiKJHI%$uoUu{+xOx&cPKHK3H>@OgdiJxE3-NW~E+~r3<_nuS|2Lp` z#)+@DWHhIix9ju?g34j7k}|7@@h8u*rVhh~5`WaCGCCvPZm%JA~+|wxGrNe{t;k5~{mo(x`@k75)BuGTle7pz;sWrqevidzGMsL-tST zn-idG^cZ<1?;pJM>p!1`y;x;Ysb!vGU&r5;zWkphg`R=NYP;WGjb1=U$?aS{XKfMs z)^)B|+wW2kYgJDN_v(hq6E+kIQ3?x;RS21%$zPC{nDl2}V-OHUzAY>LowphLsx<{8 zX8TPjK6by^tHZ;>UQ1vL;2#ftLul1Pvol}1Eh>HBQR|ro_$l^8+#+JuXYg}3XLY`f z$4`%++4{Cj*^+QULnG?>MdS)is%u@kd%wn?XkN>*3<#(Yz>upNX#s;$N3K}Q%`vex zt-#A+;gv0pcJ9Gaqkt+51FDsNY;d`x;p1~T5d4?sTWPQWnrf;f@C_6L=g3n#9xn~% zN+&5dI38AAx!>Q|jP0_HI4RjJR$cMexWU{zLLJ7@tBI(n;Jk=u)XFU`wh&Hw0=weG zV|h5aKqm`5?nMx|6<+r#DB_BqNUb&O16fZZV<#?OCS* zh8$PGsY)D6O-LH!eoD?W)0pSTwu$I?<<&rN3klD@iqjDF}3yg-?wcz zW&)aZKoU4H25Kcw;9>W-_{~4?3OPV8R|x&zH$~3-0y>4+iVGk4IY06_dU|Yek+0T` z_!jJZsvDd3cSMnma=@o-6?YT5zWFiC4+(7#K>2fmSgW`a{8azI{^22ce1ByBCJ@+d zWypj7_xX)fzYbpr3!mjwRmDJ#8X}&%4huZt|B#|!sntZdnLTeS=yIFrcBm6U1o2J)lbS|gR#`y1{^3P+bE*GgYyJ+~k^f!{8zoZl?CIhFWpuiL} z^S`0b2R+|8F4kCQdJM~7=jkX# ze^Zyf2*t9~UdAF-;58VXc%Jp<3=w!|xV@YsLORx&U!c%cq^!)9iDp3uNPC-mluIg#kKE+Go~ zlRE-9i~h!#yoy#(6!T3Bv&PMJz;E@}jYJuSR_Fv+EXnSf-eONy?2AOXy<{}MojYX) zy+jHGO0q7L$y4C@UMOR!A{+*dM6$J1e2DvoK6l*C)kSp+pd4>TP}IRoTevHv_ie+R zOqDi!Q>-h_Sx8S6V9*rLCtd+fv5gJOWZ2>f&iQ;vUnZ1kG|s7^S(J>cAjjk+5?_v) zl6l!JV*+rycu_04k{D$ar>4YcMK6FytY8qpku5YY`kAfG-=Hq79W=CBGYNJYhOAU# zjZW^tu>0SH!b2$ci?{ z!5uHm?5^R#xrf1J4Tk-5Im(quB(J*A;1$|hsS6I1=7XDWBA>~gmOEYqQcsTYlDbbb zr^q-Q%IX6X?>yc~$DWNc0ZiI)`rgSrClaw!F<$q7KxtHRWQLt}45ZUD%c&A@y-6d8 z2g&SfloJ|cLXj@k!T0+SoB7=g<6G4TD5q4E7Ki-)6Y1#G;xAbD?fxbf@9X8etAy|E zq8g$YqD!y!IDV9HdR_99lvb~LYM*H_{j>IPk|=b5^&F`d=;f;RvoGf%s~RzRg1{ov zqq7={xhqSvZww)-j;S77^h(+HDz^2#J1%D`@*1sJ6z*u==X-7Rt8E|mUZ)>WJd-@M zVgzB4u%VOhaS1Imj<5(it|p?3EVDgs2Rj{8q-Y=cOx)o2ZQi}8g9(GDcZ0tN`n_nE zxs-evDul`nr_0d<<8jb>(2S$QyVnU+_DLyK_wJf*dD1n|IwMG*5n7=(=1WcVPya{E z>r;h2%l}9<3Axh|rX4s?8`+=$P_gvj2r@_>|9;e<+co+jk6%W|v&ZJ44T|znC`5kC${c!YWtY!!>f1vILDmI}c-^~E3mwd(;8nG`=Avyn z@ni+0(sy4E+T3N)jaXKoLOaQ4N+3v9@8Oj0`sOZ@$rGeT!v<~gB0`XDajkZEIaB%?S1kc{Xg3vvVWDKr3O*e+sa#nl4>o< zgl)Q_Bsu|TZ6{7Ka`g7N+`xx|*o~ekPC_ws0lTcxRTWhy-<_pLb_)TiFU@&+J!A#Z zMos8#o?}A#rTcgDFn-ARRdyh=88{7sDkmOmDShN`mG4ALe6B*izWR6fMIrS^uhu!x zmw$~4MIF9qu92@gdObSju$dcuvc*l5%JLp}NJBC@FZ_t~g796KvBk>b7HPw>?8SZc z)gQoB#rS(5$wRR21rpvN5Y>>qrOxLStw(l%81kVWBGMaCKr6CxO9u97fKb>F6tsvh zD*E(4pUg!EYW|-+YESmgsva=8 zfia$r*H(tlIT-kcl3*_BwVz7`u5?l@YP5v)wT0%42<=qUwQ69*7$IGCW@TZSR7yr(i~;~*w;$DLR9=+ZE+T>5));Wk>z`31*W&`Wcg zNpWAizzh`^{-nTT9?G+^kVyG^PL|2 z^4^2(z@;qzEm;UAec$|Jn(Gml)cA%UmS)d9|Gzk8i|3C4;jcda|Dh>109>6N9G!17 z4JG5$>9%^0E~BU{@hHwS&B^8-ukMR1PAflzj@A&|Yz;pppLnZzT_aK&+ac9?b)oNHL*izZG^_IIXt9GN{-7eERVhJ{ih+NRB8| z>k1TRxaB0-0!kU!^@2oqcKY@;yRT$^jOD39G=YO6FSU`1`6}Q2Z&r!{v+q(ZMnQ+a zGrhP~Wvb5|?=64vL6E=V#*JL3?jczSbrw^^L5q4%e(4&hlLadr3QUb;Y8xW zjO1Fc+fH52&r8j$t4laKI+{f`^1v;Y3i}u2^jJ`NBHXC+6zBE*_FVGgQr_um0l$~h z7DpeI>w7=UI&L`R_=<$N9UwE1u$c}dsXb$^vol+d(-5tb)c~R)N8^9>4+-<|h7F7x z0;ug>kZb@W$H|dZ#v|(gx&Oy`QG{3wWl(-T_bkEk=Q7%6{Uf=FFKboZibLR0<>&YQ5 zGl|Hh+v@M&ZPj{~$%y{X+Q|=EOW?CG-|D_cP~k(viff3xV;_OsFva=1M+s8f2q?I0%zW z?wF3Sy-G0`hx1bs^+5+VBbpF*8e7}pts9NtXoz&rM_>=eqR@lA6GY+=?FxG1i22#hvCJ_hx==cd-Zb|^#t0Sp}=!3^NvzmBM{v^ zpKy2-S5@_aQ)Dm=Z{~G0>l2-XT15k6o4UVnJi+l##m}ANTFuXf0DiRg6$z!~eSMNo zdkQ~-ul+$~J6+-PP)J@_33!&QP>&)@?$;X6zem6joB%m)_O#Z&NAWoE*`M3|v5Y)_ zg}36BG*|fVqz@c0xRq?V))zCB#+URD)%R@idD0Gz%3JUapB|~wi4p!a`KgTg)iBZf zJ9JkqO&+Ygq1oh`FO+@NS$?@;eN`a~H2hEZb_{@Xhdqhl`pIiLLCWwxy!#Zg{FEvb zfNZlf^8ToH9T~89-pn^Yr~%j9)&Dk9`rsZdsK=(a-%4vuo}}5P^Jb+FB;QobGVOuf zMg#}8^4yCb=F-oS{n(bW3%+kT_k3ED;+Ybebj3ZD(W_o4R7Jo z{w0N!$|Kqd?Zb_Srq5HEPY>p{Hrf(5)_eO*-#)#EP0iPUDjSaK^=f*dteZ!MLz~?!*PShr?0#sd4tFZ(GKK;yHzaoKvhg)1$qAO6x;!*b`$P3t}jZaOn z_oM!6Lk1iv_v9;x_!Bkkqm2T>gX=hSKNc`PEGjfl`C6HH@{EUAIgo-y`)tgS$Ipt= zx>6h_N@z*--<6*b;-wl1!Z3>L9zn&0Hc1*)qv%EBT_8Ju^ybt zJ-)_<#r(zK#)wR`%E-)dad9C<<;6c$&)9r#3qsNHWl;-&+K|GenL6nxZV{8q*?j_CfbPEEx^IZLHFt0Ge>^r zarkN1mF0xK=ILo)ezH9t$&6>NeiW3Zu)JQ>kf8i{(sUeY%Uu@<&^3$)3cRo8+53cD zb9_;a@_72j>C%I5>kjY~MSTvz+_ZQa=DWtvH92cTWZd}2?+8f3bB#w4z^U*H{CKxd zO*vxq+0W1Kt3*0p*T6to8Q`kKqgV+E4xXuZparADPAin+cPaO8Q?tC6iE`m1vj z)BwF$hwxm-BnEA#M)wwo^Tm|nG~ri-dKlt4PCjh^^>&=K4)8AoZhD?`c(VL*W~3Ua z5&f?}uEDPj(D?j3&#K&(UU9>>{+iHu;^xsi*W)H9fEitH80Swr&}GXU_7!PpXbh=I z{_7bL^CO;Xd%v_fRiVPI%Ah8*t*uQwjGYKHf;j-z0It{d&4?h#m0 zsasoH^QIHc|4EfbUc>teGED^3+mSZbmOUn$<5%)c13%80be&Hbl7yWUy=QRHj}v)w z(}oYTuJqYNJ@oU|w_lFQ2IN;slckbHrW`t7L(Zb`hY8JykKWkn`*5*rzmHHXQSaqB zZe*F)3AMgnbdsep;dgsDiK4JILxh269|sYB1aT zmz?~TIcyxgFmA&ts)|7rW@b`Hc>mG#+-^vJLOh zJ!@2}-un}r-Q<%{@6&YOEOKR)*9x>>m)v)Twv(*}++H1F576*Bvu8 z0wOg!+6Jw4|EsR+fNCmfqqL>Tf&_&~FVZAJDAGlWNKXV=ih#6GBmxnnOEt8mgP<4$ zktQxRh=4!RHDx>rtqEnb*U;U~;X|-baQ08i%a!!GThvIHE|e0pJ`t|` zicT#lY!^im)?01THgBWjxIBy^!0o$j2Z9R+t^1m5F!ZReg?3KGoZC)P_S+E-wIHG{ zdOYo1a^%O{QZ*L>AdyN~K3=>;{PKcWWlom(i6ul8!hm1GajtCD^!ThY*Usdbr{k)% z=a(7s&?*6!F~_d7F*c&O&vYtj-Jr33&=8y8%e+8qVI^%gByxksAyODP>LEA@*;QrX z5csls!qtUyc24B#sPP*UWxP1EkGE(&PLSQe(3hF(8si5LX^LCC>7~)u5JM%3xOd@qUGn<~Q{)!I3Td-Mm<-*5`bUl_|Z9(2@q!zq&tL&%q7a!md4dGYzG zd;iwW$<9lw+*r2(ZXg`0i)P6FZ!Bg3RM?V8BwVt$itFm*=52^|cId>vddm@v5==RM zd%$JR!TOVCK}l(3HidHn4Z;WBtBbtYqGMzv?Z&a~``hK1nNJd!flQKN`fhl-(}6O< zo|AB3oE{L&NPLcA*U;|-tv%0{9mau9zpYD;EjC0r*o<0Rc{EPjPWlVJq}SmIeRB1+ zX&B=fR%28pztoj0F|9S2)wv~PiOvTP9V`TG!t$CdqoTFue{*ug&Ytk+yPbE~_Usi6 zNiNMGMQ^G_0+?jebU;)@?(g#wZ~u{Di4{jJ{?QW?>L+R5!|^RR!(wiPO>Z(e*9MZ;w)W?wmeTgth{w z6CZ_zE%#_Ne^z`@>}<`pWa6wTfvSprk+pCm^GK>MnH-t9!3Ge93t4c$84uUWU4i}# zVH?Y-E!%m?uTc>HmGD(otEz*5Xj-*nQKW9jM|w)^M3}ng!6m$Md27B(h%_l0^-8J63%!8!P{eKLk2UF+J8neWtRVULOZZ`V)Uos)o7By}uY zA5cZX5mKSDX6j3ip0!;J{n#34(PTc{JxZxUx#oF^s*RFdG7%Gav!CA!&^bRYdNZ^% ziCo+s5Lph~%0||PLX4j?>|J`KF$1;>XJFyH>S*?gT_~W}1j=eG6^ifbPaQAh@~}>y zEU-gIkRIL&IoYeIGu=!#maimV3$>cyy1H8EqsP=S6mY+rk#PnruGgTj<`ZDiP?-~m zVbRxD_2!<5Qd7!bVp7JMw+;;8&Id5C{#qf6T4kQ2Q4ka5Ep5N!8z8WaAxcRrL%FAF z({iGO0tIz}^IM;fJ5RDz!!$`HZ2}j-w#OebK%Wl#TLqx`XKb71pdC+-EH9%Y54nkmn zUFUnSs|!InCN;iD`trUT08j0g1U9VVfWPE8Jsbc0DBorzN&{THPk*M@%Mo}hW~|&w zU1(z-!rz?Iq};V?L=IB~#%~(NdhD3I8CR6Otbs&U?qWhQK->dvC;!i{#eoOh9S*|j z!QmW^5nsh=0L8(5eZISnzvRcbkiu&J8gO`yLEKa>^otKqG?(DLDxaEixp<_f{!6?vvH zda#@^rt&&A_e2HDo5sG>fM+?{bDX>rfIUCei2^1G`a#M%~Fe6^)Kx}pYAtmLAfj;rgX+ghH!3MY% zb~Je;B&(%oS9N((=w5Bdj3x2>WDhumx z%FP##ha|RTlx|!G!)a~GcoS|r&DpCXBnhw=LSCo8C)4Iio!gsQua+v>E>U%pJ7?~| zW}j?Pzu6y9tEP;8VuJWIjl&r8Az-COC&&B|ZS;oNFXiqazMuv0TVWo_$vKJdUgC`D z!6nh;3Z^ffr*=gu(iHEKF2q!WD_rZx9@d~Lk&>V~F3tD73|Ipq^TRdJH4jrtF%U4P zPsex4e|!O0RZb-zJs%Ct*b;0#e#Mc-o*&Cq#5Phy36qvB#P_=_X66kwJ&{@U zb**!i<1cH`(P62|rcaCqkz!|VIX1jYnGh6S+w^Hc%B*Q#N%N;$YDWd5c6yzseLD>i zbM|@UO>XPJ`kl%e2+ECiiXjx(gwdB)=;j$GcO>Ry^kKd}mdtgJspjU?eBWtBlRL5O z$sl#hJQA-@e#1WBOEAoGlJU^O8kl z0?>7#t%a6c8^6m~Wo^$S&?+#`kf)^d0PH&efD0O%Ccj09f%uPHs-QBHF*4lz=2XT0 zM4zJc4H)08lA6^ZCm9;N-*d6VUl4Gm;~_$WC9-ECEz>kkN;-=t?u%aPshP7`5PR15 zs7Op>KlK>@-BT>{4wNs=3dNN&MbGGER66c7y*2LSla>m6PiW+8JFoM7eixJC70b6^ z$<-H~1?+>v665TE`8b&H^ywMXH~gkJxoa)=fBVB~$j|a9%llu6FldjQyyR)kX9bTV zxd_b}(B2LPu!VaVi+G$);t+d*-Ti;H%?|JRZF<9~I~^2sSnwE!bFIM@My!{WE5> zV|(e)DaQ-zpZ)^KLv>5Ql3c3{UcjjI_32Sev4nhDSy>q}8CfEm2R(hz74%ZT%l|DVml{%2N0a!;$Zf|Hz+ETM<84yn@uTU* z($!P~yY|r=pg?H7W(KO~-pp}ZCwLUlu6 Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure\n state + +'' Vector Map +vector_map -left-> behavior_planner : vector map + +'' Autoware API <-> Infrastructure +autoware_api -up-> fms : lock\n request +fms -down-> autoware_api : right-of-way\n state + +autoware_api -up-> automatic_shutter : approach\n notification +automatic_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> manual_shutter : open/close\n command +manual_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> remote_controllable_traffic_light : light change\n command +remote_controllable_traffic_light -down-> autoware_api : light\n state + +autoware_api -up-> warning_light : activation\n command +warning_light -down-> autoware_api : warning light\n state + +' Layout +'' Infrastructure +fms -[hidden]right-> automatic_shutter +automatic_shutter -[hidden]right-> manual_shutter +manual_shutter -[hidden]right-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]right-> warning_light + +@enduml +``` + +Planner and each infrastructure communicate with each other using common abstracted messages. + +- Special handling for each infrastructure is not scalable. The interface is defined as an Autoware API. +- The requirements for each infrastructure are slightly different, but will be handled flexibly. + +FMS: Intersection coordination when multiple vehicles are in operation and the relevant lane is occupied + +- Automatic shutter: Open the shutter when approaching/close it when leaving +- Manual shutter: Have the driver open and close the shutter. +- Remote control signal: Have the driver change the signal status to match the direction of travel. +- Warning light: Activate the warning light + +Support different communication methods for different infrastructures + +- HTTP +- Bluetooth +- ZigBee + +Have different meta-information for each geographic location + +- Associated lane ID +- Hardware ID +- Communication method + +FMS: Fleet Management System + +```plantuml +@startuml +!theme cerulean-outline + +' Component +node "Autoware ECU" as autoware_ecu { +component "Behavior Planner" as behavior_planner +component "Autoware API" as autoware_api +component "Web.Auto Agent" as web_auto_agent +note right of web_auto_agent : (fms_bridge) +database "Vector Map" as vector_map + +package "Infrastructure Bridges" as infrastructure_bridges { + component "Automatic Shutter Bridge" as automatic_shutter_bridge + component "Manual Shutter Bridge" as manual_shutter_bridge + component "Remove Controllable Traffic Light Bridge" as remote_controllable_traffic_light_bridge + component "Warning Light Bridge" as warning_light_bridge +} +} + +cloud "FMS" as fms { + component "FMS Gateway" as fms_gateway + + component "Intersection Arbitrator" as intersection_arbitrator + database "Intersection Lock Table" as intersection_lock_table + + component "Vector Map Builder" as vector_map_builder + database "Vector Map Database" as vector_map_database +} + +package "Infrastructures" as infrastructures { + node "Automatic Shutter" as automatic_shutter + node "Manual Shutter" as manual_shutter + node "Remote Controllable Traffic Light" as remote_controllable_traffic_light + node "Warning Light" as warning_light +} + +' Relationship +'' Behavior Planner <-> Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Web.Auto +autoware_api -up-> web_auto_agent : infrastructure\n command +web_auto_agent -down-> autoware_api : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Infrastructure Bridge +autoware_api -right-> infrastructure_bridges : infrastructure\n command +infrastructure_bridges -left-> autoware_api : infrastructure state\n as virtual traffic light + +'' Infrastructure Bridge <-> Infrastructure +automatic_shutter_bridge -right-> automatic_shutter : approach notification +automatic_shutter -left-> automatic_shutter_bridge : shutter state + +manual_shutter_bridge -right-> manual_shutter : open/close command +manual_shutter -left-> manual_shutter_bridge : shutter state + +remote_controllable_traffic_light_bridge -right-> remote_controllable_traffic_light : light change command +remote_controllable_traffic_light -left-> remote_controllable_traffic_light_bridge : light state + +warning_light_bridge -right-> warning_light : activation command +warning_light -left-> warning_light_bridge : warning light state + +'' Web.Auto +web_auto_agent -up-> fms_gateway : infrastructure\n command +fms_gateway -down-> web_auto_agent : infrastructure state\n as virtual traffic light + +fms_gateway -up-> intersection_arbitrator : lock request +intersection_arbitrator -down-> fms_gateway : right-of-way state + +intersection_arbitrator -up-> intersection_lock_table : lock request +intersection_lock_table -down-> intersection_arbitrator : lock result + +vector_map_builder -down-> vector_map_database : create vector map +vector_map_database -left-> intersection_arbitrator : vector map + +'' Vector Map +vector_map_database .down.> web_auto_agent : vector map +web_auto_agent -left-> vector_map : vector map +vector_map -down-> behavior_planner : vector map + +' Layout +'' Infrastructure Bridge +automatic_shutter_bridge -[hidden]down-> manual_shutter_bridge +manual_shutter_bridge -[hidden]down-> remote_controllable_traffic_light_bridge +remote_controllable_traffic_light_bridge -[hidden]down-> warning_light_bridge + +'' Infrastructure +automatic_shutter -[hidden]down-> manual_shutter +manual_shutter -[hidden]down-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]down-> warning_light + +@enduml +``` + +#### Module Parameters + +| Parameter | Type | Description | +| ------------------------------- | ------ | --------------------------------------------------------------------- | +| `max_delay_sec` | double | [s] maximum allowed delay for command | +| `near_line_distance` | double | [m] threshold distance to stop line to check ego stop. | +| `dead_line_margin` | double | [m] threshold distance that this module continue to insert stop line. | +| `check_timeout_after_stop_line` | bool | [-] check timeout to stop when linkage is disconnected | + +#### Flowchart + +```plantuml +@startuml +!theme cerulean-outline +start + +if (before start line?) then (yes) + stop +else (no) +endif + +if (after end line?) then (yes) + stop +else (no) +endif + +:send command to infrastructure; + +if (no stop line?) then (yes) + stop +else (no) +endif + +:check infrastructure state; + +if (timeout or not received?) then (yes) + :stop at stop line; + stop +else (no) +endif + +if (no right of way?) then (yes) + :stop at stop line; +else (no) +endif + +if (finalization is requested?) then (yes) + if (not finalized?) then (yes) + :stop at end line; + else (no) + endif +else (no) +endif + +stop +@enduml +``` + +##### Known Limits + +- tbd. From 7eb4b6c58d157c78a6594c3e405adac209fc8b61 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 08:29:37 +0900 Subject: [PATCH 09/23] feat(surround_obstacle_checker): separate surround_obstacle_checker from hierarchical planning flow (#830) * fix(surroud_obstacle_checker): use alias Signed-off-by: satoshi-ota * feat(surround_obstacle_checker): use velocity limit Signed-off-by: satoshi-ota * chore(surround_obstacle_checker): rename publisher, subscriber and callback functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use parameter struct Signed-off-by: satoshi-ota * fix(surround_obstacle_checker): use alias Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup member functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup polygon handling Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use marker helper Signed-off-by: satoshi-ota * feat(planning_launch): separate surround_obstacle_checker from hierarchical motion planning flow Signed-off-by: satoshi-ota --- .../motion_planning/motion_planning.launch.py | 35 +- .../motion_planning.launch.xml | 13 +- .../surround_obstacle_checker/CMakeLists.txt | 2 +- .../surround_obstacle_checker.param.yaml | 1 + .../debug_marker.hpp | 20 +- .../surround_obstacle_checker/node.hpp | 136 ++-- .../surround_obstacle_checker.launch.xml | 12 +- .../surround_obstacle_checker/package.xml | 1 + .../src/debug_marker.cpp | 105 +-- .../surround_obstacle_checker/src/node.cpp | 632 +++++++++--------- 10 files changed, 433 insertions(+), 524 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index e8661322215fe..89d04bc5b3a00 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -92,20 +92,23 @@ def launch_setup(context, *args, **kwargs): surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] surround_obstacle_checker_component = ComposableNode( package="surround_obstacle_checker", - plugin="SurroundObstacleCheckerNode", + plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", name="surround_obstacle_checker", namespace="", remappings=[ ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/trajectory", "surround_obstacle_checker/trajectory"), + ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), + ( + "~/output/velocity_limit_clear_command", + "/planning/scenario_planning/clear_velocity_limit", + ), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ surround_obstacle_checker_param, @@ -114,22 +117,6 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # relay - relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="skip_surround_obstacle_check_relay", - namespace="", - parameters=[ - { - "input_topic": "obstacle_avoidance_planner/trajectory", - "output_topic": "surround_obstacle_checker/trajectory", - "type": "autoware_auto_planning_msgs/msg/Trajectory", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("tier4_planning_launch"), @@ -173,7 +160,7 @@ def launch_setup(context, *args, **kwargs): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "surround_obstacle_checker/trajectory"), + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ common_param, @@ -202,13 +189,7 @@ def launch_setup(context, *args, **kwargs): condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) - relay_loader = LoadComposableNodes( - composable_node_descriptions=[relay_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - - group = GroupAction([container, surround_obstacle_checker_loader, relay_loader]) + group = GroupAction([container, surround_obstacle_checker_loader]) return [group] diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 0fa8707e4fda9..3d195185d9bd6 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -19,22 +19,11 @@ - - - - - - - - - - - @@ -45,7 +34,7 @@ - + diff --git a/planning/surround_obstacle_checker/CMakeLists.txt b/planning/surround_obstacle_checker/CMakeLists.txt index b40b7c22c98ca..ab61405c9f335 100644 --- a/planning/surround_obstacle_checker/CMakeLists.txt +++ b/planning/surround_obstacle_checker/CMakeLists.txt @@ -18,7 +18,7 @@ target_link_libraries(${PROJECT_NAME} ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "SurroundObstacleCheckerNode" + PLUGIN "surround_obstacle_checker::SurroundObstacleCheckerNode" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml index b57d7506b0574..afcc532b7c604 100644 --- a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml +++ b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml @@ -9,3 +9,4 @@ # ego stop state stop_state_ego_speed: 0.1 #[m/s] + stop_state_entry_duration_time: 0.1 #[s] diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp index d076e26afc009..2891ac63c5df4 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp @@ -25,8 +25,18 @@ #include #include +namespace surround_obstacle_checker +{ + +using tier4_planning_msgs::msg::StopFactor; +using tier4_planning_msgs::msg::StopReason; +using tier4_planning_msgs::msg::StopReasonArray; +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + enum class PoseType : int8_t { NoStart = 0 }; enum class PointType : int8_t { NoStart = 0 }; + class SurroundObstacleCheckerDebugNode { public: @@ -38,16 +48,16 @@ class SurroundObstacleCheckerDebugNode void publish(); private: - rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr stop_reason_pub_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Publisher::SharedPtr stop_reason_pub_; double base_link2front_; - visualization_msgs::msg::MarkerArray makeVisualizationMarker(); - tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray(); + MarkerArray makeVisualizationMarker(); + StopReasonArray makeStopReasonArray(); std::shared_ptr stop_obstacle_point_ptr_; std::shared_ptr stop_pose_ptr_; rclcpp::Clock::SharedPtr clock_; }; - +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__DEBUG_MARKER_HPP_ diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp index 7e4bbb9ffd15a..e437787c234ac 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp @@ -16,9 +16,9 @@ #define SURROUND_OBSTACLE_CHECKER__NODE_HPP_ #include "surround_obstacle_checker/debug_marker.hpp" -#include "tier4_autoware_utils/trajectory/tmp_conversion.hpp" #include +#include #include #include @@ -27,30 +27,31 @@ #include #include #include +#include +#include #include -#include -#include -#include -#include -#include -#include - -#include #include #include #include #include #include +#include #include -using Point2d = boost::geometry::model::d2::point_xy; -using Polygon2d = - boost::geometry::model::polygon; // counter-clockwise, open +namespace surround_obstacle_checker +{ + +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; -using TrajectoryPoints = std::vector; +using tier4_planning_msgs::msg::VelocityLimit; +using tier4_planning_msgs::msg::VelocityLimitClearCommand; +using vehicle_info_util::VehicleInfo; + +using Obstacle = std::pair; enum class State { PASS, STOP }; @@ -59,70 +60,73 @@ class SurroundObstacleCheckerNode : public rclcpp::Node public: explicit SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options); + struct NodeParam + { + bool use_pointcloud; + bool use_dynamic_object; + bool is_surround_obstacle; + // For preventing chattering, + // surround_check_recover_distance_ must be bigger than surround_check_distance_ + double surround_check_recover_distance; + double surround_check_distance; + double state_clear_time; + double stop_state_ego_speed; + double stop_state_entry_duration_time; + }; + private: - void pathCallback(const Trajectory::ConstSharedPtr input_msg); - void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg); - void dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg); - void currentVelocityCallback(const nav_msgs::msg::Odometry::ConstSharedPtr input_msg); - void insertStopVelocity(const size_t closest_idx, TrajectoryPoints * traj); - bool convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose); - bool getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose); - void getNearestObstacle(double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - bool isObstacleFound(const double min_dist_to_obj); + void onTimer(); + + void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + + void onDynamicObjects(const PredictedObjects::ConstSharedPtr msg); + + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + + boost::optional getNearestObstacle() const; + + boost::optional getNearestObstacleByPointCloud() const; + + boost::optional getNearestObstacleByDynamicObject() const; + + boost::optional getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const; + bool isStopRequired(const bool is_obstacle_found, const bool is_stopped); - size_t getClosestIdx(const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose); - bool checkStop(const TrajectoryPoint & closest_point); - Polygon2d createSelfPolygon(); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint); - diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose); - std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose); - - /* - * ROS - */ + + bool isVehicleStopped(); + + // ros + mutable tf2_ros::Buffer tf_buffer_{get_clock()}; + mutable tf2_ros::TransformListener tf_listener_{tf_buffer_}; + rclcpp::TimerBase::SharedPtr timer_; + // publisher and subscriber - rclcpp::Subscription::SharedPtr path_sub_; - rclcpp::Subscription::SharedPtr pointcloud_sub_; - rclcpp::Subscription::SharedPtr - dynamic_object_sub_; - rclcpp::Subscription::SharedPtr current_velocity_sub_; - rclcpp::Publisher::SharedPtr path_pub_; - rclcpp::Publisher::SharedPtr stop_reason_diag_pub_; + rclcpp::Subscription::SharedPtr sub_pointcloud_; + rclcpp::Subscription::SharedPtr sub_dynamic_objects_; + rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Publisher::SharedPtr pub_stop_reason_; + rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + + // debug std::shared_ptr debug_ptr_; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; // parameter - nav_msgs::msg::Odometry::ConstSharedPtr current_velocity_ptr_; - sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; - autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr object_ptr_; + NodeParam node_param_; vehicle_info_util::VehicleInfo vehicle_info_; - Polygon2d self_poly_; - bool use_pointcloud_; - bool use_dynamic_object_; - double surround_check_distance_; - // For preventing chattering, - // surround_check_recover_distance_ must be bigger than surround_check_distance_ - double surround_check_recover_distance_; - double state_clear_time_; - double stop_state_ego_speed_; - bool is_surround_obstacle_; + + // data + nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr_; + sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; + PredictedObjects::ConstSharedPtr object_ptr_; // State Machine State state_ = State::PASS; std::shared_ptr last_obstacle_found_time_; + std::shared_ptr last_running_time_; }; +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__NODE_HPP_ diff --git a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml index a0dd4b307f495..53f26a05c87c3 100644 --- a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml +++ b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml @@ -1,24 +1,20 @@ - - - - - + + - - + + - diff --git a/planning/surround_obstacle_checker/package.xml b/planning/surround_obstacle_checker/package.xml index 5dfed9ddb19a7..b74ad2ccec25b 100644 --- a/planning/surround_obstacle_checker/package.xml +++ b/planning/surround_obstacle_checker/package.xml @@ -14,6 +14,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_auto_tf2 diagnostic_msgs eigen libpcl-all-dev diff --git a/planning/surround_obstacle_checker/src/debug_marker.cpp b/planning/surround_obstacle_checker/src/debug_marker.cpp index 64dbc2f349f14..8abdb67e8b2c6 100644 --- a/planning/surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/surround_obstacle_checker/src/debug_marker.cpp @@ -14,6 +14,7 @@ #include "surround_obstacle_checker/debug_marker.hpp" +#include #ifdef ROS_DISTRO_GALACTIC #include #else @@ -22,13 +23,23 @@ #include +namespace surround_obstacle_checker +{ + +using tier4_autoware_utils::appendMarkerArray; +using tier4_autoware_utils::calcOffsetPose; +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerColor; +using tier4_autoware_utils::createMarkerScale; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createStopVirtualWallMarker; + SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const double base_link2front, const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) : base_link2front_(base_link2front), clock_(clock) { debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); - stop_reason_pub_ = - node.create_publisher("~/output/stop_reasons", 1); + stop_reason_pub_ = node.create_publisher("~/output/stop_reasons", 1); } bool SurroundObstacleCheckerDebugNode::pushPose( @@ -70,87 +81,25 @@ void SurroundObstacleCheckerDebugNode::publish() stop_obstacle_point_ptr_ = nullptr; } -visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() +MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() { - visualization_msgs::msg::MarkerArray msg; + MarkerArray msg; rclcpp::Time current_time = this->clock_->now(); - tf2::Transform tf_base_link2front( - tf2::Quaternion(0.0, 0.0, 0.0, 1.0), tf2::Vector3(base_link2front_, 0.0, 0.0)); // visualize stop line if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "virtual_wall/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::CUBE; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 1.0; - marker.scale.x = 0.1; - marker.scale.y = 5.0; - marker.scale.z = 2.0; - marker.color.a = 0.5; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 0.0; - marker.color.b = 0.0; - msg.markers.push_back(marker); - } - - // visualize stop reason - if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "factor_text/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 2.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; - marker.text = "surround obstacle"; - msg.markers.push_back(marker); + const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0); + const auto markers = createStopVirtualWallMarker(p, "surround obstacle", current_time, 0); + appendMarkerArray(markers, &msg); } // visualize surround object if (stop_obstacle_point_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "no_start_obstacle_text"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; + auto marker = createDefaultMarker( + "map", current_time, "no_start_obstacle_text", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); marker.pose.position = *stop_obstacle_point_ptr_; marker.pose.position.z += 2.0; // add half of the heights of obj roughly - marker.pose.orientation.x = 0.0; - marker.pose.orientation.y = 0.0; - marker.pose.orientation.z = 0.0; - marker.pose.orientation.w = 1.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; marker.text = "!"; msg.markers.push_back(marker); } @@ -158,7 +107,7 @@ visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisua return msg; } -tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() +StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() { // create header std_msgs::msg::Header header; @@ -166,9 +115,9 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make header.stamp = this->clock_->now(); // create stop reason stamped - tier4_planning_msgs::msg::StopReason stop_reason_msg; - stop_reason_msg.reason = tier4_planning_msgs::msg::StopReason::SURROUND_OBSTACLE_CHECK; - tier4_planning_msgs::msg::StopFactor stop_factor; + StopReason stop_reason_msg; + stop_reason_msg.reason = StopReason::SURROUND_OBSTACLE_CHECK; + StopFactor stop_factor; if (stop_pose_ptr_ != nullptr) { stop_factor.stop_pose = *stop_pose_ptr_; @@ -179,8 +128,10 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make } // create stop reason array - tier4_planning_msgs::msg::StopReasonArray stop_reason_array; + StopReasonArray stop_reason_array; stop_reason_array.header = header; stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); return stop_reason_array; } + +} // namespace surround_obstacle_checker diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 09fe48f35b571..9e1fc6711bd3f 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -14,9 +14,17 @@ #include "surround_obstacle_checker/node.hpp" +#include + +#include +#include +#include +#include +#include +#include + #include #include -#include #include #ifdef ROS_DISTRO_GALACTIC #include @@ -34,313 +42,381 @@ #include #include +namespace surround_obstacle_checker +{ + +namespace bg = boost::geometry; +using Point2d = bg::model::d2::point_xy; +using Polygon2d = bg::model::polygon; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::pose2transform; + +namespace +{ +std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose) +{ + const std::string json_dumps_pose = + (boost::format( + R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % + pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % + pose.orientation.y % pose.orientation.z) + .str(); + return json_dumps_pose; +} + +diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( + const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) +{ + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; + no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + no_start_reason_diag.name = "no_start_reason"; + no_start_reason_diag.message = no_start_reason; + no_start_reason_diag_kv.key = "no_start_pose"; + no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); + no_start_reason_diag.values.push_back(no_start_reason_diag_kv); + return no_start_reason_diag; +} + +geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const double z) +{ + geometry_msgs::msg::Point32 p; + p.x = x; + p.y = y; + p.z = z; + return p; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) +{ + geometry_msgs::msg::Polygon transformed_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(pose); + tf2::doTransform(footprint, transformed_polygon, geometry_tf); + + Polygon2d object_polygon; + for (const auto & p : transformed_polygon.points) { + object_polygon.outer().push_back(Point2d(p.x, p.y)); + } + + bg::correct(object_polygon); + + return object_polygon; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +{ + const double & length_m = size.x / 2.0; + const double & width_m = size.y / 2.0; + + geometry_msgs::msg::Polygon polygon{}; + + polygon.points.push_back(createPoint32(length_m, -width_m, 0.0)); + polygon.points.push_back(createPoint32(length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, -width_m, 0.0)); + + return createObjPolygon(pose, polygon); +} + +Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) +{ + const double & front_m = vehicle_info.max_longitudinal_offset_m; + const double & width_m = vehicle_info.min_lateral_offset_m; + const double & rear_m = vehicle_info.min_longitudinal_offset_m; + + Polygon2d ego_polygon; + + ego_polygon.outer().push_back(Point2d(front_m, -width_m)); + ego_polygon.outer().push_back(Point2d(front_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + + bg::correct(ego_polygon); + + return ego_polygon; +} +} // namespace + SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options) -: Node("surround_obstacle_checker_node", node_options), - tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) +: Node("surround_obstacle_checker_node", node_options) { // Parameters - use_pointcloud_ = this->declare_parameter("use_pointcloud", true); - use_dynamic_object_ = this->declare_parameter("use_dynamic_object", true); - surround_check_distance_ = this->declare_parameter("surround_check_distance", 2.0); - surround_check_recover_distance_ = - this->declare_parameter("surround_check_recover_distance", 2.5); - state_clear_time_ = this->declare_parameter("state_clear_time", 2.0); - stop_state_ego_speed_ = this->declare_parameter("stop_state_ego_speed", 0.1); - debug_ptr_ = std::make_shared( - vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); - self_poly_ = createSelfPolygon(); + { + auto & p = node_param_; + p.use_pointcloud = this->declare_parameter("use_pointcloud", true); + p.use_dynamic_object = this->declare_parameter("use_dynamic_object", true); + p.surround_check_distance = this->declare_parameter("surround_check_distance", 2.0); + p.surround_check_recover_distance = + this->declare_parameter("surround_check_recover_distance", 2.5); + p.state_clear_time = this->declare_parameter("state_clear_time", 2.0); + p.stop_state_ego_speed = this->declare_parameter("stop_state_ego_speed", 0.1); + p.stop_state_entry_duration_time = + this->declare_parameter("stop_state_entry_duration_time", 0.1); + } + + vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); // Publishers - path_pub_ = - this->create_publisher("~/output/trajectory", 1); - stop_reason_diag_pub_ = + pub_stop_reason_ = this->create_publisher("~/output/no_start_reason", 1); + pub_clear_velocity_limit_ = + this->create_publisher("~/output/velocity_limit_clear_command", 1); + pub_velocity_limit_ = this->create_publisher("~/output/max_velocity", 1); - // Subscriber - path_sub_ = this->create_subscription( - "~/input/trajectory", 1, - std::bind(&SurroundObstacleCheckerNode::pathCallback, this, std::placeholders::_1)); - pointcloud_sub_ = this->create_subscription( + // Subscribers + sub_pointcloud_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&SurroundObstacleCheckerNode::pointCloudCallback, this, std::placeholders::_1)); - dynamic_object_sub_ = - this->create_subscription( - "~/input/objects", 1, - std::bind(&SurroundObstacleCheckerNode::dynamicObjectCallback, this, std::placeholders::_1)); - current_velocity_sub_ = this->create_subscription( + std::bind(&SurroundObstacleCheckerNode::onPointCloud, this, std::placeholders::_1)); + sub_dynamic_objects_ = this->create_subscription( + "~/input/objects", 1, + std::bind(&SurroundObstacleCheckerNode::onDynamicObjects, this, std::placeholders::_1)); + sub_odometry_ = this->create_subscription( "~/input/odometry", 1, - std::bind(&SurroundObstacleCheckerNode::currentVelocityCallback, this, std::placeholders::_1)); + std::bind(&SurroundObstacleCheckerNode::onOdometry, this, std::placeholders::_1)); + + using std::chrono_literals::operator""ms; + timer_ = rclcpp::create_timer( + this, get_clock(), 100ms, std::bind(&SurroundObstacleCheckerNode::onTimer, this)); + + last_running_time_ = std::make_shared(this->now()); + + // Debug + debug_ptr_ = std::make_shared( + vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); } -void SurroundObstacleCheckerNode::pathCallback( - const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onTimer() { - if (use_pointcloud_ && !pointcloud_ptr_) { + if (node_param_.use_pointcloud && !pointcloud_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for pointcloud info..."); return; } - if (use_dynamic_object_ && !object_ptr_) { + if (node_param_.use_dynamic_object && !object_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for dynamic object info..."); return; } - if (!current_velocity_ptr_) { + if (!odometry_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for current velocity..."); return; } - // parameter description - TrajectoryPoints output_trajectory_points = - tier4_autoware_utils::convertToTrajectoryPointArray(*input_msg); + const auto nearest_obstacle = getNearestObstacle(); + const auto is_vehicle_stopped = isVehicleStopped(); - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + switch (state_) { + case State::PASS: { + const auto is_obstacle_found = + !nearest_obstacle ? false + : nearest_obstacle.get().first < node_param_.surround_check_distance; - // get current pose in traj frame - geometry_msgs::msg::Pose current_pose; - if (!getPose(input_msg->header.frame_id, "base_link", current_pose)) { - return; - } + if (!isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } + + state_ = State::STOP; - // get closest idx - const size_t closest_idx = getClosestIdx(output_trajectory_points, current_pose); + auto velocity_limit = std::make_shared(); + velocity_limit->stamp = this->now(); + velocity_limit->max_velocity = 0.0; + velocity_limit->use_constraints = false; + velocity_limit->sender = "surround_obstacle_checker"; - // get nearest object - double min_dist_to_obj = std::numeric_limits::max(); - geometry_msgs::msg::Point nearest_obj_point; - getNearestObstacle(&min_dist_to_obj, &nearest_obj_point); + pub_velocity_limit_->publish(*velocity_limit); - // check current obstacle status (exist or not) - const auto is_obstacle_found = isObstacleFound(min_dist_to_obj); + // do not start when there is a obstacle near the ego vehicle. + RCLCPP_WARN(get_logger(), "do not start because there is obstacle near the ego vehicle."); - // check current stop status (stop or not) - const auto is_stopped = checkStop(input_msg->points.at(closest_idx)); + break; + } - const auto is_stop_required = isStopRequired(is_obstacle_found, is_stopped); + case State::STOP: { + const auto is_obstacle_found = + !nearest_obstacle + ? false + : nearest_obstacle.get().first < node_param_.surround_check_recover_distance; - // insert stop velocity - if (is_stop_required) { - state_ = State::STOP; + if (isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } - // do not start when there is a obstacle near the ego vehicle. - RCLCPP_WARN_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "do not start because there is obstacle near the ego vehicle."); - insertStopVelocity(closest_idx, &output_trajectory_points); + state_ = State::PASS; + + auto velocity_limit_clear_command = std::make_shared(); + velocity_limit_clear_command->stamp = this->now(); + velocity_limit_clear_command->command = true; + velocity_limit_clear_command->sender = "surround_obstacle_checker"; - // visualization for debug - if (is_obstacle_found) { - debug_ptr_->pushObstaclePoint(nearest_obj_point, PointType::NoStart); + pub_clear_velocity_limit_->publish(*velocity_limit_clear_command); + + break; } - debug_ptr_->pushPose(input_msg->points.at(closest_idx).pose, PoseType::NoStart); - no_start_reason_diag = makeStopReasonDiag("obstacle", input_msg->points.at(closest_idx).pose); - } else { - state_ = State::PASS; + + default: + break; } - // publish trajectory and debug info - auto output_msg = tier4_autoware_utils::convertToTrajectory(output_trajectory_points); - output_msg.header = input_msg->header; - path_pub_->publish(output_msg); - stop_reason_diag_pub_->publish(no_start_reason_diag); + if (nearest_obstacle) { + debug_ptr_->pushObstaclePoint(nearest_obstacle.get().second, PointType::NoStart); + } + + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + if (state_ == State::STOP) { + debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); + no_start_reason_diag = makeStopReasonDiag("obstacle", odometry_ptr_->pose.pose); + } + + pub_stop_reason_->publish(no_start_reason_diag); debug_ptr_->publish(); } -void SurroundObstacleCheckerNode::pointCloudCallback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onPointCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) { - pointcloud_ptr_ = input_msg; + pointcloud_ptr_ = msg; } -void SurroundObstacleCheckerNode::dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg) { - object_ptr_ = input_msg; + object_ptr_ = msg; } -void SurroundObstacleCheckerNode::currentVelocityCallback( - const nav_msgs::msg::Odometry::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) { - current_velocity_ptr_ = input_msg; + odometry_ptr_ = msg; } -void SurroundObstacleCheckerNode::insertStopVelocity( - const size_t closest_idx, TrajectoryPoints * traj) +boost::optional SurroundObstacleCheckerNode::getNearestObstacle() const { - // set zero velocity from closest idx to last idx - for (size_t i = closest_idx; i < traj->size(); i++) { - traj->at(i).longitudinal_velocity_mps = 0.0; - } -} + boost::optional nearest_pointcloud{boost::none}; + boost::optional nearest_object{boost::none}; -bool SurroundObstacleCheckerNode::getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose) -{ - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, tf2::TimePointZero); - // convert geometry_msgs::msg::Transform to geometry_msgs::msg::Pose - tf2::Transform transform; - tf2::fromMsg(ros_src2tgt.transform, transform); - tf2::toMsg(transform, pose); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_pointcloud) { + nearest_pointcloud = getNearestObstacleByPointCloud(); } - return true; -} -bool SurroundObstacleCheckerNode::convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose) -{ - tf2::Transform src2tgt; - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, time, tf2::durationFromSec(0.1)); - tf2::fromMsg(ros_src2tgt.transform, src2tgt); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_dynamic_object) { + nearest_object = getNearestObstacleByDynamicObject(); } - tf2::Transform src2obj; - tf2::fromMsg(pose, src2obj); - tf2::Transform tgt2obj = src2tgt.inverse() * src2obj; - tf2::toMsg(tgt2obj, conv_pose); - return true; -} - -size_t SurroundObstacleCheckerNode::getClosestIdx( - const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose) -{ - double min_dist = std::numeric_limits::max(); - size_t min_dist_idx = 0; - for (size_t i = 0; i < traj.size(); ++i) { - const double x = traj.at(i).pose.position.x - current_pose.position.x; - const double y = traj.at(i).pose.position.y - current_pose.position.y; - const double dist = std::hypot(x, y); - if (dist < min_dist) { - min_dist_idx = i; - min_dist = dist; - } + if (!nearest_pointcloud && !nearest_object) { + return {}; } - return min_dist_idx; -} -void SurroundObstacleCheckerNode::getNearestObstacle( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) -{ - if (use_pointcloud_) { - getNearestObstacleByPointCloud(min_dist_to_obj, nearest_obj_point); + if (!nearest_pointcloud) { + return nearest_object; } - if (use_dynamic_object_) { - getNearestObstacleByDynamicObject(min_dist_to_obj, nearest_obj_point); + if (!nearest_object) { + return nearest_pointcloud; } + + return nearest_pointcloud.get().first < nearest_object.get().first ? nearest_pointcloud + : nearest_object; } -void SurroundObstacleCheckerNode::getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCloud() const { - // wait to transform pointcloud - geometry_msgs::msg::TransformStamped transform_stamped; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, - tf2::durationFromSec(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "failed to get base_link to " << pointcloud_ptr_->header.frame_id << " transform."); - return; + const auto transform_stamped = + getTransform("base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, 0.5); + + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; } - Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.transform).cast(); - pcl::PointCloud pcl; - pcl::fromROSMsg(*pointcloud_ptr_, pcl); - pcl::transformPointCloud(pcl, pcl, isometry); - for (const auto & p : pcl) { - // create boost point - Point2d boost_p(p.x, p.y); - - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, boost_p); - - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - nearest_obj_point->x = p.x; - nearest_obj_point->y = p.y; - nearest_obj_point->z = p.z; + Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.get().transform).cast(); + pcl::PointCloud transformed_pointcloud; + pcl::fromROSMsg(*pointcloud_ptr_, transformed_pointcloud); + pcl::transformPointCloud(transformed_pointcloud, transformed_pointcloud, isometry); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); + + for (const auto & p : transformed_pointcloud) { + Point2d boost_point(p.x, p.y); + + const auto distance_to_object = bg::distance(ego_polygon, boost_point); + + if (distance_to_object < minimum_distance) { + nearest_point = createPoint(p.x, p.y, p.z); + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -void SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject() const { - const auto obj_frame = object_ptr_->header.frame_id; - const auto obj_time = object_ptr_->header.stamp; - for (const auto & obj : object_ptr_->objects) { - // change frame of obj_pose to base_link - geometry_msgs::msg::Pose pose_baselink; - if (!convertPose( - obj.kinematics.initial_pose_with_covariance.pose, obj_frame, "base_link", obj_time, - pose_baselink)) { - return; - } + const auto transform_stamped = + getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5); - // create obj polygon - Polygon2d obj_poly; - if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { - obj_poly = createObjPolygon(pose_baselink, obj.shape.footprint); - } else { - obj_poly = createObjPolygon(pose_baselink, obj.shape.dimensions); - } + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; + } + + tf2::Transform tf_src2target; + tf2::fromMsg(transform_stamped.get().transform, tf_src2target); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, obj_poly); + for (const auto & object : object_ptr_->objects) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - *nearest_obj_point = obj.kinematics.initial_pose_with_covariance.pose.position; + tf2::Transform tf_src2object; + tf2::fromMsg(object_pose, tf_src2object); + + geometry_msgs::msg::Pose transformed_object_pose; + tf2::toMsg(tf_src2target.inverse() * tf_src2object, transformed_object_pose); + + const auto object_polygon = + object.shape.type == Shape::POLYGON + ? createObjPolygon(transformed_object_pose, object.shape.footprint) + : createObjPolygon(transformed_object_pose, object.shape.dimensions); + + const auto distance_to_object = bg::distance(ego_polygon, object_polygon); + + if (distance_to_object < minimum_distance) { + nearest_point = object_pose.position; + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -bool SurroundObstacleCheckerNode::isObstacleFound(const double min_dist_to_obj) +boost::optional SurroundObstacleCheckerNode::getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const { - const auto is_obstacle_inside_range = min_dist_to_obj < surround_check_distance_; - const auto is_obstacle_outside_range = min_dist_to_obj > surround_check_recover_distance_; - - if (state_ == State::PASS) { - return is_obstacle_inside_range; - } + geometry_msgs::msg::TransformStamped transform_stamped; - if (state_ == State::STOP) { - return !is_obstacle_outside_range; + try { + transform_stamped = + tf_buffer_.lookupTransform(source, target, stamp, tf2::durationFromSec(duration_sec)); + } catch (tf2::TransformException & ex) { + return {}; } - throw std::runtime_error("invalid state"); + return transform_stamped; } bool SurroundObstacleCheckerNode::isStopRequired( - const bool is_obstacle_found, const bool is_stopped) + const bool is_obstacle_found, const bool is_vehicle_stopped) { - if (!is_stopped) { + if (!is_vehicle_stopped) { return false; } @@ -356,7 +432,7 @@ bool SurroundObstacleCheckerNode::isStopRequired( // Keep stop state if (last_obstacle_found_time_) { const auto elapsed_time = this->now() - *last_obstacle_found_time_; - if (elapsed_time.seconds() <= state_clear_time_) { + if (elapsed_time.seconds() <= node_param_.state_clear_time) { return true; } } @@ -365,118 +441,18 @@ bool SurroundObstacleCheckerNode::isStopRequired( return false; } -bool SurroundObstacleCheckerNode::checkStop( - const autoware_auto_planning_msgs::msg::TrajectoryPoint & closest_point) -{ - if (std::fabs(current_velocity_ptr_->twist.twist.linear.x) > stop_state_ego_speed_) { - // ego vehicle has high velocity now. not stop. - return false; - } - - const double closest_vel = closest_point.longitudinal_velocity_mps; - const double closest_acc = closest_point.acceleration_mps2; - - if (closest_vel * closest_acc < 0) { - // ego vehicle is about to stop (during deceleration). not stop. - return false; - } - - return true; -} - -Polygon2d SurroundObstacleCheckerNode::createSelfPolygon() -{ - const double front = vehicle_info_.max_longitudinal_offset_m; - const double rear = vehicle_info_.min_longitudinal_offset_m; - const double left = vehicle_info_.max_lateral_offset_m; - const double right = vehicle_info_.min_lateral_offset_m; - - Polygon2d poly; - boost::geometry::exterior_ring(poly) = boost::assign::list_of(front, left)(front, right)( - rear, right)(rear, left)(front, left); - return poly; -} - -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +bool SurroundObstacleCheckerNode::isVehicleStopped() { - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double h = size.x; - const double w = size.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - boost::geometry::exterior_ring(obj_poly) = boost::assign::list_of(h / 2.0, w / 2.0)( - -h / 2.0, w / 2.0)(-h / 2.0, -w / 2.0)(h / 2.0, -w / 2.0)(h / 2.0, w / 2.0); - - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} + const auto current_velocity = std::abs(odometry_ptr_->twist.twist.linear.x); -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) -{ - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - for (const auto point : footprint.points) { - const Point2d point2d(point.x, point.y); - obj_poly.outer().push_back(point2d); + if (node_param_.stop_state_ego_speed < current_velocity) { + last_running_time_ = std::make_shared(this->now()); } - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} - -diagnostic_msgs::msg::DiagnosticStatus SurroundObstacleCheckerNode::makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) -{ - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; - diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; - no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - no_start_reason_diag.name = "no_start_reason"; - no_start_reason_diag.message = no_start_reason; - no_start_reason_diag_kv.key = "no_start_pose"; - no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); - no_start_reason_diag.values.push_back(no_start_reason_diag_kv); - return no_start_reason_diag; + return node_param_.stop_state_entry_duration_time < (this->now() - *last_running_time_).seconds(); } -std::string SurroundObstacleCheckerNode::jsonDumpsPose(const geometry_msgs::msg::Pose & pose) -{ - const std::string json_dumps_pose = - (boost::format( - R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % - pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % - pose.orientation.y % pose.orientation.z) - .str(); - return json_dumps_pose; -} +} // namespace surround_obstacle_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE(SurroundObstacleCheckerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(surround_obstacle_checker::SurroundObstacleCheckerNode) From 178a65c40a5d3caad2c1d66cd0853dc14ffd79e2 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 10 May 2022 10:15:23 +0900 Subject: [PATCH 10/23] feat: remove deprecated package in prediction launch (#875) Signed-off-by: Yukihiro Saito --- .../launch/object_recognition/prediction/prediction.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 4749bd45d3e3e..fd9d1ba6f3cda 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -9,6 +9,6 @@ - + From 429a06c385faf4d588947a56ec4ebdf4d7f635cd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 12:43:47 +0900 Subject: [PATCH 11/23] fix(surround_obstacle_checker): fix ego footprint polygon (#877) Signed-off-by: satoshi-ota --- planning/surround_obstacle_checker/src/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 9e1fc6711bd3f..cd7117f360143 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -131,8 +131,8 @@ Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) ego_polygon.outer().push_back(Point2d(front_m, -width_m)); ego_polygon.outer().push_back(Point2d(front_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, -width_m)); bg::correct(ego_polygon); From c092de0ea6d2e5c8c1d47eb034faf958d4d4d8ac Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 10 May 2022 15:21:49 +0900 Subject: [PATCH 12/23] fix: update nvinfer api (#863) * fix(lidar_centerpoint): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(tensorrt_yolo): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(lidar_apollo_instance_segmentation): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_classifier): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_ssd_fine_detector): update nvinfer api Signed-off-by: Daisuke Nishimatsu * pre-commit run Signed-off-by: Daisuke Nishimatsu --- .../CMakeLists.txt | 3 --- .../lib/include/TrtNet.hpp | 6 ++--- .../lib/src/TrtNet.cpp | 2 +- .../src/detector.cpp | 26 +++++++++++++------ perception/lidar_centerpoint/CMakeLists.txt | 10 ++++--- .../lib/include/tensorrt_wrapper.hpp | 3 ++- .../lib/src/tensorrt_wrapper.cpp | 14 ++++++---- perception/tensorrt_yolo/CMakeLists.txt | 3 --- .../tensorrt_yolo/lib/include/trt_yolo.hpp | 3 ++- perception/tensorrt_yolo/lib/src/trt_yolo.cpp | 16 +++++++----- .../traffic_light_classifier/CMakeLists.txt | 3 --- .../utils/trt_common.cpp | 14 ++++++---- .../CMakeLists.txt | 3 --- .../lib/include/trt_ssd.hpp | 3 ++- .../lib/src/trt_ssd.cpp | 14 ++++++---- 15 files changed, 72 insertions(+), 51 deletions(-) diff --git a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt index 4fee2ecdd2f3b..433999051097d 100644 --- a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_apollo_instance_segmentation) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability diff --git a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp index 30d560135cb4f..14c1ff6d44c63 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp +++ b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp @@ -56,13 +56,13 @@ class trtNet } if (!mTrtRunTime) { - mTrtRunTime->destroy(); + delete mTrtRunTime; } if (!mTrtContext) { - mTrtContext->destroy(); + delete mTrtContext; } if (!mTrtEngine) { - mTrtEngine->destroy(); + delete mTrtEngine; } } diff --git a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp index c51adc83e07c1..0f1da4bdac8a6 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp +++ b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp @@ -100,7 +100,7 @@ trtNet::trtNet(const std::string & engineFile) mTrtRunTime = createInferRuntime(gLogger); assert(mTrtRunTime != nullptr); - mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length, nullptr); + mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length); assert(mTrtEngine != nullptr); InitEngine(); diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 7d628173b2e4c..af8b29f55f340 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -63,17 +63,27 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * const int batch_size = 1; builder->setMaxBatchSize(batch_size); config->setMaxWorkspaceSize(1 << 30); - nvinfer1::ICudaEngine * engine = builder->buildEngineWithConfig(*network, *config); - nvinfer1::IHostMemory * trt_model_stream = engine->serialize(); - assert(trt_model_stream != nullptr); + nvinfer1::IHostMemory * plan = builder->buildSerializedNetwork(*network, *config); + assert(plan != nullptr); std::ofstream outfile(engine_file, std::ofstream::binary); assert(!outfile.fail()); - outfile.write(reinterpret_cast(trt_model_stream->data()), trt_model_stream->size()); + outfile.write(reinterpret_cast(plan->data()), plan->size()); outfile.close(); - network->destroy(); - parser->destroy(); - builder->destroy(); - config->destroy(); + if (network) { + delete network; + } + if (parser) { + delete parser; + } + if (builder) { + delete builder; + } + if (config) { + delete config; + } + if (plan) { + delete plan; + } } net_ptr_.reset(new Tn::trtNet(engine_file)); diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 1f5c869136eb0..0cf1f51654bb1 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_centerpoint) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations -Wno-unknown-pragmas) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability @@ -144,6 +141,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) centerpoint_cuda_libraries ) + # To suppress unknown-pragmas error. The root-cause is CUB library in CUDA 11.6. + # This issue was fixed by https://github.com/NVIDIA/cub/commit/7d608bf1dc14553e2fb219eabeed80b76621b6fe + target_include_directories(centerpoint + SYSTEM PUBLIC + ${CUDA_INCLUDE_DIRS} + ) + ## node ## ament_auto_add_library(lidar_centerpoint_component SHARED src/node.cpp diff --git a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp index dd49723a5265c..b334be9e2230b 100644 --- a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp +++ b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp @@ -29,7 +29,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -82,6 +82,7 @@ class TensorRTWrapper bool createContext(); unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; }; diff --git a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp index 3691128137c39..f9882afac8f92 100644 --- a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp @@ -104,7 +104,13 @@ bool TensorRTWrapper::parseONNX( std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return false; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return false; @@ -116,9 +122,8 @@ bool TensorRTWrapper::parseONNX( bool TensorRTWrapper::saveEngine(const std::string & engine_path) { std::cout << "Writing to " << engine_path << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); return true; } @@ -139,8 +144,7 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path) } std::cout << "Loading from " << engine_path << std::endl; - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size)); return true; } diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index c05fefc38d15c..a50af6bfa9abb 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -4,9 +4,6 @@ project(tensorrt_yolo) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp index 813811226a0a6..c951154820f1a 100644 --- a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp +++ b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp @@ -59,7 +59,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -130,6 +130,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp index 1be5f279714ba..748680266ca9c 100644 --- a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp +++ b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp @@ -65,8 +65,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -253,9 +252,15 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!prepare()) { - std::cout << "Fail to prepare engine" << std::endl; + std::cout << "Fail to create engine" << std::endl; return; } } @@ -263,9 +268,8 @@ Net::Net( void Net::save(const std::string & path) const { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) diff --git a/perception/traffic_light_classifier/CMakeLists.txt b/perception/traffic_light_classifier/CMakeLists.txt index 08897bfa3cf5a..8ebd5f32db99e 100644 --- a/perception/traffic_light_classifier/CMakeLists.txt +++ b/perception/traffic_light_classifier/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_classifier) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability option(CUDA_AVAIL "CUDA available" OFF) diff --git a/perception/traffic_light_classifier/utils/trt_common.cpp b/perception/traffic_light_classifier/utils/trt_common.cpp index a920d47fa295a..cae9f0cd1682a 100644 --- a/perception/traffic_light_classifier/utils/trt_common.cpp +++ b/perception/traffic_light_classifier/utils/trt_common.cpp @@ -45,6 +45,7 @@ TrtCommon::TrtCommon(std::string model_path, std::string precision) is_initialized_(false), max_batch_size_(1) { + runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); } void TrtCommon::setup() @@ -86,9 +87,8 @@ bool TrtCommon::loadEngine(std::string engine_file_path) std::stringstream engine_buffer; engine_buffer << engine_file.rdbuf(); std::string engine_str = engine_buffer.str(); - runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); engine_ = UniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size(), nullptr)); + reinterpret_cast(engine_str.data()), engine_str.size())); return true; } @@ -117,19 +117,23 @@ bool TrtCommon::buildEngineFromOnnx(std::string onnx_file_path, std::string outp return false; } - engine_ = UniquePtr(builder->buildEngineWithConfig(*network, *config)); + auto plan = UniquePtr(builder->buildSerializedNetwork(*network, *config)); + if (!plan) { + return false; + } + engine_ = + UniquePtr(runtime_->deserializeCudaEngine(plan->data(), plan->size())); if (!engine_) { return false; } // save engine - nvinfer1::IHostMemory * data = engine_->serialize(); std::ofstream file; file.open(output_engine_file_path, std::ios::binary | std::ios::out); if (!file.is_open()) { return false; } - file.write((const char *)data->data(), data->size()); + file.write((const char *)plan->data(), plan->size()); file.close(); return true; diff --git a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt index e82c790f4fd1e..eb172b7faf981 100644 --- a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt +++ b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_ssd_fine_detector) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp index bbe5ae8da513c..cfb6c8a6d5754 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp +++ b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp @@ -31,7 +31,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -87,6 +87,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp index 766de7eb4cde1..ba9f94b014513 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp +++ b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp @@ -36,8 +36,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -136,7 +135,13 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return; @@ -151,9 +156,8 @@ Net::Net( void Net::save(const std::string & path) { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) From 8c0cc86273c299021f493c231b124f2318c6ba33 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 10 May 2022 17:39:28 +0900 Subject: [PATCH 13/23] fix(avoidance_module): ignore object instead of creating zero shift (#731) * fix: ignore object instead of creating zero shift instead of creating zero shift point, the object will be ignored. no behavior changes should be observed. Signed-off-by: Muhammad Zulfaqar Azmi * refactor: sync continue with upstream Signed-off-by: Muhammad Zulfaqar Azmi * fix: fix debug message for insufficient lateral margin Signed-off-by: Muhammad Zulfaqar Azmi --- .../avoidance/avoidance_module.cpp | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 876e5fc3112c3..2923996ca8697 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -490,24 +490,19 @@ AvoidPointArray AvoidanceModule::calcRawShiftPointsFromObjects( avoidance_debug_msg.max_shift_length = max_allowable_lateral_distance; if (!(o.to_road_shoulder_distance > max_allowable_lateral_distance)) { - avoidance_debug_msg.allow_avoidance = false; - avoidance_debug_msg.failed_reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + avoidance_debug_array_false_and_push_back(AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN); + continue; } const auto max_shift_length = o.to_road_shoulder_distance - road_shoulder_safety_margin - 0.5 * vehicle_width; - const auto max_left_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto left_shift_constraint = std::min(getLeftShiftBound(), max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? left_shift_constraint - : 0.0; + + const auto max_left_shift_limit = [&max_shift_length, this]() noexcept { + return std::min(getLeftShiftBound(), max_shift_length); }; - const auto max_right_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto right_shift_constraint = std::max(getRightShiftBound(), -max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? right_shift_constraint - : 0.0; + const auto max_right_shift_limit = [&max_shift_length, this]() noexcept { + return std::max(getRightShiftBound(), -max_shift_length); }; const auto shift_length = isOnRight(o) From 667fb38f45474a65a8fab0c9433c7813d8fc1b2a Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 10 May 2022 18:33:56 +0900 Subject: [PATCH 14/23] fix(motion_velocity_smoother): curve deceleration not working with a specific parameter set (#738) Signed-off-by: Takamasa Horibe --- .../motion_velocity_smoother/src/smoother/smoother_base.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index 2ecf683fd3028..31c6420a67870 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -105,7 +105,7 @@ boost::optional SmootherBase::applyLateralAccelerationFilter( for (size_t i = 0; i < output->size(); ++i) { double curvature = 0.0; const size_t start = i > after_decel_index ? i - after_decel_index : 0; - const size_t end = std::min(output->size(), i + before_decel_index); + const size_t end = std::min(output->size(), i + before_decel_index + 1); for (size_t j = start; j < end; ++j) { curvature = std::max(curvature, std::fabs(curvature_v->at(j))); } From f8a136c7e38a41a5d21c71022d8b5fa7750a4b57 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 10 May 2022 21:29:41 +0900 Subject: [PATCH 15/23] test(autoware_testing): fix smoke_test (#479) * fix(autoware_testing): fix smoke_test Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * restore smoke_test for trajectory_follower_nodes Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * add support multiple parameter files Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * ci(pre-commit): autofix * minor fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_testing/smoke_test.py | 39 +++++++++++++------ .../cmake/add_smoke_test.cmake | 10 ++--- .../trajectory_follower_nodes/CMakeLists.txt | 14 +++++-- 3 files changed, 42 insertions(+), 21 deletions(-) diff --git a/common/autoware_testing/autoware_testing/smoke_test.py b/common/autoware_testing/autoware_testing/smoke_test.py index 2753861269124..8c361474034ad 100644 --- a/common/autoware_testing/autoware_testing/smoke_test.py +++ b/common/autoware_testing/autoware_testing/smoke_test.py @@ -16,6 +16,7 @@ import os import shlex +import time import unittest from ament_index_python import get_package_share_directory @@ -26,21 +27,24 @@ from launch_ros.actions import Node import launch_testing import pytest +import rclpy def resolve_node(context, *args, **kwargs): + parameters = [ + os.path.join( + get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), + "param", + file_name, + ) + for file_name in shlex.split(LaunchConfiguration("arg_param_filenames").perform(context)) + ] smoke_test_node = Node( package=LaunchConfiguration("arg_package"), executable=LaunchConfiguration("arg_package_exe"), namespace="test", - parameters=[ - os.path.join( - get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), - "param", - LaunchConfiguration("arg_param_filename").perform(context), - ) - ], + parameters=parameters, arguments=shlex.split(LaunchConfiguration("arg_executable_arguments").perform(context)), ) return [smoke_test_node] @@ -55,8 +59,8 @@ def generate_test_description(): arg_package_exe = DeclareLaunchArgument( "arg_package_exe", default_value=["default"], description="Tested executable" ) - arg_param_filename = DeclareLaunchArgument( - "arg_param_filename", default_value=["test.param.yaml"], description="Test param file" + arg_param_filenames = DeclareLaunchArgument( + "arg_param_filenames", default_value=["test.param.yaml"], description="Test param file" ) arg_executable_arguments = DeclareLaunchArgument( "arg_executable_arguments", default_value=[""], description="Tested executable arguments" @@ -66,7 +70,7 @@ def generate_test_description(): [ arg_package, arg_package_exe, - arg_param_filename, + arg_param_filenames, arg_executable_arguments, OpaqueFunction(function=resolve_node), launch_testing.actions.ReadyToTest(), @@ -74,8 +78,19 @@ def generate_test_description(): ) +class DummyTest(unittest.TestCase): + def test_wait_for_node_ready(self): + """Waiting for the node is ready.""" + rclpy.init() + test_node = rclpy.create_node("test_node") + while len(test_node.get_node_names()) == 0: + time.sleep(0.1) + print("waiting for Node to be ready") + rclpy.shutdown() + + @launch_testing.post_shutdown_test() class TestProcessOutput(unittest.TestCase): def test_exit_code(self, proc_output, proc_info): - # Check that process exits with code -15 code: termination request, sent to the program - launch_testing.asserts.assertExitCodes(proc_info, [-15]) + # Check that process exits with code 0 + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/common/autoware_testing/cmake/add_smoke_test.cmake b/common/autoware_testing/cmake/add_smoke_test.cmake index 2998db4960de4..ee2cb0f06e789 100644 --- a/common/autoware_testing/cmake/add_smoke_test.cmake +++ b/common/autoware_testing/cmake/add_smoke_test.cmake @@ -19,18 +19,18 @@ # :type package_name: string # :param package_exec: package executable to run during smoke test # :type executable_name: string -# :param PARAM_FILENAME: yaml filename containing test parameters -# :type PARAM_FILENAME: string +# :param PARAM_FILENAMES: yaml filenames containing test parameters +# :type PARAM_FILENAMES: string # :param EXECUTABLE_ARGUMENTS: arguments passed to tested executable # :type EXECUTABLE_ARGUMENTS: string function(add_smoke_test package_name executable_name) - cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAME;EXECUTABLE_ARGUMENTS" "") + cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAMES;EXECUTABLE_ARGUMENTS" "") set(ARGUMENTS "arg_package:=${package_name}" "arg_package_exe:=${executable_name}") - if(smoke_test_PARAM_FILENAME) - list(APPEND ARGUMENTS "arg_param_filename:=${smoke_test_PARAM_FILENAME}") + if(smoke_test_PARAM_FILENAMES) + list(APPEND ARGUMENTS "arg_param_filenames:=${smoke_test_PARAM_FILENAMES}") endif() if(smoke_test_EXECUTABLE_ARGUMENTS) diff --git a/control/trajectory_follower_nodes/CMakeLists.txt b/control/trajectory_follower_nodes/CMakeLists.txt index 7996ac0713107..fa005c1c0bfda 100644 --- a/control/trajectory_follower_nodes/CMakeLists.txt +++ b/control/trajectory_follower_nodes/CMakeLists.txt @@ -57,10 +57,16 @@ if(BUILD_TESTING) ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} fake_test_node) target_link_libraries(${TRAJECTORY_FOLLOWER_NODES_TEST} ${LATLON_MUXER_NODE} ${LATERAL_CONTROLLER_NODE} ${LONGITUDINAL_CONTROLLER_NODE}) - #find_package(autoware_testing REQUIRED) - #add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe PARAM_FILENAME latlon_muxer_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe PARAM_FILENAME lateral_controller_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe PARAM_FILENAME longitudinal_controller_defaults.param.yaml) + find_package(autoware_testing REQUIRED) + add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe + PARAM_FILENAMES "latlon_muxer_defaults.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "lateral_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "longitudinal_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) endif() ament_auto_package( From 7bdd7a83ecb971575abd3a869a8988223fd911da Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 11 May 2022 10:22:56 +0900 Subject: [PATCH 16/23] feat(rviz_plugins): add velocity limit to autoware state panel (#879) * feat(rviz_plugins): add velocity limit to autoware state panel Signed-off-by: tanaka3 * chore(rviz_plugin): change ms to kmh Signed-off-by: tanaka3 --- common/tier4_state_rviz_plugin/package.xml | 1 + .../src/autoware_state_panel.cpp | 23 +++++++++++++++++++ .../src/autoware_state_panel.hpp | 7 ++++++ 3 files changed, 31 insertions(+) diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index 2afbe9c315f75..74f7a7418815e 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -21,6 +21,7 @@ rviz_common tier4_control_msgs tier4_external_api_msgs + tier4_planning_msgs ament_lint_auto autoware_lint_common diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 78681106b3d61..825e06dac1cd9 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -80,13 +80,26 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa engage_button_ptr_ = new QPushButton("Engage"); connect(engage_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareEngage())); + velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); + pub_velocity_limit_input_ = new QSpinBox(); + pub_velocity_limit_input_->setRange(-100.0, 100.0); + pub_velocity_limit_input_->setValue(0.0); + pub_velocity_limit_input_->setSingleStep(5.0); + connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); + auto * v_layout = new QVBoxLayout; + auto * velocity_limit_layout = new QHBoxLayout(); v_layout->addLayout(gate_layout); v_layout->addLayout(selector_layout); v_layout->addLayout(state_layout); v_layout->addLayout(gear_layout); v_layout->addLayout(engage_status_layout); v_layout->addWidget(engage_button_ptr_); + v_layout->addLayout(engage_status_layout); + velocity_limit_layout->addWidget(velocity_limit_button_ptr_); + velocity_limit_layout->addWidget(pub_velocity_limit_input_); + velocity_limit_layout->addWidget(new QLabel(" [km/h]")); + v_layout->addLayout(velocity_limit_layout); setLayout(v_layout); } @@ -114,6 +127,9 @@ void AutowareStatePanel::onInitialize() client_engage_ = raw_node_->create_client( "/api/autoware/set/engage", rmw_qos_profile_services_default); + + pub_velocity_limit_ = raw_node_->create_publisher( + "/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1)); } void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) @@ -215,6 +231,13 @@ void AutowareStatePanel::onEngageStatus( engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_))); } +void AutowareStatePanel::onClickVelocityLimit() +{ + auto velocity_limit = std::make_shared(); + velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; + pub_velocity_limit_->publish(*velocity_limit); +} + void AutowareStatePanel::onClickAutowareEngage() { auto req = std::make_shared(); diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 45cd290e5f4a3..97c559bdfb3de 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -28,6 +29,7 @@ #include #include #include +#include namespace rviz_plugins { @@ -41,6 +43,7 @@ class AutowareStatePanel : public rviz_common::Panel public Q_SLOTS: void onClickAutowareEngage(); + void onClickVelocityLimit(); protected: void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); @@ -61,12 +64,16 @@ public Q_SLOTS: rclcpp::Client::SharedPtr client_engage_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + QLabel * gate_mode_label_ptr_; QLabel * selector_mode_label_ptr_; QLabel * autoware_state_label_ptr_; QLabel * gear_label_ptr_; QLabel * engage_status_label_ptr_; QPushButton * engage_button_ptr_; + QPushButton * velocity_limit_button_ptr_; + QSpinBox * pub_velocity_limit_input_; bool current_engage_; }; From c00e120cfe627c9f2fdeddaf5e6aea271e44e3f0 Mon Sep 17 00:00:00 2001 From: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Date: Wed, 11 May 2022 11:00:51 +0900 Subject: [PATCH 17/23] fix(dummy_perception_publisher): publish multiple layers of pointcloud (#882) * fix: single -> multiple layers pointcloud Signed-off-by: Hirokazu Ishida * refactor: share common among different pcloud creators Signed-off-by: Hirokazu Ishida --- .../src/pointcloud_creator.cpp | 56 ++++++++++++++----- 1 file changed, 41 insertions(+), 15 deletions(-) diff --git a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp index 6c964625a3e69..d55c42a0c28bd 100644 --- a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp +++ b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp @@ -25,6 +25,18 @@ #include #include +namespace +{ + +static constexpr double epsilon = 0.001; +static constexpr double step = 0.05; +static constexpr double vertical_theta_step = (1.0 / 180.0) * M_PI; +static constexpr double vertical_min_theta = (-15.0 / 180.0) * M_PI; +static constexpr double vertical_max_theta = (15.0 / 180.0) * M_PI; +static constexpr double horizontal_theta_step = (0.1 / 180.0) * M_PI; +static constexpr double horizontal_min_theta = (-180.0 / 180.0) * M_PI; +static constexpr double horizontal_max_theta = (180.0 / 180.0) * M_PI; + pcl::PointXYZ getPointWrtBaseLink( const tf2::Transform & tf_base_link2moved_object, double x, double y, double z) { @@ -32,6 +44,8 @@ pcl::PointXYZ getPointWrtBaseLink( return pcl::PointXYZ(p_wrt_base.x(), p_wrt_base.y(), p_wrt_base.z()); } +} // namespace + void ObjectCentricPointCloudCreator::create_object_pointcloud( const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map, std::mt19937 & random_generator, pcl::PointCloud::Ptr pointcloud) const @@ -39,14 +53,6 @@ void ObjectCentricPointCloudCreator::create_object_pointcloud( std::normal_distribution<> x_random(0.0, obj_info.std_dev_x); std::normal_distribution<> y_random(0.0, obj_info.std_dev_y); std::normal_distribution<> z_random(0.0, obj_info.std_dev_z); - const double epsilon = 0.001; - const double step = 0.05; - const double vertical_theta_step = (1.0 / 180.0) * M_PI; - const double vertical_min_theta = (-15.0 / 180.0) * M_PI; - const double vertical_max_theta = (15.0 / 180.0) * M_PI; - const double horizontal_theta_step = (0.1 / 180.0) * M_PI; - const double horizontal_min_theta = (-180.0 / 180.0) * M_PI; - const double horizontal_max_theta = (180.0 / 180.0) * M_PI; const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; @@ -206,7 +212,18 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr pointclouds.at(i) = (pcl::PointCloud::Ptr(new pcl::PointCloud)); } - const double horizontal_theta_step = 0.25 * M_PI / 180.0; + std::vector min_zs(obj_infos.size()); + std::vector max_zs(obj_infos.size()); + + for (size_t idx = 0; idx < obj_infos.size(); ++idx) { + const auto & obj_info = obj_infos.at(idx); + const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; + const double min_z = -1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + const double max_z = 1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + min_zs.at(idx) = min_z; + max_zs.at(idx) = max_z; + } + double angle = 0.0; const auto n_scan = static_cast(std::floor(2 * M_PI / horizontal_theta_step)); for (size_t i = 0; i < n_scan; ++i) { @@ -217,13 +234,22 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr const auto x_hit = dist * cos(angle); const auto y_hit = dist * sin(angle); const auto idx_hit = composite_sdf.nearest_sdf_index(x_hit, y_hit); + const auto obj_info_here = obj_infos.at(idx_hit); + const auto min_z_here = min_zs.at(idx_hit); + const auto max_z_here = max_zs.at(idx_hit); + std::normal_distribution<> x_random(0.0, obj_info_here.std_dev_x); + std::normal_distribution<> y_random(0.0, obj_info_here.std_dev_y); + std::normal_distribution<> z_random(0.0, obj_info_here.std_dev_z); - std::normal_distribution<> x_random(0.0, obj_infos.at(idx_hit).std_dev_x); - std::normal_distribution<> y_random(0.0, obj_infos.at(idx_hit).std_dev_y); - std::normal_distribution<> z_random(0.0, obj_infos.at(idx_hit).std_dev_z); - pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( - x_hit + x_random(random_generator), y_hit + y_random(random_generator), - z_random(random_generator))); + for (double vertical_theta = vertical_min_theta; + vertical_theta <= vertical_max_theta + epsilon; vertical_theta += vertical_theta_step) { + const double z = dist * std::tan(vertical_theta); + if (min_z_here <= z && z <= max_z_here + epsilon) { + pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( + x_hit + x_random(random_generator), y_hit + y_random(random_generator), + z + z_random(random_generator))); + } + } } } From 344111e54143dd36469391d2e3ed3180dc0b7a03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 11 May 2022 12:56:26 +0900 Subject: [PATCH 18/23] feat(vehicle_info_util): add max_steer_angle (#740) * feat(vehicle_info_util): add max_steer_angle Signed-off-by: Takayuki Murooka * applied pre-commit Signed-off-by: Takayuki Murooka * Added max_steer_angle in test config Signed-off-by: Takayuki Murooka Co-authored-by: Tomoya Kimura --- .../param/test_vehicle_info.param.yaml | 1 + .../param/vehicle_characteristics.param.yaml | 1 + .../test/test_simple_planning_simulator.cpp | 1 + vehicle/vehicle_info_util/config/vehicle_info.param.yaml | 1 + .../include/vehicle_info_util/vehicle_info.hpp | 5 ++++- vehicle/vehicle_info_util/src/vehicle_info_util.cpp | 4 +++- 6 files changed, 11 insertions(+), 2 deletions(-) diff --git a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml index b1279b50ef04a..8941b92b4e78e 100644 --- a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml +++ b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml index 12b6efa79d1cd..ef594927dac4d 100644 --- a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml +++ b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml @@ -10,3 +10,4 @@ width_m: 2.0 front_overhang_m: 0.5 rear_overhang_m: 0.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index d983aeed4d8c4..fea6cd16db9d0 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -190,6 +190,7 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) node_options.append_parameter_override("left_overhang", 0.5); node_options.append_parameter_override("right_overhang", 0.5); node_options.append_parameter_override("vehicle_height", 1.5); + node_options.append_parameter_override("max_steer_angle", 0.7); } // Send a control command and run the simulation. diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml index b1279b50ef04a..8941b92b4e78e 100644 --- a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml +++ b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp index e7ba446051889..8df6d4cfe04c1 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp +++ b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp @@ -31,6 +31,7 @@ struct VehicleInfo double left_overhang_m; double right_overhang_m; double vehicle_height_m; + double max_steer_angle_m; // Derived parameters, i.e. calculated from base parameters // The offset values are relative to the base frame origin, which is located @@ -49,7 +50,8 @@ struct VehicleInfo inline VehicleInfo createVehicleInfo( const double wheel_radius_m, const double wheel_width_m, const double wheel_base_m, const double wheel_tread_m, const double front_overhang_m, const double rear_overhang_m, - const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m) + const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m, + const double max_steer_angle_m) { // Calculate derived parameters const double vehicle_length_m_ = front_overhang_m + wheel_base_m + rear_overhang_m; @@ -72,6 +74,7 @@ inline VehicleInfo createVehicleInfo( left_overhang_m, right_overhang_m, vehicle_height_m, + max_steer_angle_m, // Derived parameters vehicle_length_m_, vehicle_width_m_, diff --git a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp index 6cc2d2f27e9ce..c295155727e61 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp +++ b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp @@ -49,6 +49,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) vehicle_info_.left_overhang_m = getParameter(node, "left_overhang"); vehicle_info_.right_overhang_m = getParameter(node, "right_overhang"); vehicle_info_.vehicle_height_m = getParameter(node, "vehicle_height"); + vehicle_info_.max_steer_angle_m = getParameter(node, "max_steer_angle"); } VehicleInfo VehicleInfoUtil::getVehicleInfo() @@ -56,7 +57,8 @@ VehicleInfo VehicleInfoUtil::getVehicleInfo() return createVehicleInfo( vehicle_info_.wheel_radius_m, vehicle_info_.wheel_width_m, vehicle_info_.wheel_base_m, vehicle_info_.wheel_tread_m, vehicle_info_.front_overhang_m, vehicle_info_.rear_overhang_m, - vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m); + vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m, + vehicle_info_.max_steer_angle_m); } } // namespace vehicle_info_util From 176d33fc1c4238d999b446d22bdbf98c06a7630c Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 11 May 2022 14:52:58 +0900 Subject: [PATCH 19/23] ci(deploy-docs): remove mdx_unimoji (#883) Signed-off-by: Shumpei Wakabayashi --- mkdocs.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/mkdocs.yaml b/mkdocs.yaml index 2bd16349b24bb..02c3bb42383e8 100644 --- a/mkdocs.yaml +++ b/mkdocs.yaml @@ -66,7 +66,6 @@ markdown_extensions: - mdx_math - mdx_truly_sane_lists: nested_indent: 2 - - mdx_unimoji - plantuml_markdown: server: http://www.plantuml.com/plantuml format: svg From bb96ae7b56085a6054ad1ade970bad399faef35a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Wed, 11 May 2022 06:17:37 +0000 Subject: [PATCH 20/23] chore: sync files (#884) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 23508e63bc43d..93533b54e1dd0 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -54,7 +54,7 @@ jobs: - name: Select verb id: select-verb run: | - has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") + has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true verb=create if [ "$has_previous_draft" = "true" ]; then From 7307ce775c46083ae426e4c534caf59f6a2b61bf Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 May 2022 15:45:49 +0900 Subject: [PATCH 21/23] fix(lidar_centerpoint): fix google drive url to avoid 404 (#889) * fix(lidar_centerpoint): fix google drive url to avoid 404 * Update CMakeLists.txt Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- perception/lidar_centerpoint/CMakeLists.txt | 4 ++-- perception/tensorrt_yolo/CMakeLists.txt | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 0cf1f51654bb1..4f15575181348 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -86,13 +86,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) message(STATUS "File already exists.") else() message(STATUS "File hash changes. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() else() message(STATUS "File doesn't exists. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index a50af6bfa9abb..e8ac60c30ed37 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -93,7 +93,7 @@ message(STATUS "Checking and downloading yolov4.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx + COMMAND gdown "https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx ERROR_QUIET ) endif() @@ -115,7 +115,7 @@ message(STATUS "Checking and downloading yolov5s.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx + COMMAND gdown "https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx ERROR_QUIET ) endif() @@ -126,7 +126,7 @@ message(STATUS "Checking and downloading yolov5m.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx + COMMAND gdown "https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx ERROR_QUIET ) endif() From 35e8c0c2b88a96b8243db252621fd61d0e8003d1 Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Thu, 12 May 2022 22:23:07 +0900 Subject: [PATCH 22/23] feat(trajectory_follower): integrate latlon controller Signed-off-by: kosuke55 --- control/trajectory_follower/CMakeLists.txt | 8 + .../lateral_controller_base.hpp | 55 + .../longitudinal_controller_base.hpp | 51 + .../mpc_lateral_controller.hpp | 236 +++++ .../pid_longitudinal_controller.hpp | 382 +++++++ .../include/trajectory_follower/sync_data.hpp | 41 + control/trajectory_follower/package.xml | 1 + .../src/mpc_lateral_controller.cpp | 535 ++++++++++ .../src/pid_longitudinal_controller.cpp | 957 ++++++++++++++++++ .../trajectory_follower_nodes/CMakeLists.txt | 12 + .../controller_node.hpp | 89 ++ .../lateral_controller_defaults.param.yaml | 1 - ...ongitudinal_controller_defaults.param.yaml | 1 - .../src/controller_node.cpp | 80 ++ .../lateral_controller.param.yaml | 1 - .../longitudinal_controller.param.yaml | 1 - 16 files changed, 2447 insertions(+), 4 deletions(-) create mode 100644 control/trajectory_follower/include/trajectory_follower/lateral_controller_base.hpp create mode 100644 control/trajectory_follower/include/trajectory_follower/longitudinal_controller_base.hpp create mode 100644 control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp create mode 100644 control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp create mode 100644 control/trajectory_follower/include/trajectory_follower/sync_data.hpp create mode 100644 control/trajectory_follower/src/mpc_lateral_controller.cpp create mode 100644 control/trajectory_follower/src/pid_longitudinal_controller.cpp create mode 100644 control/trajectory_follower_nodes/include/trajectory_follower_nodes/controller_node.hpp create mode 100644 control/trajectory_follower_nodes/src/controller_node.cpp diff --git a/control/trajectory_follower/CMakeLists.txt b/control/trajectory_follower/CMakeLists.txt index 67d157df835de..5d564ba33c62b 100644 --- a/control/trajectory_follower/CMakeLists.txt +++ b/control/trajectory_follower/CMakeLists.txt @@ -7,6 +7,7 @@ autoware_package() # lateral_controller set(LATERAL_CONTROLLER_LIB lateral_controller_lib) set(LATERAL_CONTROLLER_LIB_SRC + src/mpc_lateral_controller.cpp src/interpolate.cpp src/lowpass_filter.cpp src/mpc.cpp @@ -21,6 +22,9 @@ set(LATERAL_CONTROLLER_LIB_SRC ) set(LATERAL_CONTROLLER_LIB_HEADERS + include/trajectory_follower/lateral_controller_base.hpp + include/trajectory_follower/mpc_lateral_controller.hpp + include/trajectory_follower/sync_data.hpp include/trajectory_follower/visibility_control.hpp include/trajectory_follower/interpolate.hpp include/trajectory_follower/lowpass_filter.hpp @@ -45,12 +49,16 @@ target_compile_options(${LATERAL_CONTROLLER_LIB} PRIVATE -Wno-error=old-style-ca # longitudinal_controller set(LONGITUDINAL_CONTROLLER_LIB longitudinal_controller_lib) set(LONGITUDINAL_CONTROLLER_LIB_SRC + src/pid_longitudinal_controller.cpp src/pid.cpp src/smooth_stop.cpp src/longitudinal_controller_utils.cpp ) set(LONGITUDINAL_CONTROLLER_LIB_HEADERS + include/trajectory_follower/longitudinal_controller_base.hpp + include/trajectory_follower/pid_longitudinal_controller.hpp + include/trajectory_follower/sync_data.hpp include/trajectory_follower/debug_values.hpp include/trajectory_follower/pid.hpp include/trajectory_follower/smooth_stop.hpp diff --git a/control/trajectory_follower/include/trajectory_follower/lateral_controller_base.hpp b/control/trajectory_follower/include/trajectory_follower/lateral_controller_base.hpp new file mode 100644 index 0000000000000..44c26c26a0820 --- /dev/null +++ b/control/trajectory_follower/include/trajectory_follower/lateral_controller_base.hpp @@ -0,0 +1,55 @@ +// Copyright 2022 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 TRAJECTORY_FOLLOWER__LATERAL_CONTROLLER_BASE_HPP_ +#define TRAJECTORY_FOLLOWER__LATERAL_CONTROLLER_BASE_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include "trajectory_follower/sync_data.hpp" + +#include "autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp" + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +struct LateralOutput +{ + autoware_auto_control_msgs::msg::AckermannLateralCommand control_cmd; + LateralSyncData sync_data; +}; + +class LateralControllerBase +{ +public: + virtual LateralOutput run() = 0; + void sync(LongitudinalSyncData longitudinal_sync_data) + { + longitudinal_sync_data_ = longitudinal_sync_data; + }; + +protected: + LongitudinalSyncData longitudinal_sync_data_; +}; + +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER__LATERAL_CONTROLLER_BASE_HPP_ diff --git a/control/trajectory_follower/include/trajectory_follower/longitudinal_controller_base.hpp b/control/trajectory_follower/include/trajectory_follower/longitudinal_controller_base.hpp new file mode 100644 index 0000000000000..cb50b1a6af031 --- /dev/null +++ b/control/trajectory_follower/include/trajectory_follower/longitudinal_controller_base.hpp @@ -0,0 +1,51 @@ +// Copyright 2022 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 TRAJECTORY_FOLLOWER__LONGITUDINAL_CONTROLLER_BASE_HPP_ +#define TRAJECTORY_FOLLOWER__LONGITUDINAL_CONTROLLER_BASE_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include "trajectory_follower/sync_data.hpp" + +#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp" + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +struct LongitudinalOutput +{ + autoware_auto_control_msgs::msg::LongitudinalCommand control_cmd; + LongitudinalSyncData sync_data; +}; +class LongitudinalControllerBase +{ +public: + virtual LongitudinalOutput run() = 0; + void sync(LateralSyncData lateral_sync_data) { lateral_sync_data_ = lateral_sync_data; }; + +protected: + LateralSyncData lateral_sync_data_; +}; + +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER__LONGITUDINAL_CONTROLLER_BASE_HPP_ diff --git a/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp b/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp new file mode 100644 index 0000000000000..8d954fed64f85 --- /dev/null +++ b/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp @@ -0,0 +1,236 @@ +// 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 TRAJECTORY_FOLLOWER__MPC_LATERAL_CONTROLLER_HPP_ +#define TRAJECTORY_FOLLOWER__MPC_LATERAL_CONTROLLER_HPP_ + +#include "common/types.hpp" +#include "osqp_interface/osqp_interface.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tf2/utils.h" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" +#include "trajectory_follower/interpolate.hpp" +#include "trajectory_follower/lateral_controller_base.hpp" +#include "trajectory_follower/lowpass_filter.hpp" +#include "trajectory_follower/mpc.hpp" +#include "trajectory_follower/mpc_trajectory.hpp" +#include "trajectory_follower/mpc_utils.hpp" +#include "trajectory_follower/qp_solver/qp_solver_osqp.hpp" +#include "trajectory_follower/qp_solver/qp_solver_unconstr_fast.hpp" +#include "trajectory_follower/sync_data.hpp" +#include "trajectory_follower/vehicle_model/vehicle_model_bicycle_dynamics.hpp" +#include "trajectory_follower/vehicle_model/vehicle_model_bicycle_kinematics.hpp" +#include "trajectory_follower/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" +#include "trajectory_follower/visibility_control.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include "autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_system_msgs/msg/float32_multi_array_diagnostic.hpp" +#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp" +#include "autoware_auto_vehicle_msgs/msg/vehicle_odometry.hpp" +#include "geometry_msgs/msg/pose.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "tf2_msgs/msg/tf_message.hpp" + +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +using autoware::common::types::bool8_t; +using autoware::common::types::float64_t; +namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; + +class TRAJECTORY_FOLLOWER_PUBLIC MpcLateralController : public LateralControllerBase +{ +public: + /** + * @brief constructor + */ + explicit MpcLateralController(rclcpp::Node * node); + + /** + * @brief destructor + */ + virtual ~MpcLateralController(); + +private: + rclcpp::Node::SharedPtr node_; + + //!< @brief topic publisher for control command + rclcpp::Publisher::SharedPtr + m_pub_ctrl_cmd; + //!< @brief topic publisher for predicted trajectory + rclcpp::Publisher::SharedPtr m_pub_predicted_traj; + //!< @brief topic publisher for control diagnostic + rclcpp::Publisher::SharedPtr + m_pub_diagnostic; + //!< @brief topic subscription for reference waypoints + rclcpp::Subscription::SharedPtr m_sub_ref_path; + //!< @brief subscription for current velocity + rclcpp::Subscription::SharedPtr m_sub_odometry; + //!< @brief subscription for current steering + rclcpp::Subscription::SharedPtr m_sub_steering; + //!< @brief timer to update after a given interval + rclcpp::TimerBase::SharedPtr m_timer; + //!< @brief subscription for transform messages + rclcpp::Subscription::SharedPtr m_tf_sub; + rclcpp::Subscription::SharedPtr m_tf_static_sub; + + /* parameters for path smoothing */ + //!< @brief flag for path smoothing + bool8_t m_enable_path_smoothing; + //!< @brief param of moving average filter for path smoothing + int64_t m_path_filter_moving_ave_num; + //!< @brief point-to-point index distance for curvature calculation for trajectory //NOLINT + int64_t m_curvature_smoothing_num_traj; + //!< @brief point-to-point index distance for curvature calculation for reference steer command + //!< //NOLINT + int64_t m_curvature_smoothing_num_ref_steer; + //!< @brief path resampling interval [m] + float64_t m_traj_resample_dist; + + /* parameters for stop state */ + float64_t m_stop_state_entry_ego_speed; + float64_t m_stop_state_entry_target_speed; + + // MPC object + trajectory_follower::MPC m_mpc; + + //!< @brief measured pose + geometry_msgs::msg::PoseStamped::SharedPtr m_current_pose_ptr; + //!< @brief measured velocity + nav_msgs::msg::Odometry::SharedPtr m_current_odometry_ptr; + //!< @brief measured steering + autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr m_current_steering_ptr; + //!< @brief reference trajectory + autoware_auto_planning_msgs::msg::Trajectory::SharedPtr m_current_trajectory_ptr; + + //!< @brief mpc filtered output in previous period + float64_t m_steer_cmd_prev = 0.0; + + //!< @brief flag of m_ctrl_cmd_prev initialization + bool8_t m_is_ctrl_cmd_prev_initialized = false; + //!< @brief previous control command + autoware_auto_control_msgs::msg::AckermannLateralCommand m_ctrl_cmd_prev; + + //!< @brief buffer for transforms + tf2::BufferCore m_tf_buffer{tf2::BUFFER_CORE_DEFAULT_CACHE_TIME}; + tf2_ros::TransformListener m_tf_listener{m_tf_buffer}; + + LateralSyncData lateral_sync_data_; + + //!< initialize timer to work in real, simulation, and replay + void initTimer(float64_t period_s); + /** + * @brief compute and publish control command for path follow with a constant control period + */ + LateralOutput run() override; + + /** + * @brief set m_current_trajectory with received message + */ + void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr); + + /** + * @brief update current_pose from tf + * @return true if the current pose was updated, false otherwise + */ + bool8_t updateCurrentPose(); + + /** + * @brief check if the received data is valid. + */ + bool8_t checkData() const; + + /** + * @brief set current_velocity with received message + */ + void onOdometry(const nav_msgs::msg::Odometry::SharedPtr msg); + + /** + * @brief set current_steering with received message + */ + void onSteering(const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg); + + /** + * @brief create control command + * @param [in] cmd published control command + */ + autoware_auto_control_msgs::msg::AckermannLateralCommand createCtrlCmdMsg( + autoware_auto_control_msgs::msg::AckermannLateralCommand cmd); + + /** + * @brief publish predicted future trajectory + * @param [in] predicted_traj published predicted trajectory + */ + void publishPredictedTraj(autoware_auto_planning_msgs::msg::Trajectory & predicted_traj) const; + + /** + * @brief publish diagnostic message + * @param [in] diagnostic published diagnostic + */ + void publishDiagnostic( + autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic & diagnostic) const; + + /** + * @brief get stop command + */ + autoware_auto_control_msgs::msg::AckermannLateralCommand getStopControlCommand() const; + + /** + * @brief get initial command + */ + autoware_auto_control_msgs::msg::AckermannLateralCommand getInitialControlCommand() const; + + /** + * @brief check ego car is in stopped state + */ + bool8_t isStoppedState() const; + + /** + * @brief check if the trajectory has valid value + */ + bool8_t isValidTrajectory(const autoware_auto_planning_msgs::msg::Trajectory & traj) const; + + rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res; + + /** + * @brief Declare MPC parameters as ROS parameters to allow tuning on the fly + */ + void declareMPCparameters(); + + /** + * @brief Called when parameters are changed outside of node + */ + rcl_interfaces::msg::SetParametersResult paramCallback( + const std::vector & parameters); +}; +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER__MPC_LATERAL_CONTROLLER_HPP_ diff --git a/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp b/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp new file mode 100644 index 0000000000000..df202f4b1a3e0 --- /dev/null +++ b/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp @@ -0,0 +1,382 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TRAJECTORY_FOLLOWER__PID_LONGITUDINAL_CONTROLLER_HPP_ +#define TRAJECTORY_FOLLOWER__PID_LONGITUDINAL_CONTROLLER_HPP_ + +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/Geometry" +#include "motion_common/motion_common.hpp" +#include "motion_common/trajectory_common.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tf2/utils.h" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" +#include "trajectory_follower/debug_values.hpp" +#include "trajectory_follower/longitudinal_controller_base.hpp" +#include "trajectory_follower/longitudinal_controller_utils.hpp" +#include "trajectory_follower/lowpass_filter.hpp" +#include "trajectory_follower/pid.hpp" +#include "trajectory_follower/smooth_stop.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_system_msgs/msg/float32_multi_array_diagnostic.hpp" +#include "autoware_auto_vehicle_msgs/msg/vehicle_odometry.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "tf2_msgs/msg/tf_message.hpp" + +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +using autoware::common::types::bool8_t; +using autoware::common::types::float64_t; +namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; +namespace motion_common = ::autoware::motion::motion_common; + +/// \class PidLongitudinalController +/// \brief The node class used for generating longitudinal control commands (velocity/acceleration) +class TRAJECTORY_FOLLOWER_PUBLIC PidLongitudinalController : public LongitudinalControllerBase +{ +public: + explicit PidLongitudinalController(rclcpp::Node * node); + +private: + struct Motion + { + float64_t vel{0.0}; + float64_t acc{0.0}; + }; + + enum class Shift { Forward = 0, Reverse }; + + struct ControlData + { + bool8_t is_far_from_trajectory{false}; + size_t nearest_idx{0}; // nearest_idx = 0 when nearest_idx is not found with findNearestIdx + Motion current_motion{}; + Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation + float64_t stop_dist{0.0}; // signed distance that is positive when car is before the stopline + float64_t slope_angle{0.0}; + float64_t dt{0.0}; + }; + rclcpp::Node::SharedPtr node_; + rclcpp::Logger logger_; + rclcpp::Clock::SharedPtr clock_; + + // ros variables + rclcpp::Subscription::SharedPtr m_sub_current_velocity; + rclcpp::Subscription::SharedPtr m_sub_trajectory; + rclcpp::Publisher::SharedPtr + m_pub_control_cmd; + rclcpp::Publisher::SharedPtr + m_pub_slope; + rclcpp::Publisher::SharedPtr + m_pub_debug; + rclcpp::TimerBase::SharedPtr m_timer_control; + + rclcpp::Subscription::SharedPtr m_tf_sub; + rclcpp::Subscription::SharedPtr m_tf_static_sub; + tf2::BufferCore m_tf_buffer{tf2::BUFFER_CORE_DEFAULT_CACHE_TIME}; + tf2_ros::TransformListener m_tf_listener{m_tf_buffer}; + + rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res; + rcl_interfaces::msg::SetParametersResult paramCallback( + const std::vector & parameters); + + // pointers for ros topic + std::shared_ptr m_current_velocity_ptr{nullptr}; + std::shared_ptr m_prev_velocity_ptr{nullptr}; + std::shared_ptr m_trajectory_ptr{nullptr}; + + // vehicle info + float64_t m_wheel_base; + + // control state + enum class ControlState { DRIVE = 0, STOPPING, STOPPED, EMERGENCY }; + ControlState m_control_state{ControlState::STOPPED}; + + // control period + float64_t m_longitudinal_ctrl_period; + + // delay compensation + float64_t m_delay_compensation_time; + + // enable flags + bool8_t m_enable_smooth_stop; + bool8_t m_enable_overshoot_emergency; + bool8_t m_enable_slope_compensation; + + // smooth stop transition + struct StateTransitionParams + { + // drive + float64_t drive_state_stop_dist; + float64_t drive_state_offset_stop_dist; + // stopping + float64_t stopping_state_stop_dist; + // stop + float64_t stopped_state_entry_duration_time; + float64_t stopped_state_entry_vel; + float64_t stopped_state_entry_acc; + // emergency + float64_t emergency_state_overshoot_stop_dist; + float64_t emergency_state_traj_trans_dev; + float64_t emergency_state_traj_rot_dev; + }; + StateTransitionParams m_state_transition_params; + + // drive + trajectory_follower::PIDController m_pid_vel; + std::shared_ptr m_lpf_vel_error{nullptr}; + float64_t m_current_vel_threshold_pid_integrate; + bool8_t m_enable_brake_keeping_before_stop; + float64_t m_brake_keeping_acc; + + // smooth stop + trajectory_follower::SmoothStop m_smooth_stop; + + // stop + struct StoppedStateParams + { + float64_t vel; + float64_t acc; + float64_t jerk; + }; + StoppedStateParams m_stopped_state_params; + + // emergency + struct EmergencyStateParams + { + float64_t vel; + float64_t acc; + float64_t jerk; + }; + EmergencyStateParams m_emergency_state_params; + + // acceleration limit + float64_t m_max_acc; + float64_t m_min_acc; + + // jerk limit + float64_t m_max_jerk; + float64_t m_min_jerk; + + // slope compensation + bool8_t m_use_traj_for_pitch; + std::shared_ptr m_lpf_pitch{nullptr}; + float64_t m_max_pitch_rad; + float64_t m_min_pitch_rad; + + // 1st order lowpass filter for acceleration + std::shared_ptr m_lpf_acc{nullptr}; + + // buffer of send command + std::vector m_ctrl_cmd_vec; + + // for calculating dt + std::shared_ptr m_prev_control_time{nullptr}; + + // shift mode + Shift m_prev_shift{Shift::Forward}; + + // diff limit + Motion m_prev_ctrl_cmd{}; // with slope compensation + Motion m_prev_raw_ctrl_cmd{}; // without slope compensation + std::vector> m_vel_hist; + + // debug values + trajectory_follower::DebugValues m_debug_values; + + std::shared_ptr m_last_running_time{ + std::make_shared(rclcpp::Clock{RCL_ROS_TIME}.now())}; + + LateralSyncData lateral_sync_data_; + + /** + * @brief set current and previous velocity with received message + * @param [in] msg current state message + */ + void callbackCurrentVelocity(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + + /** + * @brief set reference trajectory with received message + * @param [in] msg trajectory message + */ + void callbackTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg); + + /** + * @brief compute control command, and publish periodically + */ + // void callbackTimerControl(); + LongitudinalOutput run() override; + + /** + * @brief calculate data for controllers whose type is ControlData + * @param [in] current_pose current ego pose + */ + ControlData getControlData(const geometry_msgs::msg::Pose & current_pose); + + /** + * @brief calculate control command in emergency state + * @param [in] dt time between previous and current one + */ + Motion calcEmergencyCtrlCmd(const float64_t dt) const; + + /** + * @brief update control state according to the current situation + * @param [in] current_control_state current control state + * @param [in] control_data control data + */ + ControlState updateControlState( + const ControlState current_control_state, const ControlData & control_data); + + /** + * @brief calculate control command based on the current control state + * @param [in] current_control_state current control state + * @param [in] current_pose current ego pose + * @param [in] control_data control data + */ + Motion calcCtrlCmd( + const ControlState & current_control_state, const geometry_msgs::msg::Pose & current_pose, + const ControlData & control_data); + + /** + * @brief publish control command + * @param [in] ctrl_cmd calculated control command to control velocity + * @param [in] current_vel current velocity of the vehicle + */ + autoware_auto_control_msgs::msg::LongitudinalCommand createCtrlCmdMsg( + const Motion & ctrl_cmd, const float64_t current_vel); + + /** + * @brief publish debug data + * @param [in] ctrl_cmd calculated control command to control velocity + * @param [in] control_data data for control calculation + */ + void publishDebugData(const Motion & ctrl_cmd, const ControlData & control_data); + + /** + * @brief calculate time between current and previous one + */ + float64_t getDt(); + + /** + * @brief calculate current velocity and acceleration + */ + Motion getCurrentMotion() const; + + /** + * @brief calculate direction (forward or backward) that vehicle moves + * @param [in] nearest_idx nearest index on trajectory to vehicle + */ + enum Shift getCurrentShift(const size_t nearest_idx) const; + + /** + * @brief filter acceleration command with limitation of acceleration and jerk, and slope + * compensation + * @param [in] raw_acc acceleration before filtered + * @param [in] control_data data for control calculation + */ + float64_t calcFilteredAcc(const float64_t raw_acc, const ControlData & control_data); + + /** + * @brief store acceleration command before slope compensation + * @param [in] accel command before slope compensation + */ + void storeAccelCmd(const float64_t accel); + + /** + * @brief add acceleration to compensate for slope + * @param [in] acc acceleration before slope compensation + * @param [in] pitch pitch angle (upward is negative) + * @param [in] shift direction that vehicle move (forward or backward) + */ + float64_t applySlopeCompensation( + const float64_t acc, const float64_t pitch, const Shift shift) const; + + /** + * @brief keep target motion acceleration negative before stop + * @param [in] traj reference trajectory + * @param [in] motion delay compensated target motion + */ + Motion keepBrakeBeforeStop( + const autoware_auto_planning_msgs::msg::Trajectory & traj, const Motion & target_motion, + const size_t nearest_idx) const; + + /** + * @brief interpolate trajectory point that is nearest to vehicle + * @param [in] traj reference trajectory + * @param [in] point vehicle position + * @param [in] nearest_idx index of the trajectory point nearest to the vehicle position + */ + autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const geometry_msgs::msg::Point & point, const size_t nearest_idx) const; + + /** + * @brief calculate predicted velocity after time delay based on past control commands + * @param [in] current_motion current velocity and acceleration of the vehicle + * @param [in] delay_compensation_time predicted time delay + */ + float64_t predictedVelocityInTargetPoint( + const Motion current_motion, const float64_t delay_compensation_time) const; + + /** + * @brief calculate velocity feedback with feed forward and pid controller + * @param [in] target_motion reference velocity and acceleration. This acceleration will be used + * as feed forward. + * @param [in] dt time step to use + * @param [in] current_vel current velocity of the vehicle + */ + float64_t applyVelocityFeedback( + const Motion target_motion, const float64_t dt, const float64_t current_vel); + + /** + * @brief update variables for debugging about pitch + * @param [in] pitch current pitch of the vehicle (filtered) + * @param [in] traj_pitch current trajectory pitch + * @param [in] raw_pitch current raw pitch of the vehicle (unfiltered) + */ + void updatePitchDebugValues( + const float64_t pitch, const float64_t traj_pitch, const float64_t raw_pitch); + + /** + * @brief update variables for velocity and acceleration + * @param [in] ctrl_cmd latest calculated control command + * @param [in] current_pose current pose of the vehicle + * @param [in] control_data data for control calculation + */ + void updateDebugVelAcc( + const Motion & ctrl_cmd, const geometry_msgs::msg::Pose & current_pose, + const ControlData & control_data); +}; +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER__PID_LONGITUDINAL_CONTROLLER_HPP_ diff --git a/control/trajectory_follower/include/trajectory_follower/sync_data.hpp b/control/trajectory_follower/include/trajectory_follower/sync_data.hpp new file mode 100644 index 0000000000000..48224a5498a9c --- /dev/null +++ b/control/trajectory_follower/include/trajectory_follower/sync_data.hpp @@ -0,0 +1,41 @@ +// Copyright 2022 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 TRAJECTORY_FOLLOWER__SYNC_DATA_HPP_ +#define TRAJECTORY_FOLLOWER__SYNC_DATA_HPP_ + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +struct LateralSyncData +{ + bool is_steer_converged{false}; +}; + +struct LongitudinalSyncData +{ + bool is_velocity_converged{false}; +}; + +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER__SYNC_DATA_HPP_ diff --git a/control/trajectory_follower/package.xml b/control/trajectory_follower/package.xml index 840cad74aeb55..c68b1013ab252 100644 --- a/control/trajectory_follower/package.xml +++ b/control/trajectory_follower/package.xml @@ -27,6 +27,7 @@ std_msgs tf2 tf2_ros + vehicle_info_util ament_cmake_ros ament_lint_auto diff --git a/control/trajectory_follower/src/mpc_lateral_controller.cpp b/control/trajectory_follower/src/mpc_lateral_controller.cpp new file mode 100644 index 0000000000000..b31a3e2ea74cd --- /dev/null +++ b/control/trajectory_follower/src/mpc_lateral_controller.cpp @@ -0,0 +1,535 @@ +// 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 "trajectory_follower/mpc_lateral_controller.hpp" + +#include "tf2_ros/create_timer_ros.h" + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +namespace +{ +using namespace std::literals::chrono_literals; + +template +void update_param( + const std::vector & parameters, const std::string & name, T & value) +{ + auto it = std::find_if( + parameters.cbegin(), parameters.cend(), + [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; }); + if (it != parameters.cend()) { + value = static_cast(it->template get_value()); + } +} +} // namespace + +MpcLateralController::MpcLateralController(rclcpp::Node * node) : node_{node} +{ + using std::placeholders::_1; + + m_mpc.m_ctrl_period = node_->get_parameter("ctrl_period").as_double(); + m_enable_path_smoothing = node_->declare_parameter("enable_path_smoothing"); + m_path_filter_moving_ave_num = node_->declare_parameter("path_filter_moving_ave_num"); + m_curvature_smoothing_num_traj = + node_->declare_parameter("curvature_smoothing_num_traj"); + m_curvature_smoothing_num_ref_steer = + node_->declare_parameter("curvature_smoothing_num_ref_steer"); + m_traj_resample_dist = node_->declare_parameter("traj_resample_dist"); + m_mpc.m_admissible_position_error = + node_->declare_parameter("admissible_position_error"); + m_mpc.m_admissible_yaw_error_rad = + node_->declare_parameter("admissible_yaw_error_rad"); + m_mpc.m_use_steer_prediction = node_->declare_parameter("use_steer_prediction"); + m_mpc.m_param.steer_tau = node_->declare_parameter("vehicle_model_steer_tau"); + + /* stop state parameters */ + m_stop_state_entry_ego_speed = node_->declare_parameter("stop_state_entry_ego_speed"); + m_stop_state_entry_target_speed = + node_->declare_parameter("stop_state_entry_target_speed"); + + /* mpc parameters */ + const float64_t steer_lim_deg = node_->declare_parameter("steer_lim_deg"); + const float64_t steer_rate_lim_dps = node_->declare_parameter("steer_rate_lim_dps"); + constexpr float64_t deg2rad = static_cast(autoware::common::types::PI) / 180.0; + m_mpc.m_steer_lim = steer_lim_deg * deg2rad; + m_mpc.m_steer_rate_lim = steer_rate_lim_dps * deg2rad; + const float64_t wheelbase = + vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo().wheel_base_m; + + /* vehicle model setup */ + const std::string vehicle_model_type = + node_->declare_parameter("vehicle_model_type"); + std::shared_ptr vehicle_model_ptr; + if (vehicle_model_type == "kinematics") { + vehicle_model_ptr = std::make_shared( + wheelbase, m_mpc.m_steer_lim, m_mpc.m_param.steer_tau); + } else if (vehicle_model_type == "kinematics_no_delay") { + vehicle_model_ptr = std::make_shared( + wheelbase, m_mpc.m_steer_lim); + } else if (vehicle_model_type == "dynamics") { + const float64_t mass_fl = node_->declare_parameter("vehicle.mass_fl"); + const float64_t mass_fr = node_->declare_parameter("vehicle.mass_fr"); + const float64_t mass_rl = node_->declare_parameter("vehicle.mass_rl"); + const float64_t mass_rr = node_->declare_parameter("vehicle.mass_rr"); + const float64_t cf = node_->declare_parameter("vehicle.cf"); + const float64_t cr = node_->declare_parameter("vehicle.cr"); + + // vehicle_model_ptr is only assigned in ctor, so parameter value have to be passed at init time + // // NOLINT + vehicle_model_ptr = std::make_shared( + wheelbase, mass_fl, mass_fr, mass_rl, mass_rr, cf, cr); + } else { + RCLCPP_ERROR(node_->get_logger(), "vehicle_model_type is undefined"); + } + + /* QP solver setup */ + const std::string qp_solver_type = node_->declare_parameter("qp_solver_type"); + std::shared_ptr qpsolver_ptr; + if (qp_solver_type == "unconstraint_fast") { + qpsolver_ptr = std::make_shared(); + } else if (qp_solver_type == "osqp") { + qpsolver_ptr = std::make_shared(node_->get_logger()); + } else { + RCLCPP_ERROR(node_->get_logger(), "qp_solver_type is undefined"); + } + + /* delay compensation */ + { + const float64_t delay_tmp = node_->declare_parameter("input_delay"); + const float64_t delay_step = std::round(delay_tmp / m_mpc.m_ctrl_period); + m_mpc.m_param.input_delay = delay_step * m_mpc.m_ctrl_period; + m_mpc.m_input_buffer = std::deque(static_cast(delay_step), 0.0); + } + + /* initialize lowpass filter */ + { + const float64_t steering_lpf_cutoff_hz = + node_->declare_parameter("steering_lpf_cutoff_hz"); + const float64_t error_deriv_lpf_cutoff_hz = + node_->declare_parameter("error_deriv_lpf_cutoff_hz"); + m_mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); + } + + /* set up ros system */ + // initTimer(m_mpc.m_ctrl_period); + + m_pub_ctrl_cmd = + node_->create_publisher( + "~/output/lateral_control_cmd", 1); + m_pub_predicted_traj = node_->create_publisher( + "~/output/predicted_trajectory", 1); + m_pub_diagnostic = + node_->create_publisher( + "~/output/lateral_diagnostic", 1); + m_sub_ref_path = node_->create_subscription( + "~/input/current_trajectory", rclcpp::QoS{1}, + std::bind(&MpcLateralController::onTrajectory, this, _1)); + m_sub_steering = node_->create_subscription( + "~/input/current_steering", rclcpp::QoS{1}, + std::bind(&MpcLateralController::onSteering, this, _1)); + m_sub_odometry = node_->create_subscription( + "~/input/current_odometry", rclcpp::QoS{1}, + std::bind(&MpcLateralController::onOdometry, this, _1)); + + // TODO(Frederik.Beaujean) ctor is too long, should factor out parameter declarations + declareMPCparameters(); + + /* get parameter updates */ + m_set_param_res = node_->add_on_set_parameters_callback( + std::bind(&MpcLateralController::paramCallback, this, _1)); + + m_mpc.setQPSolver(qpsolver_ptr); + m_mpc.setVehicleModel(vehicle_model_ptr, vehicle_model_type); + + m_mpc.setLogger(node_->get_logger()); + m_mpc.setClock(node_->get_clock()); +} + +MpcLateralController::~MpcLateralController() +{ + autoware_auto_control_msgs::msg::AckermannLateralCommand stop_cmd = getStopControlCommand(); + createCtrlCmdMsg(stop_cmd); // todo +} + +LateralOutput MpcLateralController::run() +{ + if (!checkData() || !updateCurrentPose()) { + LateralOutput output{}; + return output; // todo + } + + autoware_auto_control_msgs::msg::AckermannLateralCommand ctrl_cmd; + autoware_auto_planning_msgs::msg::Trajectory predicted_traj; + autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic diagnostic; + + if (!m_is_ctrl_cmd_prev_initialized) { + m_ctrl_cmd_prev = getInitialControlCommand(); + m_is_ctrl_cmd_prev_initialized = true; + } + + const bool8_t is_mpc_solved = m_mpc.calculateMPC( + *m_current_steering_ptr, m_current_odometry_ptr->twist.twist.linear.x, m_current_pose_ptr->pose, + ctrl_cmd, predicted_traj, diagnostic); + + if (isStoppedState()) { + // Reset input buffer + for (auto & value : m_mpc.m_input_buffer) { + value = m_ctrl_cmd_prev.steering_tire_angle; + } + // Use previous command value as previous raw steer command + m_mpc.m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle; + + const auto cmd_msg = createCtrlCmdMsg(m_ctrl_cmd_prev); + publishPredictedTraj(predicted_traj); + publishDiagnostic(diagnostic); + LateralOutput output{cmd_msg}; + return output; + } + + if (!is_mpc_solved) { + RCLCPP_WARN_SKIPFIRST_THROTTLE( + node_->get_logger(), *node_->get_clock(), 5000 /*ms*/, + "MPC is not solved. publish 0 velocity."); + ctrl_cmd = getStopControlCommand(); + } + + m_ctrl_cmd_prev = ctrl_cmd; + const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd); + publishPredictedTraj(predicted_traj); + publishDiagnostic(diagnostic); + LateralOutput output{cmd_msg}; + return output; +} + +bool8_t MpcLateralController::checkData() const +{ + if (!m_mpc.hasVehicleModel()) { + RCLCPP_DEBUG(node_->get_logger(), "MPC does not have a vehicle model"); + return false; + } + if (!m_mpc.hasQPSolver()) { + RCLCPP_DEBUG(node_->get_logger(), "MPC does not have a QP solver"); + return false; + } + + if (!m_current_odometry_ptr) { + RCLCPP_DEBUG( + node_->get_logger(), "waiting data. current_velocity = %d", + m_current_odometry_ptr != nullptr); + return false; + } + + if (!m_current_steering_ptr) { + RCLCPP_DEBUG( + node_->get_logger(), "waiting data. current_steering = %d", + m_current_steering_ptr != nullptr); + return false; + } + + if (m_mpc.m_ref_traj.size() == 0) { + RCLCPP_DEBUG(node_->get_logger(), "trajectory size is zero."); + return false; + } + + return true; +} + +void MpcLateralController::onTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) +{ + m_current_trajectory_ptr = msg; + + if (!m_current_pose_ptr && !updateCurrentPose()) { + RCLCPP_DEBUG(node_->get_logger(), "Current pose is not received yet."); + return; + } + + if (msg->points.size() < 3) { + RCLCPP_DEBUG(node_->get_logger(), "received path size is < 3, not enough."); + return; + } + + if (!isValidTrajectory(*msg)) { + RCLCPP_ERROR(node_->get_logger(), "Trajectory is invalid!! stop computing."); + return; + } + + m_mpc.setReferenceTrajectory( + *msg, m_traj_resample_dist, m_enable_path_smoothing, m_path_filter_moving_ave_num, + m_curvature_smoothing_num_traj, m_curvature_smoothing_num_ref_steer, m_current_pose_ptr); +} + +bool8_t MpcLateralController::updateCurrentPose() +{ + geometry_msgs::msg::TransformStamped transform; + try { + transform = m_tf_buffer.lookupTransform( + m_current_trajectory_ptr->header.frame_id, "base_link", tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_SKIPFIRST_THROTTLE( + node_->get_logger(), *node_->get_clock(), 5000 /*ms*/, ex.what()); + RCLCPP_WARN_SKIPFIRST_THROTTLE( + node_->get_logger(), *node_->get_clock(), 5000 /*ms*/, + m_tf_buffer.allFramesAsString().c_str()); + return false; + } + + geometry_msgs::msg::PoseStamped ps; + ps.header = transform.header; + ps.pose.position.x = transform.transform.translation.x; + ps.pose.position.y = transform.transform.translation.y; + ps.pose.position.z = transform.transform.translation.z; + ps.pose.orientation = transform.transform.rotation; + m_current_pose_ptr = std::make_shared(ps); + return true; +} + +void MpcLateralController::onOdometry(const nav_msgs::msg::Odometry::SharedPtr msg) +{ + m_current_odometry_ptr = msg; +} + +void MpcLateralController::onSteering( + const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) +{ + m_current_steering_ptr = msg; +} + +autoware_auto_control_msgs::msg::AckermannLateralCommand +MpcLateralController::getStopControlCommand() const +{ + autoware_auto_control_msgs::msg::AckermannLateralCommand cmd; + cmd.steering_tire_angle = static_cast(m_steer_cmd_prev); + cmd.steering_tire_rotation_rate = 0.0; + return cmd; +} + +autoware_auto_control_msgs::msg::AckermannLateralCommand +MpcLateralController::getInitialControlCommand() const +{ + autoware_auto_control_msgs::msg::AckermannLateralCommand cmd; + cmd.steering_tire_angle = m_current_steering_ptr->steering_tire_angle; + cmd.steering_tire_rotation_rate = 0.0; + return cmd; +} + +bool8_t MpcLateralController::isStoppedState() const +{ + // Note: This function used to take into account the distance to the stop line + // for the stop state judgement. However, it has been removed since the steering + // control was turned off when approaching/exceeding the stop line on a curve or + // emergency stop situation and it caused large tracking error. + const int64_t nearest = trajectory_follower::MPCUtils::calcNearestIndex( + *m_current_trajectory_ptr, m_current_pose_ptr->pose); + + // If the nearest index is not found, return false + if (nearest < 0) { + return false; + } + + const float64_t current_vel = m_current_odometry_ptr->twist.twist.linear.x; + const float64_t target_vel = + m_current_trajectory_ptr->points.at(static_cast(nearest)).longitudinal_velocity_mps; + if ( + std::fabs(current_vel) < m_stop_state_entry_ego_speed && + std::fabs(target_vel) < m_stop_state_entry_target_speed) { + return true; + } else { + return false; + } +} + +autoware_auto_control_msgs::msg::AckermannLateralCommand MpcLateralController::createCtrlCmdMsg( + autoware_auto_control_msgs::msg::AckermannLateralCommand ctrl_cmd) +{ + ctrl_cmd.stamp = node_->now(); + // m_pub_ctrl_cmd->publish(ctrl_cmd); + m_steer_cmd_prev = ctrl_cmd.steering_tire_angle; + return ctrl_cmd; +} + +void MpcLateralController::publishPredictedTraj( + autoware_auto_planning_msgs::msg::Trajectory & predicted_traj) const +{ + predicted_traj.header.stamp = node_->now(); + predicted_traj.header.frame_id = m_current_trajectory_ptr->header.frame_id; + m_pub_predicted_traj->publish(predicted_traj); +} + +void MpcLateralController::publishDiagnostic( + autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic & diagnostic) const +{ + diagnostic.diag_header.data_stamp = node_->now(); + diagnostic.diag_header.name = std::string("linear-MPC lateral controller"); + m_pub_diagnostic->publish(diagnostic); +} + +// void MpcLateralController::initTimer(float64_t period_s) +// { +// const auto period_ns = std::chrono::duration_cast( +// std::chrono::duration(period_s)); +// m_timer = rclcpp::create_timer( +// this, node_->get_clock(), period_ns, std::bind(&MpcLateralController::onTimer, this)); +// } + +void MpcLateralController::declareMPCparameters() +{ + m_mpc.m_param.prediction_horizon = node_->declare_parameter("mpc_prediction_horizon"); + m_mpc.m_param.prediction_dt = node_->declare_parameter("mpc_prediction_dt"); + m_mpc.m_param.weight_lat_error = node_->declare_parameter("mpc_weight_lat_error"); + m_mpc.m_param.weight_heading_error = + node_->declare_parameter("mpc_weight_heading_error"); + m_mpc.m_param.weight_heading_error_squared_vel = + node_->declare_parameter("mpc_weight_heading_error_squared_vel"); + m_mpc.m_param.weight_steering_input = + node_->declare_parameter("mpc_weight_steering_input"); + m_mpc.m_param.weight_steering_input_squared_vel = + node_->declare_parameter("mpc_weight_steering_input_squared_vel"); + m_mpc.m_param.weight_lat_jerk = node_->declare_parameter("mpc_weight_lat_jerk"); + m_mpc.m_param.weight_steer_rate = node_->declare_parameter("mpc_weight_steer_rate"); + m_mpc.m_param.weight_steer_acc = node_->declare_parameter("mpc_weight_steer_acc"); + m_mpc.m_param.low_curvature_weight_lat_error = + node_->declare_parameter("mpc_low_curvature_weight_lat_error"); + m_mpc.m_param.low_curvature_weight_heading_error = + node_->declare_parameter("mpc_low_curvature_weight_heading_error"); + m_mpc.m_param.low_curvature_weight_heading_error_squared_vel = + node_->declare_parameter("mpc_low_curvature_weight_heading_error_squared_vel"); + m_mpc.m_param.low_curvature_weight_steering_input = + node_->declare_parameter("mpc_low_curvature_weight_steering_input"); + m_mpc.m_param.low_curvature_weight_steering_input_squared_vel = + node_->declare_parameter("mpc_low_curvature_weight_steering_input_squared_vel"); + m_mpc.m_param.low_curvature_weight_lat_jerk = + node_->declare_parameter("mpc_low_curvature_weight_lat_jerk"); + m_mpc.m_param.low_curvature_weight_steer_rate = + node_->declare_parameter("mpc_low_curvature_weight_steer_rate"); + m_mpc.m_param.low_curvature_weight_steer_acc = + node_->declare_parameter("mpc_low_curvature_weight_steer_acc"); + m_mpc.m_param.low_curvature_thresh_curvature = + node_->declare_parameter("mpc_low_curvature_thresh_curvature"); + m_mpc.m_param.weight_terminal_lat_error = + node_->declare_parameter("mpc_weight_terminal_lat_error"); + m_mpc.m_param.weight_terminal_heading_error = + node_->declare_parameter("mpc_weight_terminal_heading_error"); + m_mpc.m_param.zero_ff_steer_deg = node_->declare_parameter("mpc_zero_ff_steer_deg"); + m_mpc.m_param.acceleration_limit = node_->declare_parameter("mpc_acceleration_limit"); + m_mpc.m_param.velocity_time_constant = + node_->declare_parameter("mpc_velocity_time_constant"); +} + +rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback( + const std::vector & parameters) +{ + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + + // strong exception safety wrt MPCParam + trajectory_follower::MPCParam param = m_mpc.m_param; + try { + update_param(parameters, "mpc_prediction_horizon", param.prediction_horizon); + update_param(parameters, "mpc_prediction_dt", param.prediction_dt); + update_param(parameters, "mpc_weight_lat_error", param.weight_lat_error); + update_param(parameters, "mpc_weight_heading_error", param.weight_heading_error); + update_param( + parameters, "mpc_weight_heading_error_squared_vel", param.weight_heading_error_squared_vel); + update_param(parameters, "mpc_weight_steering_input", param.weight_steering_input); + update_param( + parameters, "mpc_weight_steering_input_squared_vel", param.weight_steering_input_squared_vel); + update_param(parameters, "mpc_weight_lat_jerk", param.weight_lat_jerk); + update_param(parameters, "mpc_weight_steer_rate", param.weight_steer_rate); + update_param(parameters, "mpc_weight_steer_acc", param.weight_steer_acc); + update_param( + parameters, "mpc_low_curvature_weight_lat_error", param.low_curvature_weight_lat_error); + update_param( + parameters, "mpc_low_curvature_weight_heading_error", + param.low_curvature_weight_heading_error); + update_param( + parameters, "mpc_low_curvature_weight_heading_error_squared_vel", + param.low_curvature_weight_heading_error_squared_vel); + update_param( + parameters, "mpc_low_curvature_weight_steering_input", + param.low_curvature_weight_steering_input); + update_param( + parameters, "mpc_low_curvature_weight_steering_input_squared_vel", + param.low_curvature_weight_steering_input_squared_vel); + update_param( + parameters, "mpc_low_curvature_weight_lat_jerk", param.low_curvature_weight_lat_jerk); + update_param( + parameters, "mpc_low_curvature_weight_steer_rate", param.low_curvature_weight_steer_rate); + update_param( + parameters, "mpc_low_curvature_weight_steer_acc", param.low_curvature_weight_steer_acc); + update_param( + parameters, "mpc_low_curvature_thresh_curvature", param.low_curvature_thresh_curvature); + update_param(parameters, "mpc_weight_terminal_lat_error", param.weight_terminal_lat_error); + update_param( + parameters, "mpc_weight_terminal_heading_error", param.weight_terminal_heading_error); + update_param(parameters, "mpc_zero_ff_steer_deg", param.zero_ff_steer_deg); + update_param(parameters, "mpc_acceleration_limit", param.acceleration_limit); + update_param(parameters, "mpc_velocity_time_constant", param.velocity_time_constant); + + // initialize input buffer + update_param(parameters, "input_delay", param.input_delay); + const float64_t delay_step = std::round(param.input_delay / m_mpc.m_ctrl_period); + const float64_t delay = delay_step * m_mpc.m_ctrl_period; + if (param.input_delay != delay) { + param.input_delay = delay; + m_mpc.m_input_buffer = std::deque(static_cast(delay_step), 0.0); + } + + // transaction succeeds, now assign values + m_mpc.m_param = param; + } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { + result.successful = false; + result.reason = e.what(); + } + + return result; +} + +bool8_t MpcLateralController::isValidTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory & traj) const +{ + for (const auto & p : traj.points) { + if ( + !isfinite(p.pose.position.x) || !isfinite(p.pose.position.y) || + !isfinite(p.pose.orientation.w) || !isfinite(p.pose.orientation.x) || + !isfinite(p.pose.orientation.y) || !isfinite(p.pose.orientation.z) || + !isfinite(p.longitudinal_velocity_mps) || !isfinite(p.lateral_velocity_mps) || + !isfinite(p.lateral_velocity_mps) || !isfinite(p.heading_rate_rps) || + !isfinite(p.front_wheel_angle_rad) || !isfinite(p.rear_wheel_angle_rad)) { + return false; + } + } + return true; +} + +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware diff --git a/control/trajectory_follower/src/pid_longitudinal_controller.cpp b/control/trajectory_follower/src/pid_longitudinal_controller.cpp new file mode 100644 index 0000000000000..1b7f127f25a44 --- /dev/null +++ b/control/trajectory_follower/src/pid_longitudinal_controller.cpp @@ -0,0 +1,957 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "trajectory_follower/pid_longitudinal_controller.hpp" + +#include "motion_common/motion_common.hpp" +#include "motion_common/trajectory_common.hpp" +#include "time_utils/time_utils.hpp" + +#include +#include +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower +{ +PidLongitudinalController::PidLongitudinalController(rclcpp::Node * node) +: node_{node}, logger_{node->get_logger()}, clock_{node->get_clock()} +{ + using std::placeholders::_1; + + // parameters timer + m_longitudinal_ctrl_period = node_->get_parameter("ctrl_period").as_double(); + + m_wheel_base = vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo().wheel_base_m; + + // parameters for delay compensation + m_delay_compensation_time = + node_->declare_parameter("delay_compensation_time"); // [s] + + // parameters to enable functions + m_enable_smooth_stop = node_->declare_parameter("enable_smooth_stop"); + m_enable_overshoot_emergency = node_->declare_parameter("enable_overshoot_emergency"); + m_enable_slope_compensation = node_->declare_parameter("enable_slope_compensation"); + + // parameters for state transition + { + auto & p = m_state_transition_params; + // drive + p.drive_state_stop_dist = node_->declare_parameter("drive_state_stop_dist"); // [m] + p.drive_state_offset_stop_dist = + node_->declare_parameter("drive_state_offset_stop_dist"); // [m] + // stopping + p.stopping_state_stop_dist = + node_->declare_parameter("stopping_state_stop_dist"); // [m] + p.stopped_state_entry_duration_time = + node_->declare_parameter("stopped_state_entry_duration_time"); // [s] + // stop + p.stopped_state_entry_vel = + node_->declare_parameter("stopped_state_entry_vel"); // [m/s] + p.stopped_state_entry_acc = + node_->declare_parameter("stopped_state_entry_acc"); // [m/s²] + // emergency + p.emergency_state_overshoot_stop_dist = + node_->declare_parameter("emergency_state_overshoot_stop_dist"); // [m] + p.emergency_state_traj_trans_dev = + node_->declare_parameter("emergency_state_traj_trans_dev"); // [m] + p.emergency_state_traj_rot_dev = + node_->declare_parameter("emergency_state_traj_rot_dev"); // [m] + } + + // parameters for drive state + { + // initialize PID gain + const float64_t kp{node_->declare_parameter("kp")}; + const float64_t ki{node_->declare_parameter("ki")}; + const float64_t kd{node_->declare_parameter("kd")}; + m_pid_vel.setGains(kp, ki, kd); + + // initialize PID limits + const float64_t max_pid{node_->declare_parameter("max_out")}; // [m/s^2] + const float64_t min_pid{node_->declare_parameter("min_out")}; // [m/s^2] + const float64_t max_p{node_->declare_parameter("max_p_effort")}; // [m/s^2] + const float64_t min_p{node_->declare_parameter("min_p_effort")}; // [m/s^2] + const float64_t max_i{node_->declare_parameter("max_i_effort")}; // [m/s^2] + const float64_t min_i{node_->declare_parameter("min_i_effort")}; // [m/s^2] + const float64_t max_d{node_->declare_parameter("max_d_effort")}; // [m/s^2] + const float64_t min_d{node_->declare_parameter("min_d_effort")}; // [m/s^2] + m_pid_vel.setLimits(max_pid, min_pid, max_p, min_p, max_i, min_i, max_d, min_d); + + // set lowpass filter for vel error and pitch + const float64_t lpf_vel_error_gain{node_->declare_parameter("lpf_vel_error_gain")}; + m_lpf_vel_error = + std::make_shared(0.0, lpf_vel_error_gain); + + m_current_vel_threshold_pid_integrate = + node_->declare_parameter("current_vel_threshold_pid_integration"); // [m/s] + + m_enable_brake_keeping_before_stop = + node_->declare_parameter("enable_brake_keeping_before_stop"); // [-] + m_brake_keeping_acc = node_->declare_parameter("brake_keeping_acc"); // [m/s^2] + } + + // parameters for smooth stop state + { + const float64_t max_strong_acc{ + node_->declare_parameter("smooth_stop_max_strong_acc")}; // [m/s^2] + const float64_t min_strong_acc{ + node_->declare_parameter("smooth_stop_min_strong_acc")}; // [m/s^2] + const float64_t weak_acc{ + node_->declare_parameter("smooth_stop_weak_acc")}; // [m/s^2] + const float64_t weak_stop_acc{ + node_->declare_parameter("smooth_stop_weak_stop_acc")}; // [m/s^2] + const float64_t strong_stop_acc{ + node_->declare_parameter("smooth_stop_strong_stop_acc")}; // [m/s^2] + + const float64_t max_fast_vel{ + node_->declare_parameter("smooth_stop_max_fast_vel")}; // [m/s] + const float64_t min_running_vel{ + node_->declare_parameter("smooth_stop_min_running_vel")}; // [m/s] + const float64_t min_running_acc{ + node_->declare_parameter("smooth_stop_min_running_acc")}; // [m/s^2] + const float64_t weak_stop_time{ + node_->declare_parameter("smooth_stop_weak_stop_time")}; // [s] + + const float64_t weak_stop_dist{ + node_->declare_parameter("smooth_stop_weak_stop_dist")}; // [m] + const float64_t strong_stop_dist{ + node_->declare_parameter("smooth_stop_strong_stop_dist")}; // [m] + + m_smooth_stop.setParams( + max_strong_acc, min_strong_acc, weak_acc, weak_stop_acc, strong_stop_acc, max_fast_vel, + min_running_vel, min_running_acc, weak_stop_time, weak_stop_dist, strong_stop_dist); + } + + // parameters for stop state + { + auto & p = m_stopped_state_params; + p.vel = node_->declare_parameter("stopped_vel"); // [m/s] + p.acc = node_->declare_parameter("stopped_acc"); // [m/s^2] + p.jerk = node_->declare_parameter("stopped_jerk"); // [m/s^3] + } + + // parameters for emergency state + { + auto & p = m_emergency_state_params; + p.vel = node_->declare_parameter("emergency_vel"); // [m/s] + p.acc = node_->declare_parameter("emergency_acc"); // [m/s^2] + p.jerk = node_->declare_parameter("emergency_jerk"); // [m/s^3] + } + + // parameters for acceleration limit + m_max_acc = node_->declare_parameter("max_acc"); // [m/s^2] + m_min_acc = node_->declare_parameter("min_acc"); // [m/s^2] + + // parameters for jerk limit + m_max_jerk = node_->declare_parameter("max_jerk"); // [m/s^3] + m_min_jerk = node_->declare_parameter("min_jerk"); // [m/s^3] + + // parameters for slope compensation + m_use_traj_for_pitch = node_->declare_parameter("use_trajectory_for_pitch_calculation"); + const float64_t lpf_pitch_gain{node_->declare_parameter("lpf_pitch_gain")}; + m_lpf_pitch = std::make_shared(0.0, lpf_pitch_gain); + m_max_pitch_rad = node_->declare_parameter("max_pitch_rad"); // [rad] + m_min_pitch_rad = node_->declare_parameter("min_pitch_rad"); // [rad] + + // subscriber, publisher + m_sub_current_velocity = node_->create_subscription( + "~/input/current_odometry", rclcpp::QoS{1}, + std::bind(&PidLongitudinalController::callbackCurrentVelocity, this, _1)); + m_sub_trajectory = node_->create_subscription( + "~/input/current_trajectory", rclcpp::QoS{1}, + std::bind(&PidLongitudinalController::callbackTrajectory, this, _1)); + m_pub_control_cmd = node_->create_publisher( + "~/output/longitudinal_control_cmd", rclcpp::QoS{1}); + m_pub_slope = + node_->create_publisher( + "~/output/slope_angle", rclcpp::QoS{1}); + m_pub_debug = + node_->create_publisher( + "~/output/longitudinal_diagnostic", rclcpp::QoS{1}); + + // Timer + // { + // const auto period_ns = std::chrono::duration_cast( + // std::chrono::duration(m_longitudinal_ctrl_period)); + // m_timer_control = rclcpp::create_timer( + // this, get_clock(), period_ns, std::bind(&PidLongitudinalController::callbackTimerControl, + // this)); + // } + + // set parameter callback + m_set_param_res = node_->add_on_set_parameters_callback( + std::bind(&PidLongitudinalController::paramCallback, this, _1)); + + // set lowpass filter for acc + m_lpf_acc = std::make_shared(0.0, 0.2); +} + +void PidLongitudinalController::callbackCurrentVelocity( + const nav_msgs::msg::Odometry::ConstSharedPtr msg) +{ + if (m_current_velocity_ptr) { + m_prev_velocity_ptr = m_current_velocity_ptr; + } + m_current_velocity_ptr = std::make_shared(*msg); +} + +void PidLongitudinalController::callbackTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg) +{ + if (!trajectory_follower::longitudinal_utils::isValidTrajectory(*msg)) { + RCLCPP_ERROR_THROTTLE(logger_, *clock_, 3000, "received invalid trajectory. ignore."); + return; + } + + if (msg->points.size() < 2) { + RCLCPP_WARN_THROTTLE(logger_, *clock_, 3000, "Unexpected trajectory size < 2. Ignored."); + return; + } + + m_trajectory_ptr = std::make_shared(*msg); +} + +rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallback( + const std::vector & parameters) +{ + auto update_param = [&](const std::string & name, float64_t & v) { + auto it = std::find_if( + parameters.cbegin(), parameters.cend(), + [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; }); + if (it != parameters.cend()) { + v = it->as_double(); + return true; + } + return false; + }; + + // delay compensation + update_param("delay_compensation_time", m_delay_compensation_time); + + // state transition + { + auto & p = m_state_transition_params; + update_param("drive_state_stop_dist", p.drive_state_stop_dist); + update_param("stopping_state_stop_dist", p.stopping_state_stop_dist); + update_param("stopped_state_entry_duration_time", p.stopped_state_entry_duration_time); + update_param("stopped_state_entry_vel", p.stopped_state_entry_vel); + update_param("stopped_state_entry_acc", p.stopped_state_entry_acc); + update_param("emergency_state_overshoot_stop_dist", p.emergency_state_overshoot_stop_dist); + update_param("emergency_state_traj_trans_dev", p.emergency_state_traj_trans_dev); + update_param("emergency_state_traj_rot_dev", p.emergency_state_traj_rot_dev); + } + + // drive state + { + float64_t kp{node_->get_parameter("kp").as_double()}; + float64_t ki{node_->get_parameter("ki").as_double()}; + float64_t kd{node_->get_parameter("kd").as_double()}; + update_param("kp", kp); + update_param("ki", ki); + update_param("kd", kd); + m_pid_vel.setGains(kp, ki, kd); + + float64_t max_pid{node_->get_parameter("max_out").as_double()}; + float64_t min_pid{node_->get_parameter("min_out").as_double()}; + float64_t max_p{node_->get_parameter("max_p_effort").as_double()}; + float64_t min_p{node_->get_parameter("min_p_effort").as_double()}; + float64_t max_i{node_->get_parameter("max_i_effort").as_double()}; + float64_t min_i{node_->get_parameter("min_i_effort").as_double()}; + float64_t max_d{node_->get_parameter("max_d_effort").as_double()}; + float64_t min_d{node_->get_parameter("min_d_effort").as_double()}; + update_param("max_out", max_pid); + update_param("min_out", min_pid); + update_param("max_p_effort", max_p); + update_param("min_p_effort", min_p); + update_param("max_i_effort", max_i); + update_param("min_i_effort", min_i); + update_param("max_d_effort", max_d); + update_param("min_d_effort", min_d); + m_pid_vel.setLimits(max_pid, min_pid, max_p, min_p, max_i, min_i, max_d, min_d); + + update_param("current_vel_threshold_pid_integration", m_current_vel_threshold_pid_integrate); + } + + // stopping state + { + float64_t max_strong_acc{node_->get_parameter("smooth_stop_max_strong_acc").as_double()}; + float64_t min_strong_acc{node_->get_parameter("smooth_stop_min_strong_acc").as_double()}; + float64_t weak_acc{node_->get_parameter("smooth_stop_weak_acc").as_double()}; + float64_t weak_stop_acc{node_->get_parameter("smooth_stop_weak_stop_acc").as_double()}; + float64_t strong_stop_acc{node_->get_parameter("smooth_stop_strong_stop_acc").as_double()}; + float64_t max_fast_vel{node_->get_parameter("smooth_stop_max_fast_vel").as_double()}; + float64_t min_running_vel{node_->get_parameter("smooth_stop_min_running_vel").as_double()}; + float64_t min_running_acc{node_->get_parameter("smooth_stop_min_running_acc").as_double()}; + float64_t weak_stop_time{node_->get_parameter("smooth_stop_weak_stop_time").as_double()}; + float64_t weak_stop_dist{node_->get_parameter("smooth_stop_weak_stop_dist").as_double()}; + float64_t strong_stop_dist{node_->get_parameter("smooth_stop_strong_stop_dist").as_double()}; + update_param("smooth_stop_max_strong_acc", max_strong_acc); + update_param("smooth_stop_min_strong_acc", min_strong_acc); + update_param("smooth_stop_weak_acc", weak_acc); + update_param("smooth_stop_weak_stop_acc", weak_stop_acc); + update_param("smooth_stop_strong_stop_acc", strong_stop_acc); + update_param("smooth_stop_max_fast_vel", max_fast_vel); + update_param("smooth_stop_min_running_vel", min_running_vel); + update_param("smooth_stop_min_running_acc", min_running_acc); + update_param("smooth_stop_weak_stop_time", weak_stop_time); + update_param("smooth_stop_weak_stop_dist", weak_stop_dist); + update_param("smooth_stop_strong_stop_dist", strong_stop_dist); + m_smooth_stop.setParams( + max_strong_acc, min_strong_acc, weak_acc, weak_stop_acc, strong_stop_acc, max_fast_vel, + min_running_vel, min_running_acc, weak_stop_time, weak_stop_dist, strong_stop_dist); + } + + // stop state + { + auto & p = m_stopped_state_params; + update_param("stopped_vel", p.vel); + update_param("stopped_acc", p.acc); + update_param("stopped_jerk", p.jerk); + } + + // emergency state + { + auto & p = m_emergency_state_params; + update_param("emergency_vel", p.vel); + update_param("emergency_acc", p.acc); + update_param("emergency_jerk", p.jerk); + } + + // acceleration limit + update_param("min_acc", m_min_acc); + + // jerk limit + update_param("max_jerk", m_max_jerk); + update_param("min_jerk", m_min_jerk); + + // slope compensation + update_param("max_pitch_rad", m_max_pitch_rad); + update_param("min_pitch_rad", m_min_pitch_rad); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} + +LongitudinalOutput PidLongitudinalController::run() +{ + // wait for initial pointers + if ( + !m_current_velocity_ptr || !m_prev_velocity_ptr || !m_trajectory_ptr || + !m_tf_buffer.canTransform(m_trajectory_ptr->header.frame_id, "base_link", tf2::TimePointZero)) { + LongitudinalOutput output; + return output; // todo + } + + // get current ego pose + geometry_msgs::msg::TransformStamped tf = + m_tf_buffer.lookupTransform(m_trajectory_ptr->header.frame_id, "base_link", tf2::TimePointZero); + + // calculate current pose and control data + geometry_msgs::msg::Pose current_pose; + current_pose.position.x = tf.transform.translation.x; + current_pose.position.y = tf.transform.translation.y; + current_pose.position.z = tf.transform.translation.z; + current_pose.orientation = tf.transform.rotation; + + const auto control_data = getControlData(current_pose); + + // self pose is far from trajectory + if (control_data.is_far_from_trajectory) { + m_control_state = ControlState::EMERGENCY; // update control state + const Motion raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt); // calculate control command + m_prev_raw_ctrl_cmd = raw_ctrl_cmd; + const auto cmd_msg = + createCtrlCmdMsg(raw_ctrl_cmd, control_data.current_motion.vel); // create control command + publishDebugData(raw_ctrl_cmd, control_data); // publish debug data + LongitudinalOutput output{cmd_msg}; + return output; + } + + // update control state + m_control_state = updateControlState(m_control_state, control_data); + + // calculate control command + const Motion ctrl_cmd = calcCtrlCmd(m_control_state, current_pose, control_data); + + // publish control command + const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd, control_data.current_motion.vel); + LongitudinalOutput output{cmd_msg}; + + // publish debug data + publishDebugData(ctrl_cmd, control_data); + + return output; +} + +PidLongitudinalController::ControlData PidLongitudinalController::getControlData( + const geometry_msgs::msg::Pose & current_pose) +{ + ControlData control_data{}; + + // dt + control_data.dt = getDt(); + + // current velocity and acceleration + control_data.current_motion = getCurrentMotion(); + + // nearest idx + const float64_t max_dist = m_state_transition_params.emergency_state_traj_trans_dev; + const float64_t max_yaw = m_state_transition_params.emergency_state_traj_rot_dev; + const auto nearest_idx_opt = + motion_common::findNearestIndex(m_trajectory_ptr->points, current_pose, max_dist, max_yaw); + + // return here if nearest index is not found + if (!nearest_idx_opt) { + control_data.is_far_from_trajectory = true; + return control_data; + } + control_data.nearest_idx = *nearest_idx_opt; + + // shift + control_data.shift = getCurrentShift(control_data.nearest_idx); + if (control_data.shift != m_prev_shift) { + m_pid_vel.reset(); + } + m_prev_shift = control_data.shift; + + // distance to stopline + control_data.stop_dist = trajectory_follower::longitudinal_utils::calcStopDistance( + current_pose.position, *m_trajectory_ptr); + + // pitch + const float64_t raw_pitch = + trajectory_follower::longitudinal_utils::getPitchByPose(current_pose.orientation); + const float64_t traj_pitch = trajectory_follower::longitudinal_utils::getPitchByTraj( + *m_trajectory_ptr, control_data.nearest_idx, m_wheel_base); + control_data.slope_angle = m_use_traj_for_pitch ? traj_pitch : m_lpf_pitch->filter(raw_pitch); + updatePitchDebugValues(control_data.slope_angle, traj_pitch, raw_pitch); + + return control_data; +} + +PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd( + const float64_t dt) const +{ + // These accelerations are without slope compensation + const auto & p = m_emergency_state_params; + const float64_t vel = trajectory_follower::longitudinal_utils::applyDiffLimitFilter( + p.vel, m_prev_raw_ctrl_cmd.vel, dt, p.acc); + const float64_t acc = trajectory_follower::longitudinal_utils::applyDiffLimitFilter( + p.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk); + + auto clock = rclcpp::Clock{RCL_ROS_TIME}; + RCLCPP_ERROR_THROTTLE(logger_, clock, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", vel, acc); + + return Motion{vel, acc}; +} + +PidLongitudinalController::ControlState PidLongitudinalController::updateControlState( + const ControlState current_control_state, const ControlData & control_data) +{ + const float64_t current_vel = control_data.current_motion.vel; + const float64_t current_acc = control_data.current_motion.acc; + const float64_t stop_dist = control_data.stop_dist; + + // flags for state transition + const auto & p = m_state_transition_params; + + const bool8_t departure_condition_from_stopping = + stop_dist > p.drive_state_stop_dist + p.drive_state_offset_stop_dist; + const bool8_t departure_condition_from_stopped = stop_dist > p.drive_state_stop_dist; + const bool8_t keep_stopped_condition = lateral_sync_data_.is_steer_converged; + + const bool8_t stopping_condition = stop_dist < p.stopping_state_stop_dist; + if ( + std::fabs(current_vel) > p.stopped_state_entry_vel || + std::fabs(current_acc) > p.stopped_state_entry_acc) { + m_last_running_time = std::make_shared(rclcpp::Clock{RCL_ROS_TIME}.now()); + } + const bool8_t stopped_condition = + m_last_running_time ? (rclcpp::Clock{RCL_ROS_TIME}.now() - *m_last_running_time).seconds() > + p.stopped_state_entry_duration_time + : false; + + const bool8_t emergency_condition = + m_enable_overshoot_emergency && stop_dist < -p.emergency_state_overshoot_stop_dist; + + // transit state + if (current_control_state == ControlState::DRIVE) { + if (emergency_condition) { + return ControlState::EMERGENCY; + } + + if (m_enable_smooth_stop) { + if (stopping_condition) { + // predictions after input time delay + const float64_t pred_vel_in_target = + predictedVelocityInTargetPoint(control_data.current_motion, m_delay_compensation_time); + const float64_t pred_stop_dist = + control_data.stop_dist - + 0.5 * (pred_vel_in_target + current_vel) * m_delay_compensation_time; + m_smooth_stop.init(pred_vel_in_target, pred_stop_dist); + return ControlState::STOPPING; + } + } else { + if (stopped_condition && !departure_condition_from_stopped) { + return ControlState::STOPPED; + } + } + } else if (current_control_state == ControlState::STOPPING) { + if (emergency_condition) { + return ControlState::EMERGENCY; + } + + if (stopped_condition) { + return ControlState::STOPPED; + } + + if (departure_condition_from_stopping) { + m_pid_vel.reset(); + m_lpf_vel_error->reset(0.0); + // prevent the car from taking a long time to start to move + m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc); + return ControlState::DRIVE; + } + } else if (current_control_state == ControlState::STOPPED) { + if (departure_condition_from_stopped && !keep_stopped_condition) { + m_pid_vel.reset(); + m_lpf_vel_error->reset(0.0); + // prevent the car from taking a long time to start to move + m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc); + return ControlState::DRIVE; + } + } else if (m_control_state == ControlState::EMERGENCY) { + if (stopped_condition && !emergency_condition) { + return ControlState::STOPPED; + } + } + + return current_control_state; +} + +PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd( + const ControlState & current_control_state, const geometry_msgs::msg::Pose & current_pose, + const ControlData & control_data) +{ + const size_t nearest_idx = control_data.nearest_idx; + const float64_t current_vel = control_data.current_motion.vel; + const float64_t current_acc = control_data.current_motion.acc; + + // velocity and acceleration command + Motion raw_ctrl_cmd{}; + Motion target_motion{}; + if (current_control_state == ControlState::DRIVE) { + const auto target_pose = trajectory_follower::longitudinal_utils::calcPoseAfterTimeDelay( + current_pose, m_delay_compensation_time, current_vel); + const auto target_interpolated_point = + calcInterpolatedTargetValue(*m_trajectory_ptr, target_pose.position, nearest_idx); + target_motion = Motion{ + target_interpolated_point.longitudinal_velocity_mps, + target_interpolated_point.acceleration_mps2}; + + target_motion = keepBrakeBeforeStop(*m_trajectory_ptr, target_motion, nearest_idx); + + const float64_t pred_vel_in_target = + predictedVelocityInTargetPoint(control_data.current_motion, m_delay_compensation_time); + m_debug_values.setValues( + trajectory_follower::DebugValues::TYPE::PREDICTED_VEL, pred_vel_in_target); + + raw_ctrl_cmd.vel = target_motion.vel; + raw_ctrl_cmd.acc = applyVelocityFeedback(target_motion, control_data.dt, pred_vel_in_target); + RCLCPP_DEBUG( + logger_, + "[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f " + "feedback_ctrl_cmd.ac: %3.3f", + raw_ctrl_cmd.vel, raw_ctrl_cmd.acc, control_data.dt, current_vel, target_motion.vel, + raw_ctrl_cmd.acc); + } else if (current_control_state == ControlState::STOPPING) { + raw_ctrl_cmd.acc = m_smooth_stop.calculate( + control_data.stop_dist, current_vel, current_acc, m_vel_hist, m_delay_compensation_time); + raw_ctrl_cmd.vel = m_stopped_state_params.vel; + + RCLCPP_DEBUG( + logger_, "[smooth stop]: Smooth stopping. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, + raw_ctrl_cmd.acc); + } else if (current_control_state == ControlState::STOPPED) { + // This acceleration is without slope compensation + const auto & p = m_stopped_state_params; + raw_ctrl_cmd.vel = p.vel; + raw_ctrl_cmd.acc = trajectory_follower::longitudinal_utils::applyDiffLimitFilter( + p.acc, m_prev_raw_ctrl_cmd.acc, control_data.dt, p.jerk); + + RCLCPP_DEBUG(logger_, "[Stopped]. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, raw_ctrl_cmd.acc); + } else if (current_control_state == ControlState::EMERGENCY) { + raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt); + } + + // store acceleration without slope compensation + m_prev_raw_ctrl_cmd = raw_ctrl_cmd; + + // apply slope compensation and filter acceleration and jerk + const float64_t filtered_acc_cmd = calcFilteredAcc(raw_ctrl_cmd.acc, control_data); + const Motion filtered_ctrl_cmd{raw_ctrl_cmd.vel, filtered_acc_cmd}; + + // update debug visualization + updateDebugVelAcc(target_motion, current_pose, control_data); + + return filtered_ctrl_cmd; +} + +// Do not use nearest_idx here +autoware_auto_control_msgs::msg::LongitudinalCommand PidLongitudinalController::createCtrlCmdMsg( + const Motion & ctrl_cmd, float64_t current_vel) +{ + // publish control command + autoware_auto_control_msgs::msg::LongitudinalCommand cmd{}; + cmd.stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + cmd.speed = static_cast(ctrl_cmd.vel); + cmd.acceleration = static_cast(ctrl_cmd.acc); + // m_pub_control_cmd->publish(cmd); + + // store current velocity history + m_vel_hist.push_back({rclcpp::Clock{RCL_ROS_TIME}.now(), current_vel}); + while (m_vel_hist.size() > static_cast(0.5 / m_longitudinal_ctrl_period)) { + m_vel_hist.erase(m_vel_hist.begin()); + } + + m_prev_ctrl_cmd = ctrl_cmd; + + return cmd; +} + +void PidLongitudinalController::publishDebugData( + const Motion & ctrl_cmd, const ControlData & control_data) +{ + using trajectory_follower::DebugValues; + // set debug values + m_debug_values.setValues(DebugValues::TYPE::DT, control_data.dt); + m_debug_values.setValues(DebugValues::TYPE::CALCULATED_ACC, control_data.current_motion.acc); + m_debug_values.setValues(DebugValues::TYPE::SHIFT, static_cast(control_data.shift)); + m_debug_values.setValues(DebugValues::TYPE::STOP_DIST, control_data.stop_dist); + m_debug_values.setValues( + DebugValues::TYPE::CONTROL_STATE, static_cast(m_control_state)); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_PUBLISHED, ctrl_cmd.acc); + + // publish debug values + autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic debug_msg{}; + debug_msg.diag_header.data_stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + for (const auto & v : m_debug_values.getValues()) { + debug_msg.diag_array.data.push_back( + static_cast(v)); + } + m_pub_debug->publish(debug_msg); + + // slope angle + autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic slope_msg{}; + slope_msg.diag_header.data_stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + slope_msg.diag_array.data.push_back( + static_cast(control_data.slope_angle)); + m_pub_slope->publish(slope_msg); +} + +float64_t PidLongitudinalController::getDt() +{ + float64_t dt; + if (!m_prev_control_time) { + dt = m_longitudinal_ctrl_period; + m_prev_control_time = std::make_shared(rclcpp::Clock{RCL_ROS_TIME}.now()); + } else { + dt = (rclcpp::Clock{RCL_ROS_TIME}.now() - *m_prev_control_time).seconds(); + *m_prev_control_time = rclcpp::Clock{RCL_ROS_TIME}.now(); + } + const float64_t max_dt = m_longitudinal_ctrl_period * 2.0; + const float64_t min_dt = m_longitudinal_ctrl_period * 0.5; + return std::max(std::min(dt, max_dt), min_dt); +} + +PidLongitudinalController::Motion PidLongitudinalController::getCurrentMotion() const +{ + const float64_t dv = + m_current_velocity_ptr->twist.twist.linear.x - m_prev_velocity_ptr->twist.twist.linear.x; + const float64_t dt = std::max( + (rclcpp::Time(m_current_velocity_ptr->header.stamp) - + rclcpp::Time(m_prev_velocity_ptr->header.stamp)) + .seconds(), + 1e-03); + const float64_t accel = dv / dt; + + const float64_t current_vel = m_current_velocity_ptr->twist.twist.linear.x; + const float64_t current_acc = m_lpf_acc->filter(accel); + + return Motion{current_vel, current_acc}; +} + +enum PidLongitudinalController::Shift PidLongitudinalController::getCurrentShift( + const size_t nearest_idx) const +{ + constexpr float64_t epsilon = 1e-5; + + const float64_t target_vel = m_trajectory_ptr->points.at(nearest_idx).longitudinal_velocity_mps; + + if (target_vel > epsilon) { + return Shift::Forward; + } else if (target_vel < -epsilon) { + return Shift::Reverse; + } + + return m_prev_shift; +} + +float64_t PidLongitudinalController::calcFilteredAcc( + const float64_t raw_acc, const ControlData & control_data) +{ + using trajectory_follower::DebugValues; + const float64_t acc_max_filtered = ::motion::motion_common::clamp(raw_acc, m_min_acc, m_max_acc); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, acc_max_filtered); + + // store ctrl cmd without slope filter + storeAccelCmd(acc_max_filtered); + + const float64_t acc_slope_filtered = + applySlopeCompensation(acc_max_filtered, control_data.slope_angle, control_data.shift); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, acc_slope_filtered); + + // This jerk filter must be applied after slope compensation + const float64_t acc_jerk_filtered = trajectory_follower::longitudinal_utils::applyDiffLimitFilter( + acc_slope_filtered, m_prev_ctrl_cmd.acc, control_data.dt, m_max_jerk, m_min_jerk); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, acc_jerk_filtered); + + return acc_jerk_filtered; +} + +void PidLongitudinalController::storeAccelCmd(const float64_t accel) +{ + if (m_control_state == ControlState::DRIVE) { + // convert format + autoware_auto_control_msgs::msg::LongitudinalCommand cmd; + cmd.stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + cmd.acceleration = static_cast(accel); + + // store published ctrl cmd + m_ctrl_cmd_vec.emplace_back(cmd); + } else { + // reset command + m_ctrl_cmd_vec.clear(); + } + + // remove unused ctrl cmd + if (m_ctrl_cmd_vec.size() <= 2) { + return; + } + if ( + (rclcpp::Clock{RCL_ROS_TIME}.now() - m_ctrl_cmd_vec.at(1).stamp).seconds() > + m_delay_compensation_time) { + m_ctrl_cmd_vec.erase(m_ctrl_cmd_vec.begin()); + } +} + +float64_t PidLongitudinalController::applySlopeCompensation( + const float64_t input_acc, const float64_t pitch, const Shift shift) const +{ + if (!m_enable_slope_compensation) { + return input_acc; + } + const float64_t pitch_limited = std::min(std::max(pitch, m_min_pitch_rad), m_max_pitch_rad); + + // Acceleration command is always positive independent of direction (= shift) when car is running + float64_t sign = (shift == Shift::Forward) ? -1 : (shift == Shift::Reverse ? 1 : 0); + float64_t compensated_acc = input_acc + sign * 9.81 * std::sin(pitch_limited); + return compensated_acc; +} + +PidLongitudinalController::Motion PidLongitudinalController::keepBrakeBeforeStop( + const autoware_auto_planning_msgs::msg::Trajectory & traj, const Motion & target_motion, + const size_t nearest_idx) const +{ + Motion output_motion = target_motion; + + if (m_enable_brake_keeping_before_stop == false) { + return output_motion; + } + // const auto stop_idx = tier4_autoware_utils::searchZeroVelocityIndex(traj.points); + const auto stop_idx = motion_common::searchZeroVelocityIndex(traj.points); + if (!stop_idx) { + return output_motion; + } + + float64_t min_acc_before_stop = std::numeric_limits::max(); + size_t min_acc_idx = std::numeric_limits::max(); + for (int i = static_cast(*stop_idx); i >= 0; --i) { + const auto ui = static_cast(i); + if (traj.points.at(ui).acceleration_mps2 > static_cast(min_acc_before_stop)) { + break; + } + min_acc_before_stop = traj.points.at(ui).acceleration_mps2; + min_acc_idx = ui; + } + + const float64_t brake_keeping_acc = std::max(m_brake_keeping_acc, min_acc_before_stop); + if (nearest_idx >= min_acc_idx && target_motion.acc > brake_keeping_acc) { + output_motion.acc = brake_keeping_acc; + } + + return output_motion; +} + +autoware_auto_planning_msgs::msg::TrajectoryPoint +PidLongitudinalController::calcInterpolatedTargetValue( + const autoware_auto_planning_msgs::msg::Trajectory & traj, + const geometry_msgs::msg::Point & point, const size_t nearest_idx) const +{ + if (traj.points.size() == 1) { + return traj.points.at(0); + } + + // If the current position is not within the reference trajectory, enable the edge value. + // Else, apply linear interpolation + if (nearest_idx == 0) { + if (motion_common::calcSignedArcLength(traj.points, point, 0) > 0) { + return traj.points.at(0); + } + } + if (nearest_idx == traj.points.size() - 1) { + if (motion_common::calcSignedArcLength(traj.points, point, traj.points.size() - 1) < 0) { + return traj.points.at(traj.points.size() - 1); + } + } + + // apply linear interpolation + return trajectory_follower::longitudinal_utils::lerpTrajectoryPoint(traj.points, point); +} + +float64_t PidLongitudinalController::predictedVelocityInTargetPoint( + const Motion current_motion, const float64_t delay_compensation_time) const +{ + const float64_t current_vel = current_motion.vel; + const float64_t current_acc = current_motion.acc; + + if (std::fabs(current_vel) < 1e-01) { // when velocity is low, no prediction + return current_vel; + } + + const float64_t current_vel_abs = std::fabs(current_vel); + if (m_ctrl_cmd_vec.size() == 0) { + const float64_t pred_vel = current_vel + current_acc * delay_compensation_time; + // avoid to change sign of current_vel and pred_vel + return pred_vel > 0 ? std::copysign(pred_vel, current_vel) : 0.0; + } + + float64_t pred_vel = current_vel_abs; + + const auto past_delay_time = + rclcpp::Clock{RCL_ROS_TIME}.now() - rclcpp::Duration::from_seconds(delay_compensation_time); + for (std::size_t i = 0; i < m_ctrl_cmd_vec.size(); ++i) { + if ( + (rclcpp::Clock{RCL_ROS_TIME}.now() - m_ctrl_cmd_vec.at(i).stamp).seconds() < + m_delay_compensation_time) { + if (i == 0) { + // size of m_ctrl_cmd_vec is less than m_delay_compensation_time + pred_vel = current_vel_abs + static_cast(m_ctrl_cmd_vec.at(i).acceleration) * + delay_compensation_time; + return pred_vel > 0 ? std::copysign(pred_vel, current_vel) : 0.0; + } + // add velocity to accel * dt + const float64_t acc = m_ctrl_cmd_vec.at(i - 1).acceleration; + const auto curr_time_i = rclcpp::Time(m_ctrl_cmd_vec.at(i).stamp); + const float64_t time_to_next_acc = std::min( + (curr_time_i - rclcpp::Time(m_ctrl_cmd_vec.at(i - 1).stamp)).seconds(), + (curr_time_i - past_delay_time).seconds()); + pred_vel += acc * time_to_next_acc; + } + } + + const float64_t last_acc = m_ctrl_cmd_vec.at(m_ctrl_cmd_vec.size() - 1).acceleration; + const float64_t time_to_current = + (rclcpp::Clock{RCL_ROS_TIME}.now() - m_ctrl_cmd_vec.at(m_ctrl_cmd_vec.size() - 1).stamp) + .seconds(); + pred_vel += last_acc * time_to_current; + + // avoid to change sign of current_vel and pred_vel + return pred_vel > 0 ? std::copysign(pred_vel, current_vel) : 0.0; +} + +float64_t PidLongitudinalController::applyVelocityFeedback( + const Motion target_motion, const float64_t dt, const float64_t current_vel) +{ + using trajectory_follower::DebugValues; + const float64_t current_vel_abs = std::fabs(current_vel); + const float64_t target_vel_abs = std::fabs(target_motion.vel); + const bool8_t enable_integration = (current_vel_abs > m_current_vel_threshold_pid_integrate); + const float64_t error_vel_filtered = m_lpf_vel_error->filter(target_vel_abs - current_vel_abs); + + std::vector pid_contributions(3); + const float64_t pid_acc = + m_pid_vel.calculate(error_vel_filtered, dt, enable_integration, pid_contributions); + const float64_t feedback_acc = target_motion.acc + pid_acc; + + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_PID_APPLIED, feedback_acc); + m_debug_values.setValues(DebugValues::TYPE::ERROR_VEL_FILTERED, error_vel_filtered); + m_debug_values.setValues( + DebugValues::TYPE::ACC_CMD_FB_P_CONTRIBUTION, pid_contributions.at(0)); // P + m_debug_values.setValues( + DebugValues::TYPE::ACC_CMD_FB_I_CONTRIBUTION, pid_contributions.at(1)); // I + m_debug_values.setValues( + DebugValues::TYPE::ACC_CMD_FB_D_CONTRIBUTION, pid_contributions.at(2)); // D + + return feedback_acc; +} + +void PidLongitudinalController::updatePitchDebugValues( + const float64_t pitch, const float64_t traj_pitch, const float64_t raw_pitch) +{ + using trajectory_follower::DebugValues; + const float64_t to_degrees = (180.0 / static_cast(autoware::common::types::PI)); + m_debug_values.setValues(DebugValues::TYPE::PITCH_LPF_RAD, pitch); + m_debug_values.setValues(DebugValues::TYPE::PITCH_LPF_DEG, pitch * to_degrees); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_RAD, raw_pitch); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_DEG, raw_pitch * to_degrees); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_TRAJ_RAD, traj_pitch); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_TRAJ_DEG, traj_pitch * to_degrees); +} + +void PidLongitudinalController::updateDebugVelAcc( + const Motion & target_motion, const geometry_msgs::msg::Pose & current_pose, + const ControlData & control_data) +{ + using trajectory_follower::DebugValues; + const float64_t current_vel = control_data.current_motion.vel; + const size_t nearest_idx = control_data.nearest_idx; + + const auto interpolated_point = + calcInterpolatedTargetValue(*m_trajectory_ptr, current_pose.position, nearest_idx); + + m_debug_values.setValues(DebugValues::TYPE::CURRENT_VEL, current_vel); + m_debug_values.setValues(DebugValues::TYPE::TARGET_VEL, target_motion.vel); + m_debug_values.setValues(DebugValues::TYPE::TARGET_ACC, target_motion.acc); + m_debug_values.setValues( + DebugValues::TYPE::NEAREST_VEL, interpolated_point.longitudinal_velocity_mps); + m_debug_values.setValues(DebugValues::TYPE::NEAREST_ACC, interpolated_point.acceleration_mps2); + m_debug_values.setValues(DebugValues::TYPE::ERROR_VEL, target_motion.vel - current_vel); +} + +} // namespace trajectory_follower +} // namespace control +} // namespace motion +} // namespace autoware diff --git a/control/trajectory_follower_nodes/CMakeLists.txt b/control/trajectory_follower_nodes/CMakeLists.txt index fa005c1c0bfda..1275072cb86e4 100644 --- a/control/trajectory_follower_nodes/CMakeLists.txt +++ b/control/trajectory_follower_nodes/CMakeLists.txt @@ -46,6 +46,18 @@ rclcpp_components_register_node(${LATLON_MUXER_NODE} EXECUTABLE ${LATLON_MUXER_NODE}_exe ) +set(CONTROLLER_NODE controller_node) +ament_auto_add_library(${CONTROLLER_NODE} SHARED +include/trajectory_follower_nodes/controller_node.hpp + src/controller_node.cpp +) + +target_compile_options(${CONTROLLER_NODE} PRIVATE -Wno-error=old-style-cast) +rclcpp_components_register_node(${CONTROLLER_NODE} + PLUGIN "autoware::motion::control::trajectory_follower_nodes::Controller" + EXECUTABLE ${CONTROLLER_NODE}_exe +) + if(BUILD_TESTING) set(TRAJECTORY_FOLLOWER_NODES_TEST test_trajectory_follower_nodes) ament_add_ros_isolated_gtest(${TRAJECTORY_FOLLOWER_NODES_TEST} diff --git a/control/trajectory_follower_nodes/include/trajectory_follower_nodes/controller_node.hpp b/control/trajectory_follower_nodes/include/trajectory_follower_nodes/controller_node.hpp new file mode 100644 index 0000000000000..73ead9b57266f --- /dev/null +++ b/control/trajectory_follower_nodes/include/trajectory_follower_nodes/controller_node.hpp @@ -0,0 +1,89 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TRAJECTORY_FOLLOWER_NODES__CONTROLLER_NODE_HPP_ +#define TRAJECTORY_FOLLOWER_NODES__CONTROLLER_NODE_HPP_ + +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/Geometry" +#include "motion_common/motion_common.hpp" +#include "motion_common/trajectory_common.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tf2/utils.h" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" +#include "trajectory_follower/debug_values.hpp" +#include "trajectory_follower/lateral_controller_base.hpp" +#include "trajectory_follower/longitudinal_controller_base.hpp" +#include "trajectory_follower/longitudinal_controller_utils.hpp" +#include "trajectory_follower/lowpass_filter.hpp" +#include "trajectory_follower/pid.hpp" +#include "trajectory_follower/smooth_stop.hpp" +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp" +#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_system_msgs/msg/float32_multi_array_diagnostic.hpp" +#include "autoware_auto_vehicle_msgs/msg/vehicle_odometry.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "tf2_msgs/msg/tf_message.hpp" + +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower_nodes +{ +using autoware::common::types::bool8_t; +using autoware::common::types::float64_t; +namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; +namespace motion_common = ::autoware::motion::motion_common; + +/// \classController +/// \brief The node class used for generating longitudinal control commands (velocity/acceleration) +class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node +{ +public: + explicit Controller(const rclcpp::NodeOptions & node_options); + +private: + // ros variables + rclcpp::TimerBase::SharedPtr m_timer_control_; + + std::shared_ptr longitudinal_controller_; + std::shared_ptr lateral_controller_; + + rclcpp::Publisher::SharedPtr + m_control_cmd_pub_; + + /** + * @brief compute control command, and publish periodically + */ + void callbackTimerControl(); +}; +} // namespace trajectory_follower_nodes +} // namespace control +} // namespace motion +} // namespace autoware + +#endif // TRAJECTORY_FOLLOWER_NODES__CONTROLLER_NODE_HPP_ diff --git a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml index e692fa8e14811..3133549588e1c 100644 --- a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml +++ b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml @@ -1,7 +1,6 @@ /**: ros__parameters: # -- system -- - ctrl_period: 0.03 # control period [s] traj_resample_dist: 0.1 # path resampling interval [m] use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value diff --git a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml index 129abd2680509..3ad3333535f54 100644 --- a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml +++ b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml @@ -1,6 +1,5 @@ /**: ros__parameters: - longitudinal_ctrl_period: 0.03 # control period [s] delay_compensation_time: 0.17 enable_smooth_stop: true diff --git a/control/trajectory_follower_nodes/src/controller_node.cpp b/control/trajectory_follower_nodes/src/controller_node.cpp new file mode 100644 index 0000000000000..6061074489b16 --- /dev/null +++ b/control/trajectory_follower_nodes/src/controller_node.cpp @@ -0,0 +1,80 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "trajectory_follower_nodes/controller_node.hpp" + +#include "motion_common/motion_common.hpp" +#include "motion_common/trajectory_common.hpp" +#include "time_utils/time_utils.hpp" +#include "trajectory_follower/mpc_lateral_controller.hpp" +#include "trajectory_follower/pid_longitudinal_controller.hpp" + +#include +#include +#include +#include +#include +#include + +namespace autoware +{ +namespace motion +{ +namespace control +{ +namespace trajectory_follower_nodes +{ +Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("controller", node_options) +{ + using std::placeholders::_1; + + const double m_ctrl_period = declare_parameter("ctrl_period", 0.015); + + lateral_controller_ = std::make_shared(this); + longitudinal_controller_ = std::make_shared(this); + + m_control_cmd_pub_ = create_publisher( + "~/output/control_cmd", rclcpp::QoS{1}.transient_local()); + + // Timer + { + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(m_ctrl_period)); + m_timer_control_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&Controller::callbackTimerControl, this)); + } +} + +void Controller::callbackTimerControl() +{ + const auto longitudinal_output = longitudinal_controller_->run(); + const auto lateral_output = lateral_controller_->run(); + + longitudinal_controller_->sync(lateral_output.sync_data); + lateral_controller_->sync(longitudinal_output.sync_data); + + autoware_auto_control_msgs::msg::AckermannControlCommand out; + out.stamp = this->now(); + out.lateral = lateral_output.control_cmd; + out.longitudinal = longitudinal_output.control_cmd; + m_control_cmd_pub_->publish(out); +} + +} // namespace trajectory_follower_nodes +} // namespace control +} // namespace motion +} // namespace autoware + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::motion::control::trajectory_follower_nodes::Controller) diff --git a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml index f8a129af4d2a4..efb367956586c 100644 --- a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml +++ b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml @@ -2,7 +2,6 @@ ros__parameters: # -- system -- - ctrl_period: 0.03 # control period [s] traj_resample_dist: 0.1 # path resampling interval [m] use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value diff --git a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index b3af131b2e778..aa84efc7b3acf 100644 --- a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -1,6 +1,5 @@ /**: ros__parameters: - longitudinal_ctrl_period: 0.03 # control period [s] delay_compensation_time: 0.17 enable_smooth_stop: true From d68bdc40669b519d5e5d92c53b85e578af782f90 Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Mon, 16 May 2022 12:11:55 +0900 Subject: [PATCH 23/23] Use steer_convergence for stopped state Signed-off-by: kosuke55 --- .../mpc_lateral_controller.hpp | 2 ++ .../pid_longitudinal_controller.hpp | 3 +-- .../src/mpc_lateral_controller.cpp | 22 +++++++++++++++---- .../src/pid_longitudinal_controller.cpp | 14 ++++++++---- .../lateral_controller_defaults.param.yaml | 2 ++ ...ongitudinal_controller_defaults.param.yaml | 1 + .../lateral_controller.param.yaml | 2 ++ .../longitudinal_controller.param.yaml | 1 + 8 files changed, 37 insertions(+), 10 deletions(-) diff --git a/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp b/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp index 8d954fed64f85..db05acaab33f6 100644 --- a/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp +++ b/control/trajectory_follower/include/trajectory_follower/mpc_lateral_controller.hpp @@ -115,6 +115,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC MpcLateralController : public LateralController /* parameters for stop state */ float64_t m_stop_state_entry_ego_speed; float64_t m_stop_state_entry_target_speed; + float64_t m_converged_steer_rad; + bool m_check_steer_converged_for_stopped_state; // MPC object trajectory_follower::MPC m_mpc; diff --git a/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp b/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp index df202f4b1a3e0..e66d87bb0ec22 100644 --- a/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp +++ b/control/trajectory_follower/include/trajectory_follower/pid_longitudinal_controller.hpp @@ -129,6 +129,7 @@ class TRAJECTORY_FOLLOWER_PUBLIC PidLongitudinalController : public Longitudinal bool8_t m_enable_smooth_stop; bool8_t m_enable_overshoot_emergency; bool8_t m_enable_slope_compensation; + bool8_t m_enable_keep_stopped_until_steer_convergence; // smooth stop transition struct StateTransitionParams @@ -214,8 +215,6 @@ class TRAJECTORY_FOLLOWER_PUBLIC PidLongitudinalController : public Longitudinal std::shared_ptr m_last_running_time{ std::make_shared(rclcpp::Clock{RCL_ROS_TIME}.now())}; - LateralSyncData lateral_sync_data_; - /** * @brief set current and previous velocity with received message * @param [in] msg current state message diff --git a/control/trajectory_follower/src/mpc_lateral_controller.cpp b/control/trajectory_follower/src/mpc_lateral_controller.cpp index b31a3e2ea74cd..6df6ad577fb92 100644 --- a/control/trajectory_follower/src/mpc_lateral_controller.cpp +++ b/control/trajectory_follower/src/mpc_lateral_controller.cpp @@ -72,6 +72,9 @@ MpcLateralController::MpcLateralController(rclcpp::Node * node) : node_{node} m_stop_state_entry_ego_speed = node_->declare_parameter("stop_state_entry_ego_speed"); m_stop_state_entry_target_speed = node_->declare_parameter("stop_state_entry_target_speed"); + m_converged_steer_rad = node_->declare_parameter("converged_steer_rad"); + m_check_steer_converged_for_stopped_state = + node_->declare_parameter("check_steer_converged_for_stopped_state"); /* mpc parameters */ const float64_t steer_lim_deg = node_->declare_parameter("steer_lim_deg"); @@ -180,7 +183,7 @@ MpcLateralController::~MpcLateralController() LateralOutput MpcLateralController::run() { if (!checkData() || !updateCurrentPose()) { - LateralOutput output{}; + LateralOutput output; return output; // todo } @@ -208,7 +211,11 @@ LateralOutput MpcLateralController::run() const auto cmd_msg = createCtrlCmdMsg(m_ctrl_cmd_prev); publishPredictedTraj(predicted_traj); publishDiagnostic(diagnostic); - LateralOutput output{cmd_msg}; + LateralOutput output; + output.control_cmd = cmd_msg; + output.sync_data.is_steer_converged = + std::abs(cmd_msg.steering_tire_angle - m_current_steering_ptr->steering_tire_angle) < + m_converged_steer_rad; return output; } @@ -223,7 +230,11 @@ LateralOutput MpcLateralController::run() const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd); publishPredictedTraj(predicted_traj); publishDiagnostic(diagnostic); - LateralOutput output{cmd_msg}; + LateralOutput output; + output.control_cmd = cmd_msg; + output.sync_data.is_steer_converged = + std::abs(cmd_msg.steering_tire_angle - m_current_steering_ptr->steering_tire_angle) < + m_converged_steer_rad; return output; } @@ -358,7 +369,10 @@ bool8_t MpcLateralController::isStoppedState() const m_current_trajectory_ptr->points.at(static_cast(nearest)).longitudinal_velocity_mps; if ( std::fabs(current_vel) < m_stop_state_entry_ego_speed && - std::fabs(target_vel) < m_stop_state_entry_target_speed) { + std::fabs(target_vel) < m_stop_state_entry_target_speed && + (!m_check_steer_converged_for_stopped_state || + std::abs(m_ctrl_cmd_prev.steering_tire_angle - m_current_steering_ptr->steering_tire_angle) < + m_converged_steer_rad)) { return true; } else { return false; diff --git a/control/trajectory_follower/src/pid_longitudinal_controller.cpp b/control/trajectory_follower/src/pid_longitudinal_controller.cpp index 1b7f127f25a44..80c84475b5552 100644 --- a/control/trajectory_follower/src/pid_longitudinal_controller.cpp +++ b/control/trajectory_follower/src/pid_longitudinal_controller.cpp @@ -51,6 +51,8 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node * node) m_enable_smooth_stop = node_->declare_parameter("enable_smooth_stop"); m_enable_overshoot_emergency = node_->declare_parameter("enable_overshoot_emergency"); m_enable_slope_compensation = node_->declare_parameter("enable_slope_compensation"); + m_enable_keep_stopped_until_steer_convergence = + node_->declare_parameter("enable_keep_stopped_until_steer_convergence"); // parameters for state transition { @@ -385,7 +387,8 @@ LongitudinalOutput PidLongitudinalController::run() const auto cmd_msg = createCtrlCmdMsg(raw_ctrl_cmd, control_data.current_motion.vel); // create control command publishDebugData(raw_ctrl_cmd, control_data); // publish debug data - LongitudinalOutput output{cmd_msg}; + LongitudinalOutput output; + output.control_cmd = cmd_msg; return output; } @@ -397,7 +400,8 @@ LongitudinalOutput PidLongitudinalController::run() // publish control command const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd, control_data.current_motion.vel); - LongitudinalOutput output{cmd_msg}; + LongitudinalOutput output; + output.control_cmd = cmd_msg; // publish debug data publishDebugData(ctrl_cmd, control_data); @@ -480,7 +484,7 @@ PidLongitudinalController::ControlState PidLongitudinalController::updateControl const bool8_t departure_condition_from_stopping = stop_dist > p.drive_state_stop_dist + p.drive_state_offset_stop_dist; const bool8_t departure_condition_from_stopped = stop_dist > p.drive_state_stop_dist; - const bool8_t keep_stopped_condition = lateral_sync_data_.is_steer_converged; + const bool8_t keep_stopped_condition = !lateral_sync_data_.is_steer_converged; const bool8_t stopping_condition = stop_dist < p.stopping_state_stop_dist; if ( @@ -535,7 +539,9 @@ PidLongitudinalController::ControlState PidLongitudinalController::updateControl return ControlState::DRIVE; } } else if (current_control_state == ControlState::STOPPED) { - if (departure_condition_from_stopped && !keep_stopped_condition) { + if ( + departure_condition_from_stopped && + (!m_enable_keep_stopped_until_steer_convergence || !keep_stopped_condition)) { m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); // prevent the car from taking a long time to start to move diff --git a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml index 3133549588e1c..911af5291e3c5 100644 --- a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml +++ b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml @@ -55,6 +55,8 @@ # stop state: steering command is kept in the previous value in the stop state. stop_state_entry_ego_speed: 0.001 stop_state_entry_target_speed: 0.001 + converged_steer_rad: 0.1 + check_steer_converged_for_stopped_state: true # vehicle parameters mass_kg: 2400.0 diff --git a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml index 3ad3333535f54..ee625c99de083 100644 --- a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml +++ b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml @@ -5,6 +5,7 @@ enable_smooth_stop: true enable_overshoot_emergency: true enable_slope_compensation: false + enable_keep_stopped_until_steer_convergence: true # state transition drive_state_stop_dist: 0.5 diff --git a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml index efb367956586c..75bd287291f2a 100644 --- a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml +++ b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml @@ -56,6 +56,8 @@ # stop state: steering command is kept in the previous value in the stop state. stop_state_entry_ego_speed: 0.001 stop_state_entry_target_speed: 0.001 + converged_steer_rad: 0.1 + check_steer_converged_for_stopped_state: true # vehicle parameters vehicle: diff --git a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index aa84efc7b3acf..31a5974333d67 100644 --- a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -5,6 +5,7 @@ enable_smooth_stop: true enable_overshoot_emergency: true enable_slope_compensation: false + enable_keep_stopped_until_steer_convergence: true # state transition drive_state_stop_dist: 0.5